diff --git a/.clang-format b/.clang-format index ee1bee2..419b224 100644 --- a/.clang-format +++ b/.clang-format @@ -1,2 +1,25 @@ BasedOnStyle: Google ColumnLimit: 100 +SortIncludes: CaseSensitive +IncludeBlocks: Regroup +IncludeCategories: + # 1. C system headers + - Regex: '^' + Priority: 1 + CaseSensitive: true + # 2. Third-party (path-based includes: Eigen/, ompl/, nanobind/, gtest/, etc.) + - Regex: '^<.+/' + Priority: 3 + # 3. Platform / architecture headers + - Regex: '^<(arm_neon|immintrin|xmmintrin|emmintrin)\.h>' + Priority: 3 + CaseSensitive: true + # 4. C++ standard library (lowercase start, catch-all for remaining <...>) + - Regex: '^<' + Priority: 2 + # 5. Local project headers (quoted) + - Regex: '^"geodex/' + Priority: 4 + # 6. Relative local headers (quoted, no path prefix) + - Regex: '^"' + Priority: 5 diff --git a/CHANGELOG.md b/CHANGELOG.md index 4580717..1111312 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -17,6 +17,43 @@ and this project adheres to [Semantic Versioning](https://semver.org/spec/v2.0.0 ## Released +### [0.1.1] - 2026-04-23 + +#### Added - new major features +- Discrete geodesic interpolation algorithm (`discrete_geodesic`). +- New collision checking module: smooth-SDF primitives (`CircleSmoothSDF`, `RectangleSmoothSDF`), `GridSDF`, `PolygonFootprint`, `FootprintGridChecker`. +- `SDFConformalMetric` — turns any base metric into an obstacle-aware metric via a smooth SDF callable. +- `smooth_path()` - metric-aware shortcutting and collision-constrained L-BFGS energy minimization. +- `SE2LeftInvariantMetric::car_like(radius, lateral_penalty)` static factory for turning-radius-constrained SE(2) planning. +- n-dimensional Sphere + - Sphere now supports any dimensions +- OMPL integration + - GeodexStateSpace adapts any RiemannianManifold to OMPL's StateSpace. + - GeodexOptimizationObjective for geodesic distance cost + admissible heuristic. + - GeodexDirectInfSampler for informed sampling (PHS for Euclidean heuristic, rejection otherwise). + - GeodexValidityChecker for OMPL motion validation. +- `Sampler` concept with `StochasticSampler` and `HaltonSampler`; all manifolds take a `SamplerT` template parameter. +- CMake install targets and find_package(geodex) support +- New python bindings and tests +- Examples: `sphere_interpolation` (C++ and Python), `se2_tutorial` (holonomic / diff-drive / clearance / parking on a real costmap), `minimum_energy_planning` (planar arm under KE and Jacobi metrics). +- Documentation updates + - New SE2 planning tutorial + - Minimum energy planning tutorial now includes planning with OMPL section + - New concept page for discrete geodesic interpolation algorithm + - Redesigned landing page, and vendored MathJax for offline builds. + +#### Changed +- `SE2` sampling bounds unified into `lo`/`hi` `Vector3d` over `(x, y, θ)`; default θ bounds `[−π, π)`. +- `injectivity_radius()` moved from metrics onto manifolds. +- `Sphere` exp/log/distance parameterized on the metric (was round-metric-only). +- Composable metric refactors + - WeightedMetric — uniform scalar (or configuration-dependent callable) scaling wrapper around any base metric. + - JacobiMetric — now composed over KineticEnergyMetric + WeightedMetric; static_assert callability checks on construction. + - SE2LeftInvariantMetric — composed over WeightedMetric + ConstantSPDMetric. +- `type_name()` moved to `core/debug.hpp`; `MetricHasInnerMatrix` concept and `is_riemannian_log()` resolver added in `core/metric.hpp`. +- All manifolds preallocate a sample_buf_ for random_point() (no per-call allocation) +- clang-format applied repo-wide + ### [0.1.0] - 2026-04-02 Initial public release. diff --git a/CMakeLists.txt b/CMakeLists.txt index 803b9e2..4775ad0 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,10 +1,12 @@ cmake_minimum_required(VERSION 3.20) -project(geodex VERSION 0.1.0 LANGUAGES CXX) +project(geodex VERSION 0.1.1 LANGUAGES CXX) set(CMAKE_CXX_STANDARD 20) set(CMAKE_CXX_STANDARD_REQUIRED ON) set(CMAKE_CXX_EXTENSIONS OFF) +include(GNUInstallDirs) +include(CMakePackageConfigHelpers) include(FetchContent) # Eigen3 @@ -14,24 +16,19 @@ FetchContent_Declare( GIT_TAG 5.0.0 GIT_SHALLOW TRUE ) -set(EIGEN_BUILD_DOC OFF CACHE BOOL "" FORCE) -set(EIGEN_BUILD_TESTING OFF CACHE BOOL "" FORCE) -set(BUILD_TESTING_SAVE ${BUILD_TESTING}) -set(BUILD_TESTING OFF CACHE BOOL "" FORCE) FetchContent_GetProperties(eigen) if(NOT eigen_POPULATED) FetchContent_Populate(eigen) - add_subdirectory(${eigen_SOURCE_DIR} ${eigen_BINARY_DIR} EXCLUDE_FROM_ALL) endif() -set(BUILD_TESTING ${BUILD_TESTING_SAVE} CACHE BOOL "" FORCE) # Header-only interface library add_library(geodex INTERFACE) +add_library(geodex::geodex ALIAS geodex) target_include_directories(geodex INTERFACE $ - $ + $ + $ ) -target_link_libraries(geodex INTERFACE Eigen3::Eigen) target_compile_features(geodex INTERFACE cxx_std_20) # Tests @@ -75,3 +72,40 @@ if(BUILD_DOCS) VERBATIM) endif() endif() + +# Install +install(TARGETS geodex + EXPORT geodexTargets +) + +install(DIRECTORY include/ + DESTINATION ${CMAKE_INSTALL_INCLUDEDIR} +) + +install(DIRECTORY ${eigen_SOURCE_DIR}/Eigen + DESTINATION ${CMAKE_INSTALL_INCLUDEDIR} +) + +install(EXPORT geodexTargets + FILE geodexTargets.cmake + NAMESPACE geodex:: + DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/geodex +) + +configure_package_config_file( + cmake/geodexConfig.cmake.in + ${CMAKE_CURRENT_BINARY_DIR}/geodexConfig.cmake + INSTALL_DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/geodex +) + +write_basic_package_version_file( + ${CMAKE_CURRENT_BINARY_DIR}/geodexConfigVersion.cmake + VERSION ${PROJECT_VERSION} + COMPATIBILITY SameMajorVersion +) + +install(FILES + ${CMAKE_CURRENT_BINARY_DIR}/geodexConfig.cmake + ${CMAKE_CURRENT_BINARY_DIR}/geodexConfigVersion.cmake + DESTINATION ${CMAKE_INSTALL_LIBDIR}/cmake/geodex +) diff --git a/README.md b/README.md index 6cc766b..3ccc1c6 100644 --- a/README.md +++ b/README.md @@ -29,14 +29,20 @@ All installation instructions, C++/Python tutorials, and API references are avai geodex accompanies the paper "[Geometry-Aware Sampling-Based Motion Planning on Riemannian Manifolds](https://arxiv.org/abs/2602.00992)" accepted to [WAFR 2026](https://algorithmic-robotics.org/): ```bibtex -@article{kyaw2026geometry, - title={Geometry-Aware Sampling-Based Motion Planning on Riemannian Manifolds}, - author={Kyaw, Phone Thiha and Kelly, Jonathan}, - journal={arXiv preprint arXiv:2602.00992}, - year={2026} +@inproceedings{kyaw2026geometry, + address = {Oulu, Finland}, + author = {Phone Thiha Kyaw and Jonathan Kelly}, + booktitle = {Proceedings of the 17th World Symposium on the Algorithmic Foundations of Robotics {(WAFR)}}, + date = {2026-06-15/2026-06-17}, + month = {Jun. 15--17}, + title = {Geometry-Aware Sampling-Based Motion Planning on {Riemannian} Manifolds}, + url = {https://arxiv.org/abs/2602.00992}, + year = {2026} } ``` ## License +Copyright © 2026 Space and Terrestrial Autonomous Robotic Systems (STARS) Lab. + geodex is licensed under the [Apache License 2.0](LICENSE). diff --git a/benchmarks/CMakeLists.txt b/benchmarks/CMakeLists.txt new file mode 100644 index 0000000..7cd50e0 --- /dev/null +++ b/benchmarks/CMakeLists.txt @@ -0,0 +1,34 @@ +include(FetchContent) + +FetchContent_Declare( + googlebenchmark + GIT_REPOSITORY https://github.com/google/benchmark.git + GIT_TAG v1.9.1 + GIT_SHALLOW TRUE +) +set(BENCHMARK_ENABLE_TESTING OFF CACHE BOOL "" FORCE) +set(BENCHMARK_ENABLE_INSTALL OFF CACHE BOOL "" FORCE) +set(BENCHMARK_INSTALL_DOCS OFF CACHE BOOL "" FORCE) +FetchContent_MakeAvailable(googlebenchmark) + +add_executable(bench_manifold_ops bench_manifold_ops.cpp) +target_link_libraries(bench_manifold_ops PRIVATE geodex benchmark::benchmark benchmark::benchmark_main) + +add_executable(bench_algorithms bench_algorithms.cpp) +target_link_libraries(bench_algorithms PRIVATE geodex benchmark::benchmark benchmark::benchmark_main) +target_include_directories(bench_algorithms PRIVATE ${CMAKE_SOURCE_DIR}/tests/fixtures) + +add_executable(bench_metrics bench_metrics.cpp) +target_link_libraries(bench_metrics PRIVATE geodex benchmark::benchmark benchmark::benchmark_main) +target_include_directories(bench_metrics PRIVATE ${CMAKE_SOURCE_DIR}/tests/fixtures) + +add_executable(bench_retractions bench_retractions.cpp) +target_link_libraries(bench_retractions PRIVATE geodex benchmark::benchmark benchmark::benchmark_main) + +add_executable(bench_collision bench_collision.cpp) +target_link_libraries(bench_collision PRIVATE geodex benchmark::benchmark benchmark::benchmark_main) + +if(TARGET ompl::ompl) + add_executable(bench_ompl_interpolation bench_ompl_interpolation.cpp) + target_link_libraries(bench_ompl_interpolation PRIVATE geodex benchmark::benchmark benchmark::benchmark_main ompl::ompl) +endif() diff --git a/benchmarks/README.md b/benchmarks/README.md new file mode 100644 index 0000000..eac87a1 --- /dev/null +++ b/benchmarks/README.md @@ -0,0 +1,459 @@ +# geodex Benchmarks + +Micro-benchmarks for geodex manifold operations, algorithms, metrics, and retractions using [Google Benchmark](https://github.com/google/benchmark). + +## Building + +```sh +cmake -B build -DCMAKE_BUILD_TYPE=Release -DBUILD_BENCHMARKS=ON +cmake --build build +``` + +Google Benchmark is fetched automatically via CMake FetchContent. + +## Running + +```sh +# All benchmarks +./build/benchmarks/bench_manifold_ops +./build/benchmarks/bench_algorithms +./build/benchmarks/bench_metrics +./build/benchmarks/bench_retractions +./build/benchmarks/bench_collision + +# JSON output for regression tracking +./build/benchmarks/bench_manifold_ops --benchmark_format=json --benchmark_out=results/bench_manifold_ops.json + +# Filter specific benchmarks +./build/benchmarks/bench_manifold_ops --benchmark_filter="Torus" +``` + +## Benchmark Suites + +| File | What it measures | +|------|-----------------| +| `bench_manifold_ops.cpp` | exp, log, distance, inner, norm, geodesic, random_point per manifold; dimension scaling for Torus/Euclidean (d=2..50) | +| `bench_algorithms.cpp` | `discrete_geodesic` single-pair on all manifolds; batch-steer workload (256 random endpoint pairs, shared workspace); SDFConformal FD path (midpoint guard vs forced via-log); batch `distance_midpoint` throughput (1000 pairs); dimension scaling | +| `bench_metrics.cpp` | `inner` and `norm` for all 7 metric types; ConfigurationSpace overhead vs bare manifold | +| `bench_retractions.cpp` | SE(2) and Sphere retraction speed; Sphere projection accuracy vs exponential map | +| `bench_collision.cpp` | Collision primitives: circle/rectangle SDF eval and scaling, distance grid single/batch lookup, polygon footprint transform, footprint grid checker (early-out vs full check); fast math: `fast_exp` vs `std::exp`, `sincos` vs separate trig | +| `bench_ompl_interpolation.cpp` | OMPL `GeodexStateSpace::interpolate()` with discrete geodesic cache; cache hot/cold; motion validation overhead (requires OMPL) | + +## Reference Results + +Machine: Apple M2 (8-core, arm64), 16 GB RAM, macOS 15.3.1 +Compiler: Apple clang 15.0.0, `-O2` (CMake Release) +Date: 2026-04-17 (run after `feature/ompl-integration`: discrete-geodesic +caching in OMPL adapter, FD midpoint guard with via-log fallback, `SDFConformalMetric`, +path smoothing arc-length shortcut criterion). + +### Manifold Primitives (ns per call) + +| Operation | Sphere (exp) | Sphere (proj) | Euclidean<2> | Euclidean<7> | Torus<2> | Torus<7> | SE2 (exp) | +|-----------|:---:|:---:|:---:|:---:|:---:|:---:|:---:| +| exp | 5.0 | 1.7 | 0.3 | 0.9 | 1.2 | 5.1 | 6.3 | +| log | 10.7 | 1.5 | 0.3 | 0.9 | 2.0 | 6.6 | 4.9 | +| distance | 79 | 12 | 0.9 | 6.5 | 7.9 | 31 | 30 | +| inner | 1.1 | -- | 0.4 | 4.1 | 0.5 | 4.2 | 1.1 | +| geodesic | 23 | -- | -- | -- | 3.8 | -- | 12 | +| random_point | 70 | -- | -- | -- | 25 | -- | 30 | + +### Dimension Scaling: distance_midpoint (ns) + +Torus at compile-time fixed dimension versus `Torus` constructed +at runtime. The fixed column is derived from the batch benchmarks +(`BM_DistanceMidpoint_Torus2_Batch`, `BM_DistanceMidpoint_Torus7_Batch`) by +dividing by the 1000-pair batch size; the dynamic column is per-call +(`BM_DistanceMidpoint_TorusDynamic/d`). + +| Dimension | Torus (fixed) | Torus (dynamic) | +|-----------|:---:|:---:| +| 2 | 6.3 | 138 | +| 5 | -- | 187 | +| 7 | 38 | 200 | +| 10 | -- | 195 | +| 20 | -- | 247 | +| 50 | -- | 656 | + +Fixed-dimension types are ~20x faster than dynamic at d=2 thanks to stack +allocation and compile-time loop unrolling. The dynamic cost grows roughly +linearly with dimension (heap vectors + Eigen's dynamic dispatch). + +### Algorithm Performance: discrete_geodesic single pair (ns per call) + +Single `start → target` walk with a pre-allocated `InterpolationCache` workspace. +`iters/call` is the average number of gradient steps to convergence at the +default `settings.step_size = 0.5`. + +| Manifold | Time | iters/call | +|----------|:---:|:---:| +| Sphere (round metric) | 218 | 2 | +| Sphere (anisotropic `ConstantSPD<3>`) | 2,706 | 4 | +| Torus<2> (flat metric) | 130 | 6 | +| SE2 (exp map, isotropic) | 1,246 | 23 | +| SE2 (anisotropic `SE2LeftInvariant`) | 11,630 | 22 | +| ConfigurationSpace, KineticEnergyMetric> | 1,544 | 7 | + +Isotropic metrics (`is_riemannian_log` returns true) use the log direction +directly — no FD sampling per step, so cost per iteration is minimal. The +anisotropic/point-dependent rows (`SphereAniso`, `SE2_Anisotropic`, `CSpace_KE`) +pay one central finite-difference natural gradient per step: 2·d samples of +`distance_midpoint_fd` under the metric, which dominates wall time. Each sample +itself calls the metric's `inner` (the 5.9 ns and 11.9 ns for KE/Jacobi listed +further down), so the FD cost scales with the metric's per-evaluation price. + +### SDFConformal FD path: midpoint guard vs forced via-log + +Benchmarks: `BM_DiscreteGeodesic_SE2_SDFConformal_{Midpoint,ViaLog}`. Same +`(start, target, step_size, max_steps)` under a spatially-varying +`SDFConformalMetric` (unit-circle obstacle at origin). The two rows toggle +`fd_midpoint_guard_tau` between its default (midpoint surrogate with guard) and +0.0 (force the via-log fallback on every FD sample, which reproduces the +pre-guard behavior). + +| Mode | Time | iters/call | fallbacks/call | +|------|:---:|:---:|:---:| +| Midpoint guard (default) | 13,221 ns | 24 | 0 | +| Forced via-log (tau = 0) | 12,174 ns | 24 | 72 | + +Both paths converge in the same number of iterations and have essentially the +same wall time — but the guarded midpoint form avoids the 72 per-iteration +via-log recomputations. The guard lets the cheaper midpoint distance stand when +it agrees with via-log, falling back per-sample only when the two diverge. On +this benchmark the guard always agrees, so `fallbacks/call` is 0 at the +default; forcing `tau = 0` shows the upper bound on via-log work we avoid. + +### Batch steer workload (RRT\* inner loop) + +Benchmarks: `BM_DiscreteGeodesic_*_BatchSteer`. Each invocation runs 256 +`discrete_geodesic` calls between independent random `(start, target)` pairs +reusing a single `InterpolationCache`. This is the primary "RRT\* steer loop" +shape — many short walks from unrelated roots through one workspace. + +| Manifold | Batch total | Per steer | Throughput | iters/call | +|----------|:---:|:---:|:---:|:---:| +| Sphere (round metric) | 93.8 µs | 366 ns | 2.73 M/s | 3.6 | +| Torus<7> (flat metric) | 112.7 µs | 440 ns | 2.27 M/s | 9.7 | +| SE2 (exp map) | 199.6 µs | 780 ns | 1.28 M/s | 13.5 | + +Per-steer cost is lower than the single-pair "Algorithm Performance" numbers +because the workspace stays hot across steers and random endpoints give a +distribution of distances around the injectivity-radius sweet spot. Use these +numbers as a realistic RRT*/G-RRT* budget: ~1–3 M steers/second per core for +isotropic metrics on the manifolds geodex currently supports. + +### Batch distance_midpoint Throughput (1000 pairs) + +| Manifold | Total (µs) | Throughput | +|----------|:---:|:---:| +| Torus<2> | 6.3 | 159 M/s | +| Torus<7> | 38.0 | 26 M/s | +| SE2 | 26.4 | 38 M/s | +| Sphere | 93.0 | 11 M/s | + +`distance_midpoint` is a single exp + 3 log per pair. Sphere is slowest because +log involves `acos` + vector normalization; Torus at low dim is fastest because +exp/log reduce to arithmetic + angle wrap. + +### Metric inner Product (ns per call) + +| Metric | Time | +|--------|:---:| +| EuclideanStandard<2> | 0.4 | +| EuclideanStandard<7> | 3.0 | +| TorusFlat<2> | 0.4 | +| TorusFlat<7> | 3.0 | +| ConstantSPD<3> | 0.8 | +| ConstantSPD<7> | 3.0 | +| SE2LeftInvariant | 0.8 | +| Weighted> | 0.9 | +| KineticEnergy (2-link arm) | 5.9 | +| Jacobi (2-link arm) | 11.9 | +| Pullback (2-link arm) | 15.1 | + +After the refactor, `EuclideanStandard`, `TorusFlat`, and `SE2LeftInvariant` are +all thin aliases/compositions over `ConstantSPDMetric`, which is why their +`inner` timings are essentially identical to the corresponding `ConstantSPD` +row. The `WeightedMetric` wrapper adds ~0.1 ns on top of its base metric. + +Point-dependent metrics (KineticEnergy, Jacobi, Pullback) remain 6–15× more +expensive than constant metrics due to the `std::function` evaluation and +dense matrix–vector product per call. + +### Retraction Comparison (ns per call) + +| Retraction | retract | inverse_retract | +|------------|:---:|:---:| +| SE2 ExponentialMap | 8.2 | 7.7 | +| SE2 Euler | 0.7 | 0.6 | +| Sphere ExponentialMap | 5.1 | 10.8 | +| Sphere Projection | 1.6 | 1.5 | + +### OMPL Integration: Discrete Geodesic Interpolation (ns per call) + +Benchmark: `bench_ompl_interpolation` — measures the `GeodexStateSpace::interpolate()` method +with the discrete geodesic path cache. + +Machine: Apple M2 (8-core, arm64), macOS 15.3.1, Apple clang, `-O2` + +**Interpolation throughput** (N sequential calls with same `(from, to)` pair): + +| Benchmark | N=10 | N=50 | N=100 | Per-call | +|-----------|:---:|:---:|:---:|:---:| +| SE2 Identity (fast path) | 234 | 1,137 | 2,300 | 23 | +| SE2 Anisotropic cache hot | 420 | 2,174 | 4,378 | 44 | +| Euclidean Aniso cache hot | 161 | 872 | 1,634 | 16 | + +Cache cold (first call, triggers `discrete_geodesic`): **59 µs** for anisotropic SE2. + +**Motion validation** (`DiscreteMotionValidator::checkMotion()`, single edge): + +| Mode | Time | +|------|:---:| +| Simple geodesic (discrete OFF) | 1,767 ns | +| Discrete geodesic (discrete ON) | 3,773 ns | + +The 2.1x overhead on motion validation is justified by the path quality improvement +(see analysis below). + +### Interpolation Quality Analysis + +Analysis tool: `analysis/interpolation_analysis.cpp` — compares path length and +energy between naive `geodesic(p,q,t) = exp(p, t·log(p,q))` and the discrete +geodesic path for the same (start, target) pair, sampled at 20 uniform points. + +| Scenario | Naive length | Discrete length | Ratio | Naive energy | Discrete energy | Max deviation | +|----------|:---:|:---:|:---:|:---:|:---:|:---:| +| Euclidean R², identity | 11.31 | 11.31 | 1.000 | 6.40 | 6.40 | 0.000 | +| Euclidean R², A=diag(4,1) | 17.89 | 17.89 | 1.000 | 16.00 | 16.00 | 0.000 | +| SE(2) isotropic, Euler retract | 8.54 | 8.54 | 1.000 | 3.65 | 3.65 | 0.000 | +| **SE(2) car-like w=(1,100,0.5)** | **26.33** | **9.07** | **0.344** | **34.67** | **4.37** | **0.765** | +| **SE(2) extreme w=(1,1000,0.1)** | **79.24** | **0.78** | **0.010** | **313.98** | **0.031** | **7.941** | + +**Key observations:** + +1. **Flat spaces with constant metrics (Euclidean, Torus):** Both methods produce + identical paths. Geodesics are straight lines regardless of metric — the metric + changes distances but not directions. The fast path (`is_riemannian_log`) is + correctly activated, giving zero overhead. + +2. **SE(2) with anisotropic left-invariant metric:** The discrete geodesic + produces dramatically shorter paths. With car-like weights (1,100,0.5), the + naive path is **2.9x longer** and **7.9x higher energy**. The naive midpoint + deviates 0.76 units from the true geodesic midpoint. + +3. **Extreme anisotropy amplifies the effect:** With w=(1,1000,0.1), the naive + path is **100x longer** and **10,000x higher energy**. The naive interpolation + cuts through the high-cost y-direction while the discrete geodesic avoids it. + +4. **Retraction type matters less than metric:** SE(2) with Euler retraction but + isotropic metric produces identical results to the exponential map case. + The metric-retraction mismatch drives the quality difference, not the + retraction choice alone. + +**Convergence note:** The default `InterpolationSettings` (`step_size=0.5, +max_steps=100`) may not converge for strongly anisotropic metrics. For car-like +SE(2) w=(1,100,0.5), the default budget reaches only ~50% of the path to target. +The cache gracefully handles partial convergence (appends the target, so `t=0` and +`t=1` are exact), but intermediate points are less accurate near the tail. Users +with strong anisotropy should increase `max_steps` via `setInterpolationSettings()`. + +| Metric anisotropy | step=0.5, max=100 | step=0.5, max=500 | step=0.1, max=1000 | +|---|---|---|---| +| w=(1,1,1) isotropic | Converged | Converged | Converged | +| w=(1,100,0.5) car-like | MaxStepsReached (50%) | Converged | Converged | +| w=(1,1000,0.1) extreme | MaxStepsReached (10%) | MaxStepsReached (30%) | MaxStepsReached (60%) | + +**When discrete geodesic helps:** +- Non-identity metrics on manifolds with non-trivial geometry (SE(2), SO(3), configuration spaces) +- Point-dependent metrics (KineticEnergyMetric, JacobiMetric, PullbackMetric) +- ConfigurationSpace with custom metrics overlaid on base manifolds + +**When it adds no value (fast path used):** +- Any manifold with identity metric and matching retraction +- Flat spaces (Euclidean, Torus) with constant metrics — geodesics are straight lines + +### Collision Primitives and Fast Math (ns per call) + +Benchmark: `bench_collision` — measures all collision SDF evaluation, distance grid +queries, polygon footprint transforms, and fast math utilities. + +Machine: Apple M2 (8-core, arm64), macOS 15.3.1, Apple clang, `-O2` +Date: 2026-04-11 + +**SDF evaluation scaling** (parameterized by obstacle count): + +| Benchmark | N=5 | N=10 | N=20 | N=50 | +|-----------|:---:|:---:|:---:|:---:| +| CircleSmoothSDF | 20 | 27 | 46 | 114 | +| CircleSmoothSDF (is_free) | 2.5 | 4.8 | 9.4 | 23 | +| RectSmoothSDF (NEON) | 4.8 | 6.2 | 9.4 | 22 | + +Single `CircleSDF` evaluation: **0.6 ns** (one sqrt + subtract). + +RectSmoothSDF benefits from NEON 2-wide processing and bounding-sphere early-out, +keeping cost low even at N=50. CircleSmoothSDF scales linearly with circle count +(~2.3 ns/circle) after the single-pass caching optimization. + +**Distance grid queries:** + +| Benchmark | Time | Throughput | +|-----------|:---:|:---:| +| Single bilinear lookup | 2.9 ns | — | +| Batch N=16 | 31 ns | 509M items/s | +| Batch N=32 | 61 ns | 522M items/s | +| Batch N=64 | 121 ns | 528M items/s | +| Batch N=128 | 250 ns | 513M items/s | + +Batch throughput is ~2 ns/point with NEON vectorized bilinear interpolation. +The scalar gather (no ARM NEON gather instruction) is the bottleneck. + +**Polygon footprint and checker:** + +| Benchmark | Time | +|-----------|:---:| +| PolygonFootprint transform (spe=2, 8 samples) | 6.7 ns | +| PolygonFootprint transform (spe=4, 16 samples) | 10 ns | +| PolygonFootprint transform (spe=8, 32 samples) | 18 ns | +| FootprintGridChecker (bounding sphere early-out) | 4.6 ns | +| FootprintGridChecker (full perimeter check) | 52 ns | + +The bounding-sphere early-out (center distance > bounding radius + margin) resolves +most queries in 4.6 ns without transforming the polygon. The full check (transform + +batch grid lookup + min-reduce) costs 52 ns for a 16-sample rectangle footprint. + +**Fast math utilities:** + +| Function | Time | vs stdlib | +|----------|:---:|:---:| +| `fast_exp` | 1.0 ns | **2.5x** faster than `std::exp` (2.5 ns) | +| `sincos` | 4.7 ns | ~same as separate `sin`+`cos` (Apple libm optimizes both) | + +`fast_exp` (Schraudolph IEEE 754 bit trick, ~4% max relative error) is used in all +log-sum-exp smooth-min SDF computations. The 2.5x speedup compounds across obstacle +counts in `CircleSmoothSDF` and `RectSmoothSDF`. + +### x86 Reference Results — Collision Primitives and Fast Math + +Machine: Intel Core i7-10875H (8-core/16-thread, x86_64), 32 GB RAM, Ubuntu 24.04 +Compiler: GCC 13.3.0, `-O3 -march=native` (SSE4.2 + AVX2 + FMA enabled) +Date: 2026-04-12 + +**SDF evaluation scaling** (parameterized by obstacle count): + +| Benchmark | N=5 | N=10 | N=20 | N=50 | +|-----------|:---:|:---:|:---:|:---:| +| CircleSmoothSDF | 24 | 36 | 59 | 128 | +| CircleSmoothSDF (is_free) | 3.3 | 6.1 | 12 | 29 | +| RectSmoothSDF (SSE2) | 4.1 | 5.8 | 9.7 | 21 | + +Single `CircleSDF` evaluation: **1.3 ns**. + +RectSmoothSDF SSE2 performance is on par with ARM NEON: the 2-wide processing, +bounding-sphere early-out, and `fast_exp` vectorization translate directly. The SSE2 +path uses `_mm_movemask_pd` for the early-out check, which is slightly more efficient +than NEON's per-lane extraction. + +**Distance grid queries:** + +| Benchmark | Time | Throughput | +|-----------|:---:|:---:| +| Single bilinear lookup | 6.7 ns | — | +| Batch N=16 | 74 ns | 218M items/s | +| Batch N=32 | 146 ns | 222M items/s | +| Batch N=64 | 298 ns | 217M items/s | +| Batch N=128 | 568 ns | 228M items/s | + +Batch throughput is ~4.4 ns/point with SSE2 vectorized bilinear interpolation. +Lower than ARM (~2 ns/point) because the benchmark grid (100x100 doubles = 80 KB) +fits in the M2's 128 KB L1D but spills on the i7's 32 KB L1D. Each bilinear lookup +gathers 4 grid values; on x86 these frequently miss L1 and hit L2 (~10 cycles vs +~4 cycles for an L1 hit). The scalar single-point lookup shows the same 2.3x gap +(6.7 vs 2.9 ns), confirming the bottleneck is cache capacity, not SIMD efficiency. + +**Polygon footprint and checker:** + +| Benchmark | Time | +|-----------|:---:| +| PolygonFootprint transform (spe=2, 8 samples) | 13 ns | +| PolygonFootprint transform (spe=4, 16 samples) | 19 ns | +| PolygonFootprint transform (spe=8, 32 samples) | 26 ns | +| FootprintGridChecker (bounding sphere early-out) | 9.2 ns | +| FootprintGridChecker (full perimeter check) | 99 ns | + +**Fast math utilities:** + +| Function | Time | vs stdlib | +|----------|:---:|:---:| +| `fast_exp` | 0.9 ns | **5.3x** faster than `std::exp` (4.8 ns) | +| `sincos` | 9.9 ns | ~same as separate `sin`+`cos` (glibc optimizes both) | + +`fast_exp` delivers a larger relative speedup on x86 (5.3x vs 2.5x on ARM) because +`std::exp` in glibc is slower than Apple's libm, while the Schraudolph bit trick runs +at similar speed on both architectures. + +### x86 vs ARM NEON — Collision Summary + +| Benchmark | ARM M2 (NEON) | x86 i7-10875H (SSE2) | Ratio | +|-----------|:---:|:---:|:---:| +| RectSmoothSDF N=5 | 4.8 ns | 4.1 ns | 0.85x | +| RectSmoothSDF N=50 | 22 ns | 21 ns | 0.95x | +| DistanceGrid batch throughput | 520M/s | 222M/s | 2.3x slower | +| FootprintGridChecker full | 52 ns | 99 ns | 1.9x slower | +| fast_exp | 1.0 ns | 0.9 ns | 0.90x | +| fast_exp vs std::exp speedup | 2.5x | 5.3x | — | + +The SSE2 RectSmoothSDF path matches or beats ARM NEON despite being a direct 2-wide +port (same width). The distance grid and footprint checker are slower on x86 because +the 80 KB benchmark grid fits in the M2's 128 KB L1D but exceeds the i7's 32 KB L1D, +causing L2 spills on every bilinear gather. This is a cache capacity effect, not a +SIMD efficiency issue — the vectorization code itself is equally efficient on both. + +## Key Findings + +- **OMPL discrete geodesic interpolation is a net win for anisotropic + metrics.** The 2.1x overhead on per-edge motion validation (3.8 µs vs 1.8 µs) + is negligible compared to the path quality improvement: 2.9x shorter paths and + 7.9x lower energy for car-like SE(2). For identity metrics the fast path is + taken with zero overhead — the compiler dead-code-eliminates the cache branch. +- **Cache amortization works as designed.** The cold-cache cost (59 µs for + anisotropic SE2) is paid once per `(from, to)` pair. Subsequent lookups cost + 44 ns/call — only 1.9x the identity-metric fast path (23 ns/call). OMPL's + `DiscreteMotionValidator` calls `interpolate` N-1 times with the same pair, + so the amortized cost is dominated by lookups, not computation. +- **Flat spaces with constant metrics don't benefit from discrete geodesic.** + Geodesics on Euclidean/Torus with constant SPD metrics are straight lines — + the naive `exp(p, t·log(p,q))` is already exact. The `is_riemannian_log` + signal correctly activates the fast path for identity metrics. For non-identity + constant SPD on flat spaces, both methods produce identical paths; the discrete + geodesic adds overhead without quality gain. A future `IsFlat` concept could + extend the fast path to all constant metrics on flat spaces. +- **`discrete_geodesic` cost is dominated by FD sampling for anisotropic / + point-dependent metrics.** Isotropic rows (Sphere round, Torus, SE2 exp, KE + on CSpace) converge in 2–23 iters with no FD fallback — hundreds of ns to a + few µs per walk. Anisotropic rows (`SphereAniso`, `SE2_Anisotropic`, + SDFConformal) pay 2·d `distance_midpoint_fd` samples per step; cost scales + with the metric's per-evaluation price and the number of steps, not the + loop overhead. +- **Batch-steer throughput sets the RRT\* budget.** With a reused workspace, + geodex does ~2.7 M steers/s on Sphere (round), ~2.3 M/s on Torus<7>, and + ~1.3 M/s on SE2 — a useful ceiling when sizing planners. +- **Metric unification is free.** Routing `EuclideanStandard`, `TorusFlat`, and + `SE2LeftInvariant` through `ConstantSPDMetric` did not regress `inner`/`norm` + performance (sub-nanosecond at low dim, identical to the old specialised + implementations). +- **Use fixed-dimension types** (`Torus<7>` not `Torus`) when + dimension is known at compile time. The dynamic penalty is ~20× at low + dimensions. +- **Torus and Euclidean primitives are trivially fast** — exp/log reduce to + arithmetic + angle wrapping. +- **SE2 is dominated by trig** (sin/cos/tan in the exponential map). Each + exp/log costs ~5–8 ns from trig alone. +- **Sphere distance is still the most expensive isotropic primitive** (~79 ns) + because `distance_midpoint` evaluates 1 exp + 3 log, each involving trig. +- **Point-dependent metrics** (KineticEnergy, Jacobi, Pullback) add 6–15 ns per + inner product from the callable + matrix–vector product, which compounds + through `distance_midpoint` and `discrete_geodesic`. +- **ConfigurationSpace overhead is moderate**: `distance_midpoint` on + `CSpace, KE>` costs 8.6 ns vs 5.7 ns for a bare `Torus<2>` flat — + the mass-matrix evaluation adds ~50%. diff --git a/benchmarks/bench_algorithms.cpp b/benchmarks/bench_algorithms.cpp new file mode 100644 index 0000000..de49aac --- /dev/null +++ b/benchmarks/bench_algorithms.cpp @@ -0,0 +1,424 @@ +/// @file bench_algorithms.cpp +/// @brief Benchmarks for geodex algorithms: discrete_geodesic and distance_midpoint. + +#include + +#include +#include + +#include +#include + +#include "geodex/geodex.hpp" +#include "geodex/metrics/clearance.hpp" + +#include "planar_manipulator_metric.hpp" + +using namespace geodex; + +// --------------------------------------------------------------------------- +// discrete_geodesic benchmarks +// --------------------------------------------------------------------------- + +static const InterpolationSettings settings{ + .step_size = 0.5, + .convergence_tol = 1e-4, + .max_steps = 200, + .fd_epsilon = 1e-4, + .distortion_ratio = 1.5, +}; + +static void BM_DiscreteGeodesic_Sphere(benchmark::State& state) { + Sphere<> sphere; + Eigen::Vector3d start(0.0, 0.0, 1.0); + Eigen::Vector3d target(std::sin(1.0), 0.0, std::cos(1.0)); + + InterpolationCache> ws; + long long total_iters = 0, total_halvings = 0, total_calls = 0; + for (auto _ : state) { + auto result = discrete_geodesic(sphere, start, target, settings, &ws); + total_iters += result.iterations; + total_halvings += result.distortion_halvings; + ++total_calls; + benchmark::DoNotOptimize(result); + } + state.counters["iters/call"] = static_cast(total_iters) / total_calls; + state.counters["halvings/call"] = static_cast(total_halvings) / total_calls; +} +BENCHMARK(BM_DiscreteGeodesic_Sphere); + +static void BM_DiscreteGeodesic_SphereAniso(benchmark::State& state) { + Eigen::Matrix3d A = Eigen::Matrix3d::Identity(); + A(0, 0) = 4.0; + using AnisoSphere = Sphere<2, ConstantSPDMetric<3>>; + AnisoSphere sphere{ConstantSPDMetric<3>{A}}; + Eigen::Vector3d start(0.0, 0.0, 1.0); + Eigen::Vector3d target(std::sin(0.8), 0.0, std::cos(0.8)); + + InterpolationCache ws; + long long total_iters = 0, total_halvings = 0, total_calls = 0; + for (auto _ : state) { + auto result = discrete_geodesic(sphere, start, target, settings, &ws); + total_iters += result.iterations; + total_halvings += result.distortion_halvings; + ++total_calls; + benchmark::DoNotOptimize(result); + } + state.counters["iters/call"] = static_cast(total_iters) / total_calls; + state.counters["halvings/call"] = static_cast(total_halvings) / total_calls; +} +BENCHMARK(BM_DiscreteGeodesic_SphereAniso); + +static void BM_DiscreteGeodesic_Torus2(benchmark::State& state) { + Torus<2> torus; + Eigen::Vector2d start(0.5, 0.5); + Eigen::Vector2d target(5.0, 5.0); + + InterpolationCache> ws; + long long total_iters = 0, total_halvings = 0, total_calls = 0; + for (auto _ : state) { + auto result = discrete_geodesic(torus, start, target, settings, &ws); + total_iters += result.iterations; + total_halvings += result.distortion_halvings; + ++total_calls; + benchmark::DoNotOptimize(result); + } + state.counters["iters/call"] = static_cast(total_iters) / total_calls; + state.counters["halvings/call"] = static_cast(total_halvings) / total_calls; +} +BENCHMARK(BM_DiscreteGeodesic_Torus2); + +static void BM_DiscreteGeodesic_SE2(benchmark::State& state) { + SE2<> se2; + Eigen::Vector3d start(1.0, 1.0, 0.0); + Eigen::Vector3d target(8.0, 8.0, std::numbers::pi / 2.0); + + InterpolationCache> ws; + long long total_iters = 0, total_halvings = 0, total_calls = 0; + for (auto _ : state) { + auto result = discrete_geodesic(se2, start, target, settings, &ws); + total_iters += result.iterations; + total_halvings += result.distortion_halvings; + ++total_calls; + benchmark::DoNotOptimize(result); + } + state.counters["iters/call"] = static_cast(total_iters) / total_calls; + state.counters["halvings/call"] = static_cast(total_halvings) / total_calls; +} +BENCHMARK(BM_DiscreteGeodesic_SE2); + +static void BM_DiscreteGeodesic_CSpace_KE(benchmark::State& state) { + PlanarManipulatorMetric arm_metric; + auto ke = + KineticEnergyMetric{[&](const Eigen::Vector2d& q) { return arm_metric.mass_matrix(q); }}; + using CSpace = ConfigurationSpace, decltype(ke)>; + CSpace cspace{Torus<2>{}, std::move(ke)}; + + Eigen::Vector2d start(0.5, 0.5); + Eigen::Vector2d target(2.5, 2.5); + + InterpolationCache ws; + long long total_iters = 0, total_halvings = 0, total_calls = 0; + for (auto _ : state) { + auto result = discrete_geodesic(cspace, start, target, settings, &ws); + total_iters += result.iterations; + total_halvings += result.distortion_halvings; + ++total_calls; + benchmark::DoNotOptimize(result); + } + state.counters["iters/call"] = static_cast(total_iters) / total_calls; + state.counters["halvings/call"] = static_cast(total_halvings) / total_calls; +} +BENCHMARK(BM_DiscreteGeodesic_CSpace_KE); + +// --------------------------------------------------------------------------- +// Anisotropic SE2 — exercises the FD fallback when the left-invariant weights +// produce a Riemannian geodesic that disagrees with the Lie-group exp. +// --------------------------------------------------------------------------- + +static void BM_DiscreteGeodesic_SE2_Anisotropic(benchmark::State& state) { + using Se2Aniso = SE2; + Se2Aniso se2(SE2LeftInvariantMetric{1.0, 1.0, 5.0}); + Eigen::Vector3d start(1.0, 1.0, 0.0); + Eigen::Vector3d target(8.0, 8.0, std::numbers::pi / 2.0); + + InterpolationCache ws; + long long total_iters = 0, total_halvings = 0, total_calls = 0; + for (auto _ : state) { + auto result = discrete_geodesic(se2, start, target, settings, &ws); + total_iters += result.iterations; + total_halvings += result.distortion_halvings; + ++total_calls; + benchmark::DoNotOptimize(result); + } + state.counters["iters/call"] = static_cast(total_iters) / total_calls; + state.counters["halvings/call"] = static_cast(total_halvings) / total_calls; +} +BENCHMARK(BM_DiscreteGeodesic_SE2_Anisotropic); + +// --------------------------------------------------------------------------- +// SE(2) + SDFConformal — exercises the FD path on a spatially-varying metric. +// Compares the new midpoint FD surrogate against the forced via-log fallback +// (tau=0), which reproduces the pre-fix behavior. Same (start, target, step) +// across the two entries so wall time / iterations / halvings / fallbacks are +// directly comparable. +// --------------------------------------------------------------------------- + +namespace { + +auto make_sdf_conformal_cspace() { + auto sdf = [](const Eigen::Vector3d& q) { + const double r = std::sqrt(q[0] * q[0] + q[1] * q[1]); + return r - 1.0; // unit circle at origin, positive outside + }; + SE2LeftInvariantMetric base{1.0, 1.0, 0.5}; + SE2 se2{base}; + SDFConformalMetric clearance{base, sdf, 2.0, 2.0}; + using CSpace = ConfigurationSpace; + return CSpace{se2, std::move(clearance)}; +} + +const Eigen::Vector3d kSDFStart{-2.0, 1.5, 0.0}; +const Eigen::Vector3d kSDFTarget{2.0, 1.5, 0.0}; + +} // namespace + +static void BM_DiscreteGeodesic_SE2_SDFConformal_Midpoint(benchmark::State& state) { + auto cspace = make_sdf_conformal_cspace(); + using CSpace = decltype(cspace); + + InterpolationSettings s = settings; + s.step_size = 0.2; + s.max_steps = 200; + + InterpolationCache ws; + long long total_iters = 0, total_halvings = 0, total_fallbacks = 0, total_calls = 0; + for (auto _ : state) { + auto result = discrete_geodesic(cspace, kSDFStart, kSDFTarget, s, &ws); + total_iters += result.iterations; + total_halvings += result.distortion_halvings; + total_fallbacks += result.fd_midpoint_fallbacks; + ++total_calls; + benchmark::DoNotOptimize(result); + } + state.counters["iters/call"] = static_cast(total_iters) / total_calls; + state.counters["halvings/call"] = static_cast(total_halvings) / total_calls; + state.counters["fallbacks/call"] = static_cast(total_fallbacks) / total_calls; +} +BENCHMARK(BM_DiscreteGeodesic_SE2_SDFConformal_Midpoint); + +static void BM_DiscreteGeodesic_SE2_SDFConformal_ViaLog(benchmark::State& state) { + auto cspace = make_sdf_conformal_cspace(); + using CSpace = decltype(cspace); + + InterpolationSettings s = settings; + s.step_size = 0.2; + s.max_steps = 200; + s.fd_midpoint_guard_tau = 0.0; // force via-log on every FD sample + + InterpolationCache ws; + long long total_iters = 0, total_halvings = 0, total_fallbacks = 0, total_calls = 0; + for (auto _ : state) { + auto result = discrete_geodesic(cspace, kSDFStart, kSDFTarget, s, &ws); + total_iters += result.iterations; + total_halvings += result.distortion_halvings; + total_fallbacks += result.fd_midpoint_fallbacks; + ++total_calls; + benchmark::DoNotOptimize(result); + } + state.counters["iters/call"] = static_cast(total_iters) / total_calls; + state.counters["halvings/call"] = static_cast(total_halvings) / total_calls; + state.counters["fallbacks/call"] = static_cast(total_fallbacks) / total_calls; +} +BENCHMARK(BM_DiscreteGeodesic_SE2_SDFConformal_ViaLog); + +// --------------------------------------------------------------------------- +// Batch steer workload — simulates an RRT* steer loop with N random endpoints +// and a single reused workspace. This is the primary "real workload" +// before/after comparison. +// --------------------------------------------------------------------------- + +static void BM_DiscreteGeodesic_Sphere_BatchSteer(benchmark::State& state) { + Sphere<> sphere; + const int N = 256; + std::vector starts(N), targets(N); + for (int i = 0; i < N; ++i) { + starts[i] = sphere.random_point(); + targets[i] = sphere.random_point(); + } + + InterpolationCache> ws; + long long total_iters = 0, total_halvings = 0, total_calls = 0; + for (auto _ : state) { + for (int i = 0; i < N; ++i) { + auto result = discrete_geodesic(sphere, starts[i], targets[i], settings, &ws); + total_iters += result.iterations; + total_halvings += result.distortion_halvings; + ++total_calls; + benchmark::DoNotOptimize(result); + } + } + state.SetItemsProcessed(state.iterations() * N); + state.counters["iters/call"] = static_cast(total_iters) / total_calls; + state.counters["halvings/call"] = static_cast(total_halvings) / total_calls; +} +BENCHMARK(BM_DiscreteGeodesic_Sphere_BatchSteer); + +static void BM_DiscreteGeodesic_Torus7_BatchSteer(benchmark::State& state) { + using Torus7 = Torus<7>; + Torus7 torus; + const int N = 256; + std::vector> starts(N), targets(N); + for (int i = 0; i < N; ++i) { + starts[i] = torus.random_point(); + targets[i] = torus.random_point(); + } + + InterpolationCache ws; + long long total_iters = 0, total_halvings = 0, total_calls = 0; + for (auto _ : state) { + for (int i = 0; i < N; ++i) { + auto result = discrete_geodesic(torus, starts[i], targets[i], settings, &ws); + total_iters += result.iterations; + total_halvings += result.distortion_halvings; + ++total_calls; + benchmark::DoNotOptimize(result); + } + } + state.SetItemsProcessed(state.iterations() * N); + state.counters["iters/call"] = static_cast(total_iters) / total_calls; + state.counters["halvings/call"] = static_cast(total_halvings) / total_calls; +} +BENCHMARK(BM_DiscreteGeodesic_Torus7_BatchSteer); + +static void BM_DiscreteGeodesic_SE2_BatchSteer(benchmark::State& state) { + SE2<> se2; + const int N = 256; + std::vector starts(N), targets(N); + for (int i = 0; i < N; ++i) { + starts[i] = se2.random_point(); + targets[i] = se2.random_point(); + } + + InterpolationCache> ws; + long long total_iters = 0, total_halvings = 0, total_calls = 0; + for (auto _ : state) { + for (int i = 0; i < N; ++i) { + auto result = discrete_geodesic(se2, starts[i], targets[i], settings, &ws); + total_iters += result.iterations; + total_halvings += result.distortion_halvings; + ++total_calls; + benchmark::DoNotOptimize(result); + } + } + state.SetItemsProcessed(state.iterations() * N); + state.counters["iters/call"] = static_cast(total_iters) / total_calls; + state.counters["halvings/call"] = static_cast(total_halvings) / total_calls; +} +BENCHMARK(BM_DiscreteGeodesic_SE2_BatchSteer); + +// --------------------------------------------------------------------------- +// Batch distance_midpoint throughput +// --------------------------------------------------------------------------- + +static void BM_DistanceMidpoint_Sphere_Batch(benchmark::State& state) { + Sphere<> sphere; + const int N = 1000; + + // Pre-generate random point pairs. + std::vector as(N), bs(N); + for (int i = 0; i < N; ++i) { + as[i] = sphere.random_point(); + bs[i] = sphere.random_point(); + } + + for (auto _ : state) { + double total = 0.0; + for (int i = 0; i < N; ++i) { + total += distance_midpoint(sphere, as[i], bs[i]); + } + benchmark::DoNotOptimize(total); + } + state.SetItemsProcessed(state.iterations() * N); +} +BENCHMARK(BM_DistanceMidpoint_Sphere_Batch); + +static void BM_DistanceMidpoint_Torus2_Batch(benchmark::State& state) { + Torus<2> torus; + const int N = 1000; + + std::vector as(N), bs(N); + for (int i = 0; i < N; ++i) { + as[i] = torus.random_point(); + bs[i] = torus.random_point(); + } + + for (auto _ : state) { + double total = 0.0; + for (int i = 0; i < N; ++i) { + total += distance_midpoint(torus, as[i], bs[i]); + } + benchmark::DoNotOptimize(total); + } + state.SetItemsProcessed(state.iterations() * N); +} +BENCHMARK(BM_DistanceMidpoint_Torus2_Batch); + +static void BM_DistanceMidpoint_SE2_Batch(benchmark::State& state) { + SE2<> se2; + const int N = 1000; + + std::vector as(N), bs(N); + for (int i = 0; i < N; ++i) { + as[i] = se2.random_point(); + bs[i] = se2.random_point(); + } + + for (auto _ : state) { + double total = 0.0; + for (int i = 0; i < N; ++i) { + total += distance_midpoint(se2, as[i], bs[i]); + } + benchmark::DoNotOptimize(total); + } + state.SetItemsProcessed(state.iterations() * N); +} +BENCHMARK(BM_DistanceMidpoint_SE2_Batch); + +static void BM_DistanceMidpoint_Torus7_Batch(benchmark::State& state) { + Torus<7> torus; + const int N = 1000; + + std::vector> as(N), bs(N); + for (int i = 0; i < N; ++i) { + as[i] = torus.random_point(); + bs[i] = torus.random_point(); + } + + for (auto _ : state) { + double total = 0.0; + for (int i = 0; i < N; ++i) { + total += distance_midpoint(torus, as[i], bs[i]); + } + benchmark::DoNotOptimize(total); + } + state.SetItemsProcessed(state.iterations() * N); +} +BENCHMARK(BM_DistanceMidpoint_Torus7_Batch); + +// --------------------------------------------------------------------------- +// Dimension scaling: distance_midpoint on dynamic Torus +// --------------------------------------------------------------------------- + +static void BM_DistanceMidpoint_TorusDynamic(benchmark::State& state) { + const int d = static_cast(state.range(0)); + Torus torus(d); + + Eigen::VectorXd p = Eigen::VectorXd::Constant(d, 0.5); + Eigen::VectorXd q = Eigen::VectorXd::Constant(d, 4.0); + + for (auto _ : state) { + benchmark::DoNotOptimize(distance_midpoint(torus, p, q)); + } +} +BENCHMARK(BM_DistanceMidpoint_TorusDynamic)->Arg(2)->Arg(5)->Arg(7)->Arg(10)->Arg(20)->Arg(50); diff --git a/benchmarks/bench_collision.cpp b/benchmarks/bench_collision.cpp new file mode 100644 index 0000000..215c5f0 --- /dev/null +++ b/benchmarks/bench_collision.cpp @@ -0,0 +1,222 @@ +/// @file bench_collision.cpp +/// @brief Micro-benchmarks for collision primitives and fast math utilities. + +#include + +#include + +#include +#include + +#include "geodex/collision/collision.hpp" +#include "geodex/utils/math.hpp" + +using namespace geodex::collision; + +// --------------------------------------------------------------------------- +// Helper: generate N circles spaced along the x-axis +// --------------------------------------------------------------------------- + +static std::vector make_circles(const int n) { + std::vector cs; + cs.reserve(n); + for (int i = 0; i < n; ++i) { + cs.emplace_back(static_cast(i) * 2.0, 0.0, 0.5); + } + return cs; +} + +// --------------------------------------------------------------------------- +// Helper: generate N oriented rectangles spaced along the x-axis +// --------------------------------------------------------------------------- + +static std::vector make_rects(const int n) { + std::vector rs; + rs.reserve(n); + for (int i = 0; i < n; ++i) { + rs.push_back({static_cast(i) * 3.0, 0.0, 0.1 * i, 1.0, 0.5}); + } + return rs; +} + +// --------------------------------------------------------------------------- +// Helper: synthetic 100x100 distance grid (5m x 5m at 0.05m resolution) +// --------------------------------------------------------------------------- + +static DistanceGrid make_grid() { + const int w = 100, h = 100; + std::vector data(static_cast(w) * h); + for (int r = 0; r < h; ++r) { + for (int c = 0; c < w; ++c) { + // Distance to nearest border (simple approximation). + data[static_cast(r) * w + c] = 0.05 * std::min({r, c, h - 1 - r, w - 1 - c}); + } + } + return DistanceGrid(w, h, 0.05, std::move(data)); +} + +static const DistanceGrid grid = make_grid(); + +// --------------------------------------------------------------------------- +// Fixed test data +// --------------------------------------------------------------------------- + +static const Eigen::Vector3d query_near(2.5, 2.5, 0.3); // near grid center +static const Eigen::Vector3d query_border(0.1, 0.1, 0.0); // near grid border (obstacles) +static const Eigen::Vector2d query_2d(2.5, 2.5); + +// =========================================================================== +// Circle SDF benchmarks +// =========================================================================== + +static void BM_CircleSDF(benchmark::State& state) { + CircleSDF sdf(5.0, 5.0, 1.0); + for (auto _ : state) { + benchmark::DoNotOptimize(sdf(query_2d)); + } +} +BENCHMARK(BM_CircleSDF); + +static void BM_CircleSmoothSDF(benchmark::State& state) { + const int n = static_cast(state.range(0)); + CircleSmoothSDF sdf(make_circles(n)); + for (auto _ : state) { + benchmark::DoNotOptimize(sdf(query_2d)); + } +} +BENCHMARK(BM_CircleSmoothSDF)->Arg(5)->Arg(10)->Arg(20)->Arg(50); + +static void BM_CircleSmoothSDF_IsFree(benchmark::State& state) { + const int n = static_cast(state.range(0)); + CircleSmoothSDF sdf(make_circles(n)); + // Query point that is free (far from all circles). + const Eigen::Vector2d free_pt(100.0, 100.0); + for (auto _ : state) { + benchmark::DoNotOptimize(sdf.is_free(free_pt)); + } +} +BENCHMARK(BM_CircleSmoothSDF_IsFree)->Arg(5)->Arg(10)->Arg(20)->Arg(50); + +// =========================================================================== +// Rectangle SDF benchmarks +// =========================================================================== + +static void BM_RectSmoothSDF(benchmark::State& state) { + const int n = static_cast(state.range(0)); + RectSmoothSDF sdf(make_rects(n)); + for (auto _ : state) { + benchmark::DoNotOptimize(sdf(query_2d)); + } +} +BENCHMARK(BM_RectSmoothSDF)->Arg(5)->Arg(10)->Arg(20)->Arg(50); + +// =========================================================================== +// Distance grid benchmarks +// =========================================================================== + +static void BM_DistanceGrid_Single(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(grid.distance_at(2.5, 2.5)); + } +} +BENCHMARK(BM_DistanceGrid_Single); + +static void BM_DistanceGrid_Batch(benchmark::State& state) { + const int n = static_cast(state.range(0)); + std::vector xs(n), ys(n), out(n); + for (int i = 0; i < n; ++i) { + // Spread queries across the grid. + xs[i] = 0.05 * (i % 100); + ys[i] = 0.05 * (i / 100 % 100); + } + for (auto _ : state) { + grid.distance_at_batch(xs.data(), ys.data(), out.data(), n); + benchmark::DoNotOptimize(out.data()); + } + state.SetItemsProcessed(state.iterations() * n); +} +BENCHMARK(BM_DistanceGrid_Batch)->Arg(16)->Arg(32)->Arg(64)->Arg(128); + +// =========================================================================== +// Polygon footprint benchmarks +// =========================================================================== + +static void BM_PolygonFootprint_Transform(benchmark::State& state) { + const int spe = static_cast(state.range(0)); + PolygonFootprint fp = PolygonFootprint::rectangle(0.5, 0.3, spe); + const int np = fp.sample_count(); + std::vector wx(np), wy(np); + for (auto _ : state) { + fp.transform(2.5, 2.5, 0.3, wx.data(), wy.data()); + benchmark::DoNotOptimize(wx.data()); + } +} +BENCHMARK(BM_PolygonFootprint_Transform)->Arg(2)->Arg(4)->Arg(8); + +// =========================================================================== +// Footprint grid checker benchmarks +// =========================================================================== + +static void BM_FootprintGridChecker_EarlyOut(benchmark::State& state) { + PolygonFootprint fp = PolygonFootprint::rectangle(0.1, 0.05, 4); + FootprintGridChecker checker(&grid, std::move(fp)); + // Query at grid center — far from borders, triggers bounding sphere early-out. + for (auto _ : state) { + benchmark::DoNotOptimize(checker(query_near)); + } +} +BENCHMARK(BM_FootprintGridChecker_EarlyOut); + +static void BM_FootprintGridChecker_FullCheck(benchmark::State& state) { + PolygonFootprint fp = PolygonFootprint::rectangle(0.1, 0.05, 4); + FootprintGridChecker checker(&grid, std::move(fp)); + // Query near border — center distance close to bounding radius, forces full check. + for (auto _ : state) { + benchmark::DoNotOptimize(checker(query_border)); + } +} +BENCHMARK(BM_FootprintGridChecker_FullCheck); + +// =========================================================================== +// Fast math utility benchmarks +// =========================================================================== + +static void BM_FastExp(benchmark::State& state) { + double x = -3.7; + for (auto _ : state) { + benchmark::DoNotOptimize(geodex::utils::fast_exp(x)); + x += 1e-9; // prevent constant folding + } +} +BENCHMARK(BM_FastExp); + +static void BM_StdExp(benchmark::State& state) { + double x = -3.7; + for (auto _ : state) { + benchmark::DoNotOptimize(std::exp(x)); + x += 1e-9; + } +} +BENCHMARK(BM_StdExp); + +static void BM_Sincos(benchmark::State& state) { + double angle = 1.23; + double s, c; + for (auto _ : state) { + geodex::utils::sincos(angle, &s, &c); + benchmark::DoNotOptimize(s); + benchmark::DoNotOptimize(c); + angle += 1e-9; + } +} +BENCHMARK(BM_Sincos); + +static void BM_SeparateSinCos(benchmark::State& state) { + double angle = 1.23; + for (auto _ : state) { + benchmark::DoNotOptimize(std::sin(angle)); + benchmark::DoNotOptimize(std::cos(angle)); + angle += 1e-9; + } +} +BENCHMARK(BM_SeparateSinCos); diff --git a/benchmarks/bench_manifold_ops.cpp b/benchmarks/bench_manifold_ops.cpp new file mode 100644 index 0000000..0745798 --- /dev/null +++ b/benchmarks/bench_manifold_ops.cpp @@ -0,0 +1,436 @@ +/// @file bench_manifold_ops.cpp +/// @brief Micro-benchmarks for manifold primitive operations. + +#include +#include + +#include "geodex/geodex.hpp" + +using namespace geodex; + +// --------------------------------------------------------------------------- +// Fixed test data per manifold type +// --------------------------------------------------------------------------- + +// Sphere S^2 +static const Eigen::Vector3d sphere_p = Eigen::Vector3d(0.0, 0.0, 1.0); // north pole +static const Eigen::Vector3d sphere_q = + Eigen::Vector3d(std::sin(1.0), 0.0, std::cos(1.0)); // theta=1 on great circle +static const Eigen::Vector3d sphere_v(0.3, 0.4, 0.0); // tangent at north pole +static const Eigen::Vector3d sphere_u(0.1, -0.2, 0.0); + +// SE(2) +static const Eigen::Vector3d se2_p(1.0, 1.0, 0.0); +static const Eigen::Vector3d se2_q(5.0, 3.0, 1.0); +static const Eigen::Vector3d se2_v(0.5, 0.3, 0.2); +static const Eigen::Vector3d se2_u(0.1, -0.4, 0.1); + +// Euclidean R^2 +static const Eigen::Vector2d euc2_p(1.0, 2.0); +static const Eigen::Vector2d euc2_q(4.0, 6.0); +static const Eigen::Vector2d euc2_v(0.5, 0.3); +static const Eigen::Vector2d euc2_u(0.1, -0.4); + +// Euclidean R^7 +static const Eigen::Vector euc7_p = + (Eigen::Vector() << 1, 2, 3, 4, 5, 6, 7).finished(); +static const Eigen::Vector euc7_q = + (Eigen::Vector() << 4, 6, 2, 8, 1, 3, 9).finished(); +static const Eigen::Vector euc7_v = + (Eigen::Vector() << 0.5, 0.3, 0.1, 0.2, 0.4, 0.6, 0.8).finished(); +static const Eigen::Vector euc7_u = + (Eigen::Vector() << 0.1, -0.4, 0.2, -0.1, 0.3, 0.5, -0.2).finished(); + +// Torus T^2 +static const Eigen::Vector2d tor2_p(0.5, 0.5); +static const Eigen::Vector2d tor2_q(5.0, 4.0); +static const Eigen::Vector2d tor2_v(0.3, 0.4); +static const Eigen::Vector2d tor2_u(0.1, -0.2); + +// Torus T^7 +static const Eigen::Vector tor7_p = + (Eigen::Vector() << 0.5, 1.0, 1.5, 2.0, 2.5, 3.0, 3.5).finished(); +static const Eigen::Vector tor7_q = + (Eigen::Vector() << 4.0, 5.0, 0.5, 3.0, 1.0, 4.5, 2.0).finished(); +static const Eigen::Vector tor7_v = + (Eigen::Vector() << 0.5, 0.3, 0.1, 0.2, 0.4, 0.6, 0.8).finished(); +static const Eigen::Vector tor7_u = + (Eigen::Vector() << 0.1, -0.4, 0.2, -0.1, 0.3, 0.5, -0.2).finished(); + +// --------------------------------------------------------------------------- +// Manifold instances +// --------------------------------------------------------------------------- + +static Sphere<> sphere; +static Sphere<2, SphereRoundMetric, SphereProjectionRetraction> sphere_proj; +static Sphere<2, ConstantSPDMetric<3>> sphere_aniso{ + ConstantSPDMetric<3>{(Eigen::Matrix3d() << 10, 0, 0, 0, 1, 0, 0, 0, 1).finished()}}; +static Euclidean<2> euclidean2; +static Euclidean<7> euclidean7; +static Torus<2> torus2; +static Torus<7> torus7; +static SE2<> se2_exp; + +// =========================================================================== +// Sphere (default: round metric + exponential map) +// =========================================================================== + +static void BM_Exp_Sphere(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere.exp(sphere_p, sphere_v)); + } +} +BENCHMARK(BM_Exp_Sphere); + +static void BM_Log_Sphere(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere.log(sphere_p, sphere_q)); + } +} +BENCHMARK(BM_Log_Sphere); + +static void BM_Distance_Sphere(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere.distance(sphere_p, sphere_q)); + } +} +BENCHMARK(BM_Distance_Sphere); + +static void BM_Inner_Sphere(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere.inner(sphere_p, sphere_u, sphere_v)); + } +} +BENCHMARK(BM_Inner_Sphere); + +static void BM_Norm_Sphere(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere.norm(sphere_p, sphere_v)); + } +} +BENCHMARK(BM_Norm_Sphere); + +static void BM_Geodesic_Sphere(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere.geodesic(sphere_p, sphere_q, 0.5)); + } +} +BENCHMARK(BM_Geodesic_Sphere); + +static void BM_RandomPoint_Sphere(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere.random_point()); + } +} +BENCHMARK(BM_RandomPoint_Sphere); + +// =========================================================================== +// Sphere (projection retraction) +// =========================================================================== + +static void BM_Exp_SphereProj(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere_proj.exp(sphere_p, sphere_v)); + } +} +BENCHMARK(BM_Exp_SphereProj); + +static void BM_Log_SphereProj(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere_proj.log(sphere_p, sphere_q)); + } +} +BENCHMARK(BM_Log_SphereProj); + +static void BM_Distance_SphereProj(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere_proj.distance(sphere_p, sphere_q)); + } +} +BENCHMARK(BM_Distance_SphereProj); + +// =========================================================================== +// Sphere (anisotropic: ConstantSPDMetric) +// =========================================================================== + +static void BM_Exp_SphereAniso(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere_aniso.exp(sphere_p, sphere_v)); + } +} +BENCHMARK(BM_Exp_SphereAniso); + +static void BM_Distance_SphereAniso(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere_aniso.distance(sphere_p, sphere_q)); + } +} +BENCHMARK(BM_Distance_SphereAniso); + +static void BM_Inner_SphereAniso(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere_aniso.inner(sphere_p, sphere_u, sphere_v)); + } +} +BENCHMARK(BM_Inner_SphereAniso); + +// =========================================================================== +// Euclidean R^2 +// =========================================================================== + +static void BM_Exp_Euclidean2(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(euclidean2.exp(euc2_p, euc2_v)); + } +} +BENCHMARK(BM_Exp_Euclidean2); + +static void BM_Log_Euclidean2(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(euclidean2.log(euc2_p, euc2_q)); + } +} +BENCHMARK(BM_Log_Euclidean2); + +static void BM_Distance_Euclidean2(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(euclidean2.distance(euc2_p, euc2_q)); + } +} +BENCHMARK(BM_Distance_Euclidean2); + +static void BM_Inner_Euclidean2(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(euclidean2.inner(euc2_p, euc2_u, euc2_v)); + } +} +BENCHMARK(BM_Inner_Euclidean2); + +// =========================================================================== +// Euclidean R^7 +// =========================================================================== + +static void BM_Exp_Euclidean7(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(euclidean7.exp(euc7_p, euc7_v)); + } +} +BENCHMARK(BM_Exp_Euclidean7); + +static void BM_Log_Euclidean7(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(euclidean7.log(euc7_p, euc7_q)); + } +} +BENCHMARK(BM_Log_Euclidean7); + +static void BM_Distance_Euclidean7(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(euclidean7.distance(euc7_p, euc7_q)); + } +} +BENCHMARK(BM_Distance_Euclidean7); + +static void BM_Inner_Euclidean7(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(euclidean7.inner(euc7_p, euc7_u, euc7_v)); + } +} +BENCHMARK(BM_Inner_Euclidean7); + +// =========================================================================== +// Torus T^2 +// =========================================================================== + +static void BM_Exp_Torus2(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(torus2.exp(tor2_p, tor2_v)); + } +} +BENCHMARK(BM_Exp_Torus2); + +static void BM_Log_Torus2(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(torus2.log(tor2_p, tor2_q)); + } +} +BENCHMARK(BM_Log_Torus2); + +static void BM_Distance_Torus2(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(torus2.distance(tor2_p, tor2_q)); + } +} +BENCHMARK(BM_Distance_Torus2); + +static void BM_Inner_Torus2(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(torus2.inner(tor2_p, tor2_u, tor2_v)); + } +} +BENCHMARK(BM_Inner_Torus2); + +static void BM_Geodesic_Torus2(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(torus2.geodesic(tor2_p, tor2_q, 0.5)); + } +} +BENCHMARK(BM_Geodesic_Torus2); + +static void BM_RandomPoint_Torus2(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(torus2.random_point()); + } +} +BENCHMARK(BM_RandomPoint_Torus2); + +// =========================================================================== +// Torus T^7 +// =========================================================================== + +static void BM_Exp_Torus7(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(torus7.exp(tor7_p, tor7_v)); + } +} +BENCHMARK(BM_Exp_Torus7); + +static void BM_Log_Torus7(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(torus7.log(tor7_p, tor7_q)); + } +} +BENCHMARK(BM_Log_Torus7); + +static void BM_Distance_Torus7(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(torus7.distance(tor7_p, tor7_q)); + } +} +BENCHMARK(BM_Distance_Torus7); + +static void BM_Inner_Torus7(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(torus7.inner(tor7_p, tor7_u, tor7_v)); + } +} +BENCHMARK(BM_Inner_Torus7); + +// =========================================================================== +// SE(2) — Exponential map +// =========================================================================== + +static void BM_Exp_SE2Exp(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(se2_exp.exp(se2_p, se2_v)); + } +} +BENCHMARK(BM_Exp_SE2Exp); + +static void BM_Log_SE2Exp(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(se2_exp.log(se2_p, se2_q)); + } +} +BENCHMARK(BM_Log_SE2Exp); + +static void BM_Distance_SE2Exp(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(se2_exp.distance(se2_p, se2_q)); + } +} +BENCHMARK(BM_Distance_SE2Exp); + +static void BM_Inner_SE2Exp(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(se2_exp.inner(se2_p, se2_u, se2_v)); + } +} +BENCHMARK(BM_Inner_SE2Exp); + +static void BM_Geodesic_SE2Exp(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(se2_exp.geodesic(se2_p, se2_q, 0.5)); + } +} +BENCHMARK(BM_Geodesic_SE2Exp); + +static void BM_RandomPoint_SE2Exp(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(se2_exp.random_point()); + } +} +BENCHMARK(BM_RandomPoint_SE2Exp); + +// =========================================================================== +// Dimension scaling: Torus (dynamic dimension) +// =========================================================================== + +static void BM_Distance_TorusDynamic(benchmark::State& state) { + const int d = static_cast(state.range(0)); + Torus torus(d); + + Eigen::VectorXd p = Eigen::VectorXd::Constant(d, 0.5); + Eigen::VectorXd q = Eigen::VectorXd::Constant(d, 4.0); + + for (auto _ : state) { + benchmark::DoNotOptimize(torus.distance(p, q)); + } +} +BENCHMARK(BM_Distance_TorusDynamic)->Arg(2)->Arg(5)->Arg(7)->Arg(10)->Arg(20)->Arg(50); + +static void BM_Exp_TorusDynamic(benchmark::State& state) { + const int d = static_cast(state.range(0)); + Torus torus(d); + + Eigen::VectorXd p = Eigen::VectorXd::Constant(d, 0.5); + Eigen::VectorXd v = Eigen::VectorXd::Constant(d, 0.3); + + for (auto _ : state) { + benchmark::DoNotOptimize(torus.exp(p, v)); + } +} +BENCHMARK(BM_Exp_TorusDynamic)->Arg(2)->Arg(5)->Arg(7)->Arg(10)->Arg(20)->Arg(50); + +static void BM_Log_TorusDynamic(benchmark::State& state) { + const int d = static_cast(state.range(0)); + Torus torus(d); + + Eigen::VectorXd p = Eigen::VectorXd::Constant(d, 0.5); + Eigen::VectorXd q = Eigen::VectorXd::Constant(d, 4.0); + + for (auto _ : state) { + benchmark::DoNotOptimize(torus.log(p, q)); + } +} +BENCHMARK(BM_Log_TorusDynamic)->Arg(2)->Arg(5)->Arg(7)->Arg(10)->Arg(20)->Arg(50); + +// =========================================================================== +// Dimension scaling: Euclidean (dynamic dimension) +// =========================================================================== + +static void BM_Distance_EuclideanDynamic(benchmark::State& state) { + const int d = static_cast(state.range(0)); + Euclidean euc(d); + + Eigen::VectorXd p = Eigen::VectorXd::Constant(d, 1.0); + Eigen::VectorXd q = Eigen::VectorXd::Constant(d, 4.0); + + for (auto _ : state) { + benchmark::DoNotOptimize(euc.distance(p, q)); + } +} +BENCHMARK(BM_Distance_EuclideanDynamic)->Arg(2)->Arg(5)->Arg(7)->Arg(10)->Arg(20)->Arg(50); + +static void BM_Exp_EuclideanDynamic(benchmark::State& state) { + const int d = static_cast(state.range(0)); + Euclidean euc(d); + + Eigen::VectorXd p = Eigen::VectorXd::Constant(d, 1.0); + Eigen::VectorXd v = Eigen::VectorXd::Constant(d, 0.3); + + for (auto _ : state) { + benchmark::DoNotOptimize(euc.exp(p, v)); + } +} +BENCHMARK(BM_Exp_EuclideanDynamic)->Arg(2)->Arg(5)->Arg(7)->Arg(10)->Arg(20)->Arg(50); diff --git a/benchmarks/bench_metrics.cpp b/benchmarks/bench_metrics.cpp new file mode 100644 index 0000000..01a7b36 --- /dev/null +++ b/benchmarks/bench_metrics.cpp @@ -0,0 +1,219 @@ +/// @file bench_metrics.cpp +/// @brief Benchmarks for metric inner product evaluation across all metric types. + +#include + +#include +#include + +#include "geodex/geodex.hpp" + +#include "planar_manipulator_metric.hpp" + +using namespace geodex; + +// --------------------------------------------------------------------------- +// Test data +// --------------------------------------------------------------------------- + +// 2D +static const Eigen::Vector2d q2(1.0, 1.5); +static const Eigen::Vector2d u2(0.3, 0.4); +static const Eigen::Vector2d v2(0.1, -0.2); + +// 3D +static const Eigen::Vector3d q3(1.0, 2.0, 0.5); +static const Eigen::Vector3d u3(0.3, 0.4, 0.1); +static const Eigen::Vector3d v3(0.1, -0.2, 0.5); + +// 7D +static const Eigen::Vector q7 = + (Eigen::Vector() << 1, 1.5, 2, 2.5, 3, 3.5, 4).finished(); +static const Eigen::Vector u7 = + (Eigen::Vector() << 0.5, 0.3, 0.1, 0.2, 0.4, 0.6, 0.8).finished(); +static const Eigen::Vector v7 = + (Eigen::Vector() << 0.1, -0.4, 0.2, -0.1, 0.3, 0.5, -0.2).finished(); + +// =========================================================================== +// Point-independent metrics +// =========================================================================== + +static void BM_Inner_EuclideanStandard2(benchmark::State& state) { + EuclideanStandardMetric<2> metric; + for (auto _ : state) { + benchmark::DoNotOptimize(metric.inner(q2, u2, v2)); + } +} +BENCHMARK(BM_Inner_EuclideanStandard2); + +static void BM_Inner_EuclideanStandard7(benchmark::State& state) { + EuclideanStandardMetric<7> metric; + for (auto _ : state) { + benchmark::DoNotOptimize(metric.inner(q7, u7, v7)); + } +} +BENCHMARK(BM_Inner_EuclideanStandard7); + +static void BM_Inner_TorusFlat2(benchmark::State& state) { + TorusFlatMetric<2> metric; + for (auto _ : state) { + benchmark::DoNotOptimize(metric.inner(q2, u2, v2)); + } +} +BENCHMARK(BM_Inner_TorusFlat2); + +static void BM_Inner_TorusFlat7(benchmark::State& state) { + TorusFlatMetric<7> metric; + for (auto _ : state) { + benchmark::DoNotOptimize(metric.inner(q7, u7, v7)); + } +} +BENCHMARK(BM_Inner_TorusFlat7); + +static void BM_Inner_ConstantSPD3(benchmark::State& state) { + Eigen::Matrix3d A; + A << 2.0, 0.5, 0.0, 0.5, 3.0, 0.1, 0.0, 0.1, 1.5; + ConstantSPDMetric<3> metric{A}; + for (auto _ : state) { + benchmark::DoNotOptimize(metric.inner(q3, u3, v3)); + } +} +BENCHMARK(BM_Inner_ConstantSPD3); + +static void BM_Inner_ConstantSPD7(benchmark::State& state) { + Eigen::Matrix A = Eigen::Matrix::Identity(); + A(0, 1) = 0.5; + A(1, 0) = 0.5; + A(2, 2) = 4.0; + ConstantSPDMetric<7> metric{A}; + for (auto _ : state) { + benchmark::DoNotOptimize(metric.inner(q7, u7, v7)); + } +} +BENCHMARK(BM_Inner_ConstantSPD7); + +static void BM_Inner_SE2LeftInvariant(benchmark::State& state) { + SE2LeftInvariantMetric metric(1.0, 100.0, 0.5); + for (auto _ : state) { + benchmark::DoNotOptimize(metric.inner(q3, u3, v3)); + } +} +BENCHMARK(BM_Inner_SE2LeftInvariant); + +// =========================================================================== +// Point-dependent metrics +// =========================================================================== + +static void BM_Inner_KineticEnergy_2Link(benchmark::State& state) { + PlanarManipulatorMetric arm; + auto ke = KineticEnergyMetric{[&](const Eigen::Vector2d& q) { return arm.mass_matrix(q); }}; + for (auto _ : state) { + benchmark::DoNotOptimize(ke.inner(q2, u2, v2)); + } +} +BENCHMARK(BM_Inner_KineticEnergy_2Link); + +static void BM_Inner_Jacobi_2Link(benchmark::State& state) { + PlanarManipulatorMetric arm; + auto jacobi = JacobiMetric{ + [&](const Eigen::Vector2d& q) { return arm.mass_matrix(q); }, + [](const Eigen::Vector2d& q) { + // Simple gravity potential: P(q) = -m*g*(l1*cos(q1) + l2*cos(q1+q2)) + return -9.81 * (std::cos(q[0]) + 0.5 * std::cos(q[0] + q[1])); + }, + 20.0 // total energy H + }; + for (auto _ : state) { + benchmark::DoNotOptimize(jacobi.inner(q2, u2, v2)); + } +} +BENCHMARK(BM_Inner_Jacobi_2Link); + +static void BM_Inner_Pullback_2Link(benchmark::State& state) { + // 2-link arm: 2D config space -> 2D task space (end-effector position) + auto pullback = PullbackMetric{ + [](const Eigen::Vector2d& q) -> Eigen::Matrix2d { + // Jacobian of 2-link arm end-effector + double c1 = std::cos(q[0]), s1 = std::sin(q[0]); + double c12 = std::cos(q[0] + q[1]), s12 = std::sin(q[0] + q[1]); + Eigen::Matrix2d J; + J(0, 0) = -s1 - 0.5 * s12; + J(0, 1) = -0.5 * s12; + J(1, 0) = c1 + 0.5 * c12; + J(1, 1) = 0.5 * c12; + return J; + }, + [](const Eigen::Vector2d& /*q*/) -> Eigen::Matrix2d { return Eigen::Matrix2d::Identity(); }, + 0.01 // regularization lambda + }; + for (auto _ : state) { + benchmark::DoNotOptimize(pullback.inner(q2, u2, v2)); + } +} +BENCHMARK(BM_Inner_Pullback_2Link); + +static void BM_Inner_Weighted_ConstantSPD3(benchmark::State& state) { + Eigen::Matrix3d A; + A << 2.0, 0.5, 0.0, 0.5, 3.0, 0.1, 0.0, 0.1, 1.5; + WeightedMetric weighted{ConstantSPDMetric<3>{A}, 2.5}; + for (auto _ : state) { + benchmark::DoNotOptimize(weighted.inner(q3, u3, v3)); + } +} +BENCHMARK(BM_Inner_Weighted_ConstantSPD3); + +// =========================================================================== +// ConfigurationSpace overhead: KE metric vs flat metric on Torus<2> +// =========================================================================== + +static void BM_Distance_Torus2_Flat(benchmark::State& state) { + Torus<2> torus; + Eigen::Vector2d p(0.5, 0.5); + Eigen::Vector2d q(2.5, 2.5); + for (auto _ : state) { + benchmark::DoNotOptimize(p.data()); + benchmark::DoNotOptimize(q.data()); + auto d = distance_midpoint(torus, p, q); + benchmark::DoNotOptimize(d); + } +} +BENCHMARK(BM_Distance_Torus2_Flat); + +static void BM_Distance_CSpace_Torus2_KE(benchmark::State& state) { + PlanarManipulatorMetric arm; + auto ke = KineticEnergyMetric{[&](const Eigen::Vector2d& q) { return arm.mass_matrix(q); }}; + ConfigurationSpace cspace{Torus<2>{}, std::move(ke)}; + + Eigen::Vector2d p(0.5, 0.5); + Eigen::Vector2d q(2.5, 2.5); + for (auto _ : state) { + benchmark::DoNotOptimize(p.data()); + benchmark::DoNotOptimize(q.data()); + auto d = distance_midpoint(cspace, p, q); + benchmark::DoNotOptimize(d); + } +} +BENCHMARK(BM_Distance_CSpace_Torus2_KE); + +// =========================================================================== +// Norm benchmarks (metric.norm includes sqrt overhead) +// =========================================================================== + +static void BM_Norm_ConstantSPD3(benchmark::State& state) { + Eigen::Matrix3d A; + A << 2.0, 0.5, 0.0, 0.5, 3.0, 0.1, 0.0, 0.1, 1.5; + ConstantSPDMetric<3> metric{A}; + for (auto _ : state) { + benchmark::DoNotOptimize(metric.norm(q3, u3)); + } +} +BENCHMARK(BM_Norm_ConstantSPD3); + +static void BM_Norm_KineticEnergy_2Link(benchmark::State& state) { + PlanarManipulatorMetric arm; + auto ke = KineticEnergyMetric{[&](const Eigen::Vector2d& q) { return arm.mass_matrix(q); }}; + for (auto _ : state) { + benchmark::DoNotOptimize(ke.norm(q2, u2)); + } +} +BENCHMARK(BM_Norm_KineticEnergy_2Link); diff --git a/benchmarks/bench_ompl_interpolation.cpp b/benchmarks/bench_ompl_interpolation.cpp new file mode 100644 index 0000000..e6af858 --- /dev/null +++ b/benchmarks/bench_ompl_interpolation.cpp @@ -0,0 +1,260 @@ +/// @file bench_ompl_interpolation.cpp +/// @brief Benchmarks for GeodexStateSpace interpolation with discrete geodesic caching. + +#include + +#include +#include +#include +#include +#include + +#include "geodex/integration/ompl/geodex_state_space.hpp" +#include "geodex/manifold/euclidean.hpp" +#include "geodex/manifold/se2.hpp" +#include "geodex/metrics/constant_spd.hpp" + +namespace ob = ompl::base; + +// --------------------------------------------------------------------------- +// Helpers +// --------------------------------------------------------------------------- + +static ob::RealVectorBounds makeSE2Bounds() { + ob::RealVectorBounds bounds(3); + bounds.setLow(0, 0.0); + bounds.setHigh(0, 10.0); + bounds.setLow(1, 0.0); + bounds.setHigh(1, 10.0); + bounds.setLow(2, -std::numbers::pi); + bounds.setHigh(2, std::numbers::pi); + return bounds; +} + +template +static void setStateValues(ob::State* s, double v0, double v1, double v2) { + auto* st = s->as(); + st->values[0] = v0; + st->values[1] = v1; + st->values[2] = v2; +} + +// --------------------------------------------------------------------------- +// BM_Interpolate_SE2_Identity: baseline, zero-overhead fast path +// --------------------------------------------------------------------------- + +static void BM_Interpolate_SE2_Identity(benchmark::State& state) { + using M = geodex::SE2<>; + using SS = geodex::integration::ompl::GeodexStateSpace; + using ST = geodex::integration::ompl::GeodexState; + + geodex::SE2LeftInvariantMetric metric{1.0, 1.0, 1.0}; + M manifold{metric}; + auto space = std::make_shared(manifold, makeSE2Bounds()); + space->setInterpolationMode(geodex::integration::ompl::InterpolationMode::RiemannianGeodesic); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + auto* result = space->allocState(); + setStateValues(s1, 2.0, 3.0, 0.5); + setStateValues(s2, 8.0, 7.0, -1.0); + + const int N = state.range(0); + for (auto _ : state) { + for (int j = 1; j <= N; ++j) { + space->interpolate(s1, s2, static_cast(j) / N, result); + } + benchmark::DoNotOptimize(result->as()->values[0]); + } + + space->freeState(result); + space->freeState(s1); + space->freeState(s2); +} +BENCHMARK(BM_Interpolate_SE2_Identity)->Arg(10)->Arg(50)->Arg(100); + +// --------------------------------------------------------------------------- +// BM_Interpolate_SE2_Anisotropic_CacheHot: amortized cost with cache +// --------------------------------------------------------------------------- + +static void BM_Interpolate_SE2_Anisotropic_CacheHot(benchmark::State& state) { + using M = geodex::SE2; + using SS = geodex::integration::ompl::GeodexStateSpace; + using ST = geodex::integration::ompl::GeodexState; + + geodex::SE2LeftInvariantMetric metric{1.0, 100.0, 0.5}; + M manifold{metric}; + auto space = std::make_shared(manifold, makeSE2Bounds()); + space->setInterpolationMode(geodex::integration::ompl::InterpolationMode::RiemannianGeodesic); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + auto* result = space->allocState(); + setStateValues(s1, 2.0, 3.0, 0.0); + setStateValues(s2, 8.0, 7.0, 1.0); + + const int N = state.range(0); + for (auto _ : state) { + // Same (s1,s2) pair → cache hit after first call + for (int j = 1; j <= N; ++j) { + space->interpolate(s1, s2, static_cast(j) / N, result); + } + benchmark::DoNotOptimize(result->as()->values[0]); + } + + space->freeState(result); + space->freeState(s1); + space->freeState(s2); +} +BENCHMARK(BM_Interpolate_SE2_Anisotropic_CacheHot)->Arg(10)->Arg(50)->Arg(100); + +// --------------------------------------------------------------------------- +// BM_Interpolate_SE2_Anisotropic_CacheCold: cache miss every iteration +// --------------------------------------------------------------------------- + +static void BM_Interpolate_SE2_Anisotropic_CacheCold(benchmark::State& state) { + using M = geodex::SE2; + using SS = geodex::integration::ompl::GeodexStateSpace; + using ST = geodex::integration::ompl::GeodexState; + + geodex::SE2LeftInvariantMetric metric{1.0, 100.0, 0.5}; + M manifold{metric}; + auto space = std::make_shared(manifold, makeSE2Bounds()); + space->setInterpolationMode(geodex::integration::ompl::InterpolationMode::RiemannianGeodesic); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + auto* result = space->allocState(); + setStateValues(s1, 2.0, 3.0, 0.0); + + int counter = 0; + for (auto _ : state) { + // Vary s2 to force cache miss every iteration + double offset = 0.01 * (counter++ % 100); + setStateValues(s2, 8.0 + offset, 7.0, 1.0); + space->interpolate(s1, s2, 0.5, result); + benchmark::DoNotOptimize(result->as()->values[0]); + } + + space->freeState(result); + space->freeState(s1); + space->freeState(s2); +} +BENCHMARK(BM_Interpolate_SE2_Anisotropic_CacheCold); + +// --------------------------------------------------------------------------- +// BM_Interpolate_Euclidean_Anisotropic_CacheHot +// --------------------------------------------------------------------------- + +static void BM_Interpolate_Euclidean_Anisotropic_CacheHot(benchmark::State& state) { + using M = geodex::Euclidean<2, geodex::ConstantSPDMetric<2>>; + using SS = geodex::integration::ompl::GeodexStateSpace; + using ST = geodex::integration::ompl::GeodexState; + + Eigen::Matrix2d A; + A << 4.0, 0.0, 0.0, 1.0; + geodex::ConstantSPDMetric<2> metric{A}; + M manifold{metric}; + + ob::RealVectorBounds bounds(2); + bounds.setLow(0.0); + bounds.setHigh(10.0); + auto space = std::make_shared(manifold, bounds); + space->setInterpolationMode(geodex::integration::ompl::InterpolationMode::RiemannianGeodesic); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + auto* result = space->allocState(); + s1->as()->values[0] = 1.0; + s1->as()->values[1] = 1.0; + s2->as()->values[0] = 9.0; + s2->as()->values[1] = 9.0; + + const int N = state.range(0); + for (auto _ : state) { + for (int j = 1; j <= N; ++j) { + space->interpolate(s1, s2, static_cast(j) / N, result); + } + benchmark::DoNotOptimize(result->as()->values[0]); + } + + space->freeState(result); + space->freeState(s1); + space->freeState(s2); +} +BENCHMARK(BM_Interpolate_Euclidean_Anisotropic_CacheHot)->Arg(10)->Arg(50)->Arg(100); + +// --------------------------------------------------------------------------- +// BM_MotionValidation_SE2_Anisotropic: full collision check cycle +// --------------------------------------------------------------------------- + +static void BM_MotionValidation_SE2_Anisotropic(benchmark::State& state) { + using M = geodex::SE2; + using SS = geodex::integration::ompl::GeodexStateSpace; + using ST = geodex::integration::ompl::GeodexState; + + geodex::SE2LeftInvariantMetric metric{1.0, 100.0, 0.5}; + M manifold{metric}; + auto space = std::make_shared(manifold, makeSE2Bounds()); + space->setCollisionResolution(0.1); + + const bool use_discrete = state.range(0); + space->setInterpolationMode(use_discrete + ? geodex::integration::ompl::InterpolationMode::RiemannianGeodesic + : geodex::integration::ompl::InterpolationMode::BaseGeodesic); + + auto si = std::make_shared(space); + si->setStateValidityChecker([](const ob::State*) { return true; }); + si->setup(); + + auto mv = std::make_shared(si); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + setStateValues(s1, 2.0, 3.0, 0.0); + setStateValues(s2, 8.0, 7.0, 1.0); + + for (auto _ : state) { + bool valid = mv->checkMotion(s1, s2); + benchmark::DoNotOptimize(valid); + } + + space->freeState(s1); + space->freeState(s2); +} +BENCHMARK(BM_MotionValidation_SE2_Anisotropic) + ->Arg(0) // discrete geodesic OFF + ->Arg(1); // discrete geodesic ON + +// --------------------------------------------------------------------------- +// BM_ValidSegmentCount: segment counting overhead +// --------------------------------------------------------------------------- + +static void BM_ValidSegmentCount_SE2(benchmark::State& state) { + using M = geodex::SE2; + using SS = geodex::integration::ompl::GeodexStateSpace; + using ST = geodex::integration::ompl::GeodexState; + + geodex::SE2LeftInvariantMetric metric{1.0, 100.0, 0.5}; + M manifold{metric}; + auto space = std::make_shared(manifold, makeSE2Bounds()); + space->setCollisionResolution(0.1); + + auto si = std::make_shared(space); + si->setStateValidityChecker([](const ob::State*) { return true; }); + si->setup(); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + setStateValues(s1, 2.0, 3.0, 0.0); + setStateValues(s2, 8.0, 7.0, 1.0); + + for (auto _ : state) { + unsigned int n = space->validSegmentCount(s1, s2); + benchmark::DoNotOptimize(n); + } + + space->freeState(s1); + space->freeState(s2); +} +BENCHMARK(BM_ValidSegmentCount_SE2); diff --git a/benchmarks/bench_retractions.cpp b/benchmarks/bench_retractions.cpp new file mode 100644 index 0000000..538b4ca --- /dev/null +++ b/benchmarks/bench_retractions.cpp @@ -0,0 +1,129 @@ +/// @file bench_retractions.cpp +/// @brief Benchmarks for retraction speed and accuracy comparison. + +#include + +#include +#include + +#include "geodex/geodex.hpp" + +using namespace geodex; + +// --------------------------------------------------------------------------- +// SE(2) test data +// --------------------------------------------------------------------------- + +static const Eigen::Vector3d se2_p(2.0, 3.0, 0.5); +static const Eigen::Vector3d se2_q(7.0, 5.0, 2.0); +static const Eigen::Vector3d se2_v(0.5, 0.3, 0.4); // moderate angle + +// Retraction instances +static SE2ExponentialMap se2_exp_map; +static SE2EulerRetraction se2_euler; + +// --------------------------------------------------------------------------- +// Sphere test data +// --------------------------------------------------------------------------- + +static const Eigen::Vector3d sph_p(0.0, 0.0, 1.0); // north pole +static const Eigen::Vector3d sph_v(0.3, 0.4, 0.0); // tangent at north pole +static const Eigen::Vector3d sph_q = Eigen::Vector3d(std::sin(1.0), 0.0, std::cos(1.0)); // theta=1 + +static SphereExponentialMap sphere_exp_map; +static SphereProjectionRetraction sphere_proj; + +// =========================================================================== +// SE(2) retract speed +// =========================================================================== + +static void BM_SE2_Retract_Exp(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(se2_exp_map.retract(se2_p, se2_v)); + } +} +BENCHMARK(BM_SE2_Retract_Exp); + +static void BM_SE2_Retract_Euler(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(se2_euler.retract(se2_p, se2_v)); + } +} +BENCHMARK(BM_SE2_Retract_Euler); + +// =========================================================================== +// SE(2) inverse_retract speed +// =========================================================================== + +static void BM_SE2_InvRetract_Exp(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(se2_exp_map.inverse_retract(se2_p, se2_q)); + } +} +BENCHMARK(BM_SE2_InvRetract_Exp); + +static void BM_SE2_InvRetract_Euler(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(se2_euler.inverse_retract(se2_p, se2_q)); + } +} +BENCHMARK(BM_SE2_InvRetract_Euler); + +// =========================================================================== +// Sphere retract speed +// =========================================================================== + +static void BM_Sphere_Retract_Exp(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere_exp_map.retract(sph_p, sph_v)); + } +} +BENCHMARK(BM_Sphere_Retract_Exp); + +static void BM_Sphere_Retract_Proj(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere_proj.retract(sph_p, sph_v)); + } +} +BENCHMARK(BM_Sphere_Retract_Proj); + +// =========================================================================== +// Sphere inverse_retract speed +// =========================================================================== + +static void BM_Sphere_InvRetract_Exp(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere_exp_map.inverse_retract(sph_p, sph_q)); + } +} +BENCHMARK(BM_Sphere_InvRetract_Exp); + +static void BM_Sphere_InvRetract_Proj(benchmark::State& state) { + for (auto _ : state) { + benchmark::DoNotOptimize(sphere_proj.inverse_retract(sph_p, sph_q)); + } +} +BENCHMARK(BM_Sphere_InvRetract_Proj); + +// =========================================================================== +// Sphere retraction accuracy +// =========================================================================== + +static void BM_Sphere_Accuracy_Proj(benchmark::State& state) { + const double magnitudes[] = {0.01, 0.1, 0.5, 1.0, 2.0}; + double max_error = 0.0; + + for (auto _ : state) { + max_error = 0.0; + for (double mag : magnitudes) { + Eigen::Vector3d v_scaled = sph_v.normalized() * mag; + auto ref = sphere_exp_map.retract(sph_p, v_scaled); + auto approx = sphere_proj.retract(sph_p, v_scaled); + double err = (ref - approx).norm(); + max_error = std::max(max_error, err); + } + benchmark::DoNotOptimize(max_error); + } + state.counters["max_error"] = max_error; +} +BENCHMARK(BM_Sphere_Accuracy_Proj); diff --git a/cmake/geodexConfig.cmake.in b/cmake/geodexConfig.cmake.in new file mode 100644 index 0000000..6b5a092 --- /dev/null +++ b/cmake/geodexConfig.cmake.in @@ -0,0 +1,5 @@ +@PACKAGE_INIT@ + +include("${CMAKE_CURRENT_LIST_DIR}/geodexTargets.cmake") + +check_required_components(geodex) diff --git a/docs/_static/custom.css b/docs/_static/custom.css index fa41f6e..8555ce5 100644 --- a/docs/_static/custom.css +++ b/docs/_static/custom.css @@ -1,3 +1,75 @@ +/* Make Sphinx graphviz SVGs scale to the content column instead of rendering at + their intrinsic pt size (which looks tiny in a wide RTD content area and leaves + white space on the right). The Sphinx graphviz extension wraps each diagram in +
...svg...
. */ +.graphviz { + text-align: center; + margin: 1em 0; +} +.graphviz object, +.graphviz svg { + max-width: 100%; + height: auto; + display: block; + margin: 0 auto; +} + +/* Mermaid: conf.py sets `useMaxWidth: false` so every diagram renders at its + intrinsic viewBox width (1 viewBox unit = 1 CSS pixel) and per-character + pixel size is identical across diagrams. This block just centers them and + strips the default
 code-block frame, plus caps absurdly wide diagrams
+   so they don't break out of the content column. */
+pre.mermaid {
+    text-align: center;
+    background: transparent !important;
+    border: none !important;
+    padding: 0 !important;
+    margin: 1em 0 !important;
+}
+pre.mermaid > svg,
+.mermaid > svg {
+    max-width: 100% !important;
+    height: auto !important;
+    display: block;
+    margin: 0 auto;
+}
+
+/* Tables: wrap long cell text instead of triggering the RTD theme's
+   horizontal scroll wrapper. Forces a fixed layout so the :widths:
+   directive in list-table actually pins the column proportions, and
+   allows long words to break so prose cells wrap cleanly. */
+.rst-content table.docutils {
+    width: 100%;
+    table-layout: fixed;
+}
+.rst-content table.docutils td,
+.rst-content table.docutils th {
+    white-space: normal !important;
+    word-wrap: break-word;
+    overflow-wrap: break-word;
+}
+.wy-table-responsive {
+    overflow: visible;
+}
+
+/* Opt-in horizontal scroll for tables with `:class: scroll-table`. The
+   table becomes its own scroll container (via display: block), cells keep
+   their intrinsic width, and identifiers don't break. Use this for tables
+   whose cells contain class names or function calls that must stay on one
+   line. */
+.rst-content table.docutils.scroll-table {
+    display: block;
+    overflow-x: auto;
+    width: 100%;
+    table-layout: auto;
+}
+.rst-content table.docutils.scroll-table td,
+.rst-content table.docutils.scroll-table th {
+    white-space: nowrap !important;
+    word-wrap: normal;
+    overflow-wrap: normal;
+}
+
 /* Default for Desktop: 50% width */
 .responsive-img {
     width: 40%;
@@ -10,3 +82,119 @@
         width: 90%;
     }
 }
+
+/* -------------------------------------------------------------------------
+   Landing page (docs/index.rst)
+   Hero image + 2x2 quick-links card grid. Colors match the geodex blue
+   palette used by mermaid/graphviz diagrams (#e7f0fa / #2980b9).
+   ------------------------------------------------------------------------- */
+
+.landing-hero {
+    text-align: center;
+    margin: 1.5em 0 2em 0;
+}
+.landing-hero img {
+    max-width: 85%;
+    height: auto;
+    border-radius: 6px;
+    box-shadow: 0 2px 14px rgba(0, 0, 0, 0.08);
+}
+
+.landing-grid {
+    display: grid;
+    grid-template-columns: repeat(2, 1fr);
+    gap: 1.25em;
+    margin: 2em 0 1em 0;
+}
+@media screen and (max-width: 768px) {
+    .landing-grid {
+        grid-template-columns: 1fr;
+    }
+}
+
+.landing-card {
+    display: flex;
+    flex-direction: column;
+    border: 1px solid #dfe4ea;
+    border-radius: 8px;
+    overflow: hidden;
+    text-decoration: none !important;
+    color: inherit;
+    background: #fff;
+    transition: transform 0.12s ease, box-shadow 0.12s ease, border-color 0.12s ease;
+}
+.landing-card:hover {
+    transform: translateY(-2px);
+    box-shadow: 0 6px 18px rgba(0, 0, 0, 0.08);
+    border-color: #2980b9;
+}
+
+.landing-card-thumb {
+    background: #f7fbfe;
+    border-bottom: 1px solid #e7f0fa;
+    display: flex;
+    align-items: center;
+    justify-content: center;
+    height: 190px;
+    overflow: hidden;
+    padding: 0.9em;
+    box-sizing: border-box;
+}
+.landing-card-thumb img {
+    max-width: 100%;
+    max-height: 100%;
+    height: auto;
+    width: auto;
+    object-fit: contain;
+}
+
+.landing-card-thumb-text {
+    background: #f4f7fa;
+}
+.landing-card-thumb-text pre {
+    background: transparent;
+    border: none;
+    margin: 0;
+    padding: 0;
+    font-size: 0.82em;
+    line-height: 1.55;
+    color: #2c3e50;
+    white-space: pre;
+    text-align: left;
+}
+
+.landing-card-thumb-placeholder {
+    background:
+        repeating-linear-gradient(
+            45deg,
+            #f7fbfe,
+            #f7fbfe 10px,
+            #eef4fb 10px,
+            #eef4fb 20px
+        );
+    color: #6c7a89;
+    font-size: 0.9em;
+    line-height: 1.5;
+    text-align: center;
+    padding: 1em;
+}
+.landing-card-thumb-placeholder em {
+    color: #2980b9;
+    font-style: normal;
+}
+
+.landing-card-body {
+    padding: 0.9em 1.15em 1.05em 1.15em;
+}
+.landing-card-body h3 {
+    margin: 0 0 0.35em 0;
+    font-size: 1.08em;
+    color: #2980b9;
+    font-weight: 600;
+}
+.landing-card-body p {
+    margin: 0;
+    color: #444;
+    font-size: 0.93em;
+    line-height: 1.5;
+}
\ No newline at end of file
diff --git a/docs/tutorials/figs/manifold.svg b/docs/_static/landing/manifold.svg
similarity index 100%
rename from docs/tutorials/figs/manifold.svg
rename to docs/_static/landing/manifold.svg
diff --git a/docs/_static/landing/minimum_energy_arm.gif b/docs/_static/landing/minimum_energy_arm.gif
new file mode 100644
index 0000000..e7b6176
Binary files /dev/null and b/docs/_static/landing/minimum_energy_arm.gif differ
diff --git a/docs/_static/landing/se2_parking_footprints.gif b/docs/_static/landing/se2_parking_footprints.gif
new file mode 100644
index 0000000..c99d84a
Binary files /dev/null and b/docs/_static/landing/se2_parking_footprints.gif differ
diff --git a/docs/_static/landing/se2_willow_corridor.svg b/docs/_static/landing/se2_willow_corridor.svg
new file mode 100644
index 0000000..de1061e
--- /dev/null
+++ b/docs/_static/landing/se2_willow_corridor.svg
@@ -0,0 +1,1393 @@
+
+
+
+ 
+  
+   
+    
+    2026-04-20T18:19:20.125571
+    image/svg+xml
+    
+     
+      Matplotlib v3.10.8, https://matplotlib.org/
+     
+    
+   
+  
+ 
+ 
+  
+ 
+ 
+  
+   
+  
+  
+   
+    
+   
+   
+    
+   
+   
+    
+     
+      
+       
+      
+      
+       
+      
+     
+     
+      
+      
+       
+        
+       
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+        
+       
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+        
+       
+       
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+       
+      
+     
+    
+    
+     
+     
+      
+       
+       
+       
+       
+       
+      
+      
+      
+      
+      
+      
+     
+    
+   
+   
+    
+     
+      
+       
+      
+      
+       
+      
+     
+     
+      
+      
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+        
+       
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+        
+       
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+        
+       
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+        
+       
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+       
+      
+     
+    
+    
+     
+     
+      
+       
+      
+      
+      
+      
+      
+      
+     
+    
+   
+   
+    
+   
+   
+    
+   
+   
+    
+   
+   
+    
+   
+   
+    
+    
+     
+      
+      
+      
+      
+      
+      
+      
+      
+      
+      
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+    
+   
+  
+  
+   
+    
+   
+   
+    
+   
+   
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+       
+      
+     
+    
+    
+     
+     
+      
+      
+      
+      
+      
+     
+    
+   
+   
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+       
+      
+     
+    
+    
+     
+     
+      
+      
+      
+      
+      
+     
+    
+   
+   
+    
+   
+   
+    
+   
+   
+    
+   
+   
+    
+   
+   
+    
+    
+     
+      
+      
+      
+      
+      
+      
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+     
+    
+   
+  
+  
+  
+   
+    
+   
+   
+   
+   
+    
+     
+      
+       
+      
+      
+       
+      
+     
+     
+      
+      
+       
+        
+       
+       
+       
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+       
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+       
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+       
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+       
+       
+      
+     
+    
+    
+     
+      
+       
+      
+     
+     
+      
+      
+       
+        
+       
+       
+       
+       
+      
+     
+    
+    
+     
+     
+      
+      
+      
+      
+      
+      
+      
+      
+      
+      
+      
+      
+     
+    
+   
+   
+   
+    
+   
+  
+ 
+ 
+  
+   
+  
+  
+   
+  
+ 
+
diff --git a/docs/_static/mathjax/fonts/termes/chtml.js b/docs/_static/mathjax/fonts/termes/chtml.js
new file mode 100644
index 0000000..e5ab7da
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml.js
@@ -0,0 +1 @@
+(()=>{"use strict";var s={d:(t,i)=>{for(var r in i)s.o(i,r)&&!s.o(t,r)&&Object.defineProperty(t,r,{enumerable:!0,get:i[r]})}};s.g=function(){if("object"==typeof globalThis)return globalThis;try{return this||new Function("return this")()}catch(s){if("object"==typeof window)return window}}(),s.o=(s,t)=>Object.prototype.hasOwnProperty.call(s,t),s.r=s=>{"undefined"!=typeof Symbol&&Symbol.toStringTag&&Object.defineProperty(s,Symbol.toStringTag,{value:"Module"}),Object.defineProperty(s,"__esModule",{value:!0})};var t={};s.r(t),s.d(t,{MathJaxTermesFont:()=>m});const i=("undefined"!=typeof window?window:s.g).MathJax._.components.global,r=(i.GLOBAL,i.isObject,i.combineConfig,i.combineDefaults),e=i.combineWithMathJax,c=(i.MathJax,MathJax._.output.chtml.FontData),k=c.ChtmlFontData,a=(c.AddCSS,MathJax._.output.common.FontData),f=(a.NOSTRETCH,a.mergeOptions,a.FontData);const h=MathJax._.output.common.Direction,o=(h.DIRECTION,h.V),d=h.H,n={40:{dir:o,sizes:[.817,.977,1.169,1.399,1.675,2.007,2.405],stretch:[9115,9116,9117],HDW:[.658,.158,.624]},41:{dir:o,sizes:[.817,.977,1.169,1.399,1.675,2.007,2.405],stretch:[9118,9119,9120],HDW:[.658,.158,.624]},45:{c:8722,dir:d,stretch:[0,8722],HDW:[.5,0,.66],ext:.16,hd:[.5,0]},47:{dir:o,sizes:[.801,1.049,1.373,1.799,2.357,3.087,4.045]},61:{dir:d,stretch:[0,61],HDW:[.372,-.128,.66],ext:.16,hd:[.372,-.128]},91:{dir:o,sizes:[.837,.999,1.191,1.423,1.699,2.033,2.433],stretch:[9121,9122,9123],HDW:[.668,.168,.491]},92:{dir:o,sizes:[.801,1.049,1.373,1.799,2.357,3.087,4.045]},93:{dir:o,sizes:[.837,.999,1.191,1.423,1.699,2.033,2.433],stretch:[9124,9125,9126],HDW:[.668,.168,.491]},94:{c:770,dir:d,sizes:[.342,.608,.727,.87,1.041,1.249,1.496]},95:{c:8211,dir:d,sizes:[.5],stretch:[0,8211],HDW:[.25,-.201,.5],hd:[.25,-.201]},123:{dir:o,sizes:[.821,.981,1.173,1.403,1.679,2.011,2.409],stretch:[9127,123,9129,9128],stretchv:[0,1,0,0],HDW:[.66,.16,.547]},124:{dir:o,sizes:[.801,.961,1.153,1.383,1.659,1.991,2.389],schar:[124,8739],stretch:[0,8739],HDW:[.65,.15,.204]},125:{dir:o,sizes:[.821,.981,1.173,1.403,1.679,2.011,2.409],stretch:[9131,123,9133,9132],stretchv:[0,1,0,0],HDW:[.66,.16,.547]},126:{c:771,dir:d,sizes:[.334,.601,.72,.863,1.037,1.241,1.491]},175:{c:773,dir:d,sizes:[.333,.5],stretch:[0,773],stretchv:[0,1],HDW:[.632,-.588,0],hd:[.632,-.588]},710:{c:770,dir:d,sizes:[.342,.608,.727,.87,1.041,1.249,1.496]},711:{c:780,dir:d,sizes:[.342,.608,.727,.87,1.041,1.249,1.496]},713:{c:773,dir:d,sizes:[.333,.5],stretch:[0,773],stretchv:[0,1],HDW:[.632,-.588,0],hd:[.632,-.588]},728:{c:774,dir:d,sizes:[.35,.62,.74,.885,1.058,1.266,1.515]},732:{c:771,dir:d,sizes:[.334,.601,.72,.863,1.037,1.241,1.491]},770:{dir:d,sizes:[.342,.608,.727,.87,1.041,1.249,1.496]},771:{dir:d,sizes:[.334,.601,.72,.863,1.037,1.241,1.491]},773:{dir:d,sizes:[.333,.5],stretch:[0,773],stretchv:[0,1],HDW:[.632,-.588,0],hd:[.632,-.588]},774:{dir:d,sizes:[.35,.62,.74,.885,1.058,1.266,1.515]},780:{dir:d,sizes:[.342,.608,.727,.87,1.041,1.249,1.496]},8211:{dir:d,sizes:[.5],stretch:[0,8211],HDW:[.25,-.201,.5],hd:[.25,-.201]},8212:{dir:d,sizes:[1],stretch:[0,8212],HDW:[.25,-.201,1],hd:[.25,-.201]},8213:{dir:d,stretch:[0,8213],HDW:[.276,-.224,1.16],ext:.16,hd:[.276,-.224]},8214:{dir:o,sizes:[.801,.961,1.153,1.383,1.659,1.991,2.389],schar:[8214,8741],stretch:[0,8214],HDW:[.65,.15,.348]},8254:{c:175,dir:d,sizes:[.333,.5],stretch:[0,773],stretchv:[0,1],HDW:[.632,-.588,0],hd:[.632,-.588]},8260:{dir:o,sizes:[.801,1.049,1.373,1.799,2.357,3.087,4.045]},8400:{dir:d,sizes:[.312,.598],stretch:[8400,8400],stretchv:[2,1],HDW:[.71,-.6,0],hd:[.644,-.6]},8401:{dir:d,sizes:[.312,.598],stretch:[0,8400,8401],stretchv:[0,1,3],HDW:[.71,-.6,0],hd:[.644,-.6]},8406:{dir:d,sizes:[.322,.607],stretch:[8406,8400],stretchv:[2,1],HDW:[.71,-.534,0],hd:[.644,-.6]},8407:{dir:d,sizes:[.322,.607],stretch:[0,8400,8407],stretchv:[0,1,3],HDW:[.71,-.534,0],hd:[.644,-.6]},8417:{dir:d,sizes:[.396,.68],stretch:[8406,8400,8407],stretchv:[2,1,3],HDW:[.71,-.534,0],hd:[.644,-.6]},8428:{dir:d,sizes:[.312,.598],stretch:[0,845,8428],stretchv:[0,1,3],HDW:[-.15,.26,0],hd:[-.15,.194]},8429:{dir:d,sizes:[.312,.598],stretch:[8429,845],stretchv:[2,1],HDW:[-.15,.26,0],hd:[-.15,.194]},8430:{dir:d,sizes:[.322,.607],stretch:[8430,845],stretchv:[2,1],HDW:[-.084,.26,0],hd:[-.15,.194]},8431:{dir:d,sizes:[.322,.607],stretch:[0,845,8431],stretchv:[0,1,3],HDW:[-.084,.26,0],hd:[-.15,.194]},8592:{dir:d,sizes:[.85,1.17],variants:[0,0],schar:[8592,10229],stretch:[8592,8592],stretchv:[2,1],HDW:[.43,-.07,.85],hd:[.276,-.224]},8593:{dir:o,sizes:[.691,1.011],variants:[0,2],stretch:[8593,8593],stretchv:[2,1],HDW:[.6,.09,.52]},8594:{dir:d,sizes:[.85,1.17],variants:[0,0],schar:[8594,10230],stretch:[0,8592,8594],stretchv:[0,1,3],HDW:[.43,-.07,.85],hd:[.276,-.224]},8595:{dir:o,sizes:[.691,1.011],variants:[0,2],stretch:[0,8593,8595],stretchv:[0,1,3],HDW:[.59,.1,.52]},8596:{dir:d,sizes:[1.04,1.36],variants:[0,0],schar:[8596,10231],stretch:[8592,8592,8594],stretchv:[2,1,3],HDW:[.43,-.07,1.04],hd:[.276,-.224]},8597:{dir:o,sizes:[.881,1.201],variants:[0,2],stretch:[8593,8593,8595],stretchv:[2,1,3],HDW:[.69,.19,.52]},8602:{dir:d,sizes:[.85,1.17],variants:[0,2],stretch:[8602,8592,0,8602],stretchv:[2,1,0,1],HDW:[.43,-.07,.85],hd:[.276,-.224]},8603:{dir:d,sizes:[.85,1.17],variants:[0,2],stretch:[0,8592,8603,8602],stretchv:[0,1,3,1],HDW:[.43,-.07,.85],hd:[.276,-.224]},8606:{dir:d,sizes:[1.03,1.35],variants:[0,2],stretch:[8606,8592],stretchv:[2,1],HDW:[.43,-.07,1.03],hd:[.276,-.224]},8608:{dir:d,sizes:[1.03,1.35],variants:[0,2],stretch:[0,8592,8608],stretchv:[0,1,3],HDW:[.43,-.07,1.03],hd:[.276,-.224]},8610:{dir:d,sizes:[1.04,1.36],variants:[0,2],stretch:[8592,8592,8610],stretchv:[2,1,3],HDW:[.43,-.07,1.04],hd:[.276,-.224]},8611:{dir:d,sizes:[1.04,1.36],variants:[0,2],stretch:[8611,8592,8594],stretchv:[2,1,3],HDW:[.43,-.07,1.04],hd:[.276,-.224]},8612:{dir:d,sizes:[.85,1.17],variants:[0,0],schar:[8612,10235],stretch:[8592,8592,8612],stretchv:[2,1,3],HDW:[.43,-.07,.85],hd:[.276,-.224]},8614:{dir:d,sizes:[.85,1.17],variants:[0,0],schar:[8614,10236],stretch:[8614,8592,8594],stretchv:[2,1,3],HDW:[.43,-.07,.85],hd:[.276,-.224]},8617:{dir:d,sizes:[.876,1.196],variants:[0,2],stretch:[8592,8617,8617],stretchv:[2,1,3],HDW:[.508,-.07,.876],hd:[.276,-.224]},8618:{dir:d,sizes:[.876,1.196],variants:[0,2],stretch:[8618,8617,8594],stretchv:[2,1,3],HDW:[.508,-.07,.876],hd:[.276,-.224]},8619:{dir:d,sizes:[.876,1.196],variants:[0,2],stretch:[8592,8617,8619],stretchv:[2,1,3],HDW:[.508,-.018,.876],hd:[.276,-.224]},8620:{dir:d,sizes:[.876,1.196],variants:[0,2],stretch:[8620,8617,8594],stretchv:[2,1,3],HDW:[.508,-.018,.876],hd:[.276,-.224]},8622:{dir:d,sizes:[1.04,1.36],variants:[0,2],stretch:[8602,8592,8603,8602],stretchv:[2,1,3,1],HDW:[.43,-.07,1.04],hd:[.276,-.224]},8636:{dir:d,sizes:[.84,1.16],variants:[0,2],stretch:[8636,8636],stretchv:[2,1],HDW:[.43,-.224,.84],hd:[.276,-.224]},8637:{dir:d,sizes:[.84,1.16],variants:[0,2],stretch:[8637,8636],stretchv:[2,1],HDW:[.276,-.07,.84],hd:[.276,-.224]},8638:{dir:o,sizes:[.681,1.001],variants:[0,2],stretch:[8638,8638],stretchv:[2,1],HDW:[.59,.09,.366]},8639:{dir:o,sizes:[.681,1.001],variants:[0,2],stretch:[8639,8639],stretchv:[2,1],HDW:[.59,.09,.366]},8640:{dir:d,sizes:[.84,1.16],variants:[0,2],stretch:[0,8636,8640],stretchv:[0,1,3],HDW:[.43,-.224,.84],hd:[.276,-.224]},8641:{dir:d,sizes:[.84,1.16],variants:[0,2],stretch:[0,8636,8641],stretchv:[0,1,3],HDW:[.276,-.07,.84],hd:[.276,-.224]},8642:{dir:o,sizes:[.681,1.001],variants:[0,2],stretch:[0,8638,8642],stretchv:[0,1,3],HDW:[.59,.09,.366]},8643:{dir:o,sizes:[.681,1.001],variants:[0,2],stretch:[0,8639,8643],stretchv:[0,1,3],HDW:[.59,.09,.366]},8644:{dir:d,sizes:[.86,1.18],variants:[0,2],stretch:[8644,8644,8644],stretchv:[2,1,3],HDW:[.63,.13,.86],hd:[.476,-.024]},8645:{dir:o,sizes:[.701,1.021],variants:[0,2],stretch:[8645,8645,8645],stretchv:[2,1,3],HDW:[.6,.1,.92]},8646:{dir:d,sizes:[.86,1.18],variants:[0,2],stretch:[8646,8644,8646],stretchv:[2,1,3],HDW:[.63,.13,.86],hd:[.476,-.024]},8647:{dir:d,sizes:[.85,1.17],variants:[0,2],stretch:[8647,8644],stretchv:[2,1],HDW:[.63,.13,.85],hd:[.476,-.024]},8648:{dir:o,sizes:[.691,1.011],variants:[0,2],stretch:[8648,8645],stretchv:[2,1],HDW:[.6,.09,.92]},8649:{dir:d,sizes:[.85,1.17],variants:[0,2],stretch:[0,8644,8649],stretchv:[0,1,3],HDW:[.63,.13,.85],hd:[.476,-.024]},8650:{dir:o,sizes:[.691,1.011],variants:[0,2],stretch:[0,8645,8650],stretchv:[0,1,3],HDW:[.59,.1,.92]},8651:{dir:d,sizes:[.84,1.16],variants:[0,2],stretch:[8651,8651,8651],stretchv:[2,1,3],HDW:[.526,.026,.84],hd:[.372,-.128]},8652:{dir:d,sizes:[.84,1.16],variants:[0,2],stretch:[8652,8651,8652],stretchv:[2,1,3],HDW:[.526,.026,.84],hd:[.372,-.128]},8653:{dir:d,sizes:[.85,1.17],variants:[0,2],stretch:[8653,8654,0,8653],stretchv:[2,1,0,1],HDW:[.5,0,.85],hd:[.352,-.148]},8654:{dir:d,sizes:[1.04,1.36],variants:[0,2],stretch:[8656,8654,8658,8653],stretchv:[2,1,3,1],HDW:[.5,0,1.04],hd:[.352,-.148]},8655:{dir:d,sizes:[.85,1.17],variants:[0,2],stretch:[0,8654,8658,8653],stretchv:[0,1,3,1],HDW:[.5,0,.85],hd:[.352,-.148]},8656:{dir:d,sizes:[.85,1.17],variants:[0,0],schar:[8656,10232],stretch:[8656,8656],stretchv:[2,1],HDW:[.47,-.03,.85],hd:[.352,-.148]},8657:{dir:o,sizes:[.691,1.011],variants:[0,2],stretch:[8657,8657],stretchv:[2,1],HDW:[.6,.09,.6]},8658:{dir:d,sizes:[.85,1.17],variants:[0,0],schar:[8658,10233],stretch:[0,8656,8658],stretchv:[0,1,3],HDW:[.47,-.03,.85],hd:[.352,-.148]},8659:{dir:o,sizes:[.691,1.011],variants:[0,2],stretch:[0,8657,8659],stretchv:[0,1,3],HDW:[.59,.1,.6]},8660:{dir:d,sizes:[1.04,1.36],variants:[0,0],schar:[8660,10234],stretch:[8656,8656,8658],stretchv:[2,1,3],HDW:[.47,-.03,1.04],hd:[.352,-.148]},8661:{dir:o,sizes:[.881,1.201],variants:[0,2],stretch:[8657,8657,8659],stretchv:[2,1,3],HDW:[.69,.19,.6]},8666:{dir:d,sizes:[1.03,1.35],variants:[0,2],stretch:[8666,8666],stretchv:[2,1],HDW:[.572,.072,1.03],hd:[.428,-.072]},8667:{dir:d,sizes:[1.03,1.35],variants:[0,2],stretch:[0,8666,8667],stretchv:[0,1,3],HDW:[.572,.072,1.03],hd:[.428,-.072]},8693:{dir:o,sizes:[.701,1.021],variants:[0,2],stretch:[8693,8645,8693],stretchv:[2,1,3],HDW:[.6,.1,.92]},8694:{dir:d,sizes:[.85,1.17],variants:[0,2],stretch:[0,8694,8694],stretchv:[0,1,3],HDW:[.83,.33,.85],hd:[.676,.176]},8722:{dir:d,stretch:[0,8722],HDW:[.5,0,.66],ext:.16,hd:[.5,0]},8725:{c:47,dir:o,sizes:[.801,1.049,1.373,1.799,2.357,3.087,4.045]},8730:{dir:o,sizes:[.707,1.091,1.475,1.859,2.243,2.627,3.011],stretch:[8730,8730,9143],stretchv:[2,1,0],HDW:[.616,.09,.674],fullExt:[.77,1.327]},8739:{dir:o,sizes:[.801,.961,1.153,1.383,1.659,1.991,2.389],stretch:[0,8739],HDW:[.65,.15,.204]},8741:{dir:o,sizes:[.801,.961,1.153,1.383,1.659,1.991,2.389],stretch:[0,8741],HDW:[.65,.15,.348]},8801:{dir:d,stretch:[0,8801],HDW:[.468,-.032,.66],ext:.16,hd:[.468,-.032]},8803:{dir:d,stretch:[0,8803],HDW:[.564,.064,.66],ext:.16,hd:[.564,.064]},8968:{dir:o,sizes:[.819,.98,1.172,1.403,1.679,2.012,2.411],stretch:[9121,9122],HDW:[.668,.15,.491]},8969:{dir:o,sizes:[.819,.98,1.172,1.403,1.679,2.012,2.411],stretch:[9124,9125],HDW:[.668,.15,.491]},8970:{dir:o,sizes:[.819,.98,1.172,1.403,1.679,2.012,2.411],stretch:[0,9122,9123],HDW:[.65,.168,.491]},8971:{dir:o,sizes:[.819,.98,1.172,1.403,1.679,2.012,2.411],stretch:[0,9125,9126],HDW:[.65,.168,.491]},8978:{c:9180,dir:d,sizes:[.514,1.014,1.514,2.014,2.514,3.014,3.514],stretch:[9180,9180,9180],stretchv:[2,1,3],HDW:[.758,-.541,.514],hd:[.758,-.674]},8994:{c:9180,dir:d,sizes:[.514,1.014,1.514,2.014,2.514,3.014,3.514],stretch:[9180,9180,9180],stretchv:[2,1,3],HDW:[.758,-.541,.514],hd:[.758,-.674]},8995:{c:9181,dir:d,sizes:[.514,1.014,1.514,2.014,2.514,3.014,3.514],stretch:[9181,9181,9181],stretchv:[2,1,3],HDW:[-.091,.308,.514],hd:[-.224,.308]},9001:{dir:o,sizes:[.813,1.061,1.383,1.807,2.365,3.093,4.049],schar:[9001,10216]},9002:{dir:o,sizes:[.813,1.061,1.383,1.807,2.365,3.093,4.049],schar:[9002,10217]},9130:{dir:o,sizes:[.596],stretch:[0,9130,0],HDW:[.596,0,.547]},9135:{c:8211,dir:d,sizes:[.5],stretch:[0,8211],HDW:[.25,-.201,.5],hd:[.25,-.201]},9136:{dir:o,sizes:[1.194],stretch:[9127,9130,9133],HDW:[.694,.5,.547]},9137:{dir:o,sizes:[1.194],stretch:[9131,9130,9129],HDW:[.694,.5,.547]},9140:{dir:d,sizes:[.375,.75,1.125,1.5,1.875,2.25,2.625],stretch:[9140,9140,9140],stretchv:[2,1,3],HDW:[.758,-.548,.375],hd:[.758,-.674]},9141:{dir:d,sizes:[.375,.75,1.125,1.5,1.875,2.25,2.625],stretch:[9141,9141,9141],stretchv:[2,1,3],HDW:[-.098,.308,.375],hd:[-.224,.308]},9168:{dir:o,sizes:[.527],stretch:[0,8739],HDW:[.527,0,.204]},9180:{dir:d,sizes:[.514,1.014,1.514,2.014,2.514,3.014,3.514],stretch:[9180,9180,9180],stretchv:[2,1,3],HDW:[.758,-.541,.514],hd:[.758,-.674]},9181:{dir:d,sizes:[.514,1.014,1.514,2.014,2.514,3.014,3.514],stretch:[9181,9181,9181],stretchv:[2,1,3],HDW:[-.091,.308,.514],hd:[-.224,.308]},9182:{dir:d,sizes:[.52,1.019,1.519,2.019,2.519,3.019,3.519],stretch:[9182,175,9182,9182],stretchv:[2,1,3,1],HDW:[.792,-.525,.52],hd:[.702,-.618]},9183:{dir:d,sizes:[.52,1.019,1.519,2.019,2.519,3.019,3.519],stretch:[9183,95,9183,9183],stretchv:[2,1,3,1],HDW:[-.075,.341,.52],hd:[-.168,.252]},9184:{dir:d,sizes:[.562,1.066,1.568,2.072,2.576,3.08,3.584],stretch:[9184,9184,9184],stretchv:[2,1,3],HDW:[.748,-.538,.562],hd:[.748,-.664]},9185:{dir:d,sizes:[.562,1.066,1.568,2.072,2.576,3.08,3.584],stretch:[9185,9185,9185],stretchv:[2,1,3],HDW:[-.088,.298,.562],hd:[-.214,.298]},9472:{c:8211,dir:d,sizes:[.5],stretch:[0,8211],HDW:[.25,-.201,.5],hd:[.25,-.201]},10072:{c:8739,dir:o,sizes:[.801,.961,1.153,1.383,1.659,1.991,2.389],stretch:[0,8739],HDW:[.65,.15,.204]},10214:{dir:o,sizes:[.837,.999,1.191,1.423,1.699,2.033,2.433],stretch:[10214,10214,10214],stretchv:[2,1,3],HDW:[.668,.168,.495]},10215:{dir:o,sizes:[.837,.999,1.191,1.423,1.699,2.033,2.433],stretch:[10215,10215,10215],stretchv:[2,1,3],HDW:[.668,.168,.495]},10216:{dir:o,sizes:[.813,1.061,1.383,1.807,2.365,3.093,4.049]},10217:{dir:o,sizes:[.813,1.061,1.383,1.807,2.365,3.093,4.049]},10218:{dir:o,sizes:[.813,1.061,1.383,1.807,2.365,3.093,4.049]},10219:{dir:o,sizes:[.813,1.061,1.383,1.807,2.365,3.093,4.049]},10222:{dir:o,sizes:[.815,.975,1.167,1.397,1.673,2.005,2.403],stretch:[10222,10222,10222],stretchv:[2,1,3],HDW:[.657,.157,.418]},10223:{dir:o,sizes:[.815,.975,1.167,1.397,1.673,2.005,2.403],stretch:[10223,10223,10223],stretchv:[2,1,3],HDW:[.657,.157,.418]},10229:{c:8592,dir:d,sizes:[.85,1.17],variants:[0,0],schar:[8592,10229],stretch:[8592,8592],stretchv:[2,1],HDW:[.43,-.07,.85],hd:[.276,-.224]},10230:{c:8594,dir:d,sizes:[.85,1.17],variants:[0,0],schar:[8594,10230],stretch:[0,8592,8594],stretchv:[0,1,3],HDW:[.43,-.07,.85],hd:[.276,-.224]},10231:{c:8596,dir:d,sizes:[1.04,1.36],variants:[0,0],schar:[8596,10231],stretch:[8592,8592,8594],stretchv:[2,1,3],HDW:[.43,-.07,1.04],hd:[.276,-.224]},10232:{c:8656,dir:d,sizes:[.85,1.17],variants:[0,0],schar:[8656,10232],stretch:[8656,8656],stretchv:[2,1],HDW:[.47,-.03,.85],hd:[.352,-.148]},10233:{c:8658,dir:d,sizes:[.85,1.17],variants:[0,0],schar:[8658,10233],stretch:[0,8656,8658],stretchv:[0,1,3],HDW:[.47,-.03,.85],hd:[.352,-.148]},10234:{c:8660,dir:d,sizes:[1.04,1.36],variants:[0,0],schar:[8660,10234],stretch:[8656,8656,8658],stretchv:[2,1,3],HDW:[.47,-.03,1.04],hd:[.352,-.148]},10235:{c:8612,dir:d,sizes:[.85,1.17],variants:[0,0],schar:[8612,10235],stretch:[8592,8592,8612],stretchv:[2,1,3],HDW:[.43,-.07,.85],hd:[.276,-.224]},10236:{c:8614,dir:d,sizes:[.85,1.17],variants:[0,0],schar:[8614,10236],stretch:[8614,8592,8594],stretchv:[2,1,3],HDW:[.43,-.07,.85],hd:[.276,-.224]},10570:{dir:d,sizes:[.75],stretch:[8636,8592,8641],stretchv:[2,1,3],HDW:[.43,-.07,.75],hd:[.276,-.224]},10571:{dir:d,sizes:[.75],stretch:[8637,8592,8640],stretchv:[2,1,3],HDW:[.43,-.07,.75],hd:[.276,-.224]},10574:{dir:d,sizes:[.75],stretch:[8636,8592,8640],stretchv:[2,1,3],HDW:[.43,-.224,.75],hd:[.276,-.224]},10576:{dir:d,sizes:[.75],stretch:[8637,8592,8641],stretchv:[2,1,3],HDW:[.276,-.07,.75],hd:[.276,-.224]},10586:{dir:d,sizes:[.754],stretch:[8636,8592,8612],stretchv:[2,1,3],HDW:[.43,-.07,.754],hd:[.276,-.224]},10587:{dir:d,sizes:[.754],stretch:[8614,8592,8640],stretchv:[2,1,3],HDW:[.43,-.07,.754],hd:[.276,-.224]},10590:{dir:d,sizes:[.754],stretch:[8637,8592,8612],stretchv:[2,1,3],HDW:[.43,-.07,.754],hd:[.276,-.224]},10591:{dir:d,sizes:[.754],stretch:[8614,8592,8641],stretchv:[2,1,3],HDW:[.43,-.07,.754],hd:[.276,-.224]},12296:{c:10216,dir:o,sizes:[.813,1.061,1.383,1.807,2.365,3.093,4.049]},12297:{c:10217,dir:o,sizes:[.813,1.061,1.383,1.807,2.365,3.093,4.049]},65079:{c:9182,dir:d,sizes:[.52,1.019,1.519,2.019,2.519,3.019,3.519],stretch:[9182,175,9182,9182],stretchv:[2,1,3,1],HDW:[.792,-.525,.52],hd:[.702,-.618]},65080:{c:9183,dir:d,sizes:[.52,1.019,1.519,2.019,2.519,3.019,3.519],stretch:[9183,95,9183,9183],stretchv:[2,1,3,1],HDW:[-.075,.341,.52],hd:[-.168,.252]}},l=function(s){var t;return(t=class extends s{}).defaultVariants=[...f.defaultVariants,["-size3","normal"],["-size4","normal"],["-size5","normal"],["-size6","normal"],["-tex-calligraphic","script"],["-tex-bold-calligraphic","bold-script"],["-lf-tp","normal"],["-rt-bt","normal"],["-ex-md","normal"]],t.defaultCssFonts=Object.assign(Object.assign({},f.defaultCssFonts),{"-size3":["serif",!1,!1],"-size4":["serif",!1,!1],"-size5":["serif",!1,!1],"-size6":["serif",!1,!1],"-lf-tp":["serif",!1,!1],"-rt-bt":["serif",!1,!1],"-ex-md":["serif",!1,!1]}),t.defaultAccentMap={94:"\u02c6",126:"\u02dc",768:"`",769:"\xb4",770:"\u02c6",771:"\u02dc",772:"\xaf",774:"\u02d8",775:"\u02d9",776:"\xa8",778:"\u02da",780:"\u02c7",8594:"\u20d7"},t.defaultParams=Object.assign(Object.assign({},f.defaultParams),{surd_height:.052,x_height:.441}),t.defaultSizeVariants=["normal","-smallop","-largeop","-size3","-size4","-size5","-size6"],t.defaultStretchVariants=["normal","-ex-md","-lf-tp","-rt-bt"],t}(k);class m extends l{constructor(){super(...arguments),this.cssFontPrefix="GT"}}m.NAME="MathJaxTermes",m.OPTIONS=Object.assign(Object.assign({},l.OPTIONS),{fontURL:"@mathjax/mathjax-termes-font/js/chtml/woff2",dynamicPrefix:"@mathjax/mathjax-termes-font/js/chtml/dynamic"}),m.defaultCssFamilyPrefix="MJX-GT-ZERO",m.defaultVariantLetters={normal:"",bold:"B",italic:"I","bold-italic":"BI","double-struck":"DS",fraktur:"F","bold-fraktur":"FB",script:"S","bold-script":"SB","sans-serif":"SS","bold-sans-serif":"SSB","sans-serif-italic":"SSI","sans-serif-bold-italic":"SSBI",monospace:"M","-smallop":"SO","-largeop":"LO","-size3":"S3","-size4":"S4","-size5":"S5","-size6":"S6","-tex-mathit":"MI","-tex-calligraphic":"C","-tex-bold-calligraphic":"CB","-tex-oldstyle":"OS","-tex-bold-oldstyle":"OB","-tex-variant":"V","-lf-tp":"LT","-rt-bt":"RB","-ex-md":"EM"},m.defaultDelimiters=n,m.defaultChars={normal:{32:[0,0,.25],33:[.676,.009,.333],34:[.676,-.431,.408],35:[.662,0,.5],36:[.727,.087,.5],37:[.676,.013,.833],38:[.676,.013,.778],39:[.676,-.431,.18],40:[.658,.158,.398],41:[.658,.158,.398],42:[.714,-.31,.442],43:[.5,0,.66],44:[.102,.141,.25],45:[.257,-.194,.333],46:[.1,.011,.25],47:[.65,.15,.466],48:[.676,.014,.5,{sk:-.014}],49:[.676,0,.5],50:[.676,0,.5,{sk:-.013}],51:[.676,.014,.5],52:[.676,0,.5,{sk:.094}],53:[.688,.014,.5,{sk:.177}],54:[.684,.014,.5,{sk:.152}],55:[.662,.008,.5,{sk:.013}],56:[.676,.014,.5],57:[.676,.022,.5],58:[.459,.011,.278],59:[.459,.141,.278],60:[.515,.015,.666],61:[.372,-.128,.66],62:[.515,.015,.666],63:[.676,.008,.444],64:[.676,.014,.921],65:[.674,0,.722],66:[.662,0,.667,{sk:-.13}],67:[.676,.014,.667,{sk:.107}],68:[.662,0,.722,{sk:-.152}],69:[.662,0,.611,{sk:-.028}],70:[.662,0,.556],71:[.676,.014,.722,{sk:.109}],72:[.662,0,.722],73:[.662,0,.333],74:[.662,.014,.389,{sk:.033}],75:[.662,0,.722,{ic:.001}],76:[.662,0,.611,{sk:-.152}],77:[.662,0,.889],78:[.662,.011,.722],79:[.676,.014,.722,{sk:.014}],80:[.662,0,.556,{sk:-.077}],81:[.676,.178,.722],82:[.662,0,.667,{sk:-.126}],83:[.676,.014,.556,{sk:.037}],84:[.662,0,.611],85:[.662,.014,.722],86:[.662,.011,.722],87:[.662,.011,.944],88:[.662,0,.722],89:[.662,0,.722],90:[.662,0,.611],91:[.668,.168,.387],92:[.65,.15,.466],93:[.668,.168,.387],94:[.662,-.297,.469],95:[-.075,.125,.5],96:[.675,-.504,.333,{sk:-.038}],97:[.46,.01,.444],98:[.683,.01,.5,{sk:-.117}],99:[.46,.01,.444,{sk:.022}],100:[.683,.01,.5,{sk:.151}],101:[.46,.01,.444,{sk:.013}],102:[.683,0,.333,{ic:.05,sk:.072}],103:[.46,.218,.5],104:[.683,0,.5,{sk:-.115}],105:[.641,0,.278],106:[.641,.218,.278,{sk:.012}],107:[.683,0,.5,{ic:.005,sk:-.112}],108:[.683,0,.278,{sk:.019}],109:[.46,0,.778],110:[.46,0,.5,{sk:-.011}],111:[.46,.01,.5],112:[.46,.217,.5,{sk:-.01}],113:[.461,.217,.5,{sk:.05}],114:[.46,0,.333,{ic:.002,sk:.055}],115:[.459,.01,.389,{sk:.022}],116:[.579,.01,.278,{ic:.001}],117:[.45,.01,.5,{sk:-.037}],118:[.45,.014,.5],119:[.45,.014,.722],120:[.45,0,.5,{sk:-.021}],121:[.45,.218,.5],122:[.45,0,.444],123:[.66,.16,.391],124:[.65,.15,.204],125:[.66,.16,.391],126:[.32,-.186,.541],160:[0,0,.25],163:[.676,.008,.5],165:[.662,0,.5,{ic:.012}],167:[.676,.148,.5],168:[.64,-.541,.333],172:[.276,0,.686],175:[.617,-.563,.333],176:[.676,-.39,.4],177:[.5,.122,.66],180:[.675,-.504,.333,{sk:.038}],181:[.45,.25,.59],182:[.662,.154,.453],183:[.306,-.194,.272],215:[.445,-.055,.55],240:[.686,.01,.5],247:[.488,-.012,.66],305:[.46,0,.278],567:[.46,.218,.278,{sk:.119}],600:[.46,.01,.444],601:[.46,.01,.444],710:[.674,-.507,.333],711:[.674,-.507,.333],713:[.617,-.563,.333],714:[.675,-.504,.333,{sk:.038}],715:[.675,-.504,.333,{sk:-.038}],728:[.669,-.512,.333],729:[.641,-.539,.333],730:[.69,-.491,.333],732:[.643,-.537,.333],768:[.71,-.539,0,{dx:.288}],769:[.71,-.539,0,{dx:.211}],770:[.685,-.551,0,{dx:.876,sk:.626}],771:[.665,-.555,0,{dx:1.059,sk:.809}],772:[.637,-.583,0,{dx:.249}],773:[.632,-.588,0,{dx:.988,sk:.739}],774:[.681,-.556,0,{dx:.804,sk:.554}],775:[.661,-.559,0,{dx:.25}],776:[.66,-.561,0,{dx:.249}],778:[.71,-.511,0,{dx:.249}],780:[.679,-.545,0,{dx:1.052,sk:.802}],824:[.65,.15,0,{sk:.519}],913:[.674,0,.849,{sk:-.03}],914:[.662,0,.736,{sk:.065}],915:[.662,0,.693,{sk:.049}],916:[.674,0,.76,{sk:.054}],917:[.662,0,.744,{sk:-.12}],918:[.662,0,.747,{sk:-.097}],919:[.662,0,.843,{sk:-.022}],920:[.675,.014,.814,{sk:.032}],921:[.662,0,.457,{sk:.042}],922:[.662,0,.849,{sk:-.129}],923:[.674,0,.849,{sk:-.08}],924:[.662,0,1.011,{sk:-.126}],925:[.662,.011,.854,{sk:-.175}],926:[.662,0,.726,{sk:-.086}],927:[.675,.014,.814,{sk:-.147}],928:[.662,0,.843,{sk:-.136}],929:[.662,0,.686,{sk:.072}],931:[.662,0,.753,{sk:.08}],932:[.662,0,.736,{sk:.032}],933:[.662,0,.824,{sk:.028}],934:[.662,0,.722,{sk:-.021}],935:[.662,0,.854,{sk:-.053}],936:[.662,0,.799,{sk:-.154}],937:[.676,0,.853,{sk:-.157}],945:[.46,.017,.635,{sk:.286}],946:[.673,.217,.563,{sk:.383}],947:[.461,.234,.673,{sk:.025}],948:[.671,.016,.602,{sk:.097}],949:[.46,.016,.539,{sk:.081}],950:[.667,.21,.546,{sk:.112}],951:[.46,.217,.599,{sk:.237}],952:[.674,.016,.552,{sk:.314}],953:[.46,.017,.463,{sk:.194}],954:[.46,.015,.691,{sk:.121}],955:[.673,.018,.666,{sk:.036}],956:[.444,.218,.62,{sk:.095}],957:[.46,.016,.604,{sk:.134}],958:[.667,.21,.545,{sk:.206}],959:[.46,.01,.6,{sk:.071}],960:[.471,.016,.708,{sk:.054}],961:[.46,.218,.544,{sk:.333}],962:[.46,.21,.545,{sk:.015}],963:[.471,.016,.597,{sk:.367}],964:[.471,.016,.628,{sk:.013}],965:[.46,.016,.587,{sk:.066}],966:[.46,.218,.682,{sk:.153}],967:[.46,.236,.666,{sk:.21}],968:[.46,.218,.78,{sk:-.127}],969:[.463,.016,.767,{sk:-.095}],977:[.673,.016,.727,{sk:-.092}],981:[.657,.217,.702,{sk:-.105}],982:[.471,.021,.898,{sk:-.049}],1008:[.46,.016,.676],1009:[.46,.217,.552,{sk:.164}],1012:[.675,.014,.814,{sk:.203}],1013:[.46,.016,.474,{sk:.079}],8192:[0,0,.5],8193:[0,0,1],8194:[0,0,.5],8195:[0,0,1],8196:[0,0,.333],8197:[0,0,.25],8198:[0,0,.167],8199:[0,0,.5],8200:[0,0,.25],8201:[0,0,.2],8202:[0,0,.1],8203:[0,0,0],8204:[0,0,0],8205:[0,0,0],8208:[.257,-.194,.333],8209:[.257,-.194,.333],8210:[.357,-.305,.66],8211:[.25,-.201,.5],8212:[.25,-.201,1],8213:[.276,-.224,1.16],8214:[.65,.15,.348],8216:[.676,-.433,.333],8217:[.676,-.433,.333],8220:[.676,-.433,.444],8221:[.676,-.433,.444],8224:[.676,.149,.5],8225:[.676,.153,.5],8230:[.112,0,.869],8239:[0,0,.2],8242:[.78,-.45,.321],8243:[.78,-.45,.521],8244:[.78,-.45,.721],8245:[.78,-.45,.321],8246:[.78,-.45,.521],8247:[.78,-.45,.721],8260:[.65,.15,.466],8279:[.78,-.45,.921],8287:[0,0,.222],8288:[0,0,0],8289:[0,0,0],8290:[0,0,0],8291:[0,0,0],8292:[0,0,0],8356:[.676,.008,.5],8364:[.674,.015,.5],8400:[.71,-.6,0,{dx:.977,sk:.727}],8401:[.71,-.6,0,{dx:.608,sk:.358}],8402:[.65,.15,0,{sk:.281}],8406:[.71,-.534,0,{dx:.649,sk:.399}],8407:[.71,-.534,0,{dx:.63,sk:.38}],8411:[.66,-.56,0,{dx:.755,sk:.505}],8412:[.66,-.56,0,{dx:.804,sk:.554}],8417:[.71,-.534,0,{dx:.626,sk:.376}],8428:[-.15,.26,0,{dx:.732,sk:.482}],8429:[-.15,.26,0,{dx:.895,sk:.645}],8430:[-.084,.26,0,{dx:.973,sk:.723}],8431:[-.084,.26,0,{dx:.82,sk:.57}],8455:[.676,.014,.475],8462:[.683,.009,.5,{sk:-.011}],8463:[.683,.009,.5],8486:[.676,0,.853,{sk:.128}],8487:[.658,.018,.853],8490:[.662,0,.722,{ic:.001}],8491:[.896,0,.722],8501:[.723,.019,.604],8502:[.729,.029,.522,{ic:.001}],8503:[.74,.018,.469],8504:[.717,.016,.522],8592:[.43,-.07,.85],8593:[.6,.09,.52],8594:[.43,-.07,.85],8595:[.59,.1,.52],8596:[.43,-.07,1.04],8597:[.69,.19,.52],8598:[.497,.009,.666],8599:[.497,.009,.666],8600:[.509,-.003,.666],8601:[.509,-.003,.666],8602:[.43,-.07,.85],8603:[.43,-.07,.85],8606:[.43,-.07,1.03],8608:[.43,-.07,1.03],8610:[.43,-.07,1.04],8611:[.43,-.07,1.04],8612:[.43,-.07,.85],8614:[.43,-.07,.85],8617:[.508,-.07,.876],8618:[.508,-.07,.876],8619:[.508,-.018,.876],8620:[.508,-.018,.876],8622:[.43,-.07,1.04],8630:[.535,-.241,.799],8631:[.535,-.241,.799],8634:[.547,.003,.726],8635:[.547,.003,.726],8636:[.43,-.224,.84],8637:[.276,-.07,.84],8638:[.59,.09,.366],8639:[.59,.09,.366],8640:[.43,-.224,.84],8641:[.276,-.07,.84],8642:[.59,.09,.366],8643:[.59,.09,.366],8644:[.63,.13,.86],8645:[.6,.1,.92],8646:[.63,.13,.86],8647:[.63,.13,.85],8648:[.6,.09,.92],8649:[.63,.13,.85],8650:[.59,.1,.92],8651:[.526,.026,.84],8652:[.526,.026,.84],8653:[.5,0,.85],8654:[.5,0,1.04],8655:[.5,0,.85],8656:[.47,-.03,.85],8657:[.6,.09,.6],8658:[.47,-.03,.85],8659:[.59,.1,.6],8660:[.47,-.03,1.04],8661:[.69,.19,.6],8666:[.572,.072,1.03],8667:[.572,.072,1.03],8672:[.43,-.07,1.043],8674:[.43,-.07,1.133],8693:[.6,.1,.92],8694:[.83,.33,.85],8704:[.662,.004,.58],8705:[.662,0,.56],8706:[.673,.017,.552],8707:[.662,0,.534],8708:[.729,.067,.534],8709:[.755,.093,.66],8710:[.674,0,.76,{sk:.059}],8711:[.664,.01,.76,{sk:-.079}],8712:[.5,0,.678],8713:[.65,.15,.678],8714:[.435,-.065,.548],8715:[.5,0,.678],8716:[.65,.15,.678],8717:[.435,-.065,.548],8718:[.556,0,.716],8719:[.727,.227,1.023],8720:[.727,.227,1.023],8721:[.727,.227,.944],8722:[.5,0,.66],8723:[.622,0,.66],8724:[.697,0,.66],8725:[.65,.15,.466],8726:[.608,.108,.66],8727:[.452,-.048,.522,{sk:-.015}],8728:[.4,-.1,.46],8729:[.4,-.1,.46],8730:[.616,.09,.594,{ic:.026}],8733:[.44,-.06,.797],8734:[.442,-.058,.94],8735:[.526,0,.686],8736:[.544,0,.697],8737:[.544,.085,.697],8738:[.483,-.017,.642],8739:[.65,.15,.204],8740:[.65,.15,.346],8741:[.65,.15,.348],8742:[.65,.15,.482],8743:[.506,0,.66],8744:[.5,.006,.66],8745:[.518,0,.66],8746:[.5,.018,.66],8747:[.796,.296,.666],8748:[.796,.296,1.042],8749:[.796,.296,1.418],8750:[.796,.296,.712],8751:[.796,.296,1.088],8752:[.796,.296,1.464],8753:[.796,.296,.729],8754:[.796,.296,.692],8755:[.796,.296,.692],8756:[.415,-.085,.524],8757:[.415,-.085,.524],8758:[.423,-.077,.272],8759:[.423,-.077,.506],8760:[.488,-.224,.66],8761:[.423,-.077,.76],8762:[.488,-.012,.66],8763:[.471,-.029,.642],8764:[.319,-.181,.642],8765:[.319,-.181,.642],8766:[.404,-.096,.784],8767:[.431,-.069,.66],8768:[.491,-.009,.321],8769:[.419,-.081,.642],8770:[.372,-.085,.66],8771:[.415,-.128,.66],8772:[.5,0,.66],8773:[.471,-.072,.66],8774:[.487,-.022,.66],8775:[.5,0,.66],8776:[.415,-.085,.642],8777:[.5,0,.642],8778:[.471,-.072,.66],8779:[.471,-.029,.642],8780:[.471,-.072,.66],8781:[.411,-.089,.66],8782:[.47,-.03,.66],8783:[.47,-.128,.66],8784:[.584,-.128,.66],8785:[.584,.084,.66],8786:[.584,.084,.66],8787:[.584,.084,.66],8788:[.423,-.077,.76],8789:[.423,-.077,.76],8790:[.372,-.128,.66],8791:[.772,-.128,.66],8792:[.503,-.032,.66],8793:[.546,.046,.66],8794:[.546,.046,.66],8795:[.791,-.128,.66],8796:[.829,-.128,.66],8797:[.824,-.128,.852],8798:[.712,-.128,.66],8799:[.818,-.128,.66],8800:[.65,.15,.66],8801:[.468,-.032,.66],8802:[.65,.15,.66],8803:[.564,.064,.66],8804:[.564,.054,.665],8805:[.564,.054,.665],8806:[.627,.117,.665],8807:[.627,.117,.665],8808:[.627,.184,.665],8809:[.627,.184,.665],8810:[.517,.017,.805],8811:[.517,.017,.805],8812:[.666,.166,.413],8813:[.65,.15,.66],8814:[.65,.15,.666],8815:[.65,.15,.666],8816:[.611,.111,.665],8817:[.611,.111,.665],8818:[.585,.075,.665],8819:[.585,.075,.665],8820:[.632,.132,.665],8821:[.632,.132,.665],8822:[.655,.155,.67],8823:[.655,.155,.67],8824:[.681,.181,.67],8825:[.681,.181,.67],8826:[.528,.028,.682],8827:[.528,.028,.682],8828:[.631,.131,.682],8829:[.631,.131,.682],8830:[.599,.089,.655],8831:[.599,.089,.655],8832:[.65,.15,.682],8833:[.65,.15,.682],8834:[.5,0,.678],8835:[.5,0,.678],8836:[.65,.15,.678],8837:[.65,.15,.678],8838:[.576,.076,.678],8839:[.576,.076,.678],8840:[.685,.185,.678],8841:[.685,.185,.678],8842:[.576,.143,.678],8843:[.576,.143,.678],8844:[.5,.018,.66],8845:[.5,.018,.66],8846:[.5,.018,.66],8847:[.5,0,.66],8848:[.5,0,.66],8849:[.576,.076,.66],8850:[.576,.076,.66],8851:[.513,-.013,.591],8852:[.487,.013,.591],8853:[.568,.068,.796],8854:[.568,.068,.796],8855:[.568,.068,.796],8856:[.568,.068,.796],8857:[.568,.068,.796],8858:[.568,.068,.796],8859:[.568,.068,.796],8860:[.568,.068,.796],8861:[.568,.068,.796],8862:[.5,0,.66],8863:[.5,0,.66],8864:[.5,0,.66],8865:[.5,0,.66],8866:[.65,0,.66],8867:[.65,0,.66],8868:[.65,0,.66],8869:[.65,0,.66],8870:[.65,.15,.586],8871:[.65,.15,.586],8872:[.65,.15,.66],8873:[.65,.15,.738],8874:[.65,.15,.89],8875:[.65,.15,.738],8876:[.65,.15,.712],8877:[.65,.15,.764],8878:[.65,.15,.842],8879:[.65,.15,.842],8882:[.527,.027,.697],8883:[.527,.027,.697],8884:[.57,.07,.696],8885:[.57,.07,.696],8886:[.4,-.1,.96],8887:[.4,-.1,.96],8888:[.4,-.1,.81],8889:[.5,0,.66],8890:[.65,0,.66],8891:[.526,.026,.66],8892:[.526,.026,.66],8893:[.529,.029,.66],8894:[.526,.085,.771],8895:[.544,0,.704],8896:[.698,.19,.96],8897:[.69,.198,.96],8898:[.708,.19,.96],8899:[.69,.208,.96],8900:[.448,-.052,.557],8901:[.306,-.194,.272],8902:[.42,-.11,.486],8903:[.521,.021,.671],8904:[.445,-.055,.566],8905:[.445,-.055,.558],8906:[.445,-.055,.558],8907:[.445,-.055,.55],8908:[.445,-.055,.55],8909:[.415,-.128,.66],8910:[.5,-.001,.683],8911:[.499,0,.683],8912:[.5,0,.678],8913:[.5,0,.678],8914:[.518,0,.66],8915:[.5,.018,.66],8917:[.65,.15,.66],8918:[.515,.015,.666],8919:[.515,.015,.666],8920:[.517,.017,1.082],8921:[.517,.017,1.082],8922:[.756,.256,.665],8923:[.756,.256,.665],8924:[.564,.054,.665],8925:[.564,.054,.665],8926:[.631,.131,.682],8927:[.631,.131,.682],8928:[.657,.157,.682],8929:[.657,.157,.682],8930:[.685,.185,.66],8931:[.685,.185,.66],8932:[.576,.143,.66],8933:[.576,.143,.66],8934:[.585,.125,.665],8935:[.585,.125,.665],8936:[.599,.139,.655],8937:[.599,.139,.655],8938:[.65,.15,.697],8939:[.65,.15,.697],8940:[.622,.122,.696],8941:[.622,.122,.696],8942:[.605,.105,.272],8943:[.306,-.194,.869],8944:[.517,.017,.694],8945:[.517,.017,.694],8968:[.668,.15,.387],8969:[.668,.15,.387],8970:[.65,.168,.387],8971:[.65,.168,.387],8976:[.276,0,.686],8985:[.5,-.224,.686],8988:[.676,-.41,.426],8989:[.676,-.41,.426],8990:[.09,.176,.426],8991:[.09,.176,.426],8994:[.354,-.146,.978],8995:[.354,-.146,.978],9001:[.656,.156,.357],9002:[.656,.156,.357],9115:[1.202,0,.624],9116:[.396,0,.624],9117:[1.202,0,.624],9118:[1.202,0,.624],9119:[.396,0,.624],9120:[1.202,0,.624],9121:[1.216,0,.491],9122:[.81,0,.491],9123:[1.216,0,.491],9124:[1.216,0,.491],9125:[.81,0,.491],9126:[1.216,0,.491],9127:[.607,0,.547],9128:[1.194,0,.547],9129:[.607,0,.547],9130:[.596,0,.547],9131:[.607,0,.547],9132:[1.194,0,.547],9133:[.607,0,.547],9134:[.58,0,.8],9136:[.694,.5,.547],9137:[.694,.5,.547],9140:[.726,-.548,.375],9141:[-.098,.276,.375],9143:[1.656,0,.674],9168:[.527,0,.212],9180:[.699,-.595,.514],9181:[-.145,.249,.514],9182:[.739,-.559,.52],9183:[-.109,.289,.52],9184:[.717,-.579,.562],9185:[-.129,.267,.562],9632:[.5,0,.66],9633:[.5,0,.66],9642:[.4,-.1,.46],9643:[.4,-.1,.46],9650:[.656,-.047,.862],9651:[.656,-.047,.862],9654:[.601,.101,.768],9655:[.601,.101,.768],9660:[.453,.156,.862],9661:[.453,.156,.862],9664:[.601,.101,.768],9665:[.601,.101,.768],9674:[.555,.055,.564],9675:[.568,.068,.796],9679:[.568,.068,.796],9702:[.4,-.1,.46],9711:[.668,.168,.996],10178:[.65,0,.66],10200:[.65,.15,.96],10201:[.65,.15,.96],10202:[.65,.15,1.164],10203:[.65,.15,1.164],10204:[.4,-.1,.81],10205:[.65,.15,1.16],10206:[.65,.15,1.16],10208:[.555,.055,.564],10209:[.457,-.043,.574],10210:[.457,-.043,.664],10211:[.457,-.043,.664],10214:[.668,.168,.398],10215:[.668,.168,.398],10216:[.656,.156,.357],10217:[.656,.156,.357],10218:[.656,.156,.543],10219:[.656,.156,.543],10222:[.657,.157,.32],10223:[.657,.157,.32],10229:[.43,-.07,1.17],10230:[.43,-.07,1.17],10231:[.43,-.07,1.36],10232:[.47,-.03,1.17],10233:[.47,-.03,1.17],10234:[.47,-.03,1.36],10235:[.43,-.07,1.17],10236:[.43,-.07,1.17],10237:[.47,-.03,1.35],10238:[.47,-.03,1.35],10570:[.43,-.07,.75],10571:[.43,-.07,.75],10574:[.43,-.224,.75],10576:[.276,-.07,.75],10586:[.43,-.07,.754],10587:[.43,-.07,.754],10590:[.43,-.07,.754],10591:[.43,-.07,.754],10752:[.688,.188,1.036],10753:[.688,.188,1.036],10754:[.688,.188,1.036],10755:[.69,.208,.96],10756:[.69,.208,.96],10757:[.704,.176,.896],10758:[.676,.204,.896],10761:[.608,.108,.876],10764:[.796,.296,1.794],10769:[.796,.296,.729],10799:[.455,-.045,.57],10815:[.662,0,.761],10877:[.599,.099,.666],10878:[.599,.099,.666],10885:[.646,.136,.665],10886:[.646,.136,.665],10887:[.593,.093,.665],10888:[.593,.093,.665],10889:[.646,.186,.665],10890:[.646,.186,.665],10891:[.819,.319,.665],10892:[.819,.319,.665],10901:[.599,.099,.666],10902:[.599,.099,.666],10927:[.604,.094,.682],10928:[.604,.094,.682],119808:[.69,0,.722,{sk:-.015}],119809:[.676,0,.667,{sk:-.117}],119810:[.691,.019,.722,{sk:.143}],119811:[.676,0,.722,{sk:-.131}],119812:[.676,0,.667,{sk:-.029}],119813:[.676,0,.611],119814:[.691,.019,.778,{sk:.103}],119815:[.676,0,.778],119816:[.676,0,.389],119817:[.676,.096,.5,{sk:.053}],119818:[.676,0,.778],119819:[.676,0,.667,{sk:-.14}],119820:[.676,0,.944],119821:[.676,.018,.722],119822:[.691,.019,.778],119823:[.676,0,.611,{sk:-.083}],119824:[.691,.176,.778],119825:[.676,0,.722,{sk:-.124}],119826:[.692,.019,.556,{sk:.058}],119827:[.676,0,.667],119828:[.676,.019,.722],119829:[.676,.018,.722],119830:[.676,.015,1],119831:[.676,0,.722],119832:[.676,0,.722],119833:[.676,0,.667],119834:[.473,.014,.5,{sk:-.014}],119835:[.676,.014,.556,{sk:-.164}],119836:[.473,.014,.444,{sk:.037}],119837:[.676,.014,.556,{sk:.09}],119838:[.473,.014,.444],119839:[.691,0,.333,{ic:.056,sk:.035}],119840:[.473,.206,.5],119841:[.676,0,.556,{sk:-.166}],119842:[.687,0,.278],119843:[.687,.203,.333,{sk:.022}],119844:[.676,0,.556,{sk:-.162}],119845:[.676,0,.278,{sk:-.028}],119846:[.473,0,.833,{sk:-.061}],119847:[.473,0,.556,{sk:-.057}],119848:[.473,.014,.5],119849:[.473,.205,.556,{sk:-.068}],119850:[.473,.205,.556,{sk:.054}],119851:[.473,0,.444],119852:[.473,.014,.389,{sk:.042}],119853:[.63,.012,.333,{sk:.033}],119854:[.461,.014,.556,{sk:-.029}],119855:[.461,.014,.5],119856:[.461,.014,.722],119857:[.461,0,.5],119858:[.461,.205,.5],119859:[.461,0,.444],119860:[.668,0,.611,{sk:.071}],119861:[.653,0,.611],119862:[.666,.018,.667,{ic:.022,sk:.199}],119863:[.653,0,.722,{sk:-.043}],119864:[.653,0,.611,{ic:.023,sk:.063}],119865:[.653,0,.611,{ic:.034,sk:.065}],119866:[.666,.018,.722,{sk:.189}],119867:[.653,0,.722,{ic:.045,sk:.054}],119868:[.653,0,.333,{ic:.051,sk:.056}],119869:[.653,.018,.444,{ic:.047,sk:.107}],119870:[.653,0,.667,{ic:.055,sk:.059}],119871:[.653,0,.556,{ic:.003,sk:-.013}],119872:[.653,0,.833,{ic:.04,sk:.058}],119873:[.653,.015,.667,{ic:.06,sk:.043}],119874:[.666,.018,.722,{sk:.115}],119875:[.653,0,.611,{sk:.018}],119876:[.666,.182,.722,{sk:.111}],119877:[.653,0,.611],119878:[.667,.018,.5,{ic:.008,sk:.123}],119879:[.653,0,.556,{ic:.077,sk:.03}],119880:[.653,.018,.722,{ic:.043,sk:.053}],119881:[.653,.018,.611,{ic:.077,sk:.019}],119882:[.653,.018,.833,{ic:.073,sk:.018}],119883:[.653,0,.611,{ic:.044,sk:.028}],119884:[.653,0,.556,{ic:.077,sk:.026}],119885:[.653,0,.556,{ic:.05,sk:.046}],119886:[.441,.011,.5,{sk:.114}],119887:[.683,.011,.5,{sk:-.027}],119888:[.441,.011,.444,{sk:.107}],119889:[.683,.013,.5,{ic:.027,sk:.218}],119890:[.441,.011,.444,{sk:.113}],119891:[.678,.207,.278,{ic:.146,sk:.088}],119892:[.441,.206,.5,{sk:.047}],119894:[.643,.011,.278,{sk:.085}],119895:[.643,.207,.278,{ic:.023,sk:.093}],119896:[.683,.011,.444,{ic:.017}],119897:[.683,.011,.278,{ic:.001,sk:.105}],119898:[.441,.009,.722,{sk:.038}],119899:[.441,.009,.5,{sk:.035}],119900:[.441,.011,.5,{sk:.073}],119901:[.441,.205,.5],119902:[.441,.205,.5,{sk:.13}],119903:[.441,0,.389,{ic:.023,sk:.063}],119904:[.442,.013,.389,{sk:.074}],119905:[.546,.011,.278,{ic:.018,sk:.081}],119906:[.441,.011,.5,{sk:.056}],119907:[.441,.018,.444,{sk:.02}],119908:[.441,.018,.667,{sk:.019}],119909:[.441,.011,.444,{ic:.003,sk:.057}],119910:[.441,.206,.444,{sk:.014}],119911:[.428,.081,.389,{sk:.042}],119912:[.683,0,.667,{sk:.068}],119913:[.669,0,.667,{sk:-.021}],119914:[.685,.018,.667,{ic:.01,sk:.185}],119915:[.669,0,.722,{sk:-.07}],119916:[.669,0,.667,{sk:.05}],119917:[.669,0,.667,{sk:.06}],119918:[.685,.018,.722,{sk:.149}],119919:[.669,0,.778,{ic:.021,sk:.053}],119920:[.669,0,.389,{ic:.017,sk:.05}],119921:[.669,.099,.5,{ic:.024,sk:.108}],119922:[.669,0,.667,{ic:.035,sk:.051}],119923:[.669,0,.611,{sk:-.029}],119924:[.669,.012,.889,{ic:.028,sk:.053}],119925:[.669,.015,.722,{ic:.026,sk:.05}],119926:[.685,.018,.722,{sk:.085}],119927:[.669,0,.611,{ic:.002}],119928:[.685,.208,.722,{sk:.095}],119929:[.669,0,.667,{sk:-.024}],119930:[.685,.018,.556,{sk:.104}],119931:[.669,0,.611,{ic:.039,sk:.039}],119932:[.669,.018,.722,{ic:.022,sk:.043}],119933:[.669,.018,.667,{ic:.048,sk:.021}],119934:[.669,.018,.889,{ic:.051,sk:.02}],119935:[.669,0,.667,{ic:.027,sk:.043}],119936:[.669,0,.611,{ic:.048,sk:.025}],119937:[.669,0,.611,{sk:.05}],119938:[.462,.014,.5,{sk:.085}],119939:[.699,.013,.5,{sk:.024}],119940:[.462,.013,.444,{sk:.064}],119941:[.699,.013,.5,{ic:.017,sk:.219}],119942:[.462,.013,.444,{sk:.074}],119943:[.698,.205,.333,{ic:.113,sk:.097}],119944:[.462,.203,.5],119945:[.699,.009,.556,{sk:-.016}],119946:[.658,.009,.278,{sk:.059}],119947:[.658,.207,.278,{ic:.006,sk:.072}],119948:[.699,.008,.5],119949:[.699,.009,.278,{ic:.012,sk:.108}],119950:[.462,.009,.778,{sk:.032}],119951:[.462,.009,.556,{sk:.036}],119952:[.462,.013,.5,{sk:.038}],119953:[.462,.205,.5],119954:[.462,.205,.5,{sk:.1}],119955:[.462,0,.389,{sk:.071}],119956:[.462,.013,.389,{sk:.03}],119957:[.594,.009,.278,{ic:.003,sk:.09}],119958:[.462,.009,.556,{sk:.052}],119959:[.462,.013,.444,{sk:.019}],119960:[.462,.013,.667],119961:[.462,.013,.5,{sk:.035}],119962:[.462,.205,.444],119963:[.449,.078,.389,{sk:.017}],120484:[.441,.011,.278,{sk:.254}],120485:[.441,.207,.278,{sk:.293}],120488:[.69,0,.84,{sk:.057}],120489:[.676,0,.763,{sk:.143}],120490:[.676,0,.737,{sk:-.113}],120491:[.69,0,.761,{sk:-.099}],120492:[.676,0,.785,{sk:-.099}],120493:[.676,0,.766,{sk:-.06}],120494:[.676,0,.898,{sk:-.179}],120495:[.691,.019,.868,{sk:-.138}],120496:[.676,0,.51,{sk:.299}],120497:[.676,0,.899,{sk:.161}],120498:[.69,0,.84,{sk:.019}],120499:[.676,0,1.067,{sk:-.051}],120500:[.676,.018,.845,{sk:.042}],120501:[.662,0,.731,{sk:.145}],120502:[.691,.019,.868,{sk:-.12}],120503:[.676,0,.898,{sk:-.104}],120504:[.676,0,.744,{sk:.152}],120505:[.691,.019,.868],120506:[.662,0,.784,{sk:.184}],120507:[.676,0,.765,{sk:-.028}],120508:[.676,0,.848,{sk:-.033}],120509:[.676,0,.814,{sk:-.052}],120510:[.676,0,.843,{sk:-.03}],120511:[.676,0,.88,{sk:-.155}],120512:[.691,0,.85,{sk:-.112}],120513:[.68,.01,.761,{sk:-.041}],120514:[.473,.014,.679,{sk:.179}],120515:[.691,.217,.65,{sk:.246}],120516:[.473,.232,.72,{sk:.058}],120517:[.691,.014,.666,{sk:.127}],120518:[.473,.014,.573,{sk:.052}],120519:[.667,.215,.546,{sk:.1}],120520:[.473,.218,.673,{sk:-.034}],120521:[.691,.015,.64,{sk:.013}],120522:[.473,.014,.52,{sk:.157}],120523:[.473,.014,.769,{sk:.074}],120524:[.691,.014,.72,{sk:-.064}],120525:[.461,.218,.69,{sk:-.02}],120526:[.473,.011,.665,{sk:.07}],120527:[.667,.215,.544,{sk:.171}],120528:[.473,.014,.611,{sk:-.05}],120529:[.481,.014,.715,{sk:-.075}],120530:[.473,.218,.616,{sk:.183}],120531:[.473,.215,.545,{sk:.266}],120532:[.471,.014,.674,{sk:.203}],120533:[.481,.016,.655],120534:[.473,.014,.64,{sk:.05}],120535:[.476,.218,.812,{sk:.014}],120536:[.473,.232,.72,{sk:.102}],120537:[.473,.218,.88,{sk:-.174}],120538:[.475,.014,.789,{sk:-.102}],120539:[.691,.014,.616],120540:[.482,.014,.522,{sk:.331}],120541:[.693,.014,.828,{sk:.013}],120542:[.473,.014,.649],120543:[.677,.218,.832,{sk:-.028}],120544:[.473,.217,.616,{sk:.135}],120545:[.481,.014,.955,{sk:-.074}],120546:[.668,0,.775,{sk:.011}],120547:[.653,0,.756,{sk:.06}],120548:[.662,0,.868,{sk:-.174}],120549:[.668,0,.686,{sk:-.057}],120550:[.653,0,.795],120551:[.653,0,.772,{sk:.052}],120552:[.653,0,.935,{sk:-.207}],120553:[.666,.018,.799,{sk:-.114}],120554:[.653,0,.552,{sk:-.137}],120555:[.653,0,.875,{sk:-.246}],120556:[.668,0,.775,{sk:-.186}],120557:[.653,0,1.051,{sk:-.387}],120558:[.653,.015,.907,{sk:-.286}],120559:[.653,0,.822,{sk:-.224}],120560:[.666,.018,.799,{sk:-.194}],120561:[.653,0,.935,{sk:-.046}],120562:[.653,0,.765,{sk:-.065}],120563:[.666,.018,.799,{sk:.239}],120564:[.653,0,.848,{sk:-.078}],120565:[.653,0,.734],120566:[.653,0,.798,{sk:-.053}],120567:[.653,0,.708,{sk:.028}],120568:[.653,0,.844],120569:[.653,0,.77,{sk:.023}],120570:[.649,0,.855,{sk:-.199}],120571:[.658,.01,.686,{sk:-.067}],120572:[.441,.016,.645,{sk:.079}],120573:[.645,.208,.694,{sk:.075}],120574:[.442,.224,.684,{sk:.165}],120575:[.645,.015,.63,{sk:.112}],120576:[.441,.015,.568,{sk:.079}],120577:[.639,.201,.591,{sk:.113}],120578:[.441,.208,.581,{sk:.132}],120579:[.646,.015,.577,{sk:.019}],120580:[.441,.016,.389,{sk:.151}],120581:[.441,.014,.677,{sk:.029}],120582:[.645,.017,.672,{sk:.076}],120583:[.426,.209,.685,{sk:.019}],120584:[.441,.015,.604,{sk:.127}],120585:[.639,.201,.594,{sk:.104}],120586:[.441,.011,.601,{sk:.128}],120587:[.452,.015,.766,{sk:-.051}],120588:[.441,.209,.654,{sk:-.066}],120589:[.441,.201,.582,{sk:.06}],120590:[.452,.015,.658],120591:[.452,.015,.647,{sk:-.021}],120592:[.441,.015,.588,{sk:-.03}],120593:[.441,.209,.678,{sk:-.071}],120594:[.441,.226,.806,{sk:-.109}],120595:[.441,.209,.768,{sk:-.109}],120596:[.444,.015,.763,{sk:-.205}],120597:[.645,.016,.586,{sk:.079}],120598:[.441,.015,.524,{sk:-.067}],120599:[.645,.015,.696,{sk:-.034}],120600:[.441,.015,.654],120601:[.63,.208,.698,{sk:-.09}],120602:[.441,.208,.576,{sk:.012}],120603:[.452,.02,.906,{sk:-.186}],120604:[.683,0,.82,{sk:-.111}],120605:[.669,0,.808,{sk:-.09}],120606:[.676,0,.918,{sk:-.157}],120607:[.683,0,.735,{sk:-.029}],120608:[.669,0,.84,{sk:-.07}],120609:[.669,0,.761],120610:[.669,0,.983,{sk:-.107}],120611:[.685,.018,.844,{sk:-.149}],120612:[.669,0,.598,{sk:-.024}],120613:[.669,0,.883,{sk:-.091}],120614:[.683,0,.82,{sk:-.042}],120615:[.669,.012,1.106,{sk:-.086}],120616:[.669,.015,.935,{sk:-.188}],120617:[.662,0,.874,{sk:-.151}],120618:[.685,.018,.824,{sk:-.032}],120619:[.669,0,.983,{sk:-.077}],120620:[.669,0,.8,{sk:-.069}],120621:[.685,.018,.844,{sk:.072}],120622:[.662,0,.909,{sk:-.086}],120623:[.669,0,.76],120624:[.676,0,.786,{sk:-.024}],120625:[.676,0,.786],120626:[.669,0,.878,{sk:.01}],120627:[.676,0,.86],120628:[.691,0,.892,{sk:-.191}],120629:[.673,.01,.735,{sk:-.043}],120630:[.473,.014,.728,{sk:.069}],120631:[.691,.217,.791,{sk:.018}],120632:[.473,.232,.751,{sk:.16}],120633:[.691,.014,.697,{sk:.075}],120634:[.473,.014,.624,{sk:.054}],120635:[.667,.215,.604,{sk:.133}],120636:[.473,.218,.652,{sk:.123}],120637:[.691,.015,.659],120638:[.473,.014,.443,{sk:.144}],120639:[.473,.014,.747],120640:[.691,.014,.746,{sk:.051}],120641:[.461,.218,.757,{sk:.029}],120642:[.473,.011,.673,{sk:.081}],120643:[.667,.215,.615,{sk:.134}],120644:[.473,.013,.608,{sk:.122}],120645:[.481,.014,.821,{sk:-.038}],120646:[.473,.218,.731,{sk:-.053}],120647:[.473,.215,.61,{sk:.074}],120648:[.471,.014,.742,{sk:-.011}],120649:[.481,.016,.705,{sk:-.011}],120650:[.473,.014,.648,{sk:-.032}],120651:[.476,.218,.805,{sk:-.138}],120652:[.473,.232,.877,{sk:-.113}],120653:[.473,.218,.874,{sk:-.128}],120654:[.475,.014,.772,{sk:-.182}],120655:[.691,.014,.67,{sk:.049}],120656:[.482,.014,.58,{sk:-.078}],120657:[.693,.014,.798,{sk:-.056}],120658:[.473,.014,.714],120659:[.677,.218,.822,{sk:-.127}],120660:[.473,.217,.673,{sk:-.03}],120661:[.481,.014,.985,{sk:-.225}],120662:[.671,0,.769,{sk:.081}],120663:[.671,0,.686,{sk:.189}],120664:[.671,0,.621,{sk:-.077}],120665:[.65,0,.829,{sk:-.029}],120666:[.671,0,.65,{sk:.261}],120667:[.671,0,.653,{sk:.188}],120668:[.671,0,.69,{sk:.22}],120669:[.682,.011,.792,{sk:.013}],120670:[.671,0,.295,{sk:.384}],120671:[.671,0,.739,{sk:.214}],120672:[.671,0,.769,{sk:-.128}],120673:[.671,0,.799,{sk:.154}],120674:[.671,0,.694,{sk:.263}],120675:[.671,0,.675,{sk:-.052}],120676:[.682,.011,.792,{sk:.196}],120677:[.671,0,.69,{sk:.032}],120678:[.671,0,.661,{sk:.321}],120679:[.682,.011,.792,{sk:.129}],120680:[.671,0,.648,{sk:.091}],120681:[.671,0,.686,{sk:-.039}],120682:[.671,0,.721,{sk:.089}],120683:[.671,0,.758,{sk:.098}],120684:[.671,0,.728,{sk:-.03}],120685:[.671,0,.721,{sk:.165}],120686:[.682,0,.77],120687:[.65,0,.829,{sk:.046}],120688:[.505,.011,.762,{sk:.126}],120689:[.671,.202,.637,{sk:.026}],120690:[.497,.23,.718,{sk:-.047}],120691:[.666,.011,.574,{sk:.093}],120692:[.505,.009,.565,{sk:.061}],120693:[.677,.194,.603,{sk:.022}],120694:[.505,.202,.615,{sk:.153}],120695:[.664,.01,.578,{sk:.149}],120696:[.497,.006,.371,{sk:.224}],120697:[.497,.001,.631,{sk:.233}],120698:[.673,0,.731],120699:[.497,.202,.663,{sk:-.018}],120700:[.497,0,.653],120701:[.677,.194,.603],120702:[.505,.008,.641,{sk:.102}],120703:[.497,.006,.759,{sk:-.029}],120704:[.493,.202,.635,{sk:.165}],120705:[.503,.194,.592,{sk:.17}],120706:[.524,.008,.711,{sk:.069}],120707:[.497,.006,.619,{sk:.141}],120708:[.483,.01,.622,{sk:.052}],120709:[.493,.212,.76,{sk:-.01}],120710:[.498,.213,.75,{sk:-.041}],120711:[.661,.212,.72],120712:[.497,-.004,.762,{sk:.052}],120713:[.671,.011,.585,{sk:.133}],120714:[.505,.008,.542,{sk:.227}],120715:[.671,.01,.615,{sk:.029}],120716:[.507,.01,.676],120717:[.671,.212,.729,{sk:-.042}],120718:[.493,.202,.615,{sk:.022}],120719:[.608,-.004,.764,{sk:-.088}],120720:[.671,0,.769,{sk:-.07}],120721:[.671,0,.776,{sk:-.042}],120722:[.671,0,.764,{sk:.181}],120723:[.65,0,.829,{sk:.191}],120724:[.671,0,.777,{sk:.015}],120725:[.671,0,.796,{sk:.046}],120726:[.671,0,.833,{sk:-.046}],120727:[.682,.011,.809,{sk:.019}],120728:[.671,0,.438,{sk:.188}],120729:[.671,0,.854,{sk:.026}],120730:[.671,0,.769],120731:[.671,0,.942,{sk:.028}],120732:[.671,0,.837],120733:[.671,0,.818,{sk:.14}],120734:[.682,.011,.809,{sk:.056}],120735:[.671,0,.833,{sk:.249}],120736:[.671,0,.766],120737:[.682,.011,.809],120738:[.671,0,.791,{sk:.034}],120739:[.671,0,.711,{sk:.059}],120740:[.671,0,.721,{sk:.139}],120741:[.671,0,.768,{sk:.069}],120742:[.671,0,.863,{sk:-.013}],120743:[.671,0,.779,{sk:.184}],120744:[.682,0,.847,{sk:.049}],120745:[.64,.01,.829],120746:[.505,.011,.823,{sk:.165}],120747:[.671,.202,.751,{sk:.23}],120748:[.497,.23,.718,{sk:.275}],120749:[.666,.011,.663,{sk:.086}],120750:[.505,.009,.612,{sk:.079}],120751:[.677,.194,.668,{sk:.088}],120752:[.505,.202,.672,{sk:.167}],120753:[.664,.01,.62,{sk:.155}],120754:[.497,.006,.365,{sk:.395}],120755:[.497,.001,.694,{sk:.203}],120756:[.673,0,.731,{sk:.16}],120757:[.497,.202,.767,{sk:.074}],120758:[.497,0,.637,{sk:.16}],120759:[.677,.194,.653,{sk:.211}],120760:[.505,.008,.658,{sk:.303}],120761:[.497,.006,.788,{sk:.066}],120762:[.493,.202,.738,{sk:.107}],120763:[.503,.194,.607,{sk:.186}],120764:[.524,.008,.779,{sk:.142}],120765:[.497,.006,.648,{sk:.087}],120766:[.483,.01,.629,{sk:.12}],120767:[.493,.212,.775,{sk:.026}],120768:[.498,.213,.822,{sk:.044}],120769:[.661,.212,.756,{sk:.112}],120770:[.497,-.004,.778,{sk:.037}],120771:[.671,.011,.624,{sk:.2}],120772:[.505,.008,.594,{sk:.127}],120773:[.671,.01,.661,{sk:.207}],120774:[.507,.01,.758],120775:[.671,.212,.742,{sk:.113}],120776:[.493,.202,.658,{sk:.195}],120777:[.603,-.004,.786,{sk:.075}],120782:[.688,.013,.5,{sk:-.01}],120783:[.688,0,.5],120784:[.688,0,.5],120785:[.688,.014,.5,{sk:.015}],120786:[.688,0,.5,{sk:.119}],120787:[.676,.008,.5,{sk:.058}],120788:[.688,.013,.5,{sk:.184}],120789:[.676,0,.5,{sk:.018}],120790:[.688,.013,.5,{sk:.023}],120791:[.688,.013,.5]},bold:{32:[0,0,.25],33:[.691,.013,.333],34:[.691,-.404,.555],35:[.7,0,.5],36:[.75,.099,.5],37:[.692,.01,1],38:[.691,.016,.833],39:[.691,-.404,.278],40:[.694,.168,.333],41:[.694,.168,.333],42:[.691,-.255,.5],43:[.491,-.009,.57],44:[.155,.18,.25],45:[.287,-.171,.333],46:[.156,.013,.25],47:[.691,.019,.278,{ic:.024}],58:[.472,.013,.333],59:[.472,.18,.333],60:[.511,.011,.57],61:[.379,-.122,.57],62:[.511,.011,.57],63:[.689,.013,.5],64:[.691,.019,.93],91:[.678,.149,.333],92:[.691,.019,.278,{ic:.025}],93:[.678,.149,.333],94:[.676,-.311,.581],95:[-.075,.125,.5],96:[.702,-.517,.333],123:[.698,.175,.394],124:[.678,.149,.22],125:[.698,.175,.394],126:[.331,-.175,.52],160:[0,0,.25],163:[.684,.014,.5],165:[.676,0,.5,{ic:.047}],167:[.691,.132,.5],168:[.675,-.546,.333,{ic:.004}],172:[.379,-.166,.57],175:[.646,-.574,.333],176:[.688,-.402,.4],177:[.579,0,.57],180:[.702,-.517,.333],181:[.461,.206,.556],182:[.676,.186,.54],183:[.334,-.166,.25],215:[.452,-.048,.57],240:[.691,.014,.5],247:[.503,.003,.57],305:[.461,0,.278,{sk:.134}],567:[.461,.203,.333,{sk:.134}],600:[.473,.014,.444],601:[.473,.014,.444],710:[.698,-.522,.333,{ic:.002}],711:[.698,-.522,.333,{ic:.002}],713:[.646,-.574,.333],714:[.702,-.517,.333],715:[.702,-.517,.333],728:[.692,-.529,.333],729:[.687,-.533,.333],730:[.717,-.504,.333],732:[.674,-.547,.333,{ic:.016}],768:[.702,-.517,0,{dx:.288}],769:[.702,-.517,0,{dx:.211}],770:[.698,-.522,0,{dx:.249}],771:[.674,-.547,0,{dx:.249}],772:[.646,-.574,0,{dx:.25}],774:[.692,-.529,0,{dx:.249}],775:[.687,-.533,0,{dx:.251}],776:[.675,-.546,0,{dx:.248}],778:[.717,-.504,0,{dx:.249}],780:[.698,-.522,0,{dx:.249}],8208:[.287,-.171,.333],8209:[.287,-.171,.333],8211:[.271,-.181,.5],8212:[.271,-.181,1],8214:[.678,.149,.57],8216:[.691,-.356,.333],8217:[.691,-.356,.333],8220:[.691,-.356,.5],8221:[.691,-.356,.5],8224:[.691,.134,.5],8225:[.691,.132,.5],8230:[.156,.013,1],8260:[.688,.012,.167,{ic:.162}],8356:[.684,.014,.5],8364:[.671,.028,.5],8472:[.491,.25,.63],8486:[.691,0,.766],8487:[.676,.015,.766],8592:[.501,.001,1],8593:[.673,.162,.679],8594:[.501,.001,1],8595:[.662,.173,.679],8721:[.752,.123,.713],8722:[.294,-.206,.57],8723:[.5,.079,.57],8730:[.916,.035,.549],8734:[.499,-.097,.833],8738:[.549,.049,.57],8776:[.451,-.062,.57],8800:[.486,-.014,.57],8804:[.643,.044,.57],8805:[.643,.044,.57],8902:[.478,-.037,.5],9001:[.678,.149,.405],9002:[.678,.149,.405],9674:[.74,0,.494],9702:[.478,-.198,.35],10214:[.678,.149,.44],10215:[.678,.149,.44]},italic:{32:[0,0,.25],33:[.667,.011,.333],34:[.666,-.421,.42,{ic:.012}],35:[.676,0,.5,{ic:.04}],36:[.731,.089,.5],37:[.676,.013,.833],38:[.666,.018,.778],39:[.666,-.421,.214,{ic:.027}],40:[.669,.181,.333],41:[.669,.18,.333],42:[.666,-.255,.5],43:[.548,.047,.675],44:[.101,.129,.25],45:[.255,-.192,.333],46:[.1,.011,.25],47:[.666,.018,.278,{ic:.108}],48:[.676,.007,.5],49:[.676,0,.5],50:[.676,0,.5],51:[.676,.007,.5],52:[.676,0,.5],53:[.666,.007,.5],54:[.686,.007,.5,{ic:.021}],55:[.666,.008,.5,{ic:.037}],56:[.676,.007,.5],57:[.676,.017,.5],58:[.441,.011,.333],59:[.441,.129,.333],60:[.467,-.033,.675],61:[.365,-.135,.675],62:[.467,-.033,.675],63:[.664,.012,.5],64:[.666,.018,.92],91:[.663,.153,.389,{ic:.002}],92:[.666,.018,.278,{ic:.041}],93:[.663,.153,.389],94:[.666,-.301,.422],95:[-.075,.125,.5],96:[.675,-.505,.333],123:[.687,.177,.4,{ic:.007}],124:[.663,.153,.275],125:[.687,.177,.4],126:[.32,-.186,.541],160:[0,0,.25],168:[.639,-.541,.333,{ic:.046}],175:[.616,-.565,.333,{ic:.058}],176:[.676,-.39,.4],180:[.675,-.505,.333,{ic:.013}],305:[.441,.011,.278,{sk:.254}],567:[.441,.207,.278,{sk:.293}],600:[.441,.011,.444,{ic:.006}],601:[.441,.011,.444],710:[.675,-.506,.333,{ic:.026}],711:[.675,-.506,.333,{ic:.065}],713:[.616,-.565,.333,{ic:.058}],714:[.675,-.505,.333,{ic:.013}],715:[.675,-.505,.333],728:[.669,-.511,.333,{ic:.051}],729:[.643,-.537,.333],730:[.69,-.491,.333,{ic:.002}],732:[.644,-.537,.333,{ic:.065}],768:[.675,-.505,0,{dx:.104}],769:[.675,-.505,0,{dx:.091}],770:[.675,-.506,0,{dx:.114}],771:[.644,-.537,0,{dx:.091}],772:[.616,-.565,0,{dx:.091}],774:[.669,-.511,0,{dx:.092}],775:[.643,-.537,0,{dx:.091}],776:[.639,-.541,0,{dx:.091}],778:[.69,-.491,0,{dx:.091}],780:[.675,-.506,0,{dx:.081}],8356:[.67,.006,.5,{ic:.017}],8364:[.693,0,.5,{ic:.162}],8472:[.458,.25,.583,{ic:.045}],8486:[.677,0,.766],8487:[.654,.023,.766,{ic:.197}]},"bold-italic":{32:[0,0,.25],33:[.684,.013,.389],34:[.685,-.398,.555],35:[.7,0,.5,{ic:.033}],36:[.733,.1,.5],37:[.692,.01,.833],38:[.682,.019,.778],39:[.685,-.398,.278],40:[.685,.179,.333,{ic:.011}],41:[.685,.179,.333],42:[.685,-.252,.5],43:[.491,-.009,.57],44:[.134,.182,.25],45:[.282,-.166,.333],46:[.135,.013,.25],47:[.685,.018,.278,{ic:.064}],48:[.683,.014,.5],49:[.683,0,.5],50:[.683,0,.5],51:[.683,.013,.5],52:[.683,0,.5,{ic:.003}],53:[.669,.013,.5],54:[.679,.015,.5,{ic:.009}],55:[.669,0,.5,{ic:.025}],56:[.683,.013,.5],57:[.683,.01,.5],58:[.459,.013,.333],59:[.459,.183,.333],60:[.498,-.002,.57],61:[.378,-.122,.57],62:[.498,-.002,.57],63:[.684,.013,.5],64:[.685,.018,.832],91:[.674,.159,.333,{ic:.029}],92:[.685,.018,.278,{ic:.001}],93:[.674,.157,.333,{ic:.01}],94:[.669,-.304,.57],95:[-.075,.125,.5],96:[.68,-.499,.333],123:[.686,.187,.348,{ic:.088}],124:[.674,.159,.22],125:[.686,.187,.348],126:[.331,-.175,.57],160:[0,0,.25],168:[.655,-.525,.333,{ic:.046}],175:[.625,-.555,.333,{ic:.047}],176:[.683,-.397,.4],180:[.68,-.499,.333],305:[.462,.009,.278,{sk:.377}],567:[.462,.207,.278,{sk:.428}],600:[.462,.013,.444],601:[.462,.013,.444],710:[.677,-.503,.333,{ic:.017}],711:[.677,-.503,.333,{ic:.056}],713:[.625,-.555,.333,{ic:.047}],714:[.68,-.499,.333],715:[.68,-.499,.333],728:[.671,-.509,.333,{ic:.034}],729:[.658,-.523,.333],730:[.697,-.484,.333],732:[.65,-.531,.333,{ic:.057}],768:[.68,-.499,0,{dx:.109}],769:[.68,-.499,0,{dx:.092}],770:[.677,-.503,0,{dx:.115}],771:[.65,-.531,0,{dx:.09}],772:[.625,-.555,0,{dx:.092}],774:[.671,-.509,0,{dx:.092}],775:[.658,-.523,0,{dx:.091}],776:[.655,-.525,0,{dx:.092}],778:[.697,-.484,0,{dx:.091}],780:[.677,-.503,0,{dx:.078}],8356:[.683,.012,.5,{ic:.01}],8364:[.689,.005,.5,{ic:.162}],8472:[.479,.25,.593,{ic:.044}],8486:[.691,0,.766,{ic:.062}],8487:[.67,.021,.766,{ic:.142}]},"double-struck":{},fraktur:{},"bold-fraktur":{},script:{},"bold-script":{},"sans-serif":{},"bold-sans-serif":{},"sans-serif-italic":{},"sans-serif-bold-italic":{},monospace:{},"-smallop":{40:[.738,.238,.426],41:[.738,.238,.426],47:[.774,.274,.549],91:[.749,.249,.403],92:[.774,.274,.549],93:[.749,.249,.403],123:[.74,.24,.413],125:[.74,.24,.413],770:[.697,-.537,.608],771:[.688,-.532,.601],773:[.632,-.588,.5],774:[.694,-.543,.62],780:[.693,-.533,.608],8260:[.774,.274,.549],8400:[.71,-.6,.598],8401:[.71,-.6,.598],8406:[.71,-.534,.607],8407:[.71,-.534,.607],8417:[.71,-.534,.68],8428:[-.15,.26,.598],8429:[-.15,.26,.598],8430:[-.084,.26,.607],8431:[-.084,.26,.607],8725:[.65,.15,.466],8726:[.606,.106,.659],8730:[.808,.282,.607,{ic:.026}],8739:[.73,.23,.206],8741:[.73,.23,.352],8747:[.844,.344,.576,{ic:.11}],8748:[.844,.344,.967,{ic:.11}],8749:[.844,.344,1.358,{ic:.11}],8750:[.844,.344,.734],8751:[.844,.344,1.125],8752:[.844,.344,1.516],8753:[.844,.344,.75],8754:[.844,.344,.713],8755:[.844,.344,.713],8968:[.749,.23,.403],8969:[.749,.23,.403],8970:[.73,.249,.403],8971:[.73,.249,.403],9140:[.728,-.548,.75],9141:[-.098,.278,.75],9180:[.713,-.571,1.014],9181:[-.121,.263,1.014],9182:[.763,-.534,1.019],9183:[-.084,.312,1.019],9184:[.734,-.548,1.066],9185:[-.098,.284,1.066],10214:[.749,.249,.413],10215:[.749,.249,.413],10216:[.78,.28,.381],10217:[.78,.28,.381],10218:[.78,.28,.579],10219:[.78,.28,.579],10222:[.737,.237,.334],10223:[.737,.237,.334],10764:[.844,.344,1.749,{ic:.11}],10769:[.844,.344,.75]},"-largeop":{40:[.834,.334,.457],41:[.834,.334,.457],47:[.936,.436,.658],91:[.845,.345,.418],92:[.936,.436,.658],93:[.845,.345,.418],123:[.836,.336,.435],125:[.836,.336,.435],770:[.698,-.537,.727],771:[.688,-.532,.72],774:[.694,-.542,.74],780:[.693,-.532,.727],8260:[.936,.436,.658],8719:[.937,.437,1.204],8720:[.937,.437,1.204],8721:[.937,.437,1.197],8725:[.65,.15,.466],8726:[.604,.104,.661],8730:[1,.474,.621,{ic:.026}],8739:[.826,.326,.209],8741:[.826,.326,.358],8747:[1.097,.597,.605,{ic:.125}],8748:[1.097,.597,1.03,{ic:.125}],8749:[1.097,.597,1.455,{ic:.125}],8750:[1.097,.597,.782],8751:[1.097,.597,1.207],8752:[1.097,.597,1.632],8753:[1.097,.597,.797],8754:[1.097,.597,.759],8755:[1.097,.597,.759],8896:[.839,.326,1.04],8897:[.826,.339,1.04],8898:[.844,.326,1.04],8899:[.826,.344,1.04],8968:[.845,.326,.418],8969:[.845,.326,.418],8970:[.826,.345,.418],8971:[.826,.345,.418],9140:[.732,-.548,1.125],9141:[-.098,.282,1.125],9180:[.732,-.541,1.514],9181:[-.091,.282,1.514],9182:[.766,-.533,1.519],9183:[-.083,.316,1.519],9184:[.736,-.547,1.568],9185:[-.097,.286,1.568],10145:[.47,-.03,1.35],10214:[.845,.345,.425],10215:[.845,.345,.425],10216:[.941,.441,.409],10217:[.941,.441,.409],10218:[.941,.441,.62],10219:[.941,.441,.62],10222:[.833,.333,.347],10223:[.833,.333,.347],10752:[.816,.316,1.292],10753:[.816,.316,1.292],10754:[.816,.316,1.292],10755:[.826,.344,1.04],10756:[.826,.344,1.04],10757:[.841,.311,1.04],10758:[.811,.341,1.04],10761:[.703,.203,1.065],10764:[1.097,.597,1.88,{ic:.125}],10769:[1.097,.597,.797]},"-size3":{40:[.949,.449,.491],41:[.949,.449,.491],47:[1.149,.649,.798],91:[.961,.461,.434],92:[1.149,.649,.798],93:[.961,.461,.434],123:[.951,.451,.459],125:[.951,.451,.459],770:[.698,-.536,.87],771:[.688,-.532,.863],774:[.694,-.541,.885],780:[.694,-.532,.87],8260:[1.149,.649,.798],8725:[.65,.15,.466],8726:[.602,.102,.66],8730:[1.192,.666,.634,{ic:.026}],8739:[.941,.441,.211],8741:[.941,.441,.362],8968:[.961,.441,.434],8969:[.961,.441,.434],8970:[.941,.461,.434],8971:[.941,.461,.434],9140:[.736,-.548,1.5],9141:[-.098,.286,1.5],9180:[.736,-.541,2.014],9181:[-.091,.286,2.014],9182:[.771,-.532,2.019],9183:[-.082,.32,2.019],9184:[.738,-.545,2.072],9185:[-.095,.288,2.072],10214:[.961,.461,.442],10215:[.961,.461,.442],10216:[1.153,.653,.439],10217:[1.153,.653,.439],10218:[1.153,.653,.665],10219:[1.153,.653,.665],10222:[.948,.448,.363],10223:[.948,.448,.363]},"-size4":{40:[1.087,.587,.53],41:[1.087,.587,.53],47:[1.428,.928,.982],91:[1.099,.599,.453],92:[1.428,.928,.982],93:[1.099,.599,.453],123:[1.089,.589,.487],125:[1.089,.589,.487],770:[.699,-.536,1.041],771:[.687,-.533,1.037],774:[.695,-.54,1.058],780:[.694,-.531,1.041],8260:[1.428,.928,.982],8725:[.65,.15,.466],8726:[.6,.1,.659],8730:[1.384,.858,.647,{ic:.026}],8739:[1.079,.579,.213],8741:[1.079,.579,.366],8968:[1.099,.579,.453],8969:[1.099,.579,.453],8970:[1.079,.599,.453],8971:[1.079,.599,.453],9140:[.742,-.548,1.875],9141:[-.098,.292,1.875],9180:[.742,-.541,2.514],9181:[-.091,.292,2.514],9182:[.777,-.53,2.519],9183:[-.08,.326,2.519],9184:[.741,-.543,2.576],9185:[-.093,.291,2.576],10214:[1.099,.599,.457],10215:[1.099,.599,.457],10216:[1.432,.932,.474],10217:[1.432,.932,.474],10218:[1.432,.932,.714],10219:[1.432,.932,.714],10222:[1.086,.586,.382],10223:[1.086,.586,.382]},"-size5":{40:[1.253,.753,.575],41:[1.253,.753,.575],47:[1.793,1.293,1.222],91:[1.266,.766,.472],92:[1.793,1.293,1.222],93:[1.266,.766,.472],123:[1.255,.755,.517],125:[1.255,.755,.517],770:[.699,-.536,1.249],771:[.687,-.533,1.241],774:[.695,-.54,1.266],780:[.694,-.531,1.249],8260:[1.793,1.293,1.222],8725:[.65,.15,.466],8726:[.597,.097,.66],8730:[1.576,1.05,.661,{ic:.026}],8739:[1.245,.745,.216],8741:[1.245,.745,.372],8968:[1.266,.745,.472],8969:[1.266,.745,.472],8970:[1.245,.766,.472],8971:[1.245,.766,.472],9140:[.75,-.548,2.25],9141:[-.098,.3,2.25],9180:[.75,-.541,3.014],9181:[-.091,.3,3.014],9182:[.784,-.527,3.019],9183:[-.077,.333,3.019],9184:[.745,-.541,3.08],9185:[-.091,.295,3.08],10214:[1.266,.766,.475],10215:[1.266,.766,.475],10216:[1.796,1.296,.51],10217:[1.796,1.296,.51],10218:[1.796,1.296,.765],10219:[1.796,1.296,.765],10222:[1.252,.752,.399],10223:[1.252,.752,.399]},"-size6":{40:[1.452,.952,.624],41:[1.452,.952,.624],47:[2.272,1.772,1.536],91:[1.466,.966,.491],92:[2.272,1.772,1.536],93:[1.466,.966,.491],123:[1.454,.954,.547],125:[1.454,.954,.547],770:[.7,-.535,1.496],771:[.689,-.531,1.491],774:[.695,-.539,1.515],780:[.695,-.53,1.496],8260:[2.272,1.772,1.536],8725:[.65,.15,.466],8726:[.594,.094,.66],8730:[1.768,1.242,.674,{ic:.026}],8739:[1.444,.944,.219],8741:[1.444,.944,.378],8968:[1.466,.944,.491],8969:[1.466,.944,.491],8970:[1.444,.966,.491],8971:[1.444,.966,.491],9140:[.758,-.548,2.625],9141:[-.098,.308,2.625],9180:[.758,-.541,3.514],9181:[-.091,.308,3.514],9182:[.792,-.525,3.519],9183:[-.075,.341,3.519],9184:[.748,-.538,3.584],9185:[-.088,.298,3.584],10214:[1.466,.966,.495],10215:[1.466,.966,.495],10216:[2.274,1.774,.554],10217:[2.274,1.774,.554],10218:[2.274,1.774,.825],10219:[2.274,1.774,.825],10222:[1.451,.951,.418],10223:[1.451,.951,.418]},"-tex-mathit":{65:[.668,0,.611],66:[.653,0,.611],67:[.666,.018,.667,{oc:.022}],68:[.653,0,.722],69:[.653,0,.611,{oc:.023}],70:[.653,0,.611,{oc:.034}],71:[.666,.018,.722],72:[.653,0,.722,{oc:.045}],73:[.653,0,.333,{oc:.051}],74:[.653,.018,.444,{oc:.047}],75:[.653,0,.667,{oc:.055}],76:[.653,0,.556,{oc:.003}],77:[.653,0,.833,{oc:.04}],78:[.653,.015,.667,{oc:.06}],79:[.666,.018,.722],80:[.653,0,.611],81:[.666,.182,.722],82:[.653,0,.611],83:[.667,.018,.5,{oc:.008}],84:[.653,0,.556,{oc:.077}],85:[.653,.018,.722,{oc:.043}],86:[.653,.018,.611,{oc:.077}],87:[.653,.018,.833,{oc:.073}],88:[.653,0,.611,{oc:.044}],89:[.653,0,.556,{oc:.077}],90:[.653,0,.556,{oc:.05}],97:[.441,.011,.5],98:[.683,.011,.5],99:[.441,.011,.444],100:[.683,.013,.5,{oc:.027}],101:[.441,.011,.444],102:[.678,.207,.278,{oc:.146}],103:[.441,.206,.5],104:[.683,.009,.5],105:[.643,.011,.278],106:[.643,.207,.278,{oc:.023}],107:[.683,.011,.444,{oc:.017}],108:[.683,.011,.278,{oc:.001}],109:[.441,.009,.722],110:[.441,.009,.5],111:[.441,.011,.5],112:[.441,.205,.5],113:[.441,.205,.5],114:[.441,0,.389,{oc:.023}],115:[.442,.013,.389],116:[.546,.011,.278,{oc:.018}],117:[.441,.011,.5],118:[.441,.018,.444],119:[.441,.018,.667],120:[.441,.011,.444,{oc:.003}],121:[.441,.206,.444],122:[.428,.081,.389]},"-tex-calligraphic":{},"-tex-bold-calligraphic":{},"-tex-oldstyle":{36:[.745,.083,.556],48:[.47,.02,.532],49:[.471,0,.363],50:[.47,0,.525],51:[.47,.22,.469],52:[.509,.167,.54],53:[.47,.232,.486],54:[.684,.014,.514],55:[.456,.214,.509],56:[.676,.014,.469],57:[.47,.228,.509],162:[.533,.083,.444]},"-tex-bold-oldstyle":{36:[.759,.083,.556],48:[.481,.02,.54],49:[.481,0,.465],50:[.481,0,.549],51:[.481,.221,.54],52:[.544,.144,.544],53:[.481,.203,.536],54:[.688,.013,.535],55:[.462,.214,.548],56:[.688,.013,.532],57:[.481,.22,.535],162:[.544,.083,.444]},"-tex-variant":{8216:[.596,-.15,.404],8217:[.596,-.15,.404],8218:[.596,-.15,.404],8219:[.596,-.15,.404],8220:[.596,-.15,.644],8221:[.596,-.15,.644],8222:[.596,-.15,.644],8223:[.596,-.15,.644],8242:[.596,-.15,.404],8243:[.596,-.15,.644],8244:[.596,-.15,.884],8245:[.596,-.15,.404],8246:[.596,-.15,.644],8247:[.596,-.15,.884],8279:[.596,-.15,1.124],8463:[.683,.009,.598],8709:[.513,.013,.686],8725:[.676,.014,0],8902:[.48,-.036,.5],59965:[.617,-.563,.333],60165:[.42,.27,.921],60169:[.48,-.036,.5],60207:[.257,-.194,.167,{ic:.118}],60210:[.356,-.095,.167,{ic:.118}],60236:[.662,.154,.428],60250:[.742,-.392,.43],60267:[.25,-.201,.667],60416:[.738,-.388,.43],60422:[.617,0,.278],60423:[.809,0,.333]},"-lf-tp":{8400:[.71,-.6,.164],8406:[.71,-.534,.168],8429:[-.15,.26,.164],8430:[-.084,.26,.168],8592:[.43,-.07,.379],8593:[.379,0,.52],8602:[.43,-.07,.289],8606:[.43,-.07,.446],8607:[.446,0,.52],8611:[.43,-.07,.45],8614:[.43,-.07,.379],8615:[.379,0,.52],8618:[.508,-.224,.389],8620:[.508,-.018,.389],8636:[.43,-.224,.375],8637:[.276,-.07,.375],8638:[.375,0,.366],8639:[.375,0,.366],8644:[.476,.13,.383],8645:[.382,0,.92],8646:[.63,-.024,.383],8647:[.63,.13,.379],8648:[.379,0,.92],8651:[.526,-.128,.375],8652:[.372,.026,.375],8653:[.47,-.03,.289],8656:[.47,-.03,.379],8657:[.379,0,.6],8666:[.572,.072,.446],8693:[.383,0,.92],8730:[.301,0,.674,{ic:.026}],9140:[.758,-.548,1.313],9141:[-.098,.308,1.313],9180:[.758,-.541,1.757],9181:[-.091,.308,1.757],9182:[.702,-.525,.88],9183:[-.075,.252,.88],9184:[.748,-.538,1.792],9185:[-.088,.298,1.792],10214:[.811,0,.495],10215:[.811,0,.495],10222:[1.201,0,.418],10223:[1.201,0,.418],10572:[.59,.09,.52],10573:[.59,.09,.52],11057:[.83,.33,.379]},"-rt-bt":{8401:[.71,-.6,.165],8407:[.71,-.534,.168],8428:[-.15,.26,.165],8431:[-.084,.26,.168],8594:[.43,-.07,.379],8595:[.379,0,.52],8603:[.43,-.07,.289],8608:[.43,-.07,.446],8609:[.446,0,.52],8610:[.43,-.07,.45],8612:[.43,-.07,.379],8613:[.379,0,.52],8617:[.508,-.224,.389],8619:[.508,-.018,.389],8640:[.43,-.224,.375],8641:[.276,-.07,.375],8642:[.375,0,.366],8643:[.375,0,.366],8644:[.63,-.024,.382],8645:[.383,0,.92],8646:[.476,.13,.382],8649:[.63,.13,.379],8650:[.379,0,.92],8651:[.372,.026,.375],8652:[.526,-.128,.375],8654:[.47,-.03,.343],8658:[.47,-.03,.379],8659:[.379,0,.6],8667:[.572,.072,.446],8693:[.382,0,.92],8694:[.83,.33,.379],9140:[.758,-.548,1.312],9141:[-.098,.308,1.312],9180:[.758,-.541,1.757],9181:[-.091,.308,1.757],9182:[.702,-.525,.88],9183:[-.075,.252,.88],9184:[.748,-.538,1.792],9185:[-.088,.298,1.792],10214:[.811,0,.495],10215:[.811,0,.495],10222:[1.201,0,.418],10223:[1.201,0,.418],10572:[.59,.09,.52],10573:[.59,.09,.52]},"-ex-md":{95:[-.168,.252,.874],123:[.596,0,.547],175:[.702,-.618,.874],773:[.632,-.588,.166],8400:[.644,-.6,.109],8592:[.276,-.224,.252],8593:[.252,0,.52],8602:[.43,-.07,.288],8617:[.276,-.224,.259],8636:[.276,-.224,.25],8638:[.25,0,.366],8639:[.25,0,.366],8644:[.476,-.024,.255],8645:[.255,0,.92],8651:[.372,-.128,.25],8653:[.5,0,.288],8654:[.352,-.148,.086],8656:[.352,-.148,.252],8657:[.252,0,.6],8666:[.428,-.072,.298],8694:[.676,.176,.252],8730:[1.053,0,.674],9140:[.758,-.674,.875],9141:[-.224,.308,.875],9180:[.758,-.674,.874],9181:[-.224,.308,.874],9182:[.792,-.618,1.759],9183:[-.168,.341,1.759],9184:[.748,-.664,1.194],9185:[-.214,.298,1.194],10214:[.81,0,.495],10215:[.81,0,.495],10222:[.794,0,.418],10223:[.794,0,.418]}},m.defaultStyles=Object.assign(Object.assign({},k.defaultStyles),{'mjx-container[jax="CHTML"] > mjx-math.GT-N[breakable] > *':{"font-family":"MJX-GT-ZERO, MJX-GT-N"},".GT-N":{"font-family":"MJX-GT-ZERO, MJX-GT-N"},".GT-B":{"font-family":"MJX-GT-ZERO, MJX-GT-B"},".GT-I":{"font-family":"MJX-GT-ZERO, MJX-GT-I"},".GT-BI":{"font-family":"MJX-GT-ZERO, MJX-GT-BI"},".GT-DS":{"font-family":"MJX-GT-ZERO, MJX-GT-DS"},".GT-F":{"font-family":"MJX-GT-ZERO, MJX-GT-F"},".GT-FB":{"font-family":"MJX-GT-ZERO, MJX-GT-FB"},".GT-S":{"font-family":"MJX-GT-ZERO, MJX-GT-S"},".GT-SB":{"font-family":"MJX-GT-ZERO, MJX-GT-SB"},".GT-SS":{"font-family":"MJX-GT-ZERO, MJX-GT-SS"},".GT-SSB":{"font-family":"MJX-GT-ZERO, MJX-GT-SSB"},".GT-SSI":{"font-family":"MJX-GT-ZERO, MJX-GT-SSI"},".GT-SSBI":{"font-family":"MJX-GT-ZERO, MJX-GT-SSBI"},".GT-M":{"font-family":"MJX-GT-ZERO, MJX-GT-M"},".GT-SO":{"font-family":"MJX-GT-ZERO, MJX-GT-SO"},".GT-LO":{"font-family":"MJX-GT-ZERO, MJX-GT-LO"},".GT-S3":{"font-family":"MJX-GT-ZERO, MJX-GT-S3"},".GT-S4":{"font-family":"MJX-GT-ZERO, MJX-GT-S4"},".GT-S5":{"font-family":"MJX-GT-ZERO, MJX-GT-S5"},".GT-S6":{"font-family":"MJX-GT-ZERO, MJX-GT-S6"},".GT-MI":{"font-family":"MJX-GT-ZERO, MJX-GT-MI"},".GT-C":{"font-family":"MJX-GT-ZERO, MJX-GT-C"},".GT-CB":{"font-family":"MJX-GT-ZERO, MJX-GT-CB"},".GT-OS":{"font-family":"MJX-GT-ZERO, MJX-GT-OS"},".GT-OB":{"font-family":"MJX-GT-ZERO, MJX-GT-OB"},".GT-V":{"font-family":"MJX-GT-ZERO, MJX-GT-V"},".GT-LT":{"font-family":"MJX-GT-ZERO, MJX-GT-LT"},".GT-RB":{"font-family":"MJX-GT-ZERO, MJX-GT-RB"},".GT-EM":{"font-family":"MJX-GT-ZERO, MJX-GT-EM"}}),m.defaultFonts=Object.assign(Object.assign({},k.defaultFonts),{"@font-face /* MJX-GT-ZERO */":{"font-family":"MJX-GT-ZERO",src:'url("%%URL%%/mjx-gt-zero.woff2") format("woff2")'},"@font-face /* MJX-BRK */":{"font-family":"MJX-BRK",src:'url("%%URL%%/mjx-gt-brk.woff2") format("woff2")'},"@font-face /* MJX-GT-N */":{"font-family":"MJX-GT-N",src:'url("%%URL%%/mjx-gt-n.woff2") format("woff2")'},"@font-face /* MJX-GT-B */":{"font-family":"MJX-GT-B",src:'url("%%URL%%/mjx-gt-b.woff2") format("woff2")'},"@font-face /* MJX-GT-I */":{"font-family":"MJX-GT-I",src:'url("%%URL%%/mjx-gt-i.woff2") format("woff2")'},"@font-face /* MJX-GT-BI */":{"font-family":"MJX-GT-BI",src:'url("%%URL%%/mjx-gt-bi.woff2") format("woff2")'},"@font-face /* MJX-GT-DS */":{"font-family":"MJX-GT-DS",src:'url("%%URL%%/mjx-gt-ds.woff2") format("woff2")'},"@font-face /* MJX-GT-F */":{"font-family":"MJX-GT-F",src:'url("%%URL%%/mjx-gt-f.woff2") format("woff2")'},"@font-face /* MJX-GT-FB */":{"font-family":"MJX-GT-FB",src:'url("%%URL%%/mjx-gt-fb.woff2") format("woff2")'},"@font-face /* MJX-GT-S */":{"font-family":"MJX-GT-S",src:'url("%%URL%%/mjx-gt-s.woff2") format("woff2")'},"@font-face /* MJX-GT-SB */":{"font-family":"MJX-GT-SB",src:'url("%%URL%%/mjx-gt-sb.woff2") format("woff2")'},"@font-face /* MJX-GT-SS */":{"font-family":"MJX-GT-SS",src:'url("%%URL%%/mjx-gt-ss.woff2") format("woff2")'},"@font-face /* MJX-GT-SSB */":{"font-family":"MJX-GT-SSB",src:'url("%%URL%%/mjx-gt-ssb.woff2") format("woff2")'},"@font-face /* MJX-GT-SSI */":{"font-family":"MJX-GT-SSI",src:'url("%%URL%%/mjx-gt-ssi.woff2") format("woff2")'},"@font-face /* MJX-GT-SSBI */":{"font-family":"MJX-GT-SSBI",src:'url("%%URL%%/mjx-gt-ssbi.woff2") format("woff2")'},"@font-face /* MJX-GT-M */":{"font-family":"MJX-GT-M",src:'url("%%URL%%/mjx-gt-m.woff2") format("woff2")'},"@font-face /* MJX-GT-SO */":{"font-family":"MJX-GT-SO",src:'url("%%URL%%/mjx-gt-so.woff2") format("woff2")'},"@font-face /* MJX-GT-LO */":{"font-family":"MJX-GT-LO",src:'url("%%URL%%/mjx-gt-lo.woff2") format("woff2")'},"@font-face /* MJX-GT-S3 */":{"font-family":"MJX-GT-S3",src:'url("%%URL%%/mjx-gt-s3.woff2") format("woff2")'},"@font-face /* MJX-GT-S4 */":{"font-family":"MJX-GT-S4",src:'url("%%URL%%/mjx-gt-s4.woff2") format("woff2")'},"@font-face /* MJX-GT-S5 */":{"font-family":"MJX-GT-S5",src:'url("%%URL%%/mjx-gt-s5.woff2") format("woff2")'},"@font-face /* MJX-GT-S6 */":{"font-family":"MJX-GT-S6",src:'url("%%URL%%/mjx-gt-s6.woff2") format("woff2")'},"@font-face /* MJX-GT-MI */":{"font-family":"MJX-GT-MI",src:'url("%%URL%%/mjx-gt-mi.woff2") format("woff2")'},"@font-face /* MJX-GT-C */":{"font-family":"MJX-GT-C",src:'url("%%URL%%/mjx-gt-c.woff2") format("woff2")'},"@font-face /* MJX-GT-CB */":{"font-family":"MJX-GT-CB",src:'url("%%URL%%/mjx-gt-cb.woff2") format("woff2")'},"@font-face /* MJX-GT-OS */":{"font-family":"MJX-GT-OS",src:'url("%%URL%%/mjx-gt-os.woff2") format("woff2")'},"@font-face /* MJX-GT-OB */":{"font-family":"MJX-GT-OB",src:'url("%%URL%%/mjx-gt-ob.woff2") format("woff2")'},"@font-face /* MJX-GT-V */":{"font-family":"MJX-GT-V",src:'url("%%URL%%/mjx-gt-v.woff2") format("woff2")'},"@font-face /* MJX-GT-LT */":{"font-family":"MJX-GT-LT",src:'url("%%URL%%/mjx-gt-lt.woff2") format("woff2")'},"@font-face /* MJX-GT-RB */":{"font-family":"MJX-GT-RB",src:'url("%%URL%%/mjx-gt-rb.woff2") format("woff2")'},"@font-face /* MJX-GT-EM */":{"font-family":"MJX-GT-EM",src:'url("%%URL%%/mjx-gt-em.woff2") format("woff2")'}}),m.dynamicFiles=k.defineDynamicFiles([["latin",{normal:[[192,214],[216,239],[241,246],[248,304],[306,311],[313,328],[330,357],[360,383],398,402,416,417,431,432,[461,468],[471,477],486,487,490,491,496,500,501,[506,513],516,517,520,521,524,525,528,529,532,533,[536,539],[7692,7695],[7716,7719],7722,7723,7726,7727,[7734,7737],[7746,7751],[7768,7773],7778,7779,[7788,7791],[7808,7813],7826,7827,7831,7838,[7840,7929]]}],["latin-b",{bold:[[192,214],[216,239],[241,246],[248,304],[306,311],[313,328],[330,357],[360,383],398,402,416,417,431,432,[461,468],[471,477],486,487,490,491,496,500,501,[506,513],516,517,520,521,524,525,528,529,532,533,[536,539],[7692,7695],[7716,7719],7722,7723,7726,7727,[7734,7737],[7746,7751],[7768,7773],7778,7779,[7788,7791],[7808,7813],7826,7827,7831,[7840,7929]]}],["latin-i",{italic:[[192,214],[216,239],[241,246],[248,304],[306,311],[313,328],[330,357],[360,383],398,402,416,417,431,432,[461,468],[471,477],486,487,490,491,496,500,501,[506,513],516,517,520,521,524,525,528,529,532,533,[536,539],[7692,7695],[7716,7719],7722,7723,7726,7727,[7734,7737],[7746,7751],[7768,7773],7778,7779,[7788,7791],[7808,7813],7826,7827,7831,[7840,7929]]}],["latin-bi",{"bold-italic":[[192,214],[216,239],[241,246],[248,304],[306,311],[313,328],[330,357],[360,383],398,402,416,417,431,432,[461,468],[471,477],486,487,490,491,496,500,501,[506,513],516,517,520,521,524,525,528,529,532,533,[536,539],[7692,7695],[7716,7719],7722,7723,7726,7727,[7734,7737],[7746,7751],[7768,7773],7778,7779,[7788,7791],[7808,7813],7826,7827,7831,[7840,7929]]}],["double-struck",{normal:[8450,8461,8469,8473,8474,8477,8484,[8508,8512],[8517,8521],120120,120121,[120123,120126],[120128,120132],120134,[120138,120144],[120146,120171],[120792,120801]],"double-struck":[305,567]},[8512]],["fraktur",{normal:[8460,8465,8476,8488,8493,120068,120069,[120071,120074],[120077,120084],[120086,120092],[120094,120119],[120172,120223]],fraktur:[305,567],"bold-fraktur":[305,567]}],["script",{normal:[8458,8459,8464,8466,8467,8472,8475,8492,[8495,8497],8499,8500,119964,119966,119967,119970,119973,119974,[119977,119980],[119982,119993],119995,[119997,120003],[120005,120067]],script:[305,567],"bold-script":[305,567]}],["sans-serif",{normal:[[120224,120431],[120802,120821]],"sans-serif":[305,567],"bold-sans-serif":[305,567],"sans-serif-italic":[305,567],"sans-serif-bold-italic":[305,567]}],["monospace",{normal:[[120432,120483],[120822,120831]],monospace:[305,567]}],["calligraphic",{"-tex-calligraphic":[[65,90]],"-tex-bold-calligraphic":[[65,90]]}],["symbols",{normal:[161,162,164,166,[169,171],173,174,[186,191],3647,8215,8218,8222,8226,8240,8241,[8249,8251],8253,8255,8256,8261,8262,8274,8276,8353,8358,8361,8363,8369,8370,8451,8457,8470,8471,8478,8480,8482,8494,8960,8965,8966,9250,9251,11800,12310,12311,[64256,64260],65279],"-largeop":[8512]},[8215]],["symbols-b-i",{bold:[161,162,164,166,[169,171],173,174,[186,191],3647,8218,8222,8226,8240,8241,[8249,8251],8253,8255,8256,8261,8262,8274,8276,8353,8358,8361,8363,8369,8451,8470,8471,8478,8480,8482,8494,8960,9250,9251],italic:[[161,167],[169,174],177,[181,183],[186,191],215,240,247,3647,8224,8225,8240,8241,8253,8255,8256,8274,8276,8353,8358,8361,8363,8369,8451,8470,8471,8478,8480,8482,8494,9250,9251,[64256,64260]],"bold-italic":[[161,167],[169,174],177,[181,183],[186,191],215,240,247,3647,8224,8225,8240,8241,8253,8255,8256,8274,8276,8353,8358,8361,8363,8369,8451,8470,8471,8478,8480,8482,8494,9250,9251,[64256,64260]]}],["arrows",{normal:[8607,8609,8613,8615,8621,[8624,8629],[8662,8665],8668,8669,[8678,8681],8691,10145,10228,10239,10502,10503,10572,10573,10575,10577,10588,10589,10592,10593,[11012,11015],11020,11021,11057,11059],bold:[],"-largeop":[8593,8595,[8597,8603],[8606,8611],8613,8615,[8617,8622],[8624,8627],8630,8631,[8636,8655],8657,8659,[8661,8667],[8678,8681],8691,8693,8694,[11012,11015],11020,11021,11057],"-lf-tp":[[8678,8681],10503,11013,11014],"-rt-bt":[[8678,8681],10502,11015,11020],"-ex-md":[8678,8679,11013,11014]},[8607,[8598,8601],8609,8613,8615,8621,[8624,8627],8630,8631,[8662,8665],8668,8669,[8678,8681],8691,10145,10237,10238,10502,10503,10572,10573,10575,10577,10588,10589,10592,10593,[11012,11015],11020,11021,11057]],["accents",{normal:[184,702,703,731,733,777,779,783,785,803,806,[812,819],831,845,[8403,8405],8408,[8413,8415],[8420,8422],[8424,8427],8432],"-smallop":[785,[812,816],818,819,831,845],"-largeop":[785,[812,816]],"-size3":[785,[812,816]],"-size4":[785,[812,816]],"-size5":[785,[812,816]],"-size6":[785,[812,816]],"-ex-md":[818,819,831,845]},[785,[812,816],818,819,831,845,8425]],["accents-b-i",{bold:[184,702,703,731,733,777,779,783,785,803,806,[814,818]],italic:[184,702,703,731,733,777,779,783,785,803,806,[814,818]],"bold-italic":[184,702,703,731,733,777,779,783,785,803,806,[814,818]]}],["shapes",{normal:[9472,9474,9484,9488,9492,9496,9500,9508,9516,9524,9532,9601,9608,[9617,9619],9644,9645,[9824,9831],9834,[9837,9839],9901,9902,10003,10016,10145,11034],bold:[9834,9901,9902],italic:[9834,9901,9902],"bold-italic":[9834,9901,9902]}],["stretchy",{normal:[8992,8993,9138,9139],bold:[],"-size3":[[8747,8755],10764,10769],"-size4":[[8747,8755],10764,10769],"-size5":[[8747,8755],10764,10769],"-size6":[[8747,8755],10764,10769],"-lf-tp":[[8747,8749],10764],"-rt-bt":[[8747,8749],10764],"-ex-md":[8748,8749,10764]},[[8747,8755],10764,10769,8512,[8719,8721],[8866,8869],[8896,8899],[10752,10758],10761]],["variants",{"-tex-variant":[34,39,42,96,126,170,176,178,179,185,186,8212,8289,8304,8305,[8308,8334]]}],["PUA",{normal:[[57344,57353],59395,[59908,59910],59913,59915,59917,59920,59927,59930,59932,59934,59935,59942,59946,59948,59951,59957,59959,59962,59966,59970,59973,60163,60164,60168,[60175,60178],60182,60185,60190,60191,60200,60201,60203,60209,60213,60214,60218,60219,60224,60232,60233,60237,60257,60259,60261,60270,60271,[60424,60430],60432,60433,63166,63198],bold:[[57344,57353],59395,[59908,59910],59913,59915,59917,59920,59927,59930,59932,59934,59935,59942,59946,59948,59951,59957,59959,59962,59966,59970,59973,60163,60164,60168,[60175,60178],60182,60185,60190,60191,60200,60201,60203,60209,60213,60214,60218,60219,60224,60232,60233,60237,60257,60259,60261,60270,60271,[60424,60430],60432,60433,63166,63198],italic:[[57344,57353],59395,[59908,59910],59913,59915,59917,59920,59927,59930,59932,59934,59935,59942,59946,59948,59951,59957,59959,59962,59966,59970,59973,60163,60164,60168,[60175,60178],60182,60185,60190,60191,60200,60201,60203,60209,60213,60214,60218,60219,60224,60232,60233,60237,60257,60259,60261,60270,60271,[60424,60430],60432,60433,63166,63198],"bold-italic":[[57344,57353],59395,[59908,59910],59913,59915,59917,59920,59927,59930,59932,59934,59935,59942,59946,59948,59951,59957,59959,59962,59966,59970,59973,60163,60164,60168,[60175,60178],60182,60185,60190,60191,60200,60201,60203,60209,60213,60214,60218,60219,60224,60232,60233,60237,60257,60259,60261,60270,60271,[60424,60430],60432,60433,63166,63198]}]]),MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml","4.1.1","font"),e({_:{output:{fonts:{"mathjax-termes":{chtml_ts:t}}}}});const z=MathJax._.components.package,T=(z.PackageError,z.Package);MathJax.startup&&(r(MathJax,"config",{output:{font:"[mathjax-termes]"},chtml:{fontData:m,dynamicPrefix:"[mathjax-termes]/chtml/dynamic"},loader:{paths:{"mathjax-termes":"[mathjax]/output/fonts/mathjax-termes"}}}),r(MathJax.config,"chtml",{fontURL:T.resolvePath("[mathjax-termes]/chtml/woff2",!1)}))})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/PUA.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/PUA.js
new file mode 100644
index 0000000..93c6a01
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/PUA.js
@@ -0,0 +1 @@
+(()=>{"use strict";const c=MathJax._.output.chtml.DynamicFonts.AddFontIds;MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont.dynamicSetup("","PUA",c({PU:{normal:{57344:[.676,.281,.722],57345:[.733,.218,.5],57346:[.662,.281,.722,{ic:.001}],57347:[.683,.281,.5,{ic:.005}],57348:[.662,.281,.611],57349:[.683,.281,.278],57350:[.662,.281,.722],57351:[.46,.281,.5],57352:[.662,.281,.667],57353:[.46,.281,.333,{ic:.002}],59395:[.683,0,.791,{ic:.005}],59908:[.798,-.501,.333,{ic:.008}],59909:[-.071,.209,.333],59910:[-.071,.209,.333],59913:[.798,-.501,.333],59915:[.772,-.501,.333],59917:[.669,-.512,.333],59920:[.772,-.501,.333],59927:[.794,-.506,.333,{ic:.007}],59930:[.794,-.506,.333,{ic:.007}],59932:[.808,-.506,.333,{ic:.007}],59934:[.771,-.506,.333,{ic:.007}],59935:[-.038,.281,.333],59942:[.676,-.505,.333,{sk:-.066}],59946:[.811,-.541,.333],59948:[.807,-.541,.333,{ic:.006}],59951:[.811,-.541,.333],59957:[.684,-.497,.333],59959:[.56,-.4,.333],59962:[-.113,.167,.333],59966:[-.113,.167,.333],59970:[.843,-.485,.333],59973:[-.087,.193,.333],60163:[.851,.245,.722],60164:[.675,.245,.444],60168:[.686,.014,.76],60175:[.686,.014,.76],60176:[0,0,0],60177:[0,0,0],60178:[0,0,0],60182:[.662,0,.58],60185:[-.089,.191,.333],60190:[.851,.245,.611],60191:[.675,.245,.444],60200:[.676,.014,1.06],60201:[.503,.241,.444],60203:[.745,.083,.722],60209:[.356,-.095,.333],60213:[.851,.245,.333],60214:[.675,.245,.278,{ic:.01}],60218:[.851,.014,.389],60219:[.675,.218,.278,{ic:.024}],60224:[.721,.059,1],60232:[.851,.245,.722],60233:[.675,.245,.5],60237:[.371,0,.336],60257:[.532,-.262,.278],60259:[.662,-.55,.333,{ic:.256}],60261:[.682,-.57,.277,{ic:.204}],60270:[.662,.209,.722],60271:[.45,.209,.5],60424:[.835,0,.722],60425:[.856,0,.5],60426:[.835,0,.611],60427:[.856,0,.278,{ic:.027}],60428:[.835,0,.611],60429:[.752,.01,.278,{ic:.027}],60430:[.832,0,.611],60432:[.824,.162,.722],60433:[.608,.162,.5],63166:[.46,.218,.278],63198:[.25,-.201,.75]}},PUB:{bold:{57344:[.691,.341,.778],57345:[.804,.206,.5],57346:[.676,.341,.778],57347:[.676,.341,.556],57348:[.676,.341,.667],57349:[.676,.341,.278],57350:[.676,.341,.722],57351:[.473,.341,.556],57352:[.676,.341,.722],57353:[.473,.341,.444],59395:[.691,0,.834],59908:[.861,-.508,.333,{ic:.03}],59909:[-.067,.231,.333,{ic:.019}],59910:[-.067,.231,.333,{ic:.019}],59913:[.861,-.508,.333,{ic:.019}],59915:[.856,-.508,.333,{ic:.019}],59917:[.692,-.529,.333],59920:[.828,-.508,.333,{ic:.019}],59927:[.857,-.511,.333,{ic:.036}],59930:[.857,-.511,.333,{ic:.036}],59932:[.898,-.511,.333,{ic:.036}],59934:[.827,-.511,.333,{ic:.036}],59935:[-.04,.341,.333],59942:[.703,-.518,.333],59946:[.878,-.546,.333,{ic:.01}],59948:[.875,-.546,.333,{ic:.035}],59951:[.878,-.546,.333,{ic:.004}],59957:[.725,-.496,.333],59959:[.583,-.393,.333],59962:[-.113,.185,.333],59966:[-.113,.185,.333],59970:[.903,-.503,.333,{ic:.01}],59973:[-.085,.212,.333,{ic:.016}],60163:[.888,.25,.722],60164:[.702,.25,.5],60168:[.689,.018,.747],60175:[.689,.018,.747],60176:[0,0,0],60177:[0,0,0],60178:[0,0,0],60182:[.676,0,.588],60185:[-.072,.226,.333],60190:[.888,.25,.667],60191:[.702,.25,.444],60200:[.692,.019,1.123],60201:[.52,.224,.5],60203:[.759,.083,.778],60209:[.419,-.039,.333],60213:[.888,.25,.389],60214:[.702,.25,.278,{ic:.018}],60218:[.888,.096,.5],60219:[.702,.203,.333,{ic:.015}],60224:[.745,.069,1],60232:[.888,.25,.778],60233:[.702,.25,.5],60237:[.376,.01,.382],60257:[.545,-.258,.278],60259:[.676,-.56,.333,{ic:.247}],60261:[.696,-.58,.277,{ic:.187}],60270:[.676,.231,.722],60271:[.461,.231,.556],60424:[.869,0,.778],60425:[.869,0,.556],60426:[.869,0,.667],60427:[.869,0,.278,{ic:.041}],60428:[.869,0,.667],60429:[.823,.012,.333,{ic:.048}],60430:[.87,0,.667],60432:[.866,.194,.778],60433:[.648,.194,.5],63166:[.461,.203,.333],63198:[.271,-.181,.75]}},PUI:{italic:{57344:[.666,.27,.722],57345:[.725,.206,.5],57346:[.653,.27,.667,{ic:.055}],57347:[.683,.27,.444,{ic:.017}],57348:[.653,.27,.556,{ic:.003}],57349:[.683,.27,.278,{ic:.001}],57350:[.653,.27,.667,{ic:.06}],57351:[.441,.27,.5],57352:[.653,.27,.611],57353:[.441,.27,.389,{ic:.023}],59395:[.682,.204,.702,{ic:.017}],59908:[.792,-.507,.333,{ic:.073}],59909:[-.094,.221,.333],59910:[-.094,.221,.333],59913:[.792,-.507,.333,{ic:.063}],59915:[.805,-.507,.333,{ic:.063}],59917:[.669,-.511,.333,{ic:.1}],59920:[.767,-.507,.333,{ic:.098}],59927:[.796,-.502,.333,{ic:.037}],59930:[.796,-.502,.333,{ic:.046}],59932:[.849,-.502,.333,{ic:.116}],59934:[.775,-.502,.333,{ic:.1}],59935:[-.04,.27,.25],59942:[.69,-.49,.333],59946:[.813,-.541,.333,{ic:.149}],59948:[.812,-.541,.333,{ic:.209}],59951:[.813,-.541,.333,{ic:.136}],59957:[.696,-.484,.183,{ic:.079}],59959:[.522,-.372,.333,{ic:.124}],59962:[-.132,.183,.333],59966:[-.132,.183,.333],59970:[.842,-.485,.333,{ic:.066}],59973:[-.104,.211,.333],60163:[.86,.245,.611],60164:[.675,.245,.5],60168:[.686,.014,.76],60175:[.686,.014,.76],60176:[0,0,0],60177:[0,0,0],60178:[0,0,0],60182:[.653,0,.58,{ic:.089}],60185:[-.105,.211,.333],60190:[.86,.245,.611,{ic:.023}],60191:[.675,.245,.444],60200:[.667,.018,.909,{ic:.078}],60201:[.487,.232,.5],60203:[.736,.083,.722],60209:[.354,-.093,.333],60213:[.86,.245,.333,{ic:.097}],60214:[.675,.245,.278,{ic:.061}],60218:[.86,.018,.444,{ic:.093}],60219:[.675,.207,.278,{ic:.086}],60224:[.712,.059,1],60232:[.86,.245,.722],60233:[.675,.245,.5,{ic:.02}],60237:[.371,0,.351],60257:[.513,-.276,.278,{ic:.034}],60259:[.653,-.541,.333,{ic:.417}],60261:[.673,-.561,.277,{ic:.371}],60270:[.653,.221,.722,{ic:.043}],60271:[.441,.221,.5],60424:[.845,0,.722,{ic:.045}],60425:[.875,.009,.5,{ic:.134}],60426:[.845,0,.556,{ic:.003}],60427:[.875,.011,.278,{ic:.167}],60428:[.845,0,.556,{ic:.077}],60429:[.738,.011,.278,{ic:.159}],60430:[.84,0,.556,{ic:.077}],60432:[.832,.18,.722],60433:[.607,.18,.5],63166:[.441,.207,.278],63198:[.243,-.197,.667,{ic:.02}]}},PUBI:{"bold-italic":{57344:[.685,.324,.722],57345:[.776,.203,.5],57346:[.669,.324,.667,{ic:.035}],57347:[.699,.324,.5],57348:[.669,.324,.611],57349:[.699,.324,.278,{ic:.012}],57350:[.669,.324,.722,{ic:.026}],57351:[.462,.324,.556],57352:[.669,.324,.667],57353:[.462,.324,.389],59395:[.704,.205,.771],59908:[.804,-.505,.333,{ic:.068}],59909:[-.075,.206,.333],59910:[-.075,.206,.333],59913:[.804,-.505,.333,{ic:.046}],59915:[.799,-.505,.333,{ic:.046}],59917:[.671,-.509,.333,{ic:.107}],59920:[.784,-.505,.333,{ic:.093}],59927:[.807,-.5,.333,{ic:.029}],59930:[.807,-.5,.333,{ic:.029}],59932:[.848,-.5,.333,{ic:.107}],59934:[.79,-.5,.333,{ic:.094}],59935:[-.04,.324,.25],59942:[.696,-.485,.333],59946:[.849,-.525,.333,{ic:.175}],59948:[.847,-.525,.333,{ic:.238}],59951:[.849,-.525,.333,{ic:.161}],59957:[.693,-.487,.197,{ic:.054}],59959:[.561,-.396,.333,{ic:.132}],59962:[-.106,.176,.333],59966:[-.106,.176,.333],59970:[.862,-.483,.333,{ic:.063}],59973:[-.081,.2,.333],60163:[.863,.25,.667],60164:[.68,.25,.5],60168:[.669,.018,.747],60175:[.669,.018,.747],60176:[0,0,0],60177:[0,0,0],60178:[0,0,0],60182:[.669,0,.588,{ic:.098}],60185:[-.073,.208,.333],60190:[.863,.25,.667],60191:[.68,.25,.444],60200:[.685,.018,1.022,{ic:.056}],60201:[.507,.24,.5,{ic:.053}],60203:[.752,.083,.722],60209:[.414,-.034,.333],60213:[.863,.25,.389,{ic:.054}],60214:[.68,.25,.278,{ic:.04}],60218:[.863,.099,.5,{ic:.062}],60219:[.68,.207,.278,{ic:.058}],60224:[.737,.068,1],60232:[.863,.25,.722],60233:[.68,.25,.5,{ic:.028}],60237:[.376,.01,.376],60257:[.553,-.256,.278,{ic:.041}],60259:[.669,-.553,.333,{ic:.412}],60261:[.689,-.573,.277,{ic:.358}],60270:[.669,.206,.722,{ic:.022}],60271:[.462,.206,.556],60424:[.85,0,.778,{ic:.021}],60425:[.88,.009,.556,{ic:.121}],60426:[.85,0,.611],60427:[.88,.009,.278,{ic:.165}],60428:[.85,0,.611,{ic:.039}],60429:[.775,.009,.278,{ic:.165}],60430:[.855,0,.611,{ic:.039}],60432:[.852,.186,.722],60433:[.629,.186,.5],63166:[.462,.207,.278],63198:[.269,-.178,.75,{ic:.001}]}}},"GT"),{},["MJX-GT-PU","MJX-GT-PUB","MJX-GT-PUI","MJX-GT-PUBI"]);MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/PUA","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/accents-b-i.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/accents-b-i.js
new file mode 100644
index 0000000..8a042c3
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/accents-b-i.js
@@ -0,0 +1 @@
+(()=>{"use strict";const d=MathJax._.output.chtml.DynamicFonts.AddFontIds;MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont.dynamicSetup("","accents-b-i",d({ACB:{bold:{184:[.005,.218,.333],702:[.662,-.321,.374],703:[.662,-.321,.374],731:[.017,.25,.333],733:[.703,-.518,.333,{ic:.132}],777:[.725,-.496,0,{dx:.249}],779:[.703,-.518,0,{dx:.165}],783:[.703,-.518,0,{dx:.334}],785:[.692,-.529,0,{dx:.249}],803:[-.072,.226,0,{dx:.251}],806:[-.04,.341,0,{dx:.249}],814:[-.067,.231,0,{dx:.249}],815:[-.067,.231,0,{dx:.249}],816:[-.085,.212,0,{dx:.249}],817:[-.113,.185,0,{dx:.25}],818:[-.113,.185,0,{dx:.25}]}},ACI:{italic:{184:[.005,.217,.333],702:[.641,-.324,.335,{ic:.045}],703:[.641,-.324,.335,{ic:.055}],731:[.017,.245,.333],733:[.69,-.49,.333,{ic:.092}],777:[.696,-.484,0,{dx:.081}],779:[.69,-.49,0,{dx:.068}],783:[.69,-.49,0,{dx:.128}],785:[.669,-.511,0,{dx:.134}],803:[-.105,.211,0,{dx:.291}],806:[-.04,.27,0,{dx:.296}],814:[-.094,.221,0,{dx:.287}],815:[-.094,.221,0,{dx:.322}],816:[-.104,.211,0,{dx:.292}],817:[-.132,.183,0,{dx:.292}],818:[-.132,.183,0,{dx:.292}]}},ACBI:{"bold-italic":{184:[.005,.218,.333],702:[.655,-.322,.348,{ic:.007}],703:[.655,-.322,.348,{ic:.011}],731:[.017,.25,.333],733:[.696,-.485,.333,{ic:.112}],777:[.693,-.487,0,{dx:.081}],779:[.696,-.485,0,{dx:.051}],783:[.696,-.485,0,{dx:.149}],785:[.671,-.509,0,{dx:.134}],803:[-.073,.208,0,{dx:.287}],806:[-.04,.324,0,{dx:.336}],814:[-.075,.206,0,{dx:.283}],815:[-.075,.206,0,{dx:.318}],816:[-.081,.2,0,{dx:.286}],817:[-.106,.176,0,{dx:.288}],818:[-.106,.176,0,{dx:.288}]}}},"GT"),{},["MJX-GT-ACB","MJX-GT-ACI","MJX-GT-ACBI"]);MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/accents-b-i","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/accents.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/accents.js
new file mode 100644
index 0000000..5edc27d
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/accents.js
@@ -0,0 +1 @@
+(()=>{"use strict";const s=MathJax._.output.chtml.DynamicFonts.AddFontIds,t=MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont,d=MathJax._.output.common.Direction,e=(d.DIRECTION,d.V,d.H);t.dynamicSetup("","accents",s({AC:{normal:{184:[.005,.215,.333],702:[.65,-.321,.354],703:[.65,-.321,.354],731:[.017,.245,.333],733:[.676,-.505,.333,{ic:.094}],777:[.704,-.517,0,{dx:.249}],779:[.711,-.54,0,{dx:.184}],783:[.711,-.54,0,{dx:.315}],785:[.692,-.567,0,{dx:.964,sk:.714}],803:[-.089,.191,0,{dx:.25}],806:[-.038,.281,0,{dx:.249}],812:[-.07,.204,0,{dx:.772,sk:.522}],813:[-.08,.214,0,{dx:.876,sk:.626}],814:[-.07,.195,0,{dx:.828,sk:.578}],815:[-.088,.213,0,{dx:.791,sk:.541}],816:[-.088,.197,0,{dx:.961,sk:.711}],817:[-.113,.167,0,{dx:.249}],818:[-.07,.114,0,{dx:.983,sk:.734}],819:[-.07,.228,0,{dx:1.006,sk:.756}],831:[.746,-.588,0,{dx:.844,sk:.595}],845:[-.084,.26,0,{dx:.25}],8403:[.5,0,0,{sk:.302}],8404:[.768,-.599,0,{dx:.601,sk:.351}],8405:[.768,-.599,0,{dx:.658,sk:.408}],8408:[.4,-.1,0,{sk:.43}],8413:[.668,.168,0],8414:[.65,.15,0],8415:[.872,.372,0],8420:[.735,.209,0],8421:[.65,.15,0,{sk:.436}],8422:[.65,.15,0,{sk:.436}],8424:[-.07,.17,0,{dx:.815,sk:.565}],8425:[.726,-.548,0,{dx:.85,sk:.6}],8426:[.43,-.07,0,{sk:.235}],8427:[.65,.15,0,{sk:.458}],8432:[.747,-.509,0,{dx:.9,sk:.65}]}},"":{"-smallop":{785:[.706,-.554,.62],812:[-.07,.23,.608],813:[-.08,.24,.608],814:[-.07,.222,.62],815:[-.088,.24,.62],816:[-.088,.245,.601],818:[-.07,.114,.5],819:[-.07,.228,.5],831:[.746,-.588,.5],845:[-.084,.26,.68]},"-largeop":{785:[.707,-.554,.74],812:[-.07,.231,.727],813:[-.08,.241,.727],814:[-.07,.223,.74],815:[-.088,.241,.74],816:[-.088,.244,.72]},"-size3":{785:[.707,-.554,.885],812:[-.07,.232,.87],813:[-.08,.242,.87],814:[-.07,.223,.885],815:[-.088,.241,.885],816:[-.088,.244,.863]},"-size4":{785:[.708,-.553,1.058],812:[-.07,.233,1.041],813:[-.08,.243,1.041],814:[-.07,.225,1.058],815:[-.088,.243,1.058],816:[-.088,.243,1.037]},"-size5":{785:[.709,-.553,1.266],812:[-.07,.233,1.249],813:[-.08,.243,1.249],814:[-.07,.225,1.266],815:[-.088,.243,1.266],816:[-.088,.242,1.241]},"-size6":{785:[.71,-.553,1.515],812:[-.07,.235,1.496],813:[-.08,.245,1.496],814:[-.07,.226,1.515],815:[-.088,.244,1.515],816:[-.088,.246,1.491]},"-ex-md":{818:[-.07,.114,.166],819:[-.07,.228,.166],831:[.746,-.588,.166],845:[-.15,.194,.13]}}},"GT"),{785:{dir:e,sizes:[.35,.62,.74,.885,1.058,1.266,1.515]},812:{dir:e,sizes:[.342,.608,.727,.87,1.041,1.249,1.496]},813:{dir:e,sizes:[.342,.608,.727,.87,1.041,1.249,1.496]},814:{dir:e,sizes:[.35,.62,.74,.885,1.058,1.266,1.515]},815:{dir:e,sizes:[.35,.62,.74,.885,1.058,1.266,1.515]},816:{dir:e,sizes:[.334,.601,.72,.863,1.037,1.241,1.491]},818:{dir:e,sizes:[.333,.5],stretch:[0,818],stretchv:[0,1],HDW:[-.07,.114,0],hd:[-.07,.114]},819:{dir:e,sizes:[.333,.5],stretch:[0,819],stretchv:[0,1],HDW:[-.07,.228,0],hd:[-.07,.228]},831:{dir:e,sizes:[.333,.5],stretch:[0,831],stretchv:[0,1],HDW:[.746,-.588,0],hd:[.746,-.588]},845:{dir:e,sizes:[.396,.68],stretch:[8430,845,8431],stretchv:[2,1,3],HDW:[-.084,.26,0],hd:[-.15,.194]},8425:{dir:e,sizes:[.375,.75,1.125,1.5,1.875,2.25,2.625],schar:[8425,9140],stretch:[9140,9140,9140],stretchv:[2,1,3],HDW:[.758,-.548,0],hd:[.758,-.674]}},["MJX-GT-AC"]);MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/accents","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/arrows.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/arrows.js
new file mode 100644
index 0000000..4ba7062
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/arrows.js
@@ -0,0 +1 @@
+(()=>{"use strict";const s=MathJax._.output.chtml.DynamicFonts.AddFontIds,t=MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont,r=MathJax._.output.common.Direction,i=(r.DIRECTION,r.V),e=r.H;t.dynamicSetup("","arrows",s({AR:{normal:{8607:[.69,.18,.52],8609:[.68,.19,.52],8613:[.6,.09,.52],8615:[.59,.1,.52],8621:[.43,-.07,1.04],8624:[.598,.098,.54],8625:[.598,.098,.54],8626:[.598,.098,.54],8627:[.598,.098,.54],8628:[.478,-.012,.77],8629:[.555,.055,.626],8662:[.497,.063,.72],8663:[.497,.063,.72],8664:[.563,-.003,.72],8665:[.563,-.003,.72],8668:[.43,-.07,.85],8669:[.43,-.07,.85],8678:[.47,-.03,1.073],8679:[.715,.198,.6],8680:[.47,-.03,1.073],8681:[.698,.215,.6],8691:[.715,.215,.6],10145:[.47,-.03,1.03],10228:[.568,.068,1.132],10239:[.43,-.07,1.17],10502:[.47,-.03,1.03],10503:[.47,-.03,1.03],10572:[.65,.09,.52],10573:[.65,.09,.52],10575:[.65,.09,.52],10577:[.65,.09,.52],10588:[.649,.1,.52],10589:[.59,.09,.52],10592:[.649,.1,.52],10593:[.59,.09,.52],11012:[.47,-.03,1.091],11013:[.47,-.03,1.03],11014:[.69,.18,.6],11015:[.68,.19,.6],11020:[.47,-.03,1.04],11021:[.69,.19,.6],11057:[.83,.33,.85],11059:[.43,-.07,1.17]}},ARB:{bold:{}},"":{"-largeop":{8593:[.76,.25,.52],8595:[.75,.26,.52],8597:[.85,.35,.52],8598:[.611,.122,.893],8599:[.611,.122,.893],8600:[.622,.111,.893],8601:[.622,.111,.893],8602:[.43,-.07,1.17],8603:[.43,-.07,1.17],8606:[.43,-.07,1.35],8607:[.85,.34,.52],8608:[.43,-.07,1.35],8609:[.84,.35,.52],8610:[.43,-.07,1.36],8611:[.43,-.07,1.36],8613:[.76,.25,.52],8615:[.75,.26,.52],8617:[.508,-.07,1.196],8618:[.508,-.07,1.196],8619:[.508,-.018,1.196],8620:[.508,-.018,1.196],8621:[.43,-.07,1.36],8622:[.43,-.07,1.36],8624:[.694,.194,.668],8625:[.694,.194,.668],8626:[.694,.194,.668],8627:[.694,.194,.668],8630:[.576,-.241,1.039],8631:[.576,-.241,1.039],8636:[.43,-.224,1.16],8637:[.276,-.07,1.16],8638:[.75,.25,.366],8639:[.75,.25,.366],8640:[.43,-.224,1.16],8641:[.276,-.07,1.16],8642:[.75,.25,.366],8643:[.75,.25,.366],8644:[.63,.13,1.18],8645:[.76,.26,.92],8646:[.63,.13,1.18],8647:[.63,.13,1.17],8648:[.76,.25,.92],8649:[.63,.13,1.17],8650:[.75,.26,.92],8651:[.526,.026,1.16],8652:[.526,.026,1.16],8653:[.5,0,1.17],8654:[.5,0,1.36],8655:[.5,0,1.17],8657:[.76,.25,.6],8659:[.75,.26,.6],8661:[.85,.35,.6],8662:[.611,.176,.946],8663:[.611,.176,.946],8664:[.676,.111,.946],8665:[.676,.111,.946],8666:[.572,.072,1.35],8667:[.572,.072,1.35],8678:[.47,-.03,1.393],8679:[.875,.358,.6],8680:[.47,-.03,1.393],8681:[.858,.375,.6],8691:[.875,.375,.6],8693:[.76,.26,.92],8694:[.83,.33,1.17],11012:[.47,-.03,1.411],11013:[.47,-.03,1.35],11014:[.85,.34,.6],11015:[.84,.35,.6],11020:[.47,-.03,1.36],11021:[.85,.35,.6],11057:[.83,.33,1.17]},"-lf-tp":{8678:[.47,-.03,.463],8679:[.462,0,.6],8680:[.344,-.156,.463],8681:[.463,0,.6],10503:[.47,-.03,.446],11013:[.47,-.03,.446],11014:[.446,0,.6]},"-rt-bt":{8678:[.344,-.156,.462],8679:[.463,0,.6],8680:[.47,-.03,.462],8681:[.462,0,.6],10502:[.47,-.03,.446],11015:[.446,0,.6],11020:[.47,-.03,.45]},"-ex-md":{8678:[.344,-.156,.308],8679:[.308,0,.6],11013:[.326,-.174,.298],11014:[.298,0,.6]}}},"GT"),{8598:{dir:i,sizes:[.507,.734],variants:[0,2]},8599:{dir:i,sizes:[.507,.734],variants:[0,2]},8600:{dir:i,sizes:[.507,.734],variants:[0,2]},8601:{dir:i,sizes:[.507,.734],variants:[0,2]},8607:{dir:i,sizes:[.871,1.191],variants:[0,2],stretch:[8607,8593],stretchv:[2,1],HDW:[.69,.18,.52]},8609:{dir:i,sizes:[.871,1.191],variants:[0,2],stretch:[0,8593,8609],stretchv:[0,1,3],HDW:[.68,.19,.52]},8613:{dir:i,sizes:[.691,1.011],variants:[0,2],stretch:[8593,8593,8613],stretchv:[2,1,3],HDW:[.6,.09,.52]},8615:{dir:i,sizes:[.691,1.011],variants:[0,2],stretch:[8615,8593,8595],stretchv:[2,1,3],HDW:[.59,.1,.52]},8621:{dir:e,sizes:[1.04,1.36],variants:[0,2]},8624:{dir:i,sizes:[.697,.889],variants:[0,2]},8625:{dir:i,sizes:[.697,.889],variants:[0,2]},8626:{dir:i,sizes:[.697,.889],variants:[0,2]},8627:{dir:i,sizes:[.697,.889],variants:[0,2]},8630:{dir:e,sizes:[.799,1.039],variants:[0,2]},8631:{dir:e,sizes:[.799,1.039],variants:[0,2]},8662:{dir:i,sizes:[.561,.788],variants:[0,2]},8663:{dir:i,sizes:[.561,.788],variants:[0,2]},8664:{dir:i,sizes:[.561,.788],variants:[0,2]},8665:{dir:i,sizes:[.561,.788],variants:[0,2]},8668:{dir:e,sizes:[.85,1.17],variants:[0,0],schar:[8668,11059]},8669:{dir:e,sizes:[.85,1.17],variants:[0,0],schar:[8669,10239]},8678:{dir:e,sizes:[1.073,1.393],variants:[0,2],stretch:[8678,8678,8678],stretchv:[2,1,3],HDW:[.47,-.03,1.073],hd:[.344,-.156]},8679:{dir:i,sizes:[.914,1.234],variants:[0,2],stretch:[8679,8679,8679],stretchv:[2,1,3],HDW:[.715,.198,.6]},8680:{dir:e,sizes:[1.073,1.393],variants:[0,2],stretch:[8680,8678,8680],stretchv:[2,1,3],HDW:[.47,-.03,1.073],hd:[.344,-.156]},8681:{dir:i,sizes:[.914,1.234],variants:[0,2],stretch:[8681,8679,8681],stretchv:[2,1,3],HDW:[.698,.215,.6]},8691:{dir:i,sizes:[.931,1.251],variants:[0,2],stretch:[8679,8679,8681],stretchv:[2,1,3],HDW:[.715,.215,.6]},10145:{dir:e,sizes:[1.03,1.35],variants:[0,2],stretch:[0,11013,11020],stretchv:[0,1,3],HDW:[.47,-.03,1.03],hd:[.326,-.174]},10237:{c:10502,dir:e,sizes:[1.03,1.35],variants:[0,0],schar:[10502,10237],stretch:[8656,8656,10502],stretchv:[2,1,3],HDW:[.47,-.03,1.03],hd:[.352,-.148]},10238:{c:10503,dir:e,sizes:[1.03,1.35],variants:[0,0],schar:[10503,10238],stretch:[10503,8656,8658],stretchv:[2,1,3],HDW:[.47,-.03,1.03],hd:[.352,-.148]},10502:{dir:e,sizes:[1.03,1.35],variants:[0,0],schar:[10502,10237],stretch:[8656,8656,10502],stretchv:[2,1,3],HDW:[.47,-.03,1.03],hd:[.352,-.148]},10503:{dir:e,sizes:[1.03,1.35],variants:[0,0],schar:[10503,10238],stretch:[10503,8656,8658],stretchv:[2,1,3],HDW:[.47,-.03,1.03],hd:[.352,-.148]},10572:{dir:i,sizes:[.74],stretch:[10572,8593,10572],stretchv:[2,1,3],HDW:[.65,.09,.52]},10573:{dir:i,sizes:[.74],stretch:[10573,8593,10573],stretchv:[2,1,3],HDW:[.65,.09,.52]},10575:{dir:i,sizes:[.74],stretch:[10572,8593,10573],stretchv:[2,1,3],HDW:[.65,.09,.52]},10577:{dir:i,sizes:[.74],stretch:[10573,8593,10572],stretchv:[2,1,3],HDW:[.65,.09,.52]},10588:{dir:i,sizes:[.749],stretch:[10572,8593,8613],stretchv:[2,1,3],HDW:[.649,.1,.52]},10589:{dir:i,sizes:[.679],stretch:[8615,8593,10573],stretchv:[2,1,3],HDW:[.59,.09,.52]},10592:{dir:i,sizes:[.749],stretch:[10573,8593,8613],stretchv:[2,1,3],HDW:[.649,.1,.52]},10593:{dir:i,sizes:[.679],stretch:[8615,8593,10572],stretchv:[2,1,3],HDW:[.59,.09,.52]},11012:{dir:e,sizes:[1.091,1.411],variants:[0,2],stretch:[8678,8678,8680],stretchv:[2,1,3],HDW:[.47,-.03,1.091],hd:[.344,-.156]},11013:{dir:e,sizes:[1.03,1.35],variants:[0,2],stretch:[11013,11013],stretchv:[2,1],HDW:[.47,-.03,1.03],hd:[.326,-.174]},11014:{dir:i,sizes:[.871,1.191],variants:[0,2],stretch:[11014,11014],stretchv:[2,1],HDW:[.69,.18,.6]},11015:{dir:i,sizes:[.871,1.191],variants:[0,2],stretch:[0,11014,11015],stretchv:[0,1,3],HDW:[.68,.19,.6]},11020:{dir:e,sizes:[1.04,1.36],variants:[0,2],stretch:[0,11013,11020],stretchv:[0,1,3],HDW:[.47,-.03,1.04],hd:[.326,-.174]},11021:{dir:i,sizes:[.881,1.201],variants:[0,2],stretch:[11014,11014,11015],stretchv:[2,1,3],HDW:[.69,.19,.6]},11057:{dir:e,sizes:[.85,1.17],variants:[0,2],stretch:[11057,8694],stretchv:[2,1],HDW:[.83,.33,.85],hd:[.676,.176]}},["MJX-GT-AR","MJX-GT-ARB"]);MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/arrows","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/calligraphic.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/calligraphic.js
new file mode 100644
index 0000000..8ae6312
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/calligraphic.js
@@ -0,0 +1 @@
+(()=>{"use strict";const c=MathJax._.output.chtml.DynamicFonts.AddFontIds;MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont.dynamicSetup("","calligraphic",c({C:{"-tex-calligraphic":{65:[.722,.05,.798],66:[.706,.022,.656,{ic:.009}],67:[.705,.024,.526,{ic:.008}],68:[.683,0,.771],69:[.705,.022,.527,{ic:.038}],70:[.691,.032,.719,{ic:.111}],71:[.705,.119,.594,{ic:.007}],72:[.683,.049,.844],73:[.683,0,.544,{ic:.091}],74:[.683,.119,.677,{ic:.163}],75:[.705,.022,.761],76:[.705,.022,.689],77:[.705,.05,1.2],78:[.775,.05,.82,{ic:.158}],79:[.705,.022,.796],80:[.683,.05,.695,{ic:.038}],81:[.705,.124,.816],82:[.683,.022,.847],83:[.705,.022,.605,{ic:.037}],84:[.717,.068,.544,{ic:.29}],85:[.683,.028,.625,{ic:.063}],86:[.683,.045,.612,{ic:.048}],87:[.683,.045,.987,{ic:.049}],88:[.683,0,.713,{ic:.095}],89:[.683,.135,.668,{ic:.049}],90:[.683,0,.724,{ic:.043}]}},CB:{"-tex-bold-calligraphic":{65:[.745,.049,.92,{ic:.049}],66:[.705,.017,.747],67:[.703,.02,.612],68:[.686,0,.892],69:[.703,.017,.606,{ic:.021}],70:[.686,.031,.814,{ic:.116}],71:[.703,.114,.681],72:[.686,.048,.987],73:[.686,0,.642,{ic:.098}],74:[.686,.114,.779,{ic:.159}],75:[.703,.017,.871],76:[.703,.017,.788],77:[.703,.049,1.377],78:[.825,.049,.937,{ic:.167}],79:[.703,.017,.905],80:[.686,.061,.809,{ic:.037}],81:[.703,.14,.939],82:[.686,.017,.989],83:[.703,.017,.696,{ic:.025}],84:[.72,.069,.644,{ic:.304}],85:[.686,.024,.714,{ic:.058}],86:[.686,.069,.737,{ic:.039}],87:[.686,.069,1.168,{ic:.04}],88:[.686,0,.816,{ic:.091}],89:[.686,.156,.758,{ic:.042}],90:[.686,0,.818,{ic:.036}]}}},"GT"));MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/calligraphic","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/double-struck.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/double-struck.js
new file mode 100644
index 0000000..30c3f72
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/double-struck.js
@@ -0,0 +1 @@
+(()=>{"use strict";const s=MathJax._.output.chtml.DynamicFonts.AddFontIds,k=MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont,t=MathJax._.output.common.Direction,a=(t.DIRECTION,t.V);t.H;k.dynamicSetup("","double-struck",s({DS:{normal:{8450:[.718,.014,.816,{sk:-.125}],8461:[.702,0,.923,{sk:-.069}],8469:[.702,.011,.915,{sk:-.31}],8473:[.702,0,.754,{sk:-.01}],8474:[.716,.178,.875,{sk:-.31}],8477:[.702,0,.876,{sk:-.02}],8484:[.702,0,.808,{sk:-.039}],8508:[.511,.016,.738,{sk:-.121}],8509:[.491,.234,.715,{sk:-.245}],8510:[.702,0,.734,{sk:-.118}],8511:[.702,0,.883,{sk:-.194}],8512:[.728,.228,.884],8517:[.702,0,.869,{ic:.001}],8518:[.727,.013,.699],8519:[.5,.01,.624],8520:[.728,0,.455],8521:[.728,.218,.493,{ic:.027}],120120:[.714,0,.923,{sk:-.17}],120121:[.702,0,.806,{sk:-.099}],120123:[.702,0,.869,{sk:-.16}],120124:[.702,0,.795,{sk:-.121}],120125:[.702,0,.756,{sk:-.041}],120126:[.719,.014,.897,{sk:-.183}],120128:[.702,0,.517],120129:[.702,.014,.6,{sk:.043}],120130:[.702,0,.929,{sk:-.13}],120131:[.702,0,.795,{sk:.011}],120132:[.702,0,1.037,{sk:-.154}],120134:[.716,.014,.873,{sk:-.057}],120138:[.716,.017,.679,{sk:.021}],120139:[.702,0,.8,{sk:-.01}],120140:[.702,.014,.911,{sk:-.174}],120141:[.702,.013,.892,{sk:-.056}],120142:[.702,.014,1.167,{sk:-.283}],120143:[.702,0,.914,{sk:-.126}],120144:[.702,0,.903,{sk:-.144}],120146:[.5,.01,.63,{sk:.023}],120147:[.729,.01,.695,{sk:.129}],120148:[.5,.01,.608,{sk:.034}],120149:[.727,.013,.699,{sk:-.013}],120150:[.5,.01,.624],120151:[.723,0,.583,{sk:-.017}],120152:[.5,.218,.632,{sk:-.22}],120153:[.73,0,.725,{sk:-.104}],120154:[.728,0,.455,{sk:.227}],120155:[.728,.218,.493,{sk:.035}],120156:[.727,0,.754,{sk:-.173}],120157:[.725,0,.46,{sk:.103}],120158:[.502,0,1.022,{sk:-.399}],120159:[.503,0,.713,{sk:-.257}],120160:[.501,.011,.661,{sk:-.221}],120161:[.5,.217,.702,{sk:.027}],120162:[.501,.217,.698,{sk:-.113}],120163:[.501,0,.562],120164:[.503,.014,.497,{sk:-.034}],120165:[.601,.014,.471,{sk:.101}],120166:[.486,.017,.713,{sk:-.161}],120167:[.49,.014,.69,{sk:-.098}],120168:[.49,.014,.936,{sk:-.341}],120169:[.487,0,.677,{sk:-.065}],120170:[.49,.218,.704,{sk:-.104}],120171:[.49,0,.62,{sk:.047}],120792:[.716,.014,.672,{sk:.104}],120793:[.716,0,.503,{sk:.233}],120794:[.716,-.001,.659,{sk:.092}],120795:[.718,.014,.61,{sk:.159}],120796:[.716,0,.723,{sk:.149}],120797:[.727,.014,.607,{sk:-.029}],120798:[.723,.014,.672,{sk:-.033}],120799:[.703,.008,.63,{sk:-.033}],120800:[.716,.014,.599,{sk:-.033}],120801:[.716,.021,.672,{sk:.042}]},"double-struck":{305:[.501,0,.455,{sk:-.116}],567:[.497,.218,.493,{sk:.196}]}}},"GT"),{8512:{dir:a,sizes:[.957,1.361],variants:[0,2]}});MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/double-struck","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/fraktur.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/fraktur.js
new file mode 100644
index 0000000..9fbd00e
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/fraktur.js
@@ -0,0 +1 @@
+(()=>{"use strict";const s=MathJax._.output.chtml.DynamicFonts.AddFontIds;MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont.dynamicSetup("","fraktur",s({F:{normal:{120068:[.656,.022,.742,{sk:-.17}],120069:[.657,.021,.853,{sk:-.178}],8493:[.657,.019,.707,{sk:-.214}],120071:[.656,.038,.865,{sk:-.157}],120072:[.66,.019,.684,{sk:-.093}],120073:[.658,.172,.695],120074:[.671,.021,.771,{sk:-.136}],8460:[.659,.159,.749,{sk:-.128}],8465:[.659,.022,.634,{sk:-.091}],120077:[.659,.152,.633],120078:[.656,.021,.764,{sk:-.071}],120079:[.656,.021,.603,{sk:.086}],120080:[.659,.022,1.03,{sk:-.12}],120081:[.659,.022,.798,{sk:-.038}],120082:[.675,.019,.813,{sk:-.069}],120083:[.658,.175,.731,{sk:-.046}],120084:[.675,.031,.869,{sk:-.159}],8476:[.656,.021,.828],120086:[.657,.021,.794,{sk:-.038}],120087:[.658,.021,.708,{sk:-.066}],120088:[.657,.028,.685,{sk:-.035}],120089:[.656,.019,.842,{sk:-.127}],120090:[.669,.023,1.065,{sk:-.225}],120091:[.654,.02,.68,{sk:-.029}],120092:[.66,.178,.774,{sk:.02}],8488:[.656,.183,.589,{sk:.119}],120094:[.44,.031,.52,{sk:.085}],120095:[.637,.022,.466,{sk:.091}],120096:[.442,.024,.384,{sk:.193}],120097:[.637,.021,.484,{sk:.139}],120098:[.44,.024,.41,{sk:.176}],120099:[.64,.174,.412,{sk:.158}],120100:[.44,.177,.487,{sk:.17}],120101:[.637,.175,.474,{sk:.086}],120102:[.647,.025,.337,{sk:.111}],120103:[.647,.177,.319,{sk:.13}],120104:[.637,.016,.35,{sk:.113}],120105:[.637,.016,.343,{sk:.163}],120106:[.445,.024,.73,{sk:-.051}],120107:[.445,.024,.534,{sk:.023}],120108:[.446,.021,.464,{sk:.09}],120109:[.463,.174,.498,{sk:.111}],120110:[.442,.178,.474,{sk:.046}],120111:[.445,.024,.409,{sk:.179}],120112:[.44,.02,.505,{sk:.102}],120113:[.543,.016,.354,{sk:.056}],120114:[.44,.028,.534,{sk:-.124}],120115:[.463,.021,.484,{sk:.095}],120116:[.463,.021,.666,{sk:.046}],120117:[.447,.022,.473,{sk:.124}],120118:[.463,.175,.485,{sk:.077}],120119:[.459,.177,.371,{sk:.203}]},fraktur:{305:[.445,.025,.337,{sk:.204}],567:[.445,.177,.319,{sk:.164}]}},FB:{normal:{120172:[.654,.024,.781,{sk:-.098}],120173:[.657,.019,.859,{sk:-.113}],120174:[.659,.02,.731,{sk:-.038}],120175:[.659,.038,.836,{sk:-.073}],120176:[.66,.018,.717,{sk:-.21}],120177:[.663,.167,.731],120178:[.676,.02,.812],120179:[.658,.164,.77,{sk:-.038}],120180:[.666,.023,.651,{sk:.07}],120181:[.666,.191,.689,{sk:-.052}],120182:[.666,.02,.795,{sk:-.054}],120183:[.658,.021,.654,{sk:.037}],120184:[.665,.034,1.091,{sk:.074}],120185:[.66,.027,.834,{sk:-.014}],120186:[.669,.018,.837,{sk:.082}],120187:[.677,.17,.781],120188:[.669,.068,.937],120189:[.657,.019,.852,{sk:.022}],120190:[.656,.019,.811,{sk:.113}],120191:[.66,.02,.746,{sk:.103}],120192:[.655,.03,.72,{sk:-.086}],120193:[.656,.018,.838,{sk:.095}],120194:[.667,.021,1.058,{sk:-.036}],120195:[.652,.019,.716,{sk:-.067}],120196:[.661,.209,.774,{sk:.142}],120197:[.653,.179,.612,{sk:.172}],120198:[.439,.035,.549,{sk:.241}],120199:[.627,.019,.491,{sk:.163}],120200:[.441,.03,.42,{sk:.31}],120201:[.629,.019,.506,{sk:.183}],120202:[.439,.03,.438,{sk:.228}],120203:[.629,.167,.44,{sk:.199}],120204:[.439,.169,.508,{sk:.224}],120205:[.627,.175,.507,{sk:.195}],120206:[.657,.025,.378,{sk:.381}],120207:[.657,.169,.36,{sk:.269}],120208:[.628,.021,.379,{sk:.262}],120209:[.627,.026,.388,{sk:.224}],120210:[.45,.02,.752,{sk:-.015}],120211:[.45,.02,.567,{sk:-.018}],120212:[.454,.02,.496,{sk:.111}],120213:[.47,.167,.524,{sk:.31}],120214:[.441,.17,.496,{sk:.098}],120215:[.45,.025,.44,{sk:.132}],120216:[.443,.023,.532,{sk:.169}],120217:[.538,.021,.381,{sk:.083}],120218:[.435,.036,.567],120219:[.469,.022,.517,{sk:.013}],120220:[.469,.022,.701,{sk:-.086}],120221:[.452,.029,.504,{sk:.021}],120222:[.469,.175,.512,{sk:.209}],120223:[.461,.17,.403,{sk:.138}]},"bold-fraktur":{305:[.455,.025,.378,{sk:.245}],567:[.455,.169,.36,{sk:.128}]}}},"GT"));MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/fraktur","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/latin-b.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/latin-b.js
new file mode 100644
index 0000000..8f97366
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/latin-b.js
@@ -0,0 +1 @@
+(()=>{"use strict";const c=MathJax._.output.chtml.DynamicFonts.AddFontIds;MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont.dynamicSetup("","latin-b",c({LB:{bold:{192:[.888,0,.722],193:[.888,0,.722],194:[.885,0,.722],195:[.869,0,.722],196:[.87,0,.722],197:[.931,0,.722],198:[.676,0,1],199:[.691,.218,.722],200:[.888,0,.667],201:[.888,0,.667],202:[.885,0,.667],203:[.87,0,.667],204:[.888,0,.389],205:[.888,0,.389],206:[.885,0,.389,{ic:.008}],207:[.87,0,.389],208:[.676,0,.722],209:[.869,.018,.722],210:[.888,.019,.778],211:[.888,.019,.778],212:[.885,.019,.778],213:[.869,.019,.778],214:[.87,.019,.778],216:[.737,.074,.778],217:[.888,.019,.722],218:[.888,.019,.722],219:[.885,.019,.722],220:[.87,.019,.722],221:[.888,0,.722],222:[.676,0,.611],223:[.691,.012,.556],224:[.702,.014,.5],225:[.702,.014,.5],226:[.698,.014,.5],227:[.674,.014,.5],228:[.675,.014,.5],229:[.717,.014,.5],230:[.473,.014,.722],231:[.473,.218,.444],232:[.702,.014,.444],233:[.702,.014,.444],234:[.698,.014,.444],235:[.675,.014,.444],236:[.702,0,.278],237:[.702,0,.278,{ic:.018}],238:[.698,0,.278,{ic:.029}],239:[.675,0,.278,{ic:.031}],241:[.674,0,.556],242:[.702,.014,.5],243:[.702,.014,.5],244:[.698,.014,.5],245:[.674,.014,.5],246:[.675,.014,.5],248:[.549,.092,.5],249:[.702,.014,.556],250:[.702,.014,.556],251:[.698,.014,.556],252:[.675,.014,.556],253:[.702,.205,.5],254:[.676,.205,.556],255:[.675,.205,.5],256:[.841,0,.722],257:[.646,.014,.5],258:[.887,0,.722],259:[.692,.014,.5],260:[.69,.25,.722],261:[.473,.25,.5],262:[.888,.019,.722],263:[.702,.014,.444],264:[.885,.019,.722],265:[.698,.014,.444],266:[.882,.019,.722],267:[.687,.014,.444],268:[.885,.019,.722],269:[.698,.014,.444],270:[.885,0,.722],271:[.676,.014,.556,{ic:.128}],272:[.676,0,.722],273:[.676,.014,.556],274:[.841,0,.667],275:[.646,.014,.444],276:[.887,0,.667],277:[.692,.014,.444],278:[.882,0,.667],279:[.687,.014,.444],280:[.676,.25,.667],281:[.473,.25,.444],282:[.885,0,.667],283:[.698,.014,.444],284:[.885,.019,.778],285:[.698,.206,.5],286:[.887,.019,.778],287:[.692,.206,.5],288:[.882,.019,.778],289:[.687,.206,.5],290:[.691,.341,.778],291:[.804,.206,.5],292:[.885,0,.778],293:[.885,0,.556],294:[.676,0,.778],295:[.676,0,.606],296:[.869,0,.389],297:[.674,0,.278,{ic:.043}],298:[.841,0,.389],299:[.646,0,.278,{ic:.025}],300:[.887,0,.389],301:[.692,0,.278,{ic:.012}],302:[.676,.25,.389],303:[.687,.25,.278],304:[.882,0,.389],306:[.676,.096,.961],307:[.687,.203,.61],308:[.885,.096,.5,{ic:.012}],309:[.698,.203,.333,{ic:.026}],310:[.676,.341,.778],311:[.676,.341,.556],313:[.888,0,.667],314:[.888,0,.278,{ic:.042}],315:[.676,.341,.667],316:[.676,.341,.278],317:[.676,0,.667],318:[.676,0,.278,{ic:.137}],319:[.676,0,.667],320:[.676,0,.352,{ic:.038}],321:[.676,0,.667],322:[.676,0,.278],323:[.888,.018,.722],324:[.702,0,.556],325:[.676,.341,.722],326:[.473,.341,.556],327:[.885,.018,.722],328:[.698,0,.556],330:[.676,.228,.722],331:[.473,.203,.556],332:[.841,.019,.778],333:[.646,.014,.5],334:[.887,.019,.778],335:[.692,.014,.5],336:[.888,.019,.778],337:[.703,.014,.5,{ic:.05}],338:[.684,.005,1],339:[.473,.014,.722],340:[.888,0,.722],341:[.702,0,.444],342:[.676,.341,.722],343:[.473,.341,.444],344:[.885,0,.722],345:[.698,0,.444],346:[.888,.019,.556],347:[.702,.014,.389],348:[.885,.019,.556],349:[.698,.014,.389],350:[.692,.228,.556],351:[.473,.218,.389],352:[.885,.019,.556],353:[.698,.014,.389],354:[.676,.228,.667],355:[.63,.218,.333],356:[.885,0,.667],357:[.784,.012,.333,{ic:.065}],360:[.869,.019,.722],361:[.674,.014,.556],362:[.841,.019,.722],363:[.646,.014,.556],364:[.887,.019,.722],365:[.692,.014,.556],366:[.931,.019,.722],367:[.717,.014,.556],368:[.888,.019,.722,{ic:.033}],369:[.703,.014,.556,{ic:.016}],370:[.676,.25,.722],371:[.461,.25,.556],372:[.885,.015,1],373:[.698,.014,.722],374:[.885,0,.722],375:[.698,.205,.5],376:[.87,0,.722],377:[.888,0,.667],378:[.702,0,.444],379:[.882,0,.667],380:[.687,0,.444],381:[.885,0,.667],382:[.698,0,.444],383:[.691,0,.333,{ic:.056}],398:[.676,0,.667],402:[.706,.155,.5],416:[.798,.019,.778],417:[.583,.014,.5],431:[.798,.019,.743],432:[.583,.014,.603],461:[.885,0,.722],462:[.698,.014,.5],463:[.885,0,.389,{ic:.007}],464:[.698,0,.278,{ic:.029}],465:[.885,.019,.778],466:[.698,.014,.5],467:[.885,.019,.722],468:[.698,.014,.556],471:[1.082,.019,.722],472:[.878,.014,.556],473:[1.079,.019,.722],474:[.875,.014,.556],475:[1.082,.019,.722],476:[.878,.014,.556],477:[.473,.014,.444],486:[.885,.019,.778],487:[.698,.206,.5],490:[.691,.25,.778],491:[.473,.25,.5],496:[.698,.203,.333,{ic:.026}],500:[.888,.019,.778],501:[.702,.206,.5],506:[1.118,0,.722],507:[.903,.014,.5],508:[.888,0,1],509:[.702,.014,.722],510:[.888,.074,.778],511:[.702,.092,.5],512:[.888,0,.722],513:[.703,.014,.5],516:[.888,0,.667],517:[.703,.014,.444],520:[.888,0,.389],521:[.703,0,.278],524:[.888,.019,.778],525:[.703,.014,.5],528:[.888,0,.722],529:[.703,0,.444],532:[.888,.019,.722],533:[.703,.014,.556],536:[.692,.341,.556],537:[.473,.341,.389],538:[.676,.341,.667],539:[.63,.341,.333],7692:[.676,.226,.722],7693:[.676,.226,.556],7694:[.676,.185,.722],7695:[.676,.185,.556],7716:[.676,.226,.778],7717:[.676,.226,.556],7718:[.87,0,.778],7719:[.87,0,.556],7722:[.676,.231,.778],7723:[.676,.231,.556],7726:[1.082,0,.389],7727:[.878,0,.278,{ic:.037}],7734:[.676,.226,.667],7735:[.676,.226,.278],7736:[.841,.226,.667],7737:[.841,.226,.278,{ic:.022}],7746:[.676,.226,.944],7747:[.473,.226,.833],7748:[.882,.018,.722],7749:[.687,0,.556],7750:[.676,.226,.722],7751:[.473,.226,.556],7768:[.882,0,.722],7769:[.687,0,.444],7770:[.676,.226,.722],7771:[.473,.226,.444],7772:[.841,.226,.722],7773:[.658,.226,.444],7778:[.692,.226,.556],7779:[.473,.226,.389],7788:[.676,.226,.667],7789:[.63,.226,.333],7790:[.676,.185,.667],7791:[.63,.185,.333,{ic:.016}],7808:[.888,.015,1],7809:[.702,.014,.722],7810:[.888,.015,1],7811:[.702,.014,.722],7812:[.87,.015,1],7813:[.675,.014,.722],7826:[.676,.226,.667],7827:[.461,.226,.444],7831:[.824,.012,.333,{ic:.036}],7840:[.69,.226,.722],7841:[.473,.226,.5],7842:[.94,0,.722],7843:[.725,.014,.5],7844:[1.072,0,.722],7845:[.857,.014,.5],7846:[1.072,0,.722],7847:[.857,.014,.5],7848:[1.113,0,.722],7849:[.898,.014,.5],7850:[1.042,0,.722],7851:[.827,.014,.5],7852:[.885,.226,.722],7853:[.698,.226,.5],7854:[1.076,0,.722],7855:[.861,.014,.5],7856:[1.076,0,.722],7857:[.861,.014,.5],7858:[1.071,0,.722],7859:[.856,.014,.5],7860:[1.043,0,.722],7861:[.828,.014,.5],7862:[.887,.226,.722],7863:[.692,.226,.5],7864:[.676,.226,.667],7865:[.473,.226,.444],7866:[.94,0,.667],7867:[.725,.014,.444],7868:[.869,0,.667],7869:[.674,.014,.444],7870:[1.072,0,.667],7871:[.857,.014,.444],7872:[1.072,0,.667],7873:[.857,.014,.444],7874:[1.113,0,.667],7875:[.898,.014,.444],7876:[1.042,0,.667],7877:[.827,.014,.444],7878:[.885,.226,.667],7879:[.698,.226,.444],7880:[.94,0,.389],7881:[.725,0,.278],7882:[.676,.226,.389],7883:[.687,.226,.278],7884:[.691,.226,.778],7885:[.473,.226,.5],7886:[.94,.019,.778],7887:[.725,.014,.5],7888:[1.072,.019,.778],7889:[.857,.014,.5],7890:[1.072,.019,.778],7891:[.857,.014,.5],7892:[1.113,.019,.778],7893:[.898,.014,.5],7894:[1.042,.019,.778],7895:[.827,.014,.5],7896:[.885,.226,.778],7897:[.698,.226,.5],7898:[.888,.019,.778],7899:[.702,.014,.5],7900:[.888,.019,.778],7901:[.702,.014,.5],7902:[.94,.019,.778],7903:[.725,.014,.5],7904:[.869,.019,.778],7905:[.674,.014,.5],7906:[.798,.226,.778],7907:[.583,.226,.5],7908:[.676,.226,.722],7909:[.461,.226,.556],7910:[.94,.019,.722],7911:[.725,.014,.556],7912:[.888,.019,.743],7913:[.702,.014,.603],7914:[.888,.019,.743],7915:[.702,.014,.603],7916:[.94,.019,.743],7917:[.725,.014,.603],7918:[.869,.019,.743],7919:[.674,.014,.603],7920:[.798,.226,.743],7921:[.583,.226,.603],7922:[.888,0,.722],7923:[.702,.205,.5],7924:[.676,.226,.722],7925:[.461,.226,.5],7926:[.94,0,.722],7927:[.725,.205,.5],7928:[.869,0,.722],7929:[.674,.205,.5]}}},"GT"),{},["MJX-GT-LB"]);MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/latin-b","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/latin-bi.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/latin-bi.js
new file mode 100644
index 0000000..e59aa61
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/latin-bi.js
@@ -0,0 +1 @@
+(()=>{"use strict";const c=MathJax._.output.chtml.DynamicFonts.AddFontIds;MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont.dynamicSetup("","latin-bi",c({LIB:{"bold-italic":{192:[.863,0,.667],193:[.863,0,.667],194:[.861,0,.667],195:[.85,0,.667],196:[.855,0,.667],197:[.916,0,.667],198:[.669,0,.944],199:[.685,.218,.667,{ic:.01}],200:[.863,0,.667],201:[.863,0,.667],202:[.861,0,.667],203:[.855,0,.667],204:[.863,0,.389,{ic:.017}],205:[.863,0,.389,{ic:.054}],206:[.861,0,.389,{ic:.078}],207:[.855,0,.389,{ic:.09}],208:[.669,0,.722],209:[.85,.015,.722,{ic:.026}],210:[.863,.018,.722],211:[.863,.018,.722],212:[.861,.018,.722],213:[.85,.018,.722],214:[.855,.018,.722],216:[.764,.125,.722],217:[.863,.018,.722,{ic:.022}],218:[.863,.018,.722,{ic:.022}],219:[.861,.018,.722,{ic:.022}],220:[.855,.018,.722,{ic:.022}],221:[.863,0,.611,{ic:.048}],222:[.669,0,.611],223:[.705,.2,.5],224:[.68,.014,.5],225:[.68,.014,.5],226:[.677,.014,.5],227:[.65,.014,.5],228:[.655,.014,.5],229:[.697,.014,.5],230:[.462,.013,.722],231:[.462,.218,.444],232:[.68,.013,.444],233:[.68,.013,.444],234:[.677,.013,.444],235:[.655,.013,.444,{ic:.029}],236:[.68,.009,.278],237:[.68,.009,.278,{ic:.04}],238:[.677,.009,.278,{ic:.061}],239:[.655,.009,.278,{ic:.09}],241:[.65,.009,.556],242:[.68,.013,.5],243:[.68,.013,.5],244:[.677,.013,.5],245:[.65,.013,.5],246:[.655,.013,.5],248:[.56,.119,.5],249:[.68,.009,.556],250:[.68,.009,.556],251:[.677,.009,.556],252:[.655,.009,.556],253:[.68,.205,.444],254:[.699,.205,.5],255:[.655,.205,.444,{ic:.006}],256:[.825,0,.667],257:[.625,.014,.5],258:[.856,0,.667],259:[.671,.014,.5],260:[.683,.25,.667],261:[.462,.25,.5],262:[.863,.018,.667,{ic:.01}],263:[.68,.013,.444],264:[.861,.018,.667,{ic:.01}],265:[.677,.013,.444],266:[.858,.018,.667,{ic:.01}],267:[.658,.013,.444],268:[.861,.018,.667,{ic:.01}],269:[.677,.013,.444,{ic:.027}],270:[.861,0,.722],271:[.699,.013,.5,{ic:.188}],272:[.669,0,.722],273:[.699,.013,.5,{ic:.037}],274:[.825,0,.667],275:[.625,.013,.444,{ic:.03}],276:[.856,0,.667],277:[.671,.013,.444,{ic:.017}],278:[.858,0,.667],279:[.658,.013,.444],280:[.669,.25,.667],281:[.462,.25,.444],282:[.861,0,.667],283:[.677,.013,.444,{ic:.039}],284:[.861,.018,.722],285:[.677,.203,.5],286:[.856,.018,.722],287:[.671,.203,.5],288:[.858,.018,.722],289:[.658,.203,.5],290:[.685,.324,.722],291:[.776,.203,.5],292:[.861,0,.778,{ic:.021}],293:[.891,.009,.556,{ic:.099}],294:[.669,0,.778,{ic:.021}],295:[.699,.009,.649],296:[.85,0,.389,{ic:.1}],297:[.65,.009,.278,{ic:.101}],298:[.825,0,.389,{ic:.091}],299:[.625,.009,.278,{ic:.091}],300:[.856,0,.389,{ic:.095}],301:[.671,.009,.278,{ic:.078}],302:[.669,.25,.389,{ic:.017}],303:[.658,.25,.278],304:[.858,0,.389,{ic:.017}],306:[.669,.099,.819,{ic:.128}],307:[.658,.207,.58,{ic:.121}],308:[.861,.099,.5,{ic:.086}],309:[.677,.207,.278,{ic:.079}],310:[.669,.324,.667,{ic:.035}],311:[.699,.324,.5],313:[.863,0,.611],314:[.893,.009,.278,{ic:.111}],315:[.669,.324,.611],316:[.699,.324,.278,{ic:.012}],317:[.669,0,.611,{ic:.001}],318:[.699,.009,.278,{ic:.183}],319:[.669,0,.611],320:[.699,.009,.316,{ic:.049}],321:[.669,0,.611],322:[.699,.009,.278,{ic:.041}],323:[.863,.015,.722,{ic:.026}],324:[.68,.009,.556],325:[.669,.324,.722,{ic:.026}],326:[.462,.324,.556],327:[.861,.015,.722,{ic:.026}],328:[.677,.009,.556],330:[.676,.228,.722,{ic:.16}],331:[.464,.199,.556,{ic:.044}],332:[.825,.018,.722],333:[.625,.013,.5],334:[.856,.018,.722],335:[.671,.013,.5],336:[.863,.018,.722,{ic:.055}],337:[.696,.013,.5,{ic:.052}],338:[.677,.008,.944,{ic:.002}],339:[.462,.013,.722],340:[.863,0,.667],341:[.68,0,.389],342:[.669,.324,.667],343:[.462,.324,.389],344:[.861,0,.667],345:[.677,0,.389,{ic:.042}],346:[.863,.018,.556],347:[.68,.013,.389],348:[.861,.018,.556],349:[.677,.013,.389],350:[.685,.228,.556],351:[.462,.218,.389],352:[.861,.018,.556,{ic:.005}],353:[.677,.013,.389,{ic:.029}],354:[.669,.228,.611,{ic:.039}],355:[.594,.218,.278,{ic:.003}],356:[.861,0,.611,{ic:.039}],357:[.755,.009,.278,{ic:.162}],360:[.85,.018,.722,{ic:.022}],361:[.65,.009,.556],362:[.825,.018,.722,{ic:.022}],363:[.625,.009,.556],364:[.856,.018,.722,{ic:.022}],365:[.671,.009,.556],366:[.916,.018,.722,{ic:.022}],367:[.697,.009,.556],368:[.863,.018,.722,{ic:.097}],369:[.696,.009,.556,{ic:.022}],370:[.669,.25,.722,{ic:.022}],371:[.462,.25,.556],372:[.861,.018,.889,{ic:.051}],373:[.677,.013,.667],374:[.861,0,.611,{ic:.048}],375:[.677,.205,.444],376:[.855,0,.611,{ic:.048}],377:[.863,0,.611],378:[.68,.078,.389],379:[.858,0,.611],380:[.658,.078,.389],381:[.861,0,.611],382:[.677,.078,.389,{ic:.04}],383:[.698,.205,.333,{ic:.11}],398:[.669,0,.667,{ic:.046}],402:[.707,.156,.5,{ic:.037}],416:[.775,.018,.722],417:[.561,.013,.5],431:[.775,.018,.722,{ic:.073}],432:[.561,.009,.579,{ic:.019}],461:[.861,0,.667],462:[.677,.014,.5],463:[.861,0,.389,{ic:.117}],464:[.677,.009,.278,{ic:.1}],465:[.861,.018,.722],466:[.677,.013,.5],467:[.861,.018,.722,{ic:.022}],468:[.677,.009,.556],471:[1.049,.018,.722,{ic:.022}],472:[.849,.009,.556],473:[1.047,.018,.722,{ic:.05}],474:[.847,.009,.556,{ic:.033}],475:[1.049,.018,.722,{ic:.022}],476:[.849,.009,.556],477:[.462,.013,.444],486:[.861,.018,.722],487:[.677,.203,.5],490:[.685,.25,.722],491:[.462,.25,.5],496:[.677,.207,.278,{ic:.118}],500:[.863,.018,.722],501:[.68,.203,.5],506:[1.082,0,.667],507:[.862,.014,.5],508:[.863,0,.944],509:[.68,.013,.722],510:[.863,.125,.722],511:[.68,.119,.5],512:[.863,0,.667],513:[.696,.014,.5],516:[.863,0,.667],517:[.696,.013,.444],520:[.863,0,.389,{ic:.022}],521:[.696,.009,.278,{ic:.018}],524:[.863,.018,.722],525:[.696,.013,.5],528:[.863,0,.667],529:[.696,0,.389],532:[.863,.018,.722,{ic:.022}],533:[.696,.009,.556],536:[.685,.324,.556],537:[.462,.324,.389],538:[.669,.324,.611,{ic:.039}],539:[.594,.324,.278,{ic:.003}],7692:[.669,.208,.722],7693:[.699,.208,.5,{ic:.017}],7694:[.669,.176,.722],7695:[.699,.176,.5,{ic:.017}],7716:[.669,.208,.778,{ic:.021}],7717:[.699,.208,.556],7718:[.855,0,.778,{ic:.021}],7719:[.885,.009,.556,{ic:.111}],7722:[.669,.206,.778,{ic:.021}],7723:[.699,.206,.556],7726:[1.049,0,.389,{ic:.104}],7727:[.849,.009,.278,{ic:.104}],7734:[.669,.208,.611],7735:[.699,.208,.278,{ic:.012}],7736:[.825,.208,.611],7737:[.855,.208,.278,{ic:.204}],7746:[.669,.208,.889,{ic:.028}],7747:[.462,.208,.778],7748:[.858,.015,.722,{ic:.026}],7749:[.658,.009,.556],7750:[.669,.208,.722,{ic:.026}],7751:[.462,.208,.556],7768:[.858,0,.667],7769:[.658,0,.389],7770:[.669,.208,.667],7771:[.462,.208,.389],7772:[.825,.208,.667],7773:[.638,.208,.389,{ic:.036}],7778:[.685,.208,.556],7779:[.462,.208,.389],7788:[.669,.208,.611,{ic:.039}],7789:[.594,.208,.278,{ic:.003}],7790:[.669,.176,.611,{ic:.039}],7791:[.594,.176,.278,{ic:.003}],7808:[.863,.018,.889,{ic:.051}],7809:[.68,.013,.667],7810:[.863,.018,.889,{ic:.051}],7811:[.68,.013,.667],7812:[.855,.018,.889,{ic:.051}],7813:[.655,.013,.667],7826:[.669,.208,.611],7827:[.449,.208,.389],7831:[.78,.009,.278,{ic:.155}],7840:[.683,.208,.667],7841:[.462,.208,.5],7842:[.913,0,.667],7843:[.693,.014,.5],7844:[1.027,0,.667],7845:[.807,.014,.5],7846:[1.027,0,.667],7847:[.807,.014,.5],7848:[1.068,0,.667],7849:[.848,.014,.5,{ic:.017}],7850:[1.01,0,.667],7851:[.79,.014,.5,{ic:.004}],7852:[.861,.208,.667],7853:[.677,.208,.5],7854:[1.024,0,.667],7855:[.804,.014,.5],7856:[1.024,0,.667],7857:[.804,.014,.5],7858:[1.019,0,.667],7859:[.799,.014,.5],7860:[1.004,0,.667],7861:[.784,.014,.5,{ic:.003}],7862:[.856,.208,.667],7863:[.671,.208,.5],7864:[.669,.208,.667],7865:[.462,.208,.444],7866:[.913,0,.667],7867:[.693,.013,.444],7868:[.85,0,.667],7869:[.65,.013,.444,{ic:.04}],7870:[1.027,0,.667],7871:[.807,.013,.444,{ic:.012}],7872:[1.027,0,.667],7873:[.807,.013,.444,{ic:.012}],7874:[1.068,0,.667,{ic:.03}],7875:[.848,.013,.444,{ic:.09}],7876:[1.01,0,.667,{ic:.017}],7877:[.79,.013,.444,{ic:.077}],7878:[.861,.208,.667],7879:[.677,.208,.444],7880:[.913,0,.389,{ic:.035}],7881:[.693,.009,.278,{ic:.03}],7882:[.669,.208,.389,{ic:.017}],7883:[.658,.208,.278],7884:[.685,.208,.722],7885:[.462,.208,.5],7886:[.913,.018,.722],7887:[.693,.013,.5],7888:[1.027,.018,.722],7889:[.807,.013,.5],7890:[1.027,.018,.722],7891:[.807,.013,.5],7892:[1.068,.018,.722],7893:[.848,.013,.5,{ic:.047}],7894:[1.01,.018,.722],7895:[.79,.013,.5,{ic:.034}],7896:[.861,.208,.722],7897:[.677,.208,.5],7898:[.863,.018,.722],7899:[.68,.013,.5],7900:[.863,.018,.722],7901:[.68,.013,.5],7902:[.913,.018,.722],7903:[.693,.013,.5],7904:[.85,.018,.722],7905:[.65,.013,.5],7906:[.775,.208,.722],7907:[.561,.208,.5],7908:[.669,.208,.722,{ic:.022}],7909:[.462,.208,.556],7910:[.913,.018,.722,{ic:.022}],7911:[.693,.009,.556],7912:[.863,.018,.722,{ic:.073}],7913:[.68,.009,.579,{ic:.019}],7914:[.863,.018,.722,{ic:.073}],7915:[.68,.009,.579,{ic:.019}],7916:[.913,.018,.722,{ic:.073}],7917:[.693,.009,.579,{ic:.019}],7918:[.85,.018,.722,{ic:.073}],7919:[.65,.009,.579,{ic:.019}],7920:[.775,.208,.722,{ic:.073}],7921:[.561,.208,.579,{ic:.019}],7922:[.863,0,.611,{ic:.048}],7923:[.68,.205,.444],7924:[.669,.208,.611,{ic:.048}],7925:[.462,.208,.444],7926:[.913,0,.611,{ic:.048}],7927:[.693,.205,.444],7928:[.85,0,.611,{ic:.048}],7929:[.65,.205,.444,{ic:.017}]}}},"GT"),{},["MJX-GT-LIB"]);MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/latin-bi","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/latin-i.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/latin-i.js
new file mode 100644
index 0000000..d5d2549
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/latin-i.js
@@ -0,0 +1 @@
+(()=>{"use strict";const c=MathJax._.output.chtml.DynamicFonts.AddFontIds;MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont.dynamicSetup("","latin-i",c({LI:{italic:{192:[.86,0,.611],193:[.86,0,.611],194:[.859,0,.611],195:[.845,0,.611],196:[.84,0,.611],197:[.905,0,.611],198:[.653,0,.889,{ic:.022}],199:[.666,.217,.667,{ic:.022}],200:[.86,0,.611,{ic:.023}],201:[.86,0,.611,{ic:.023}],202:[.859,0,.611,{ic:.023}],203:[.84,0,.611,{ic:.023}],204:[.86,0,.333,{ic:.069}],205:[.86,0,.333,{ic:.097}],206:[.859,0,.333,{ic:.122}],207:[.84,0,.333,{ic:.125}],208:[.653,0,.722],209:[.845,.015,.667,{ic:.06}],210:[.86,.018,.722],211:[.86,.018,.722],212:[.859,.018,.722],213:[.845,.018,.722],214:[.84,.018,.722],216:[.722,.105,.722],217:[.86,.018,.722,{ic:.043}],218:[.86,.018,.722,{ic:.043}],219:[.859,.018,.722,{ic:.043}],220:[.84,.018,.722,{ic:.043}],221:[.86,0,.556,{ic:.077}],222:[.653,0,.611],223:[.679,.207,.5],224:[.675,.011,.5],225:[.675,.011,.5],226:[.675,.011,.5],227:[.644,.011,.5,{ic:.006}],228:[.639,.011,.5],229:[.69,.011,.5],230:[.441,.011,.667],231:[.441,.217,.444],232:[.675,.011,.444],233:[.675,.011,.444],234:[.675,.011,.444,{ic:.004}],235:[.639,.011,.444,{ic:.024}],236:[.675,.011,.278,{ic:.016}],237:[.675,.011,.278,{ic:.061}],238:[.675,.011,.278,{ic:.074}],239:[.639,.011,.278,{ic:.094}],241:[.644,.009,.5],242:[.675,.011,.5],243:[.675,.011,.5],244:[.675,.011,.5],245:[.644,.011,.5,{ic:.028}],246:[.639,.011,.5,{ic:.009}],248:[.554,.135,.5],249:[.675,.011,.5],250:[.675,.011,.5],251:[.675,.011,.5],252:[.639,.011,.5],253:[.675,.206,.444],254:[.683,.205,.5],255:[.639,.206,.444],256:[.817,0,.611],257:[.616,.011,.5],258:[.855,0,.611],259:[.669,.011,.5],260:[.668,.245,.611],261:[.441,.245,.5],262:[.86,.018,.667,{ic:.022}],263:[.675,.011,.444,{ic:.016}],264:[.859,.018,.667,{ic:.022}],265:[.675,.011,.444,{ic:.029}],266:[.844,.018,.667,{ic:.022}],267:[.643,.011,.444],268:[.859,.018,.667,{ic:.033}],269:[.675,.011,.444,{ic:.068}],270:[.859,0,.722],271:[.683,.013,.5,{ic:.167}],272:[.653,0,.722],273:[.683,.013,.5,{ic:.053}],274:[.817,0,.611,{ic:.023}],275:[.616,.011,.444,{ic:.036}],276:[.855,0,.611,{ic:.023}],277:[.669,.011,.444,{ic:.029}],278:[.844,0,.611,{ic:.023}],279:[.643,.011,.444],280:[.653,.245,.611,{ic:.023}],281:[.441,.245,.444],282:[.859,0,.611,{ic:.029}],283:[.675,.011,.444,{ic:.043}],284:[.859,.018,.722],285:[.675,.206,.5],286:[.855,.018,.722],287:[.669,.206,.5],288:[.844,.018,.722],289:[.643,.206,.5],290:[.666,.27,.722],291:[.725,.206,.5],292:[.859,0,.722,{ic:.045}],293:[.889,.009,.5,{ic:.111}],294:[.653,0,.722,{ic:.045}],295:[.683,.009,.598],296:[.845,0,.333,{ic:.145}],297:[.644,.011,.278,{ic:.113}],298:[.817,0,.333,{ic:.137}],299:[.616,.011,.278,{ic:.106}],300:[.855,0,.333,{ic:.148}],301:[.669,.011,.278,{ic:.099}],302:[.653,.245,.333,{ic:.051}],303:[.643,.245,.278],304:[.844,0,.333,{ic:.051}],306:[.653,.018,.714,{ic:.131}],307:[.643,.207,.539,{ic:.126}],308:[.859,.018,.444,{ic:.118}],309:[.675,.207,.278,{ic:.099}],310:[.653,.27,.667,{ic:.055}],311:[.683,.27,.444,{ic:.017}],313:[.86,0,.556,{ic:.003}],314:[.89,.011,.278,{ic:.104}],315:[.653,.27,.556,{ic:.003}],316:[.683,.27,.278,{ic:.001}],317:[.653,0,.556,{ic:.003}],318:[.683,.011,.278,{ic:.141}],319:[.653,0,.556,{ic:.003}],320:[.683,.011,.278,{ic:.066}],321:[.653,0,.556,{ic:.003}],322:[.683,.011,.278,{ic:.034}],323:[.86,.015,.667,{ic:.06}],324:[.675,.009,.5],325:[.653,.27,.667,{ic:.06}],326:[.441,.27,.5],327:[.859,.015,.667,{ic:.06}],328:[.675,.009,.5],330:[.662,.218,.722,{ic:.162}],331:[.442,.209,.5,{ic:.028}],332:[.817,.018,.722],333:[.616,.011,.5,{ic:.021}],334:[.855,.018,.722],335:[.669,.011,.5,{ic:.014}],336:[.86,.018,.722,{ic:.051}],337:[.69,.011,.5,{ic:.055}],338:[.666,.008,.944,{ic:.02}],339:[.441,.012,.667],340:[.86,0,.611],341:[.675,0,.389,{ic:.023}],342:[.653,.27,.611],343:[.441,.27,.389,{ic:.023}],344:[.859,0,.611,{ic:.003}],345:[.675,0,.389,{ic:.051}],346:[.86,.018,.5,{ic:.008}],347:[.675,.013,.389,{ic:.007}],348:[.859,.018,.5,{ic:.012}],349:[.675,.013,.389,{ic:.02}],350:[.667,.227,.5,{ic:.008}],351:[.442,.217,.389],352:[.859,.018,.5,{ic:.047}],353:[.675,.013,.389,{ic:.059}],354:[.653,.227,.556,{ic:.077}],355:[.546,.217,.278,{ic:.018}],356:[.859,0,.556,{ic:.077}],357:[.682,.011,.278,{ic:.125}],360:[.845,.018,.722,{ic:.043}],361:[.644,.011,.5,{ic:.006}],362:[.817,.018,.722,{ic:.043}],363:[.616,.011,.5],364:[.855,.018,.722,{ic:.043}],365:[.669,.011,.5],366:[.905,.018,.722,{ic:.043}],367:[.69,.011,.5],368:[.86,.018,.722,{ic:.071}],369:[.69,.011,.5,{ic:.033}],370:[.653,.245,.722,{ic:.043}],371:[.441,.245,.5],372:[.859,.018,.833,{ic:.073}],373:[.675,.018,.667],374:[.859,0,.556,{ic:.077}],375:[.675,.206,.444],376:[.84,0,.556,{ic:.077}],377:[.86,0,.556,{ic:.05}],378:[.675,.081,.389,{ic:.004}],379:[.844,0,.556,{ic:.05}],380:[.643,.081,.389],381:[.859,0,.556,{ic:.05}],382:[.675,.081,.389,{ic:.056}],383:[.678,.207,.278,{ic:.14}],398:[.653,0,.611,{ic:.089}],402:[.682,.182,.5,{ic:.007}],416:[.743,.018,.722],417:[.52,.011,.5,{ic:.016}],431:[.744,.018,.722,{ic:.08}],432:[.522,.011,.522,{ic:.045}],461:[.859,0,.611],462:[.675,.011,.5,{ic:.006}],463:[.859,0,.333,{ic:.157}],464:[.675,.011,.278,{ic:.113}],465:[.859,.018,.722],466:[.675,.011,.5,{ic:.028}],467:[.859,.018,.722,{ic:.043}],468:[.675,.011,.5,{ic:.006}],471:[1.047,.018,.722,{ic:.043}],472:[.813,.011,.5],473:[1.046,.018,.722,{ic:.043}],474:[.812,.011,.5,{ic:.06}],475:[1.047,.018,.722,{ic:.043}],476:[.813,.011,.5],477:[.441,.011,.444],486:[.859,.018,.722],487:[.675,.206,.5],490:[.666,.245,.722],491:[.441,.245,.5],496:[.675,.207,.278,{ic:.138}],500:[.86,.018,.722],501:[.675,.206,.5],506:[1.063,0,.611],507:[.842,.011,.5,{ic:.007}],508:[.86,0,.889,{ic:.022}],509:[.675,.011,.667],510:[.86,.105,.722],511:[.675,.135,.5],512:[.86,0,.611],513:[.69,.011,.5],516:[.86,0,.611,{ic:.023}],517:[.69,.011,.444],520:[.86,0,.333,{ic:.079}],521:[.69,.011,.278,{ic:.039}],524:[.86,.018,.722],525:[.69,.011,.5],528:[.86,0,.611],529:[.69,0,.389,{ic:.023}],532:[.86,.018,.722,{ic:.043}],533:[.69,.011,.5],536:[.667,.27,.5,{ic:.008}],537:[.442,.27,.389],538:[.653,.27,.556,{ic:.077}],539:[.546,.27,.278,{ic:.018}],7692:[.653,.211,.722],7693:[.683,.211,.5,{ic:.027}],7694:[.653,.183,.722],7695:[.683,.183,.5,{ic:.027}],7716:[.653,.211,.722,{ic:.045}],7717:[.683,.211,.5],7718:[.84,0,.722,{ic:.045}],7719:[.87,.009,.5,{ic:.114}],7722:[.653,.221,.722,{ic:.045}],7723:[.683,.221,.5],7726:[1.047,0,.333,{ic:.147}],7727:[.813,.011,.278,{ic:.107}],7734:[.653,.211,.556,{ic:.003}],7735:[.683,.211,.278,{ic:.001}],7736:[.817,.211,.556,{ic:.003}],7737:[.847,.211,.278,{ic:.216}],7746:[.653,.211,.833,{ic:.04}],7747:[.441,.211,.722],7748:[.844,.015,.667,{ic:.06}],7749:[.643,.009,.5],7750:[.653,.211,.667,{ic:.06}],7751:[.441,.211,.5],7768:[.844,0,.611],7769:[.643,0,.389,{ic:.023}],7770:[.653,.211,.611],7771:[.441,.211,.389,{ic:.023}],7772:[.817,.211,.611],7773:[.625,.211,.389,{ic:.046}],7778:[.667,.211,.5,{ic:.008}],7779:[.442,.211,.389],7788:[.653,.211,.556,{ic:.077}],7789:[.546,.211,.278,{ic:.018}],7790:[.653,.183,.556,{ic:.077}],7791:[.546,.183,.278,{ic:.018}],7808:[.86,.018,.833,{ic:.073}],7809:[.675,.018,.667],7810:[.86,.018,.833,{ic:.073}],7811:[.675,.018,.667],7812:[.84,.018,.833,{ic:.073}],7813:[.639,.018,.667],7826:[.653,.211,.556,{ic:.05}],7827:[.428,.211,.389],7831:[.733,.011,.278,{ic:.139}],7840:[.668,.211,.611],7841:[.441,.211,.5],7842:[.917,0,.611],7843:[.696,.011,.5],7844:[1.017,0,.611],7845:[.796,.011,.5],7846:[1.017,0,.611],7847:[.796,.011,.5],7848:[1.07,0,.611,{ic:.023}],7849:[.849,.011,.5,{ic:.057}],7850:[.996,0,.611,{ic:.007}],7851:[.775,.011,.5,{ic:.041}],7852:[.859,.211,.611],7853:[.675,.211,.5],7854:[1.013,0,.611],7855:[.792,.011,.5,{ic:.014}],7856:[1.013,0,.611],7857:[.792,.011,.5,{ic:.004}],7858:[1.026,0,.611],7859:[.805,.011,.5,{ic:.004}],7860:[.988,0,.611,{ic:.005}],7861:[.767,.011,.5,{ic:.039}],7862:[.855,.211,.611],7863:[.669,.211,.5],7864:[.653,.211,.611,{ic:.023}],7865:[.441,.211,.444],7866:[.917,0,.611,{ic:.023}],7867:[.696,.011,.444],7868:[.845,0,.611,{ic:.023}],7869:[.644,.011,.444,{ic:.043}],7870:[1.017,0,.611,{ic:.023}],7871:[.796,.011,.444,{ic:.015}],7872:[1.017,0,.611,{ic:.023}],7873:[.796,.011,.444,{ic:.024}],7874:[1.07,0,.611,{ic:.073}],7875:[.849,.011,.444,{ic:.094}],7876:[.996,0,.611,{ic:.057}],7877:[.775,.011,.444,{ic:.078}],7878:[.859,.211,.611,{ic:.023}],7879:[.675,.211,.444,{ic:.004}],7880:[.917,0,.333,{ic:.089}],7881:[.696,.011,.278,{ic:.052}],7882:[.653,.211,.333,{ic:.051}],7883:[.643,.211,.278],7884:[.666,.211,.722],7885:[.441,.211,.5],7886:[.917,.018,.722],7887:[.696,.011,.5],7888:[1.017,.018,.722],7889:[.796,.011,.5],7890:[1.017,.018,.722],7891:[.796,.011,.5,{ic:.009}],7892:[1.07,.018,.722,{ic:.005}],7893:[.849,.011,.5,{ic:.079}],7894:[.996,.018,.722],7895:[.775,.011,.5,{ic:.063}],7896:[.859,.211,.722],7897:[.675,.211,.5],7898:[.86,.018,.722],7899:[.675,.011,.5,{ic:.016}],7900:[.86,.018,.722],7901:[.675,.011,.5,{ic:.016}],7902:[.917,.018,.722],7903:[.696,.011,.5,{ic:.016}],7904:[.845,.018,.722],7905:[.644,.011,.5,{ic:.016}],7906:[.743,.211,.722],7907:[.52,.211,.5,{ic:.016}],7908:[.653,.211,.722,{ic:.043}],7909:[.441,.211,.5],7910:[.917,.018,.722,{ic:.043}],7911:[.696,.011,.5],7912:[.86,.018,.722,{ic:.08}],7913:[.675,.011,.522,{ic:.045}],7914:[.86,.018,.722,{ic:.08}],7915:[.675,.011,.522,{ic:.045}],7916:[.917,.018,.722,{ic:.08}],7917:[.696,.011,.522,{ic:.045}],7918:[.845,.018,.722,{ic:.08}],7919:[.644,.011,.522,{ic:.045}],7920:[.744,.211,.722,{ic:.08}],7921:[.522,.211,.522,{ic:.045}],7922:[.86,0,.556,{ic:.077}],7923:[.675,.206,.444],7924:[.653,.211,.556,{ic:.077}],7925:[.441,.211,.444],7926:[.917,0,.556,{ic:.077}],7927:[.696,.206,.444],7928:[.845,0,.556,{ic:.077}],7929:[.644,.206,.444,{ic:.009}]}}},"GT"),{},["MJX-GT-LI"]);MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/latin-i","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/latin.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/latin.js
new file mode 100644
index 0000000..616d974
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/latin.js
@@ -0,0 +1 @@
+(()=>{"use strict";const c=MathJax._.output.chtml.DynamicFonts.AddFontIds;MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont.dynamicSetup("","latin",c({LR:{normal:{192:[.851,0,.722],193:[.851,0,.722],194:[.847,0,.722],195:[.835,0,.722],196:[.832,0,.722],197:[.896,0,.722],198:[.662,0,.889],199:[.676,.215,.667],200:[.851,0,.611],201:[.851,0,.611],202:[.847,0,.611],203:[.832,0,.611],204:[.851,0,.333],205:[.851,0,.333],206:[.847,0,.333,{ic:.007}],207:[.832,0,.333],208:[.662,0,.722],209:[.835,.011,.722],210:[.851,.014,.722],211:[.851,.014,.722],212:[.847,.014,.722],213:[.835,.014,.722],214:[.832,.014,.722],216:[.734,.08,.722],217:[.851,.014,.722],218:[.851,.014,.722],219:[.847,.014,.722],220:[.832,.014,.722],221:[.851,0,.722],222:[.662,0,.556],223:[.683,.009,.5],224:[.675,.01,.444],225:[.675,.01,.444],226:[.674,.01,.444],227:[.643,.01,.444],228:[.64,.01,.444],229:[.69,.01,.444],230:[.46,.01,.667],231:[.46,.215,.444],232:[.675,.01,.444],233:[.675,.01,.444],234:[.674,.01,.444],235:[.64,.01,.444],236:[.675,0,.278],237:[.675,0,.278,{ic:.01}],238:[.674,0,.278,{ic:.015}],239:[.64,0,.278,{ic:.009}],241:[.643,0,.5],242:[.675,.01,.5],243:[.675,.01,.5],244:[.674,.01,.5],245:[.643,.01,.5],246:[.64,.01,.5],248:[.551,.112,.5],249:[.675,.01,.5],250:[.675,.01,.5],251:[.674,.01,.5],252:[.64,.01,.5],253:[.675,.218,.5],254:[.683,.217,.5],255:[.64,.218,.5],256:[.809,0,.722],257:[.617,.01,.444],258:[.851,0,.722],259:[.669,.01,.444],260:[.674,.245,.722],261:[.46,.245,.444],262:[.851,.014,.667],263:[.675,.01,.444],264:[.847,.014,.667],265:[.674,.01,.444],266:[.833,.014,.667],267:[.641,.01,.444],268:[.847,.014,.667],269:[.674,.01,.444],270:[.847,0,.722],271:[.683,.01,.5,{ic:.103}],272:[.662,0,.722],273:[.683,.01,.5],274:[.809,0,.611],275:[.617,.01,.444],276:[.851,0,.611],277:[.669,.01,.444],278:[.833,0,.611],279:[.641,.01,.444],280:[.662,.245,.611],281:[.46,.245,.444],282:[.847,0,.611],283:[.674,.01,.444],284:[.847,.014,.722],285:[.674,.218,.5],286:[.851,.014,.722],287:[.669,.218,.5],288:[.833,.014,.722],289:[.641,.218,.5],290:[.676,.281,.722],291:[.733,.218,.5],292:[.847,0,.722],293:[.868,0,.5],294:[.662,0,.722],295:[.683,0,.558],296:[.835,0,.333],297:[.643,0,.278,{ic:.024}],298:[.809,0,.333],299:[.617,0,.278,{ic:.015}],300:[.851,0,.333],301:[.669,0,.278],302:[.662,.245,.333],303:[.641,.245,.278],304:[.833,0,.333],306:[.662,.014,.787],307:[.641,.218,.535],308:[.847,.014,.389,{ic:.012}],309:[.674,.218,.278,{ic:.029}],310:[.662,.281,.722,{ic:.001}],311:[.683,.281,.5,{ic:.005}],313:[.851,0,.611],314:[.872,0,.278,{ic:.005}],315:[.662,.281,.611],316:[.683,.281,.278],317:[.662,0,.611],318:[.683,0,.278,{ic:.083}],319:[.662,0,.611],320:[.683,0,.278,{ic:.052}],321:[.662,0,.611],322:[.683,0,.278],323:[.851,.011,.722],324:[.675,0,.5],325:[.662,.281,.722],326:[.46,.281,.5],327:[.847,.011,.722],328:[.674,0,.5],330:[.662,.218,.722],331:[.46,.218,.5],332:[.809,.014,.722],333:[.617,.01,.5],334:[.851,.014,.722],335:[.669,.01,.5],336:[.851,.014,.722],337:[.676,.01,.5,{ic:.011}],338:[.668,.006,.889],339:[.46,.01,.722],340:[.851,0,.667],341:[.675,0,.333,{ic:.002}],342:[.662,.281,.667],343:[.46,.281,.333,{ic:.002}],344:[.847,0,.667],345:[.674,0,.333,{ic:.002}],346:[.851,.014,.556],347:[.675,.01,.389],348:[.847,.014,.556],349:[.674,.01,.389],350:[.676,.225,.556],351:[.459,.215,.389],352:[.847,.014,.556],353:[.674,.01,.389],354:[.662,.225,.611],355:[.579,.215,.278,{ic:.001}],356:[.847,0,.611],357:[.713,.01,.278,{ic:.035}],360:[.835,.014,.722],361:[.643,.01,.5],362:[.809,.014,.722],363:[.617,.01,.5],364:[.851,.014,.722],365:[.669,.01,.5],366:[.896,.014,.722],367:[.69,.01,.5],368:[.851,.014,.722],369:[.676,.01,.5,{ic:.005}],370:[.662,.245,.722],371:[.45,.245,.5],372:[.847,.011,.944],373:[.674,.014,.722],374:[.847,0,.722],375:[.674,.218,.5],376:[.832,0,.722],377:[.851,0,.611],378:[.675,0,.444],379:[.833,0,.611],380:[.641,0,.444],381:[.847,0,.611],382:[.674,0,.444],383:[.683,0,.333,{ic:.05}],398:[.662,0,.611],402:[.676,.189,.5],416:[.771,.014,.722],417:[.559,.01,.5],431:[.771,.014,.706],432:[.56,.01,.513],461:[.847,0,.722],462:[.674,.01,.444],463:[.847,0,.333,{ic:.006}],464:[.674,0,.278,{ic:.015}],465:[.847,.014,.722],466:[.674,.01,.5],467:[.847,.014,.722],468:[.674,.01,.5],471:[1.021,.014,.722],472:[.811,.01,.5],473:[1.017,.014,.722],474:[.807,.01,.5],475:[1.021,.014,.722],476:[.811,.01,.5],477:[.46,.01,.444],486:[.847,.014,.722],487:[.674,.218,.5],490:[.676,.245,.722],491:[.46,.245,.5],496:[.674,.218,.278,{ic:.029}],500:[.851,.014,.722],501:[.675,.218,.5],506:[1.055,0,.722],507:[.843,.01,.444],508:[.851,0,.889],509:[.675,.01,.667],510:[.851,.08,.722],511:[.675,.112,.5],512:[.851,0,.722],513:[.676,.01,.444],516:[.851,0,.611],517:[.676,.01,.444],520:[.851,0,.333],521:[.676,0,.278],524:[.851,.014,.722],525:[.676,.01,.5],528:[.851,0,.667],529:[.676,0,.333,{ic:.002}],532:[.851,.014,.722],533:[.676,.01,.5],536:[.676,.281,.556],537:[.459,.281,.389],538:[.662,.281,.611],539:[.579,.281,.278,{ic:.001}],7692:[.662,.191,.722],7693:[.683,.191,.5],7694:[.662,.167,.722],7695:[.683,.167,.5],7716:[.662,.191,.722],7717:[.683,.191,.5],7718:[.832,0,.722],7719:[.853,0,.5],7722:[.662,.209,.722],7723:[.683,.209,.5],7726:[1.021,0,.333],7727:[.811,0,.278,{ic:.014}],7734:[.662,.191,.611],7735:[.683,.191,.278],7736:[.809,.191,.611],7737:[.83,.191,.278,{ic:.017}],7746:[.662,.191,.889],7747:[.46,.191,.778],7748:[.833,.011,.722],7749:[.641,0,.5],7750:[.662,.191,.722],7751:[.46,.191,.5],7768:[.833,0,.667],7769:[.641,0,.333,{ic:.002}],7770:[.662,.191,.667],7771:[.46,.191,.333,{ic:.002}],7772:[.809,.191,.667],7773:[.627,.191,.333,{ic:.002}],7778:[.676,.191,.556],7779:[.459,.191,.389],7788:[.662,.191,.611],7789:[.579,.191,.278,{ic:.001}],7790:[.662,.167,.611],7791:[.579,.167,.278,{ic:.032}],7808:[.851,.011,.944],7809:[.675,.014,.722],7810:[.851,.011,.944],7811:[.675,.014,.722],7812:[.832,.011,.944],7813:[.64,.014,.722],7826:[.662,.191,.611],7827:[.45,.191,.444],7831:[.749,.01,.278,{ic:.012}],7838:[.676,.014,1.06],7840:[.674,.191,.722],7841:[.46,.191,.444],7842:[.896,0,.722],7843:[.684,.01,.444],7844:[1.006,0,.722],7845:[.794,.01,.444],7846:[1.006,0,.722],7847:[.794,.01,.444],7848:[1.02,0,.722],7849:[.808,.01,.444],7850:[.983,0,.722],7851:[.771,.01,.444],7852:[.847,.191,.722],7853:[.674,.191,.444],7854:[1.01,0,.722],7855:[.798,.01,.444],7856:[1.01,0,.722],7857:[.798,.01,.444],7858:[.984,0,.722],7859:[.772,.01,.444],7860:[.984,0,.722],7861:[.772,.01,.444],7862:[.851,.191,.722],7863:[.669,.191,.444],7864:[.662,.191,.611],7865:[.46,.191,.444],7866:[.896,0,.611],7867:[.684,.01,.444],7868:[.835,0,.611],7869:[.643,.01,.444],7870:[1.006,0,.611],7871:[.794,.01,.444],7872:[1.006,0,.611],7873:[.794,.01,.444],7874:[1.02,0,.611],7875:[.808,.01,.444],7876:[.983,0,.611],7877:[.771,.01,.444],7878:[.847,.191,.611],7879:[.674,.191,.444],7880:[.896,0,.333],7881:[.684,0,.278],7882:[.662,.191,.333],7883:[.641,.191,.278],7884:[.676,.191,.722],7885:[.46,.191,.5],7886:[.896,.014,.722],7887:[.684,.01,.5],7888:[1.006,.014,.722],7889:[.794,.01,.5],7890:[1.006,.014,.722],7891:[.794,.01,.5],7892:[1.02,.014,.722],7893:[.808,.01,.5],7894:[.983,.014,.722],7895:[.771,.01,.5],7896:[.847,.191,.722],7897:[.674,.191,.5],7898:[.851,.014,.722],7899:[.675,.01,.5],7900:[.851,.014,.722],7901:[.675,.01,.5],7902:[.896,.014,.722],7903:[.684,.01,.5],7904:[.835,.014,.722],7905:[.643,.01,.5],7906:[.771,.191,.722],7907:[.559,.191,.5],7908:[.662,.191,.722],7909:[.45,.191,.5],7910:[.896,.014,.722],7911:[.684,.01,.5],7912:[.851,.014,.706],7913:[.675,.01,.513],7914:[.851,.014,.706],7915:[.675,.01,.513],7916:[.896,.014,.706],7917:[.684,.01,.513],7918:[.835,.014,.706],7919:[.643,.01,.513],7920:[.771,.191,.706],7921:[.56,.191,.513],7922:[.851,0,.722],7923:[.675,.218,.5],7924:[.662,.191,.722],7925:[.45,.218,.5],7926:[.896,0,.722],7927:[.684,.218,.5],7928:[.835,0,.722],7929:[.643,.218,.5]}}},"GT"),{},["MJX-GT-LR"]);MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/latin","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/monospace.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/monospace.js
new file mode 100644
index 0000000..005b304
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/monospace.js
@@ -0,0 +1 @@
+(()=>{"use strict";const s=MathJax._.output.chtml.DynamicFonts.AddFontIds;MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont.dynamicSetup("","monospace",s({M:{normal:{120432:[.563,0,.6,{sk:.226}],120433:[.563,0,.6,{sk:.173}],120434:[.576,.016,.6,{sk:.061}],120435:[.563,0,.6,{sk:.175}],120436:[.563,0,.6,{sk:.167}],120437:[.563,0,.6,{sk:.076}],120438:[.576,.016,.6,{sk:.181}],120439:[.563,0,.6,{sk:.059}],120440:[.563,0,.6,{sk:.057}],120441:[.563,.016,.6,{sk:.063}],120442:[.563,0,.6,{sk:.099}],120443:[.563,0,.6,{sk:.175}],120444:[.563,0,.6,{sk:.108}],120445:[.563,0,.6,{sk:.132}],120446:[.576,.016,.6,{sk:.248}],120447:[.563,0,.6,{sk:.186}],120448:[.576,.115,.6,{sk:.162}],120449:[.563,0,.6,{sk:.221}],120450:[.576,.016,.6,{sk:.143}],120451:[.563,0,.6,{sk:.119}],120452:[.563,.016,.6,{sk:.156}],120453:[.563,0,.6,{sk:.176}],120454:[.563,0,.6,{sk:.071}],120455:[.563,0,.6,{sk:.073}],120456:[.563,0,.6,{sk:.078}],120457:[.563,0,.6,{sk:.076}],120458:[.431,.016,.6,{sk:.164}],120459:[.604,.016,.6,{sk:.084}],120460:[.431,.016,.6,{sk:.032}],120461:[.604,.016,.6,{sk:.019}],120462:[.431,.016,.6,{sk:.143}],120463:[.604,0,.6,{sk:.062}],120464:[.431,.186,.6,{sk:.126}],120465:[.604,0,.6,{sk:.167}],120466:[.61,0,.6,{sk:.131}],120467:[.61,.186,.6,{sk:.056}],120468:[.604,0,.6,{sk:.068}],120469:[.604,0,.6,{sk:-.082}],120470:[.431,0,.6,{sk:.062}],120471:[.431,0,.6,{sk:.151}],120472:[.431,.016,.6,{sk:.118}],120473:[.431,.186,.6,{sk:.076}],120474:[.431,.186,.6,{sk:.231}],120475:[.427,0,.6,{sk:.135}],120476:[.431,.016,.6,{sk:.158}],120477:[.563,.016,.6,{sk:.165}],120478:[.417,.016,.6,{sk:.186}],120479:[.417,0,.6,{sk:-.012}],120480:[.417,0,.6,{sk:.196}],120481:[.417,0,.6,{sk:.24}],120482:[.417,.186,.6,{sk:.188}],120483:[.417,0,.6,{sk:.173}],120822:[.618,.015,.6,{sk:.063}],120823:[.612,0,.6,{sk:-.03}],120824:[.618,0,.6,{sk:.081}],120825:[.618,.015,.6,{sk:.055}],120826:[.604,0,.6,{sk:.154}],120827:[.604,.015,.6,{sk:.056}],120828:[.618,.015,.6,{sk:.053}],120829:[.604,.001,.6,{sk:.031}],120830:[.618,.015,.6,{sk:.072}],120831:[.618,.015,.6,{sk:.151}]},monospace:{305:[.417,0,.6,{sk:.207}],567:[.417,.186,.6,{sk:.115}]}}},"GT"));MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/monospace","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/sans-serif.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/sans-serif.js
new file mode 100644
index 0000000..567e54c
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/sans-serif.js
@@ -0,0 +1 @@
+(()=>{"use strict";const s=MathJax._.output.chtml.DynamicFonts.AddFontIds;MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont.dynamicSetup("","sans-serif",s({SS:{normal:{120224:[.671,0,.616,{sk:.235}],120225:[.671,0,.623,{sk:.306}],120226:[.687,.017,.672,{sk:.344}],120227:[.671,0,.676],120228:[.671,0,.625,{sk:.06}],120229:[.671,0,.572,{sk:.185}],120230:[.687,.017,.725,{sk:.155}],120231:[.671,0,.677,{sk:.034}],120232:[.671,0,.271,{sk:.274}],120233:[.671,.017,.467,{sk:.254}],120234:[.671,0,.621,{sk:.226}],120235:[.671,0,.52,{sk:.121}],120236:[.671,0,.778,{sk:.03}],120237:[.671,0,.676,{sk:.222}],120238:[.687,.017,.722,{sk:.255}],120239:[.671,0,.625,{sk:.09}],120240:[.687,.05,.722,{sk:.082}],120241:[.671,0,.675,{sk:.258}],120242:[.687,.017,.621,{sk:.344}],120243:[.671,0,.565,{sk:.122}],120244:[.671,.017,.677,{sk:.106}],120245:[.671,0,.618,{sk:.112}],120246:[.671,0,.871,{sk:.028}],120247:[.671,0,.617,{sk:.113}],120248:[.671,0,.615,{sk:.155}],120249:[.671,0,.567,{sk:.157}],120250:[.496,.014,.517,{sk:.226}],120251:[.671,.014,.518,{sk:.194}],120252:[.496,.014,.464,{sk:.267}],120253:[.671,.014,.518,{sk:.207}],120254:[.496,.014,.518,{sk:.254}],120255:[.673,0,.259,{sk:.337}],120256:[.496,.201,.519,{sk:.254}],120257:[.671,0,.523,{sk:.199}],120258:[.65,0,.214,{sk:.499}],120259:[.65,.201,.207,{sk:.338}],120260:[.671,0,.464,{ic:.002,sk:.273}],120261:[.671,0,.215,{sk:.29}],120262:[.496,0,.778,{sk:.049}],120263:[.496,0,.523,{sk:.221}],120264:[.496,.014,.518,{sk:.271}],120265:[.496,.201,.519,{sk:.189}],120266:[.496,.201,.518,{sk:.233}],120267:[.496,0,.313,{sk:.363}],120268:[.496,.014,.466,{sk:.339}],120269:[.615,.006,.259,{sk:.343}],120270:[.482,.014,.523,{sk:.258}],120271:[.482,0,.462,{sk:.292}],120272:[.482,0,.666,{sk:.242}],120273:[.482,0,.464,{sk:.227}],120274:[.482,.201,.463,{sk:.274}],120275:[.482,0,.466,{sk:.318}],120802:[.652,.014,.519,{sk:.335}],120803:[.652,0,.536,{sk:.211}],120804:[.652,0,.518,{sk:.267}],120805:[.652,.014,.518,{sk:.28}],120806:[.652,0,.517,{sk:.335}],120807:[.638,.014,.518,{sk:.205}],120808:[.652,.014,.518,{sk:.252}],120809:[.638,0,.518,{sk:.332}],120810:[.652,.014,.518,{sk:.391}],120811:[.652,.014,.518,{sk:.235}]},"sans-serif":{305:[.482,0,.214,{sk:.338}],567:[.482,.201,.207,{sk:.273}]}},SSB:{normal:{120276:[.671,0,.654,{sk:.121}],120277:[.671,0,.664,{sk:-.037}],120278:[.682,.011,.658],120279:[.671,0,.662,{sk:.088}],120280:[.671,0,.612,{sk:.155}],120281:[.671,0,.56,{sk:.012}],120282:[.682,.011,.711,{sk:-.035}],120283:[.671,0,.663,{sk:.099}],120284:[.671,0,.263,{sk:.342}],120285:[.671,.011,.51,{sk:.068}],120286:[.671,0,.658,{sk:.027}],120287:[.671,0,.561,{sk:.05}],120288:[.671,0,.762,{sk:-.018}],120289:[.671,0,.663,{sk:.028}],120290:[.682,.011,.708,{sk:.04}],120291:[.671,0,.611,{sk:.068}],120292:[.682,.04,.708,{sk:.056}],120293:[.671,0,.662,{sk:-.028}],120294:[.682,.011,.607,{sk:.029}],120295:[.671,0,.553,{sk:.089}],120296:[.671,.011,.664,{sk:.071}],120297:[.671,0,.605,{sk:.037}],120298:[.671,0,.852,{sk:-.052}],120299:[.671,0,.604,{sk:.116}],120300:[.671,0,.605,{sk:.158}],120301:[.671,0,.556,{sk:.127}],120302:[.505,.008,.506,{sk:.192}],120303:[.671,.008,.559,{sk:.103}],120304:[.505,.008,.507,{sk:.168}],120305:[.671,.008,.559,{sk:.164}],120306:[.505,.008,.506,{sk:.235}],120307:[.671,0,.303,{sk:.287}],120308:[.505,.201,.56,{sk:.203}],120309:[.671,0,.564,{sk:-.088}],120310:[.685,0,.264,{sk:.081}],120311:[.685,.201,.257,{sk:.082}],120312:[.671,0,.507,{sk:-.022}],120313:[.671,0,.264,{sk:.092}],120314:[.505,0,.813,{sk:-.16}],120315:[.505,0,.563,{sk:-.04}],120316:[.505,.008,.558,{sk:-.013}],120317:[.505,.201,.559,{sk:.106}],120318:[.505,.201,.559,{sk:.145}],120319:[.505,0,.358,{sk:.21}],120320:[.505,.008,.507,{sk:.174}],120321:[.62,.004,.304,{sk:.265}],120322:[.497,.008,.563,{sk:.177}],120323:[.497,0,.504,{sk:.181}],120324:[.497,0,.702,{sk:.126}],120325:[.497,0,.504,{sk:-.037}],120326:[.497,.201,.503,{sk:-.015}],120327:[.497,0,.455,{sk:.159}],120812:[.666,.008,.507,{sk:.1}],120813:[.652,0,.525,{sk:.151}],120814:[.666,0,.507,{sk:.202}],120815:[.666,.008,.507,{sk:.05}],120816:[.652,0,.506,{sk:.08}],120817:[.652,.008,.507,{sk:.107}],120818:[.666,.008,.507,{sk:.143}],120819:[.652,0,.506,{sk:.089}],120820:[.666,.008,.506,{sk:.123}],120821:[.666,.008,.507,{sk:.153}]},"bold-sans-serif":{305:[.497,0,.264,{sk:.312}],567:[.497,.201,.257,{sk:.36}]}},SSI:{normal:{120328:[.671,0,.616,{sk:.177}],120329:[.671,0,.616,{sk:.146}],120330:[.687,.017,.669,{sk:.166}],120331:[.671,0,.668,{sk:.151}],120332:[.671,0,.614,{ic:.034,sk:.202}],120333:[.671,0,.559,{ic:.073,sk:.173}],120334:[.687,.017,.722,{sk:.197}],120335:[.671,0,.665,{ic:.027,sk:.118}],120336:[.671,0,.258,{ic:.021,sk:.373}],120337:[.671,.017,.457,{ic:.031,sk:.348}],120338:[.671,0,.608,{ic:.096,sk:.283}],120339:[.671,0,.518,{sk:.21}],120340:[.671,0,.766,{ic:.033,sk:.107}],120341:[.671,0,.664,{ic:.029,sk:.274}],120342:[.687,.017,.72,{ic:.001,sk:.33}],120343:[.671,0,.616,{ic:.016,sk:.045}],120344:[.687,.05,.72,{ic:.001,sk:.041}],120345:[.671,0,.668,{sk:.095}],120346:[.687,.017,.617,{sk:.164}],120347:[.671,0,.564,{ic:.087,sk:.062}],120348:[.671,.017,.668,{ic:.028,sk:.095}],120349:[.671,0,.618,{ic:.083,sk:.113}],120350:[.671,0,.871,{ic:.09,sk:.029}],120351:[.671,0,.605,{ic:.077,sk:-.073}],120352:[.671,0,.615,{ic:.099,sk:-.066}],120353:[.671,0,.554,{ic:.076,sk:.174}],120354:[.496,.014,.516,{sk:.301}],120355:[.671,.014,.513,{sk:.086}],120356:[.496,.014,.462,{ic:.004,sk:.144}],120357:[.671,.014,.51,{ic:.044,sk:.285}],120358:[.496,.014,.516,{sk:.372}],120359:[.673,0,.252,{ic:.085,sk:.181}],120360:[.496,.201,.51,{sk:.153}],120361:[.671,0,.516,{sk:.118}],120362:[.65,0,.203,{ic:.04,sk:.278}],120363:[.65,.201,.192,{ic:.04,sk:.195}],120364:[.671,0,.458,{ic:.034,sk:.16}],120365:[.671,0,.203,{ic:.035,sk:.268}],120366:[.496,0,.771,{sk:.051}],120367:[.496,0,.516,{sk:.156}],120368:[.496,.014,.516,{sk:.197}],120369:[.496,.196,.51,{sk:.078}],120370:[.496,.196,.513,{ic:.001,sk:.11}],120371:[.496,0,.304,{ic:.053,sk:.269}],120372:[.496,.014,.463,{sk:.276}],120373:[.615,.006,.257,{ic:.038,sk:.219}],120374:[.482,.014,.516,{sk:.156}],120375:[.482,0,.462,{ic:.048,sk:.24}],120376:[.482,0,.666,{ic:.048,sk:.189}],120377:[.482,0,.455,{ic:.033,sk:.038}],120378:[.482,.201,.453,{ic:.04,sk:.063}],120379:[.482,0,.458,{ic:.007,sk:.138}]},"sans-serif-italic":{305:[.482,0,.203,{sk:.327}],567:[.482,.201,.192,{sk:.308}]}},SSBI:{normal:{120380:[.671,0,.654,{ic:.04,sk:.117}],120381:[.671,0,.664,{ic:.034,sk:.165}],120382:[.682,.011,.658,{ic:.057,sk:-.016}],120383:[.671,0,.662,{ic:.042,sk:.029}],120384:[.671,0,.612,{ic:.084,sk:.169}],120385:[.671,0,.56,{ic:.118,sk:.224}],120386:[.682,.011,.711,{ic:.031,sk:-.071}],120387:[.671,0,.663,{ic:.078,sk:-.051}],120388:[.671,0,.263,{ic:.078,sk:.194}],120389:[.671,.011,.51,{ic:.073,sk:.112}],120390:[.671,0,.658,{ic:.11,sk:-.056}],120391:[.671,0,.561,{sk:.112}],120392:[.671,0,.762,{ic:.086,sk:.029}],120393:[.671,0,.663,{ic:.082,sk:.13}],120394:[.682,.011,.708,{ic:.045,sk:-.059}],120395:[.671,0,.611,{ic:.071}],120396:[.682,.04,.708,{ic:.049,sk:-.029}],120397:[.671,0,.662,{ic:.056,sk:.025}],120398:[.682,.011,.607,{ic:.047,sk:.032}],120399:[.671,0,.553,{ic:.13,sk:.034}],120400:[.671,.011,.664,{ic:.075,sk:.02}],120401:[.671,0,.605,{ic:.123,sk:.054}],120402:[.671,0,.852,{ic:.131,sk:-.224}],120403:[.671,0,.604,{ic:.121,sk:-.063}],120404:[.671,0,.605,{ic:.126,sk:-.077}],120405:[.671,0,.556,{ic:.11}],120406:[.505,.008,.506,{ic:.019,sk:.033}],120407:[.671,.008,.559,{ic:.023,sk:.033}],120408:[.505,.008,.507,{ic:.035,sk:.056}],120409:[.671,.008,.559,{ic:.077,sk:.032}],120410:[.505,.008,.506,{ic:.028,sk:.071}],120411:[.671,0,.303,{ic:.118,sk:.14}],120412:[.505,.201,.56,{ic:.036,sk:.049}],120413:[.671,0,.564,{ic:.007,sk:.105}],120414:[.685,0,.264,{ic:.077,sk:.171}],120415:[.685,.201,.257,{ic:.078,sk:.21}],120416:[.671,0,.507,{ic:.086,sk:.07}],120417:[.671,0,.264,{ic:.072,sk:.241}],120418:[.505,0,.813,{ic:.015,sk:-.086}],120419:[.505,0,.563,{ic:.012,sk:.074}],120420:[.505,.008,.558,{ic:.019,sk:.051}],120421:[.505,.201,.559,{ic:.025,sk:.081}],120422:[.505,.201,.559,{ic:.039,sk:.053}],120423:[.505,0,.358,{ic:.088,sk:.153}],120424:[.505,.008,.507,{ic:.026,sk:.105}],120425:[.62,.004,.304,{ic:.072,sk:.21}],120426:[.497,.008,.563,{ic:.036,sk:.065}],120427:[.497,0,.504,{ic:.086,sk:.093}],120428:[.497,0,.702,{ic:.094}],120429:[.497,0,.504,{ic:.081,sk:.156}],120430:[.497,.201,.503,{ic:.088,sk:.141}],120431:[.497,0,.455,{ic:.066,sk:.226}]},"sans-serif-bold-italic":{305:[.497,0,.264,{ic:.035,sk:.276}],567:[.497,.201,.257,{ic:.038,sk:.32}]}}},"GT"));MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/sans-serif","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/script.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/script.js
new file mode 100644
index 0000000..d49978c
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/script.js
@@ -0,0 +1 @@
+(()=>{"use strict";const s=MathJax._.output.chtml.DynamicFonts.AddFontIds;MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont.dynamicSetup("","script",s({S:{normal:{119964:[.689,.019,1.09,{sk:-.169}],8492:[.69,.019,.95],119966:[.689,.017,.871,{sk:-.059}],119967:[.69,.019,.902],8496:[.694,.017,.755,{sk:.063}],8497:[.689,.017,.986,{sk:.018}],119970:[.689,.017,.859,{sk:.04}],8459:[.687,.017,1.07,{sk:-.283}],8464:[.689,.015,.806,{sk:.079}],119973:[.689,.253,.852,{sk:.048}],119974:[.689,.017,1.156,{sk:-.346}],8466:[.687,.019,.948,{sk:.049}],8499:[.691,.017,1.266,{sk:-.167}],119977:[.697,.024,1.193,{sk:-.095}],119978:[.691,.019,.864,{sk:-.038}],119979:[.69,.016,.897,{sk:.053}],119980:[.691,.14,.864,{sk:-.018}],8475:[.69,.017,1.027,{sk:-.092}],119982:[.689,.015,.993,{sk:-.086}],119983:[.689,.017,.996,{sk:-.029}],119984:[.687,.018,1.016,{sk:-.065}],119985:[.689,.019,1.05,{sk:.056}],119986:[.689,.019,1.269,{sk:-.191}],119987:[.688,.017,1.001,{sk:-.059}],119988:[.689,.27,.974,{sk:-.063}],119989:[.687,.019,.938,{sk:-.121}],119990:[.418,.017,.726,{sk:-.162}],119991:[.735,.014,.617,{sk:.025}],119992:[.418,.014,.484,{sk:.315}],119993:[.721,.014,.778,{sk:-.058}],8495:[.418,.014,.519,{sk:.05}],119995:[.735,.28,.797,{sk:.011}],8458:[.426,.308,.729,{sk:-.147}],119997:[.735,.014,.748,{sk:-.169}],119998:[.671,.017,.466,{sk:-.018}],119999:[.671,.308,.77,{sk:.052}],12e4:[.735,.017,.72,{sk:-.068}],120001:[.735,.014,.644,{sk:.018}],120002:[.416,.014,1.034,{sk:-.249}],120003:[.41,.014,.75,{sk:.035}],8500:[.427,.014,.629,{sk:-.057}],120005:[.41,.28,.873,{sk:-.131}],120006:[.413,.28,.707,{sk:-.14}],120007:[.41,0,.59,{sk:.039}],120008:[.506,.014,.5,{sk:.06}],120009:[.606,.014,.479,{sk:.179}],120010:[.406,.014,.721,{sk:-.05}],120011:[.41,.017,.642,{sk:-.01}],120012:[.409,.017,.892,{sk:-.136}],120013:[.41,.014,.645,{sk:-.114}],120014:[.406,.308,.754,{sk:-.168}],120015:[.413,.014,.663,{sk:-.083}],8467:[.676,.014,.433],8472:[.538,.186,.71,{sk:.056}]},script:{305:[.406,.017,.466],567:[.41,.308,.77]}},SB:{normal:{120016:[.703,.014,1.265,{sk:-.348}],120017:[.705,.014,1.099,{sk:-.3}],120018:[.703,.014,.925,{sk:-.218}],120019:[.703,.014,.984,{sk:-.164}],120020:[.703,.016,.848,{sk:-.152}],120021:[.713,.014,1.092,{sk:-.278}],120022:[.703,.014,.92,{sk:-.206}],120023:[.719,.016,1.22,{sk:-.361}],120024:[.707,.014,.854,{sk:-.183}],120025:[.701,.253,.912,{sk:-.122}],120026:[.709,.016,1.29,{sk:-.38}],120027:[.732,.014,1.062,{sk:-.171}],120028:[.704,.018,1.463,{sk:-.474}],120029:[.718,.026,1.378,{sk:-.373}],120030:[.703,.017,.899,{sk:-.144}],120031:[.706,.014,1.018,{sk:-.132}],120032:[.703,.154,.899,{sk:-.117}],120033:[.711,.014,1.196,{sk:-.467}],120034:[.703,.015,1.096,{sk:-.175}],120035:[.713,.014,1.112,{sk:-.206}],120036:[.703,.016,1.162,{sk:-.433}],120037:[.701,.016,1.24,{sk:-.234}],120038:[.701,.016,1.556,{sk:-.443}],120039:[.703,.014,1.09,{sk:-.19}],120040:[.702,.263,1.13,{sk:-.307}],120041:[.703,.018,1.093,{sk:-.188}],120042:[.425,.014,.762,{sk:-.094}],120043:[.735,.014,.696,{sk:-.055}],120044:[.425,.017,.574,{sk:-.01}],120045:[.72,.02,.851,{sk:-.089}],120046:[.425,.017,.581,{sk:.015}],120047:[.735,.28,.884,{sk:-.015}],120048:[.425,.309,.817,{sk:-.102}],120049:[.735,.014,.803,{sk:-.093}],120050:[.701,.014,.501,{sk:.026}],120051:[.701,.291,.811,{sk:-.143}],120052:[.735,.014,.8,{sk:-.278}],120053:[.735,.014,.779,{sk:-.133}],120054:[.425,.014,1.088,{sk:-.114}],120055:[.425,.014,.809,{sk:-.157}],120056:[.425,.014,.677,{sk:-.128}],120057:[.425,.28,.956,{sk:-.148}],120058:[.425,.28,.751,{sk:-.245}],120059:[.426,0,.699,{sk:-.217}],120060:[.521,.014,.537,{sk:-.142}],120061:[.615,.014,.554,{sk:-.155}],120062:[.411,.014,.78,{sk:-.26}],120063:[.411,.014,.702,{sk:.014}],120064:[.411,.014,.951,{sk:-.248}],120065:[.429,.014,.741,{sk:-.096}],120066:[.411,.291,.812,{sk:-.183}],120067:[.425,.014,.716,{sk:-.03}]},"bold-script":{305:[.411,.014,.501],567:[.411,.291,.811]}}},"GT"));MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/script","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/shapes.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/shapes.js
new file mode 100644
index 0000000..7ff68e8
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/shapes.js
@@ -0,0 +1 @@
+(()=>{"use strict";const t=MathJax._.output.chtml.DynamicFonts.AddFontIds;MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont.dynamicSetup("","shapes",t({SH:{normal:{9472:[.276,-.224,.5],9474:[.65,.15,.5],9484:[.276,.15,.5],9488:[.276,.15,.5],9492:[.65,-.224,.5],9496:[.65,-.224,.5],9500:[.65,.15,.5],9508:[.65,.15,.5],9516:[.276,.15,.5],9524:[.65,-.224,.5],9532:[.65,.15,.5],9601:[.1,0,.8],9608:[.8,0,.8],9617:[.8,0,.8],9618:[.8,0,.8],9619:[.8,0,.8],9644:[.375,-.125,.66],9645:[.375,-.125,.66],9824:[.668,0,.796],9825:[.668,0,.76],9826:[.67,0,.782],9827:[.668,0,.822],9828:[.668,0,.796],9829:[.668,0,.76],9830:[.67,0,.782],9831:[.668,0,.822],9834:[.662,.014,.6],9837:[.65,.035,.424],9838:[.65,.15,.399],9839:[.678,.178,.493],9901:[.475,-.025,.5,{ic:.117}],9902:[.7,.2,.5,{ic:.171}],10003:[.65,0,.752],10016:[.662,0,.822],10145:[.47,-.03,1.03],11034:[.702,.202,1.008]}},SHB:{bold:{9834:[.676,.019,.6],9901:[.481,-.02,.5,{ic:.128}],9902:[.711,.211,.5,{ic:.179}]}},"":{italic:{9834:[.653,.014,.6,{ic:.045}],9901:[.466,-.034,.5,{ic:.198}],9902:[.682,.182,.5,{ic:.254}]},"bold-italic":{9834:[.669,.019,.6,{ic:.023}],9901:[.475,-.026,.5,{ic:.216}],9902:[.699,.199,.5,{ic:.268}]}}},"GT"),{},["MJX-GT-SH","MJX-GT-SHB"]);MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/shapes","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/stretchy.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/stretchy.js
new file mode 100644
index 0000000..aea38cc
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/stretchy.js
@@ -0,0 +1 @@
+(()=>{"use strict";const s=MathJax._.output.chtml.DynamicFonts.AddFontIds,i=MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont,a=MathJax._.output.common.Direction,r=(a.DIRECTION,a.V);a.H;i.dynamicSetup("","stretchy",s({"":{normal:{8992:[1.212,0,.776],8993:[1.194,.018,.776],9138:[.763,0,1.353],9139:[.884,0,1.353]},bold:{},"-size3":{8747:[.959,.459,.708],8748:[.959,.459,1.116],8749:[.959,.459,1.524],8750:[.959,.459,.758],8751:[.959,.459,1.166],8752:[.959,.459,1.574],8753:[.959,.459,.774],8754:[.959,.459,.736],8755:[.959,.459,.736],10764:[.959,.459,1.932],10769:[.959,.459,.774]},"-size4":{8747:[1.263,.763,.75],8748:[1.263,.763,1.188],8749:[1.263,.763,1.626],8750:[1.263,.763,.804],8751:[1.263,.763,1.242],8752:[1.263,.763,1.68],8753:[1.263,.763,.818],8754:[1.263,.763,.78],8755:[1.263,.763,.78],10764:[1.263,.763,2.064],10769:[1.263,.763,.818]},"-size5":{8747:[1.462,.962,.776],8748:[1.462,.962,1.235],8749:[1.462,.962,1.694],8750:[1.462,.962,.832],8751:[1.462,.962,1.291],8752:[1.462,.962,1.75],8753:[1.462,.962,.846],8754:[1.462,.962,.807],8755:[1.462,.962,.807],10764:[1.462,.962,2.153],10769:[1.462,.962,.846]},"-size6":{8747:[1.701,1.201,.8],8748:[1.701,1.201,1.275],8749:[1.701,1.201,1.75],8750:[1.701,1.201,.858],8751:[1.701,1.201,1.333],8752:[1.701,1.201,1.808],8753:[1.701,1.201,.871],8754:[1.701,1.201,.832],8755:[1.701,1.201,.832],10764:[1.701,1.201,2.225],10769:[1.701,1.201,.871]},"-lf-tp":{8747:[1.161,0,.8],8748:[1.161,0,1.275],8749:[1.161,0,1.75],10764:[1.161,0,2.225]},"-rt-bt":{8747:[1.161,0,.8],8748:[1.161,0,1.275],8749:[1.161,0,1.75],10764:[1.161,0,2.225]},"-ex-md":{8748:[.58,0,1.275],8749:[.58,0,1.75],10764:[.58,0,2.225]}}},"GT"),{8512:{dir:r,sizes:[.957,1.361],variants:[0,2]},8719:{dir:r,sizes:[.955,1.375],variants:[0,2]},8720:{dir:r,sizes:[.955,1.375],variants:[0,2]},8721:{dir:r,sizes:[.955,1.375],variants:[0,2]},8747:{dir:r,sizes:[1.093,1.189,1.419,1.695,2.027,2.425,2.903],variants:[0,1,3,2,4,5,6],stretch:[8747,9134,8747],stretchv:[2,0,3],HDW:[.796,.296,.8]},8748:{dir:r,sizes:[1.093,1.189,1.419,1.695,2.027,2.425,2.903],variants:[0,1,3,2,4,5,6],stretch:[8748,8748,8748],stretchv:[2,1,3],HDW:[.796,.296,1.275]},8749:{dir:r,sizes:[1.093,1.189,1.419,1.695,2.027,2.425,2.903],variants:[0,1,3,2,4,5,6],stretch:[8749,8749,8749],stretchv:[2,1,3],HDW:[.796,.296,1.75]},8750:{dir:r,sizes:[1.093,1.189,1.419,1.695,2.027,2.425,2.903],variants:[0,1,3,2,4,5,6]},8751:{dir:r,sizes:[1.093,1.189,1.419,1.695,2.027,2.425,2.903],variants:[0,1,3,2,4,5,6]},8752:{dir:r,sizes:[1.093,1.189,1.419,1.695,2.027,2.425,2.903],variants:[0,1,3,2,4,5,6]},8753:{dir:r,sizes:[1.093,1.189,1.419,1.695,2.027,2.425,2.903],variants:[0,1,3,2,4,5,6]},8754:{dir:r,sizes:[1.093,1.189,1.419,1.695,2.027,2.425,2.903],variants:[0,1,3,2,4,5,6]},8755:{dir:r,sizes:[1.093,1.189,1.419,1.695,2.027,2.425,2.903],variants:[0,1,3,2,4,5,6]},8866:{dir:r,sizes:[.651,.801],variants:[0,0],schar:[8866,10205]},8867:{dir:r,sizes:[.651,.801],variants:[0,0],schar:[8867,10206]},8868:{dir:r,sizes:[.651,.801],variants:[0,0],schar:[8868,10201]},8869:{dir:r,sizes:[.651,.801],variants:[0,0],schar:[8869,10200]},8896:{dir:r,sizes:[.889,1.166],variants:[0,2]},8897:{dir:r,sizes:[.889,1.166],variants:[0,2]},8898:{dir:r,sizes:[.899,1.171],variants:[0,2]},8899:{dir:r,sizes:[.899,1.171],variants:[0,2]},10752:{dir:r,sizes:[.877,1.133],variants:[0,2]},10753:{dir:r,sizes:[.877,1.133],variants:[0,2]},10754:{dir:r,sizes:[.877,1.133],variants:[0,2]},10755:{dir:r,sizes:[.899,1.171],variants:[0,2]},10756:{dir:r,sizes:[.899,1.171],variants:[0,2]},10757:{dir:r,sizes:[.881,1.153],variants:[0,2]},10758:{dir:r,sizes:[.881,1.153],variants:[0,2]},10761:{dir:r,sizes:[.717,.907],variants:[0,2]},10764:{dir:r,sizes:[1.093,1.189,1.419,1.695,2.027,2.425,2.903],variants:[0,1,3,2,4,5,6],stretch:[10764,10764,10764],stretchv:[2,1,3],HDW:[.796,.296,2.225]},10769:{dir:r,sizes:[1.093,1.189,1.419,1.695,2.027,2.425,2.903],variants:[0,1,3,2,4,5,6]}});MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/stretchy","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/symbols-b-i.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/symbols-b-i.js
new file mode 100644
index 0000000..13522a8
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/symbols-b-i.js
@@ -0,0 +1 @@
+(()=>{"use strict";const c=MathJax._.output.chtml.DynamicFonts.AddFontIds;MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont.dynamicSetup("","symbols-b-i",c({SYB:{bold:{161:[.474,.23,.333],162:[.588,.14,.5],164:[.613,-.061,.5,{ic:.026}],166:[.678,.149,.22],169:[.689,.018,.747],170:[.688,-.349,.3,{ic:.001}],171:[.415,-.036,.5],173:[.287,-.171,.333],174:[.689,.018,.747],186:[.688,-.349,.33],187:[.415,-.036,.5],188:[.688,.012,.75],189:[.688,.012,.75,{ic:.025}],190:[.688,.012,.75],191:[.474,.228,.5],3647:[.759,.083,.667],8218:[.155,.18,.333],8222:[.155,.18,.5],8226:[.478,-.198,.35],8240:[.692,.01,1],8241:[.692,.01,1.32],8249:[.415,-.036,.333],8250:[.415,-.036,.333],8251:[.535,.035,.57],8253:[.731,.013,.5],8255:[-.089,.205,.5],8256:[.676,-.56,.5],8261:[.69,.167,.406],8262:[.69,.167,.406],8274:[.676,0,.5],8276:[-.089,.205,.5],8353:[.759,.083,.722],8358:[.676,.018,.722],8361:[.676,.015,1],8363:[.676,.03,.521],8369:[.676,0,.611],8451:[.691,.019,1.113],8470:[.681,.025,.983],8471:[.689,.018,.747],8478:[.676,0,.722],8480:[.684,-.309,.943],8482:[.676,-.319,1],8494:[.608,0,.764],8960:[.5,0,.57],9250:[.676,.014,.556],9251:[.216,.102,.5]}},SYI:{italic:{161:[.443,.235,.333,{ic:.077}],162:[.56,.143,.5],164:[.597,-.053,.5,{ic:.022}],166:[.663,.153,.275],169:[.686,.014,.76],170:[.676,-.361,.276,{ic:.076}],171:[.411,-.033,.5,{ic:.047}],173:[.255,-.192,.333],174:[.686,.014,.76],186:[.676,-.361,.31,{ic:.052}],187:[.411,-.033,.5],188:[.676,.01,.75],189:[.676,.01,.75],190:[.676,.01,.75],191:[.444,.232,.5],3647:[.736,.083,.611],8240:[.706,.019,1,{ic:.01}],8241:[.706,.019,1.36,{ic:.01}],8253:[.707,.012,.5],8255:[-.093,.205,.5],8256:[.653,-.541,.5,{ic:.129}],8274:[.653,0,.5,{ic:.127}],8276:[-.093,.205,.5],8353:[.736,.083,.667,{ic:.022}],8358:[.653,.015,.667,{ic:.06}],8361:[.653,.018,.833,{ic:.073}],8363:[.653,.028,.479,{ic:.069}],8369:[.653,0,.611],8451:[.676,.018,.947,{ic:.045}],8470:[.669,.015,.982,{ic:.036}],8471:[.686,.014,.76],8478:[.653,0,.611],8480:[.661,-.279,.936,{ic:.111}],8482:[.653,-.289,1.009,{ic:.111}],8494:[.588,0,.733],9250:[.683,.011,.5],9251:[.202,.102,.5,{ic:.015}],64256:[.681,.207,.533,{ic:.146}],64257:[.681,.207,.5],64258:[.682,.204,.5,{ic:.018}],64259:[.681,.207,.768],64260:[.682,.207,.762,{ic:.006}],163:[.67,.006,.5,{ic:.017}],165:[.653,0,.5,{ic:.103}],167:[.666,.162,.5],172:[.365,-.168,.675],177:[.614,0,.675],181:[.43,.215,.5],182:[.653,.123,.523,{ic:.093}],183:[.306,-.194,.25],215:[.485,-.016,.675],240:[.683,.011,.5],247:[.469,-.031,.675],8224:[.666,.159,.5],8225:[.666,.143,.5]}},SYBI:{"bold-italic":{161:[.462,.235,.389,{ic:.053}],162:[.576,.143,.5],164:[.586,-.034,.5,{ic:.026}],166:[.674,.159,.22],169:[.669,.018,.747],170:[.685,-.351,.266,{ic:.064}],171:[.415,-.032,.5],173:[.282,-.166,.333],174:[.669,.018,.747],186:[.685,-.352,.3,{ic:.05}],187:[.415,-.032,.5],188:[.683,.014,.75],189:[.683,.014,.75],190:[.683,.014,.75],191:[.462,.235,.5,{ic:.041}],3647:[.752,.083,.667],8240:[.706,.029,1],8241:[.706,.029,1.362],8253:[.734,.013,.5],8255:[-.089,.205,.5],8256:[.669,-.553,.5,{ic:.129}],8274:[.669,0,.5,{ic:.11}],8276:[-.089,.205,.5],8353:[.752,.083,.667,{ic:.01}],8358:[.669,.015,.722,{ic:.026}],8361:[.669,.018,.889,{ic:.051}],8363:[.669,.03,.496,{ic:.077}],8369:[.669,0,.611,{ic:.002}],8451:[.685,.018,.952,{ic:.048}],8470:[.681,.025,1.001,{ic:.041}],8471:[.669,.018,.747],8478:[.669,0,.667],8480:[.678,-.293,.964,{ic:.111}],8482:[.669,-.296,1.012,{ic:.111}],8494:[.602,0,.757],9250:[.699,.013,.5],9251:[.21,.102,.5,{ic:.013}],64256:[.703,.205,.617,{ic:.089}],64257:[.703,.205,.556],64258:[.704,.205,.556],64259:[.703,.205,.834],64260:[.704,.205,.819,{ic:.012}],163:[.683,.012,.5,{ic:.01}],165:[.669,0,.5,{ic:.128}],167:[.685,.143,.5],172:[.378,-.166,.57],177:[.579,0,.57],181:[.439,.216,.576],182:[.669,.193,.5,{ic:.062}],183:[.334,-.166,.25],215:[.452,-.048,.57],240:[.699,.013,.5],247:[.501,.001,.57],8224:[.685,.145,.5],8225:[.685,.139,.5]}}},"GT"),{},["MJX-GT-SYB","MJX-GT-SYI","MJX-GT-SYBI"]);MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/symbols-b-i","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/symbols.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/symbols.js
new file mode 100644
index 0000000..ca9f599
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/symbols.js
@@ -0,0 +1 @@
+(()=>{"use strict";const t=MathJax._.output.chtml.DynamicFonts.AddFontIds,a=MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont,o=MathJax._.output.common.Direction,s=(o.DIRECTION,o.V,o.H);a.dynamicSetup("","symbols",t({SY:{normal:{161:[.459,.226,.333],162:[.579,.138,.5],164:[.602,-.058,.5,{ic:.022}],166:[.662,.156,.2],169:[.686,.014,.76],170:[.676,-.349,.276],171:[.411,-.033,.5],173:[.257,-.194,.333],174:[.686,.014,.76],186:[.676,-.349,.31],187:[.411,-.033,.5],188:[.676,.014,.75],189:[.676,.014,.75],190:[.676,.014,.75],191:[.458,.226,.444],3647:[.745,.083,.667],8215:[-.07,.228,.493,{sk:.013}],8218:[.102,.141,.333],8222:[.102,.141,.444],8226:[.4,-.1,.46],8240:[.676,.013,1],8241:[.676,.013,1.32],8249:[.411,-.033,.333],8250:[.411,-.033,.333],8251:[.514,.014,.564],8253:[.736,.008,.444],8255:[-.105,.217,.5],8256:[.662,-.55,.5],8261:[.672,.173,.33],8262:[.672,.173,.33],8274:[.662,0,.5],8276:[-.105,.217,.5],8353:[.745,.083,.667],8358:[.662,.011,.722],8361:[.662,.011,.944],8363:[.662,.028,.482],8369:[.662,0,.556],8370:[.745,.083,.722],8451:[.676,.014,1.029],8457:[.676,0,.929],8470:[.669,.015,1.001],8471:[.686,.014,.76],8478:[.662,0,.667],8480:[.669,-.297,.939],8482:[.662,-.305,.98],8494:[.596,0,.742],8960:[.513,.013,.686],8965:[.45,-.05,.66],8966:[.546,.046,.66],9250:[.683,.01,.5],9251:[.16,.106,.5],11800:[.503,.241,.444],12310:[.668,.168,.43],12311:[.668,.168,.43],64256:[.683,0,.6,{ic:.05}],64257:[.683,0,.556],64258:[.683,0,.556],64259:[.683,0,.827],64260:[.683,0,.827],65279:[0,0,0]}},"":{"-largeop":{8512:[.93,.43,1.152]}}},"GT"),{8215:{dir:s,sizes:[.493],stretch:[0,8215],HDW:[-.07,.228,.493],ext:.16,hd:[-.07,.228]}},["MJX-GT-SY"]);MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/symbols","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/dynamic/variants.js b/docs/_static/mathjax/fonts/termes/chtml/dynamic/variants.js
new file mode 100644
index 0000000..693ad64
--- /dev/null
+++ b/docs/_static/mathjax/fonts/termes/chtml/dynamic/variants.js
@@ -0,0 +1 @@
+(()=>{"use strict";const t=MathJax._.output.chtml.DynamicFonts.AddFontIds;MathJax._.output.fonts["mathjax-termes"].chtml_ts.MathJaxTermesFont.dynamicSetup("","variants",t({VX:{"-tex-variant":{34:[.596,-.15,.644],39:[.596,-.15,.404],42:[.452,-.048,.522,{sk:-.015}],96:[.596,-.15,.404],126:[.067,.067,.541],170:[.46,.114,.444,{c:"a\u0332"}],176:[.4,-.1,.46],178:[.676,0,.5,{sk:-.013}],179:[.676,.014,.5],185:[.676,0,.5],186:[.46,.114,.5,{c:"o\u0332"}],8212:[.25,-.201,.667],8289:[.702,.202,1.008],8304:[.676,.014,.5,{sk:-.014}],8305:[.641,0,.278],8308:[.676,0,.5,{sk:.094}],8309:[.688,.014,.5,{sk:.177}],8310:[.684,.014,.5,{sk:.152}],8311:[.662,.008,.5,{sk:.013}],8312:[.676,.014,.5],8313:[.676,.022,.5],8314:[.5,0,.66],8315:[.276,-.224,.66],8316:[.372,-.128,.66],8317:[.658,.158,.398],8318:[.658,.158,.398],8319:[.46,0,.5,{sk:-.011}],8320:[.676,.014,.5,{sk:-.014}],8321:[.676,0,.5],8322:[.676,0,.5,{sk:-.013}],8323:[.676,.014,.5],8324:[.676,0,.5,{sk:.094}],8325:[.688,.014,.5,{sk:.177}],8326:[.684,.014,.5,{sk:.152}],8327:[.662,.008,.5,{sk:.013}],8328:[.676,.014,.5],8329:[.676,.022,.5],8330:[.5,0,.66],8331:[.276,-.224,.66],8332:[.372,-.128,.66],8333:[.658,.158,.398],8334:[.658,.158,.398]}}},"GT"),{},["MJX-GT-VX"]);MathJax.loader&&MathJax.loader.checkVersion("[mathjax-termes]/chtml/dynamic/variants","4.1.1","dynamic-font")})();
\ No newline at end of file
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ac.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ac.woff2
new file mode 100644
index 0000000..2d1bce7
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ac.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-acb.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-acb.woff2
new file mode 100644
index 0000000..2f1a286
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-acb.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-acbi.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-acbi.woff2
new file mode 100644
index 0000000..fbef5a9
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-acbi.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-aci.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-aci.woff2
new file mode 100644
index 0000000..bbe26ae
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-aci.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ar.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ar.woff2
new file mode 100644
index 0000000..0c95208
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ar.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-b.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-b.woff2
new file mode 100644
index 0000000..b862590
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-b.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-bi.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-bi.woff2
new file mode 100644
index 0000000..5692244
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-bi.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-brk.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-brk.woff2
new file mode 100644
index 0000000..d97b904
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-brk.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-c.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-c.woff2
new file mode 100644
index 0000000..7b86103
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-c.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-cb.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-cb.woff2
new file mode 100644
index 0000000..196606f
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-cb.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ds.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ds.woff2
new file mode 100644
index 0000000..429eae3
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ds.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-em.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-em.woff2
new file mode 100644
index 0000000..ad15453
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-em.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-f.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-f.woff2
new file mode 100644
index 0000000..d1a4e3f
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-f.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-fb.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-fb.woff2
new file mode 100644
index 0000000..70f6cba
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-fb.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-i.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-i.woff2
new file mode 100644
index 0000000..37d1a7b
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-i.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-lb.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-lb.woff2
new file mode 100644
index 0000000..d97abac
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-lb.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-li.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-li.woff2
new file mode 100644
index 0000000..f7e7789
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-li.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-lib.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-lib.woff2
new file mode 100644
index 0000000..3845c85
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-lib.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-lo.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-lo.woff2
new file mode 100644
index 0000000..18fe53e
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-lo.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-lr.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-lr.woff2
new file mode 100644
index 0000000..513dd68
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-lr.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-lt.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-lt.woff2
new file mode 100644
index 0000000..8fcca31
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-lt.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-m.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-m.woff2
new file mode 100644
index 0000000..a996e34
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-m.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-mi.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-mi.woff2
new file mode 100644
index 0000000..7d8000f
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-mi.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-n.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-n.woff2
new file mode 100644
index 0000000..1ad3e83
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-n.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ob.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ob.woff2
new file mode 100644
index 0000000..c1776ff
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ob.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-os.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-os.woff2
new file mode 100644
index 0000000..18ee693
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-os.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-pu.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-pu.woff2
new file mode 100644
index 0000000..e97b175
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-pu.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-pub.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-pub.woff2
new file mode 100644
index 0000000..4cd0fb1
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-pub.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-pubi.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-pubi.woff2
new file mode 100644
index 0000000..0c4c400
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-pubi.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-pui.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-pui.woff2
new file mode 100644
index 0000000..382a2da
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-pui.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-rb.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-rb.woff2
new file mode 100644
index 0000000..07a06fc
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-rb.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-s.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-s.woff2
new file mode 100644
index 0000000..429e069
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-s.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-s3.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-s3.woff2
new file mode 100644
index 0000000..e2fddfa
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-s3.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-s4.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-s4.woff2
new file mode 100644
index 0000000..6c4e39b
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-s4.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-s5.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-s5.woff2
new file mode 100644
index 0000000..c21e5ea
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-s5.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-s6.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-s6.woff2
new file mode 100644
index 0000000..4203878
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-s6.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-sb.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-sb.woff2
new file mode 100644
index 0000000..2ab566d
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-sb.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-sh.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-sh.woff2
new file mode 100644
index 0000000..4714192
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-sh.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-shb.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-shb.woff2
new file mode 100644
index 0000000..e6e2097
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-shb.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-so.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-so.woff2
new file mode 100644
index 0000000..61276a8
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-so.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ss.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ss.woff2
new file mode 100644
index 0000000..7436e0c
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ss.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ssb.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ssb.woff2
new file mode 100644
index 0000000..32565cb
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ssb.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ssbi.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ssbi.woff2
new file mode 100644
index 0000000..18984fd
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ssbi.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ssi.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ssi.woff2
new file mode 100644
index 0000000..4977635
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-ssi.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-sy.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-sy.woff2
new file mode 100644
index 0000000..ed23a64
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-sy.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-syb.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-syb.woff2
new file mode 100644
index 0000000..6de5281
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-syb.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-sybi.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-sybi.woff2
new file mode 100644
index 0000000..4382c32
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-sybi.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-syi.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-syi.woff2
new file mode 100644
index 0000000..d5924f7
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-syi.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-v.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-v.woff2
new file mode 100644
index 0000000..f01f255
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-v.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-vx.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-vx.woff2
new file mode 100644
index 0000000..9d5407a
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-vx.woff2 differ
diff --git a/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-zero.woff2 b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-zero.woff2
new file mode 100644
index 0000000..185518a
Binary files /dev/null and b/docs/_static/mathjax/fonts/termes/chtml/woff2/mjx-gt-zero.woff2 differ
diff --git a/docs/_static/mathjax/tex-mml-chtml.js b/docs/_static/mathjax/tex-mml-chtml.js
new file mode 100644
index 0000000..757b18b
--- /dev/null
+++ b/docs/_static/mathjax/tex-mml-chtml.js
@@ -0,0 +1 @@
+(()=>{var __webpack_modules__={870(t,e){"use strict";function s(t,e){return void 0===e&&(e=Object),e&&"function"==typeof e.getOwnPropertyDescriptors&&(t=e.create(null,e.getOwnPropertyDescriptors(t))),e&&"function"==typeof e.freeze?e.freeze(t):t}function i(t,e){return Object.prototype.hasOwnProperty.call(t,e)}var r=s({allowfullscreen:!0,async:!0,autofocus:!0,autoplay:!0,checked:!0,controls:!0,default:!0,defer:!0,disabled:!0,formnovalidate:!0,hidden:!0,ismap:!0,itemscope:!0,loop:!0,multiple:!0,muted:!0,nomodule:!0,novalidate:!0,open:!0,playsinline:!0,readonly:!0,required:!0,reversed:!0,selected:!0});var n=s({area:!0,base:!0,br:!0,col:!0,embed:!0,hr:!0,img:!0,input:!0,link:!0,meta:!0,param:!0,source:!0,track:!0,wbr:!0});var o=s({script:!1,style:!1,textarea:!0,title:!0});function a(t){return t===l.HTML}var l=s({HTML:"text/html",XML_APPLICATION:"application/xml",XML_TEXT:"text/xml",XML_XHTML_APPLICATION:"application/xhtml+xml",XML_SVG_IMAGE:"image/svg+xml"}),c=Object.keys(l).map(function(t){return l[t]});var h=s({HTML:"http://www.w3.org/1999/xhtml",SVG:"http://www.w3.org/2000/svg",XML:"http://www.w3.org/XML/1998/namespace",XMLNS:"http://www.w3.org/2000/xmlns/"});e.assign=function(t,e){if(null===t||"object"!=typeof t)throw new TypeError("target is not an object");for(var s in e)i(e,s)&&(t[s]=e[s]);return t},e.find=function(t,e,s){if(void 0===s&&(s=Array.prototype),t&&"function"==typeof s.find)return s.find.call(t,e);for(var r=0;r-1},e.MIME_TYPE=l,e.NAMESPACE=h},576(t,e,s){"use strict";var i=s(870),r=s(786),n=s(767),o=s(159),a=s(802),l=r.DOMImplementation,c=i.hasDefaultHTMLNamespace,h=i.isHTMLMimeType,d=i.isValidMimeType,u=i.MIME_TYPE,p=i.NAMESPACE,m=n.ParseError,f=a.XMLReader;function g(t){return t.replace(/\r[\n\u0085]/g,"\n").replace(/[\r\u0085\u2028\u2029]/g,"\n")}function b(t){if(void 0===(t=t||{}).locator&&(t.locator=!0),this.assign=t.assign||i.assign,this.domHandler=t.domHandler||E,this.onError=t.onError||t.errorHandler,t.errorHandler&&"function"!=typeof t.errorHandler)throw new TypeError("errorHandler object is no longer supported, switch to onError!");t.errorHandler&&t.errorHandler("warning","The `errorHandler` option has been deprecated, use `onError` instead!",this),this.normalizeLineEndings=t.normalizeLineEndings||g,this.locator=!!t.locator,this.xmlns=this.assign(Object.create(null),t.xmlns)}function E(t){var e=t||{};this.mimeType=e.mimeType||u.XML_APPLICATION,this.defaultNamespace=e.defaultNamespace||null,this.cdata=!1,this.currentElement=void 0,this.doc=void 0,this.locator=void 0,this.onError=e.onError}function x(t,e){e.lineNumber=t.lineNumber,e.columnNumber=t.columnNumber}function y(t,e,s){return"string"==typeof t?t.substr(e,s):t.length>=e+s||e?new java.lang.String(t,e,s)+"":t}function N(t,e){t.currentElement?t.currentElement.appendChild(e):t.doc.appendChild(e)}b.prototype.parseFromString=function(t,e){if(!d(e))throw new TypeError('DOMParser.parseFromString: the provided mimeType "'+e+'" is not valid.');var s=this.assign(Object.create(null),this.xmlns),r=o.XML_ENTITIES,n=s[""]||null;c(e)?(r=o.HTML_ENTITIES,n=p.HTML):e===u.XML_SVG_IMAGE&&(n=p.SVG),s[""]=n,s.xml=s.xml||p.XML;var a=new this.domHandler({mimeType:e,defaultNamespace:n,onError:this.onError}),l=this.locator?{}:void 0;this.locator&&a.setDocumentLocator(l);var h=new f;return h.errorHandler=a,h.domBuilder=a,!i.isHTMLMimeType(e)&&"string"!=typeof t&&h.errorHandler.fatalError("source is not a string"),h.parse(this.normalizeLineEndings(String(t)),s,r),a.doc.documentElement||h.errorHandler.fatalError("missing root element"),a.doc},E.prototype={startDocument:function(){var t=new l;this.doc=h(this.mimeType)?t.createHTMLDocument(!1):t.createDocument(this.defaultNamespace,"")},startElement:function(t,e,s,i){var r=this.doc,n=r.createElementNS(t,s||e),o=i.length;N(this,n),this.currentElement=n,this.locator&&x(this.locator,n);for(var a=0;a=0){var n=e.split(":");s=n[0],r=n[1]}if(null!==s&&null===t)throw new m(m.NAMESPACE_ERR,"prefix is non-null and namespace is null");if("xml"===s&&t!==i.NAMESPACE.XML)throw new m(m.NAMESPACE_ERR,'prefix is "xml" and namespace is not the XML namespace');if(("xmlns"===s||"xmlns"===e)&&t!==i.NAMESPACE.XMLNS)throw new m(m.NAMESPACE_ERR,'either qualifiedName or prefix is "xmlns" and namespace is not the XMLNS namespace');if(t===i.NAMESPACE.XMLNS&&"xmlns"!==s&&"xmlns"!==e)throw new m(m.NAMESPACE_ERR,'namespace is the XMLNS namespace and neither qualifiedName nor prefix is "xmlns"');return[t,s,r]}function T(t,e){for(var s in t)o(t,s)&&(e[s]=t[s])}function w(t,e){var s=t.prototype;if(!(s instanceof e)){function i(){}i.prototype=e.prototype,T(s,i=new i),t.prototype=s=i}s.constructor!=t&&("function"!=typeof t&&console.error("unknown Class:"+t),s.constructor=t)}var C={},k=C.ELEMENT_NODE=1,_=C.ATTRIBUTE_NODE=2,L=C.TEXT_NODE=3,A=C.CDATA_SECTION_NODE=4,R=C.ENTITY_REFERENCE_NODE=5,S=C.ENTITY_NODE=6,M=C.PROCESSING_INSTRUCTION_NODE=7,I=C.COMMENT_NODE=8,O=C.DOCUMENT_NODE=9,D=C.DOCUMENT_TYPE_NODE=10,P=C.DOCUMENT_FRAGMENT_NODE=11,B=C.NOTATION_NODE=12,F=i.freeze({DOCUMENT_POSITION_DISCONNECTED:1,DOCUMENT_POSITION_PRECEDING:2,DOCUMENT_POSITION_FOLLOWING:4,DOCUMENT_POSITION_CONTAINS:8,DOCUMENT_POSITION_CONTAINED_BY:16,DOCUMENT_POSITION_IMPLEMENTATION_SPECIFIC:32});function j(t,e){if(e.length=0){for(var r=e.length-1;i<=r;)e[i]=e[++i];if(e.length=r,t){var n=t.ownerDocument;n&&Z(n,t,s),s.ownerElement=null}}}function J(){}function K(t){b(t)}function $(t){return("<"==t?"<":">"==t&&">")||"&"==t&&"&"||'"'==t&&"""||"&#"+t.charCodeAt()+";"}function Y(t,e){if(e(t))return!0;if(t=t.firstChild)do{if(Y(t,e))return!0}while(t=t.nextSibling)}function Q(t,e){b(t);var s=e||{};this.ownerDocument=this,this.contentType=s.contentType||h.XML_APPLICATION,this.type=a(this.contentType)?"html":"xml"}function Z(t,e,s,i){t&&t._inc++,s.namespaceURI===d.XMLNS&&delete e._nsMap[s.prefix?s.localName:""]}function tt(t,e,s){if(t&&t._inc){t._inc++;var i=e.childNodes;if(s&&!s.nextSibling)i[i.length++]=s;else{for(var r=e.firstChild,n=0;r;)i[n++]=r,r=r.nextSibling;i.length=n,delete i[i.length]}}}function et(t,e){if(t!==e.parentNode)throw new m(m.NOT_FOUND_ERR,"child's parent is not parent");var s=e.previousSibling,i=e.nextSibling;return s?s.nextSibling=i:t.firstChild=i,i?i.previousSibling=s:t.lastChild=s,tt(t.ownerDocument,t),e.parentNode=null,e.previousSibling=null,e.nextSibling=null,e}function st(t){return t&&t.nodeType===K.DOCUMENT_TYPE_NODE}function it(t){return t&&t.nodeType===K.ELEMENT_NODE}function rt(t){return t&&t.nodeType===K.TEXT_NODE}function nt(t,e){var s=t.childNodes||[];if(r(s,it)||st(e))return!1;var i=r(s,st);return!(e&&i&&s.indexOf(i)>s.indexOf(e))}function ot(t,e){var s=t.childNodes||[];if(r(s,function(t){return it(t)&&t!==e}))return!1;var i=r(s,st);return!(e&&i&&s.indexOf(i)>s.indexOf(e))}function at(t,e,s){if(!function(t){return t&&(t.nodeType===K.DOCUMENT_NODE||t.nodeType===K.DOCUMENT_FRAGMENT_NODE||t.nodeType===K.ELEMENT_NODE)}(t))throw new m(m.HIERARCHY_REQUEST_ERR,"Unexpected parent node type "+t.nodeType);if(s&&s.parentNode!==t)throw new m(m.NOT_FOUND_ERR,"child not in parent");if(!function(t){return t&&(t.nodeType===K.CDATA_SECTION_NODE||t.nodeType===K.COMMENT_NODE||t.nodeType===K.DOCUMENT_FRAGMENT_NODE||t.nodeType===K.DOCUMENT_TYPE_NODE||t.nodeType===K.ELEMENT_NODE||t.nodeType===K.PROCESSING_INSTRUCTION_NODE||t.nodeType===K.TEXT_NODE)}(e)||st(e)&&t.nodeType!==K.DOCUMENT_NODE)throw new m(m.HIERARCHY_REQUEST_ERR,"Unexpected node type "+e.nodeType+" for parent node type "+t.nodeType)}function lt(t,e,s){var i=t.childNodes||[],n=e.childNodes||[];if(e.nodeType===K.DOCUMENT_FRAGMENT_NODE){var o=n.filter(it);if(o.length>1||r(n,rt))throw new m(m.HIERARCHY_REQUEST_ERR,"More than one element or text in fragment");if(1===o.length&&!nt(t,s))throw new m(m.HIERARCHY_REQUEST_ERR,"Element in fragment can not be inserted before doctype")}if(it(e)&&!nt(t,s))throw new m(m.HIERARCHY_REQUEST_ERR,"Only one element can be added and only after doctype");if(st(e)){if(r(i,st))throw new m(m.HIERARCHY_REQUEST_ERR,"Only one doctype is allowed");var a=r(i,it);if(s&&i.indexOf(a)1||r(n,rt))throw new m(m.HIERARCHY_REQUEST_ERR,"More than one element or text in fragment");if(1===o.length&&!ot(t,s))throw new m(m.HIERARCHY_REQUEST_ERR,"Element in fragment can not be inserted before doctype")}if(it(e)&&!ot(t,s))throw new m(m.HIERARCHY_REQUEST_ERR,"Only one element can be added and only after doctype");if(st(e)){function l(t){return st(t)&&t!==s}if(r(i,l))throw new m(m.HIERARCHY_REQUEST_ERR,"Only one doctype is allowed");var a=r(i,it);if(s&&i.indexOf(a)=0;f--){if(""===(b=i[f]).prefix&&b.namespace===t.namespaceURI){p=b.namespace;break}}if(p!==t.namespaceURI)for(f=i.length-1;f>=0;f--){var b;if((b=i[f]).namespace===t.namespaceURI){b.prefix&&(u=b.prefix+":"+h);break}}}e.push("<",u);for(var E=0;E");else{if(e.push(">"),r&&l(h))for(;a;)a.data?e.push(a.data):_t(a,e,s,i.slice()),a=a.nextSibling;else for(;a;)_t(a,e,s,i.slice()),a=a.nextSibling;e.push("")}return;case O:case P:for(a=t.firstChild;a;)_t(a,e,s,i.slice()),a=a.nextSibling;return;case _:return kt(e,t.name,t.value);case L:return e.push(t.data.replace(/[<&>]/g,$));case A:return e.push(g.CDATA_START,t.data,g.CDATA_END);case I:return e.push(g.COMMENT_START,t.data,g.COMMENT_END);case D:var T=t.publicId,w=t.systemId;return e.push(g.DOCTYPE_DECL_START," ",t.name),T?(e.push(" ",g.PUBLIC," ",T),w&&"."!==w&&e.push(" ",w)):w&&"."!==w&&e.push(" ",g.SYSTEM," ",w),t.internalSubset&&e.push(" [",t.internalSubset,"]"),void e.push(">");case M:return e.push("");case R:return e.push("&",t.nodeName,";");default:e.push("??",t.nodeName)}}function Lt(t,e,s){var i;switch(e.nodeType){case k:(i=e.cloneNode(!1)).ownerDocument=t;case P:break;case _:s=!0}if(i||(i=e.cloneNode(!1)),i.ownerDocument=t,i.parentNode=null,s)for(var r=e.firstChild;r;)i.appendChild(Lt(t,r,s)),r=r.nextSibling;return i}function At(t,e,s){var i=new e.constructor(u);for(var r in e)if(o(e,r)){var n=e[r];"object"!=typeof n&&n!=i[r]&&(i[r]=n)}switch(e.childNodes&&(i.childNodes=new H),i.ownerDocument=t,i.nodeType){case k:var a=e.attributes,l=i.attributes=new z,c=a.length;l._ownerElement=i;for(var h=0;h=0&&tU(e.ownerDocument)?F.DOCUMENT_POSITION_FOLLOWING:F.DOCUMENT_POSITION_PRECEDING);if(r&&e===s)return F.DOCUMENT_POSITION_CONTAINS+F.DOCUMENT_POSITION_PRECEDING;if(i&&e===s)return F.DOCUMENT_POSITION_CONTAINED_BY+F.DOCUMENT_POSITION_FOLLOWING;for(var a=[],l=e.parentNode;l;){if(!r&&l===s)return F.DOCUMENT_POSITION_CONTAINED_BY+F.DOCUMENT_POSITION_FOLLOWING;a.push(l),l=l.parentNode}a.reverse();for(var c=[],h=s.parentNode;h;){if(!i&&h===e)return F.DOCUMENT_POSITION_CONTAINS+F.DOCUMENT_POSITION_PRECEDING;c.push(h),h=h.parentNode}c.reverse();var d=j(a,c);for(var u in d.childNodes){var p=d.childNodes[u];if(p===s)return F.DOCUMENT_POSITION_FOLLOWING;if(p===e)return F.DOCUMENT_POSITION_PRECEDING;if(c.indexOf(p)>=0)return F.DOCUMENT_POSITION_FOLLOWING;if(a.indexOf(p)>=0)return F.DOCUMENT_POSITION_PRECEDING}return 0}},T(C,K),T(C,K.prototype),T(F,K),T(F,K.prototype),Q.prototype={implementation:null,nodeName:"#document",nodeType:O,doctype:null,documentElement:null,_inc:1,insertBefore:function(t,e){if(t.nodeType===P){for(var s=t.firstChild;s;){var i=s.nextSibling;this.insertBefore(s,e),s=i}return t}return ht(this,t,e),t.ownerDocument=this,null===this.documentElement&&t.nodeType===k&&(this.documentElement=t),t},removeChild:function(t){var e=et(this,t);return e===this.documentElement&&(this.documentElement=null),e},replaceChild:function(t,e){ht(this,t,e,ct),t.ownerDocument=this,e&&this.removeChild(e),it(t)&&(this.documentElement=t)},importNode:function(t,e){return Lt(this,t,e)},getElementById:function(t){var e=null;return Y(this.documentElement,function(s){if(s.nodeType==k&&s.getAttribute("id")==t)return e=s,!0}),e},createElement:function(t){var e=new dt(u);return e.ownerDocument=this,"html"===this.type&&(t=t.toLowerCase()),n(this.contentType)&&(e.namespaceURI=d.HTML),e.nodeName=t,e.tagName=t,e.localName=t,e.childNodes=new H,(e.attributes=new z)._ownerElement=e,e},createDocumentFragment:function(){var t=new Nt(u);return t.ownerDocument=this,t.childNodes=new H,t},createTextNode:function(t){var e=new mt(u);return e.ownerDocument=this,e.childNodes=new H,e.appendData(t),e},createComment:function(t){var e=new ft(u);return e.ownerDocument=this,e.childNodes=new H,e.appendData(t),e},createCDATASection:function(t){var e=new gt(u);return e.ownerDocument=this,e.childNodes=new H,e.appendData(t),e},createProcessingInstruction:function(t,e){var s=new vt(u);return s.ownerDocument=this,s.childNodes=new H,s.nodeName=s.target=t,s.nodeValue=s.data=e,s},createAttribute:function(t){if(!g.QName_exact.test(t))throw new m(m.INVALID_CHARACTER_ERR,'invalid character in name "'+t+'"');return"html"===this.type&&(t=t.toLowerCase()),this._createAttribute(t)},_createAttribute:function(t){var e=new ut(u);return e.ownerDocument=this,e.childNodes=new H,e.name=t,e.nodeName=t,e.localName=t,e.specified=!0,e},createEntityReference:function(t){if(!g.Name.test(t))throw new m(m.INVALID_CHARACTER_ERR,'not a valid xml name "'+t+'"');if("html"===this.type)throw new m("document is an html document",f.NotSupportedError);var e=new yt(u);return e.ownerDocument=this,e.childNodes=new H,e.nodeName=t,e},createElementNS:function(t,e){var s=v(t,e),i=new dt(u),r=i.attributes=new z;return i.childNodes=new H,i.ownerDocument=this,i.nodeName=e,i.tagName=e,i.namespaceURI=s[0],i.prefix=s[1],i.localName=s[2],r._ownerElement=i,i},createAttributeNS:function(t,e){var s=v(t,e),i=new ut(u);return i.ownerDocument=this,i.childNodes=new H,i.nodeName=e,i.name=e,i.specified=!0,i.namespaceURI=s[0],i.prefix=s[1],i.localName=s[2],i}},w(Q,K),dt.prototype={nodeType:k,attributes:null,getQualifiedName:function(){return this.prefix?this.prefix+":"+this.localName:this.localName},_isInHTMLDocumentAndNamespace:function(){return"html"===this.ownerDocument.type&&this.namespaceURI===d.HTML},hasAttributes:function(){return!(!this.attributes||!this.attributes.length)},hasAttribute:function(t){return!!this.getAttributeNode(t)},getAttribute:function(t){var e=this.getAttributeNode(t);return e?e.value:null},getAttributeNode:function(t){return this._isInHTMLDocumentAndNamespace()&&(t=t.toLowerCase()),this.attributes.getNamedItem(t)},setAttribute:function(t,e){this._isInHTMLDocumentAndNamespace()&&(t=t.toLowerCase());var s=this.getAttributeNode(t);s?s.value=s.nodeValue=""+e:((s=this.ownerDocument._createAttribute(t)).value=s.nodeValue=""+e,this.setAttributeNode(s))},removeAttribute:function(t){var e=this.getAttributeNode(t);e&&this.removeAttributeNode(e)},setAttributeNode:function(t){return this.attributes.setNamedItem(t)},setAttributeNodeNS:function(t){return this.attributes.setNamedItemNS(t)},removeAttributeNode:function(t){return this.attributes.removeNamedItem(t.nodeName)},removeAttributeNS:function(t,e){var s=this.getAttributeNodeNS(t,e);s&&this.removeAttributeNode(s)},hasAttributeNS:function(t,e){return null!=this.getAttributeNodeNS(t,e)},getAttributeNS:function(t,e){var s=this.getAttributeNodeNS(t,e);return s?s.value:null},setAttributeNS:function(t,e,s){var i=v(t,e)[2],r=this.getAttributeNodeNS(t,i);r?r.value=r.nodeValue=""+s:((r=this.ownerDocument.createAttributeNS(t,e)).value=r.nodeValue=""+s,this.setAttributeNode(r))},getAttributeNodeNS:function(t,e){return this.attributes.getNamedItemNS(t,e)},getElementsByClassName:function(t){var e=y(t);return new q(this,function(s){var i=[];return e.length>0&&Y(s,function(r){if(r!==s&&r.nodeType===k){var n=r.getAttribute("class");if(n){var o=t===n;if(!o){var a=y(n);o=e.every((l=a,function(t){return l&&-1!==l.indexOf(t)}))}o&&i.push(r)}}var l}),i})},getElementsByTagName:function(t){var e="html"===(this.nodeType===O?this:this.ownerDocument).type,s=t.toLowerCase();return new q(this,function(i){var r=[];return Y(i,function(n){n!==i&&n.nodeType===k&&(("*"===t||n.getQualifiedName()===(e&&n.namespaceURI===d.HTML?s:t))&&r.push(n))}),r})},getElementsByTagNameNS:function(t,e){return new q(this,function(s){var i=[];return Y(s,function(r){r===s||r.nodeType!==k||"*"!==t&&r.namespaceURI!==t||"*"!==e&&r.localName!=e||i.push(r)}),i})}},Q.prototype.getElementsByClassName=dt.prototype.getElementsByClassName,Q.prototype.getElementsByTagName=dt.prototype.getElementsByTagName,Q.prototype.getElementsByTagNameNS=dt.prototype.getElementsByTagNameNS,w(dt,K),ut.prototype.nodeType=_,w(ut,K),pt.prototype={data:"",substringData:function(t,e){return this.data.substring(t,t+e)},appendData:function(t){t=this.data+t,this.nodeValue=this.data=t,this.length=t.length},insertData:function(t,e){this.replaceData(t,0,e)},deleteData:function(t,e){this.replaceData(t,e,"")},replaceData:function(t,e,s){s=this.data.substring(0,t)+s+this.data.substring(t+e),this.nodeValue=this.data=s,this.length=s.length}},w(pt,K),mt.prototype={nodeName:"#text",nodeType:L,splitText:function(t){var e=this.data,s=e.substring(t);e=e.substring(0,t),this.data=this.nodeValue=e,this.length=e.length;var i=this.ownerDocument.createTextNode(s);return this.parentNode&&this.parentNode.insertBefore(i,this.nextSibling),i}},w(mt,pt),ft.prototype={nodeName:"#comment",nodeType:I},w(ft,pt),gt.prototype={nodeName:"#cdata-section",nodeType:A},w(gt,mt),bt.prototype.nodeType=D,w(bt,K),Et.prototype.nodeType=B,w(Et,K),xt.prototype.nodeType=S,w(xt,K),yt.prototype.nodeType=R,w(yt,K),Nt.prototype.nodeName="#document-fragment",Nt.prototype.nodeType=P,w(Nt,K),vt.prototype.nodeType=M,w(vt,pt),Tt.prototype.serializeToString=function(t,e){return wt.call(t,e)},K.prototype.toString=wt;try{if(Object.defineProperty){function St(t){switch(t.nodeType){case k:case P:var e=[];for(t=t.firstChild;t;)7!==t.nodeType&&8!==t.nodeType&&e.push(St(t)),t=t.nextSibling;return e.join("");default:return t.nodeValue}}Object.defineProperty(q.prototype,"length",{get:function(){return W(this),this.$$length}}),Object.defineProperty(K.prototype,"textContent",{get:function(){return St(this)},set:function(t){switch(this.nodeType){case k:case P:for(;this.firstChild;)this.removeChild(this.firstChild);(t||String(t))&&this.appendChild(this.ownerDocument.createTextNode(t));break;default:this.data=t,this.value=t,this.nodeValue=t}}}),Rt=function(t,e,s){t["$$"+e]=s}}}catch(Mt){}e._updateLiveList=W,e.Attr=ut,e.CDATASection=gt,e.CharacterData=pt,e.Comment=ft,e.Document=Q,e.DocumentFragment=Nt,e.DocumentType=bt,e.DOMImplementation=J,e.Element=dt,e.Entity=xt,e.EntityReference=yt,e.LiveNodeList=q,e.NamedNodeMap=z,e.Node=K,e.NodeList=H,e.Notation=Et,e.Text=mt,e.ProcessingInstruction=vt,e.XMLSerializer=Tt},159(t,e,s){"use strict";var i=s(870).freeze;e.XML_ENTITIES=i({amp:"&",apos:"'",gt:">",lt:"<",quot:'"'}),e.HTML_ENTITIES=i({Aacute:"\xc1",aacute:"\xe1",Abreve:"\u0102",abreve:"\u0103",ac:"\u223e",acd:"\u223f",acE:"\u223e\u0333",Acirc:"\xc2",acirc:"\xe2",acute:"\xb4",Acy:"\u0410",acy:"\u0430",AElig:"\xc6",aelig:"\xe6",af:"\u2061",Afr:"\u{1d504}",afr:"\u{1d51e}",Agrave:"\xc0",agrave:"\xe0",alefsym:"\u2135",aleph:"\u2135",Alpha:"\u0391",alpha:"\u03b1",Amacr:"\u0100",amacr:"\u0101",amalg:"\u2a3f",AMP:"&",amp:"&",And:"\u2a53",and:"\u2227",andand:"\u2a55",andd:"\u2a5c",andslope:"\u2a58",andv:"\u2a5a",ang:"\u2220",ange:"\u29a4",angle:"\u2220",angmsd:"\u2221",angmsdaa:"\u29a8",angmsdab:"\u29a9",angmsdac:"\u29aa",angmsdad:"\u29ab",angmsdae:"\u29ac",angmsdaf:"\u29ad",angmsdag:"\u29ae",angmsdah:"\u29af",angrt:"\u221f",angrtvb:"\u22be",angrtvbd:"\u299d",angsph:"\u2222",angst:"\xc5",angzarr:"\u237c",Aogon:"\u0104",aogon:"\u0105",Aopf:"\u{1d538}",aopf:"\u{1d552}",ap:"\u2248",apacir:"\u2a6f",apE:"\u2a70",ape:"\u224a",apid:"\u224b",apos:"'",ApplyFunction:"\u2061",approx:"\u2248",approxeq:"\u224a",Aring:"\xc5",aring:"\xe5",Ascr:"\u{1d49c}",ascr:"\u{1d4b6}",Assign:"\u2254",ast:"*",asymp:"\u2248",asympeq:"\u224d",Atilde:"\xc3",atilde:"\xe3",Auml:"\xc4",auml:"\xe4",awconint:"\u2233",awint:"\u2a11",backcong:"\u224c",backepsilon:"\u03f6",backprime:"\u2035",backsim:"\u223d",backsimeq:"\u22cd",Backslash:"\u2216",Barv:"\u2ae7",barvee:"\u22bd",Barwed:"\u2306",barwed:"\u2305",barwedge:"\u2305",bbrk:"\u23b5",bbrktbrk:"\u23b6",bcong:"\u224c",Bcy:"\u0411",bcy:"\u0431",bdquo:"\u201e",becaus:"\u2235",Because:"\u2235",because:"\u2235",bemptyv:"\u29b0",bepsi:"\u03f6",bernou:"\u212c",Bernoullis:"\u212c",Beta:"\u0392",beta:"\u03b2",beth:"\u2136",between:"\u226c",Bfr:"\u{1d505}",bfr:"\u{1d51f}",bigcap:"\u22c2",bigcirc:"\u25ef",bigcup:"\u22c3",bigodot:"\u2a00",bigoplus:"\u2a01",bigotimes:"\u2a02",bigsqcup:"\u2a06",bigstar:"\u2605",bigtriangledown:"\u25bd",bigtriangleup:"\u25b3",biguplus:"\u2a04",bigvee:"\u22c1",bigwedge:"\u22c0",bkarow:"\u290d",blacklozenge:"\u29eb",blacksquare:"\u25aa",blacktriangle:"\u25b4",blacktriangledown:"\u25be",blacktriangleleft:"\u25c2",blacktriangleright:"\u25b8",blank:"\u2423",blk12:"\u2592",blk14:"\u2591",blk34:"\u2593",block:"\u2588",bne:"=\u20e5",bnequiv:"\u2261\u20e5",bNot:"\u2aed",bnot:"\u2310",Bopf:"\u{1d539}",bopf:"\u{1d553}",bot:"\u22a5",bottom:"\u22a5",bowtie:"\u22c8",boxbox:"\u29c9",boxDL:"\u2557",boxDl:"\u2556",boxdL:"\u2555",boxdl:"\u2510",boxDR:"\u2554",boxDr:"\u2553",boxdR:"\u2552",boxdr:"\u250c",boxH:"\u2550",boxh:"\u2500",boxHD:"\u2566",boxHd:"\u2564",boxhD:"\u2565",boxhd:"\u252c",boxHU:"\u2569",boxHu:"\u2567",boxhU:"\u2568",boxhu:"\u2534",boxminus:"\u229f",boxplus:"\u229e",boxtimes:"\u22a0",boxUL:"\u255d",boxUl:"\u255c",boxuL:"\u255b",boxul:"\u2518",boxUR:"\u255a",boxUr:"\u2559",boxuR:"\u2558",boxur:"\u2514",boxV:"\u2551",boxv:"\u2502",boxVH:"\u256c",boxVh:"\u256b",boxvH:"\u256a",boxvh:"\u253c",boxVL:"\u2563",boxVl:"\u2562",boxvL:"\u2561",boxvl:"\u2524",boxVR:"\u2560",boxVr:"\u255f",boxvR:"\u255e",boxvr:"\u251c",bprime:"\u2035",Breve:"\u02d8",breve:"\u02d8",brvbar:"\xa6",Bscr:"\u212c",bscr:"\u{1d4b7}",bsemi:"\u204f",bsim:"\u223d",bsime:"\u22cd",bsol:"\\",bsolb:"\u29c5",bsolhsub:"\u27c8",bull:"\u2022",bullet:"\u2022",bump:"\u224e",bumpE:"\u2aae",bumpe:"\u224f",Bumpeq:"\u224e",bumpeq:"\u224f",Cacute:"\u0106",cacute:"\u0107",Cap:"\u22d2",cap:"\u2229",capand:"\u2a44",capbrcup:"\u2a49",capcap:"\u2a4b",capcup:"\u2a47",capdot:"\u2a40",CapitalDifferentialD:"\u2145",caps:"\u2229\ufe00",caret:"\u2041",caron:"\u02c7",Cayleys:"\u212d",ccaps:"\u2a4d",Ccaron:"\u010c",ccaron:"\u010d",Ccedil:"\xc7",ccedil:"\xe7",Ccirc:"\u0108",ccirc:"\u0109",Cconint:"\u2230",ccups:"\u2a4c",ccupssm:"\u2a50",Cdot:"\u010a",cdot:"\u010b",cedil:"\xb8",Cedilla:"\xb8",cemptyv:"\u29b2",cent:"\xa2",CenterDot:"\xb7",centerdot:"\xb7",Cfr:"\u212d",cfr:"\u{1d520}",CHcy:"\u0427",chcy:"\u0447",check:"\u2713",checkmark:"\u2713",Chi:"\u03a7",chi:"\u03c7",cir:"\u25cb",circ:"\u02c6",circeq:"\u2257",circlearrowleft:"\u21ba",circlearrowright:"\u21bb",circledast:"\u229b",circledcirc:"\u229a",circleddash:"\u229d",CircleDot:"\u2299",circledR:"\xae",circledS:"\u24c8",CircleMinus:"\u2296",CirclePlus:"\u2295",CircleTimes:"\u2297",cirE:"\u29c3",cire:"\u2257",cirfnint:"\u2a10",cirmid:"\u2aef",cirscir:"\u29c2",ClockwiseContourIntegral:"\u2232",CloseCurlyDoubleQuote:"\u201d",CloseCurlyQuote:"\u2019",clubs:"\u2663",clubsuit:"\u2663",Colon:"\u2237",colon:":",Colone:"\u2a74",colone:"\u2254",coloneq:"\u2254",comma:",",commat:"@",comp:"\u2201",compfn:"\u2218",complement:"\u2201",complexes:"\u2102",cong:"\u2245",congdot:"\u2a6d",Congruent:"\u2261",Conint:"\u222f",conint:"\u222e",ContourIntegral:"\u222e",Copf:"\u2102",copf:"\u{1d554}",coprod:"\u2210",Coproduct:"\u2210",COPY:"\xa9",copy:"\xa9",copysr:"\u2117",CounterClockwiseContourIntegral:"\u2233",crarr:"\u21b5",Cross:"\u2a2f",cross:"\u2717",Cscr:"\u{1d49e}",cscr:"\u{1d4b8}",csub:"\u2acf",csube:"\u2ad1",csup:"\u2ad0",csupe:"\u2ad2",ctdot:"\u22ef",cudarrl:"\u2938",cudarrr:"\u2935",cuepr:"\u22de",cuesc:"\u22df",cularr:"\u21b6",cularrp:"\u293d",Cup:"\u22d3",cup:"\u222a",cupbrcap:"\u2a48",CupCap:"\u224d",cupcap:"\u2a46",cupcup:"\u2a4a",cupdot:"\u228d",cupor:"\u2a45",cups:"\u222a\ufe00",curarr:"\u21b7",curarrm:"\u293c",curlyeqprec:"\u22de",curlyeqsucc:"\u22df",curlyvee:"\u22ce",curlywedge:"\u22cf",curren:"\xa4",curvearrowleft:"\u21b6",curvearrowright:"\u21b7",cuvee:"\u22ce",cuwed:"\u22cf",cwconint:"\u2232",cwint:"\u2231",cylcty:"\u232d",Dagger:"\u2021",dagger:"\u2020",daleth:"\u2138",Darr:"\u21a1",dArr:"\u21d3",darr:"\u2193",dash:"\u2010",Dashv:"\u2ae4",dashv:"\u22a3",dbkarow:"\u290f",dblac:"\u02dd",Dcaron:"\u010e",dcaron:"\u010f",Dcy:"\u0414",dcy:"\u0434",DD:"\u2145",dd:"\u2146",ddagger:"\u2021",ddarr:"\u21ca",DDotrahd:"\u2911",ddotseq:"\u2a77",deg:"\xb0",Del:"\u2207",Delta:"\u0394",delta:"\u03b4",demptyv:"\u29b1",dfisht:"\u297f",Dfr:"\u{1d507}",dfr:"\u{1d521}",dHar:"\u2965",dharl:"\u21c3",dharr:"\u21c2",DiacriticalAcute:"\xb4",DiacriticalDot:"\u02d9",DiacriticalDoubleAcute:"\u02dd",DiacriticalGrave:"`",DiacriticalTilde:"\u02dc",diam:"\u22c4",Diamond:"\u22c4",diamond:"\u22c4",diamondsuit:"\u2666",diams:"\u2666",die:"\xa8",DifferentialD:"\u2146",digamma:"\u03dd",disin:"\u22f2",div:"\xf7",divide:"\xf7",divideontimes:"\u22c7",divonx:"\u22c7",DJcy:"\u0402",djcy:"\u0452",dlcorn:"\u231e",dlcrop:"\u230d",dollar:"$",Dopf:"\u{1d53b}",dopf:"\u{1d555}",Dot:"\xa8",dot:"\u02d9",DotDot:"\u20dc",doteq:"\u2250",doteqdot:"\u2251",DotEqual:"\u2250",dotminus:"\u2238",dotplus:"\u2214",dotsquare:"\u22a1",doublebarwedge:"\u2306",DoubleContourIntegral:"\u222f",DoubleDot:"\xa8",DoubleDownArrow:"\u21d3",DoubleLeftArrow:"\u21d0",DoubleLeftRightArrow:"\u21d4",DoubleLeftTee:"\u2ae4",DoubleLongLeftArrow:"\u27f8",DoubleLongLeftRightArrow:"\u27fa",DoubleLongRightArrow:"\u27f9",DoubleRightArrow:"\u21d2",DoubleRightTee:"\u22a8",DoubleUpArrow:"\u21d1",DoubleUpDownArrow:"\u21d5",DoubleVerticalBar:"\u2225",DownArrow:"\u2193",Downarrow:"\u21d3",downarrow:"\u2193",DownArrowBar:"\u2913",DownArrowUpArrow:"\u21f5",DownBreve:"\u0311",downdownarrows:"\u21ca",downharpoonleft:"\u21c3",downharpoonright:"\u21c2",DownLeftRightVector:"\u2950",DownLeftTeeVector:"\u295e",DownLeftVector:"\u21bd",DownLeftVectorBar:"\u2956",DownRightTeeVector:"\u295f",DownRightVector:"\u21c1",DownRightVectorBar:"\u2957",DownTee:"\u22a4",DownTeeArrow:"\u21a7",drbkarow:"\u2910",drcorn:"\u231f",drcrop:"\u230c",Dscr:"\u{1d49f}",dscr:"\u{1d4b9}",DScy:"\u0405",dscy:"\u0455",dsol:"\u29f6",Dstrok:"\u0110",dstrok:"\u0111",dtdot:"\u22f1",dtri:"\u25bf",dtrif:"\u25be",duarr:"\u21f5",duhar:"\u296f",dwangle:"\u29a6",DZcy:"\u040f",dzcy:"\u045f",dzigrarr:"\u27ff",Eacute:"\xc9",eacute:"\xe9",easter:"\u2a6e",Ecaron:"\u011a",ecaron:"\u011b",ecir:"\u2256",Ecirc:"\xca",ecirc:"\xea",ecolon:"\u2255",Ecy:"\u042d",ecy:"\u044d",eDDot:"\u2a77",Edot:"\u0116",eDot:"\u2251",edot:"\u0117",ee:"\u2147",efDot:"\u2252",Efr:"\u{1d508}",efr:"\u{1d522}",eg:"\u2a9a",Egrave:"\xc8",egrave:"\xe8",egs:"\u2a96",egsdot:"\u2a98",el:"\u2a99",Element:"\u2208",elinters:"\u23e7",ell:"\u2113",els:"\u2a95",elsdot:"\u2a97",Emacr:"\u0112",emacr:"\u0113",empty:"\u2205",emptyset:"\u2205",EmptySmallSquare:"\u25fb",emptyv:"\u2205",EmptyVerySmallSquare:"\u25ab",emsp:"\u2003",emsp13:"\u2004",emsp14:"\u2005",ENG:"\u014a",eng:"\u014b",ensp:"\u2002",Eogon:"\u0118",eogon:"\u0119",Eopf:"\u{1d53c}",eopf:"\u{1d556}",epar:"\u22d5",eparsl:"\u29e3",eplus:"\u2a71",epsi:"\u03b5",Epsilon:"\u0395",epsilon:"\u03b5",epsiv:"\u03f5",eqcirc:"\u2256",eqcolon:"\u2255",eqsim:"\u2242",eqslantgtr:"\u2a96",eqslantless:"\u2a95",Equal:"\u2a75",equals:"=",EqualTilde:"\u2242",equest:"\u225f",Equilibrium:"\u21cc",equiv:"\u2261",equivDD:"\u2a78",eqvparsl:"\u29e5",erarr:"\u2971",erDot:"\u2253",Escr:"\u2130",escr:"\u212f",esdot:"\u2250",Esim:"\u2a73",esim:"\u2242",Eta:"\u0397",eta:"\u03b7",ETH:"\xd0",eth:"\xf0",Euml:"\xcb",euml:"\xeb",euro:"\u20ac",excl:"!",exist:"\u2203",Exists:"\u2203",expectation:"\u2130",ExponentialE:"\u2147",exponentiale:"\u2147",fallingdotseq:"\u2252",Fcy:"\u0424",fcy:"\u0444",female:"\u2640",ffilig:"\ufb03",fflig:"\ufb00",ffllig:"\ufb04",Ffr:"\u{1d509}",ffr:"\u{1d523}",filig:"\ufb01",FilledSmallSquare:"\u25fc",FilledVerySmallSquare:"\u25aa",fjlig:"fj",flat:"\u266d",fllig:"\ufb02",fltns:"\u25b1",fnof:"\u0192",Fopf:"\u{1d53d}",fopf:"\u{1d557}",ForAll:"\u2200",forall:"\u2200",fork:"\u22d4",forkv:"\u2ad9",Fouriertrf:"\u2131",fpartint:"\u2a0d",frac12:"\xbd",frac13:"\u2153",frac14:"\xbc",frac15:"\u2155",frac16:"\u2159",frac18:"\u215b",frac23:"\u2154",frac25:"\u2156",frac34:"\xbe",frac35:"\u2157",frac38:"\u215c",frac45:"\u2158",frac56:"\u215a",frac58:"\u215d",frac78:"\u215e",frasl:"\u2044",frown:"\u2322",Fscr:"\u2131",fscr:"\u{1d4bb}",gacute:"\u01f5",Gamma:"\u0393",gamma:"\u03b3",Gammad:"\u03dc",gammad:"\u03dd",gap:"\u2a86",Gbreve:"\u011e",gbreve:"\u011f",Gcedil:"\u0122",Gcirc:"\u011c",gcirc:"\u011d",Gcy:"\u0413",gcy:"\u0433",Gdot:"\u0120",gdot:"\u0121",gE:"\u2267",ge:"\u2265",gEl:"\u2a8c",gel:"\u22db",geq:"\u2265",geqq:"\u2267",geqslant:"\u2a7e",ges:"\u2a7e",gescc:"\u2aa9",gesdot:"\u2a80",gesdoto:"\u2a82",gesdotol:"\u2a84",gesl:"\u22db\ufe00",gesles:"\u2a94",Gfr:"\u{1d50a}",gfr:"\u{1d524}",Gg:"\u22d9",gg:"\u226b",ggg:"\u22d9",gimel:"\u2137",GJcy:"\u0403",gjcy:"\u0453",gl:"\u2277",gla:"\u2aa5",glE:"\u2a92",glj:"\u2aa4",gnap:"\u2a8a",gnapprox:"\u2a8a",gnE:"\u2269",gne:"\u2a88",gneq:"\u2a88",gneqq:"\u2269",gnsim:"\u22e7",Gopf:"\u{1d53e}",gopf:"\u{1d558}",grave:"`",GreaterEqual:"\u2265",GreaterEqualLess:"\u22db",GreaterFullEqual:"\u2267",GreaterGreater:"\u2aa2",GreaterLess:"\u2277",GreaterSlantEqual:"\u2a7e",GreaterTilde:"\u2273",Gscr:"\u{1d4a2}",gscr:"\u210a",gsim:"\u2273",gsime:"\u2a8e",gsiml:"\u2a90",Gt:"\u226b",GT:">",gt:">",gtcc:"\u2aa7",gtcir:"\u2a7a",gtdot:"\u22d7",gtlPar:"\u2995",gtquest:"\u2a7c",gtrapprox:"\u2a86",gtrarr:"\u2978",gtrdot:"\u22d7",gtreqless:"\u22db",gtreqqless:"\u2a8c",gtrless:"\u2277",gtrsim:"\u2273",gvertneqq:"\u2269\ufe00",gvnE:"\u2269\ufe00",Hacek:"\u02c7",hairsp:"\u200a",half:"\xbd",hamilt:"\u210b",HARDcy:"\u042a",hardcy:"\u044a",hArr:"\u21d4",harr:"\u2194",harrcir:"\u2948",harrw:"\u21ad",Hat:"^",hbar:"\u210f",Hcirc:"\u0124",hcirc:"\u0125",hearts:"\u2665",heartsuit:"\u2665",hellip:"\u2026",hercon:"\u22b9",Hfr:"\u210c",hfr:"\u{1d525}",HilbertSpace:"\u210b",hksearow:"\u2925",hkswarow:"\u2926",hoarr:"\u21ff",homtht:"\u223b",hookleftarrow:"\u21a9",hookrightarrow:"\u21aa",Hopf:"\u210d",hopf:"\u{1d559}",horbar:"\u2015",HorizontalLine:"\u2500",Hscr:"\u210b",hscr:"\u{1d4bd}",hslash:"\u210f",Hstrok:"\u0126",hstrok:"\u0127",HumpDownHump:"\u224e",HumpEqual:"\u224f",hybull:"\u2043",hyphen:"\u2010",Iacute:"\xcd",iacute:"\xed",ic:"\u2063",Icirc:"\xce",icirc:"\xee",Icy:"\u0418",icy:"\u0438",Idot:"\u0130",IEcy:"\u0415",iecy:"\u0435",iexcl:"\xa1",iff:"\u21d4",Ifr:"\u2111",ifr:"\u{1d526}",Igrave:"\xcc",igrave:"\xec",ii:"\u2148",iiiint:"\u2a0c",iiint:"\u222d",iinfin:"\u29dc",iiota:"\u2129",IJlig:"\u0132",ijlig:"\u0133",Im:"\u2111",Imacr:"\u012a",imacr:"\u012b",image:"\u2111",ImaginaryI:"\u2148",imagline:"\u2110",imagpart:"\u2111",imath:"\u0131",imof:"\u22b7",imped:"\u01b5",Implies:"\u21d2",in:"\u2208",incare:"\u2105",infin:"\u221e",infintie:"\u29dd",inodot:"\u0131",Int:"\u222c",int:"\u222b",intcal:"\u22ba",integers:"\u2124",Integral:"\u222b",intercal:"\u22ba",Intersection:"\u22c2",intlarhk:"\u2a17",intprod:"\u2a3c",InvisibleComma:"\u2063",InvisibleTimes:"\u2062",IOcy:"\u0401",iocy:"\u0451",Iogon:"\u012e",iogon:"\u012f",Iopf:"\u{1d540}",iopf:"\u{1d55a}",Iota:"\u0399",iota:"\u03b9",iprod:"\u2a3c",iquest:"\xbf",Iscr:"\u2110",iscr:"\u{1d4be}",isin:"\u2208",isindot:"\u22f5",isinE:"\u22f9",isins:"\u22f4",isinsv:"\u22f3",isinv:"\u2208",it:"\u2062",Itilde:"\u0128",itilde:"\u0129",Iukcy:"\u0406",iukcy:"\u0456",Iuml:"\xcf",iuml:"\xef",Jcirc:"\u0134",jcirc:"\u0135",Jcy:"\u0419",jcy:"\u0439",Jfr:"\u{1d50d}",jfr:"\u{1d527}",jmath:"\u0237",Jopf:"\u{1d541}",jopf:"\u{1d55b}",Jscr:"\u{1d4a5}",jscr:"\u{1d4bf}",Jsercy:"\u0408",jsercy:"\u0458",Jukcy:"\u0404",jukcy:"\u0454",Kappa:"\u039a",kappa:"\u03ba",kappav:"\u03f0",Kcedil:"\u0136",kcedil:"\u0137",Kcy:"\u041a",kcy:"\u043a",Kfr:"\u{1d50e}",kfr:"\u{1d528}",kgreen:"\u0138",KHcy:"\u0425",khcy:"\u0445",KJcy:"\u040c",kjcy:"\u045c",Kopf:"\u{1d542}",kopf:"\u{1d55c}",Kscr:"\u{1d4a6}",kscr:"\u{1d4c0}",lAarr:"\u21da",Lacute:"\u0139",lacute:"\u013a",laemptyv:"\u29b4",lagran:"\u2112",Lambda:"\u039b",lambda:"\u03bb",Lang:"\u27ea",lang:"\u27e8",langd:"\u2991",langle:"\u27e8",lap:"\u2a85",Laplacetrf:"\u2112",laquo:"\xab",Larr:"\u219e",lArr:"\u21d0",larr:"\u2190",larrb:"\u21e4",larrbfs:"\u291f",larrfs:"\u291d",larrhk:"\u21a9",larrlp:"\u21ab",larrpl:"\u2939",larrsim:"\u2973",larrtl:"\u21a2",lat:"\u2aab",lAtail:"\u291b",latail:"\u2919",late:"\u2aad",lates:"\u2aad\ufe00",lBarr:"\u290e",lbarr:"\u290c",lbbrk:"\u2772",lbrace:"{",lbrack:"[",lbrke:"\u298b",lbrksld:"\u298f",lbrkslu:"\u298d",Lcaron:"\u013d",lcaron:"\u013e",Lcedil:"\u013b",lcedil:"\u013c",lceil:"\u2308",lcub:"{",Lcy:"\u041b",lcy:"\u043b",ldca:"\u2936",ldquo:"\u201c",ldquor:"\u201e",ldrdhar:"\u2967",ldrushar:"\u294b",ldsh:"\u21b2",lE:"\u2266",le:"\u2264",LeftAngleBracket:"\u27e8",LeftArrow:"\u2190",Leftarrow:"\u21d0",leftarrow:"\u2190",LeftArrowBar:"\u21e4",LeftArrowRightArrow:"\u21c6",leftarrowtail:"\u21a2",LeftCeiling:"\u2308",LeftDoubleBracket:"\u27e6",LeftDownTeeVector:"\u2961",LeftDownVector:"\u21c3",LeftDownVectorBar:"\u2959",LeftFloor:"\u230a",leftharpoondown:"\u21bd",leftharpoonup:"\u21bc",leftleftarrows:"\u21c7",LeftRightArrow:"\u2194",Leftrightarrow:"\u21d4",leftrightarrow:"\u2194",leftrightarrows:"\u21c6",leftrightharpoons:"\u21cb",leftrightsquigarrow:"\u21ad",LeftRightVector:"\u294e",LeftTee:"\u22a3",LeftTeeArrow:"\u21a4",LeftTeeVector:"\u295a",leftthreetimes:"\u22cb",LeftTriangle:"\u22b2",LeftTriangleBar:"\u29cf",LeftTriangleEqual:"\u22b4",LeftUpDownVector:"\u2951",LeftUpTeeVector:"\u2960",LeftUpVector:"\u21bf",LeftUpVectorBar:"\u2958",LeftVector:"\u21bc",LeftVectorBar:"\u2952",lEg:"\u2a8b",leg:"\u22da",leq:"\u2264",leqq:"\u2266",leqslant:"\u2a7d",les:"\u2a7d",lescc:"\u2aa8",lesdot:"\u2a7f",lesdoto:"\u2a81",lesdotor:"\u2a83",lesg:"\u22da\ufe00",lesges:"\u2a93",lessapprox:"\u2a85",lessdot:"\u22d6",lesseqgtr:"\u22da",lesseqqgtr:"\u2a8b",LessEqualGreater:"\u22da",LessFullEqual:"\u2266",LessGreater:"\u2276",lessgtr:"\u2276",LessLess:"\u2aa1",lesssim:"\u2272",LessSlantEqual:"\u2a7d",LessTilde:"\u2272",lfisht:"\u297c",lfloor:"\u230a",Lfr:"\u{1d50f}",lfr:"\u{1d529}",lg:"\u2276",lgE:"\u2a91",lHar:"\u2962",lhard:"\u21bd",lharu:"\u21bc",lharul:"\u296a",lhblk:"\u2584",LJcy:"\u0409",ljcy:"\u0459",Ll:"\u22d8",ll:"\u226a",llarr:"\u21c7",llcorner:"\u231e",Lleftarrow:"\u21da",llhard:"\u296b",lltri:"\u25fa",Lmidot:"\u013f",lmidot:"\u0140",lmoust:"\u23b0",lmoustache:"\u23b0",lnap:"\u2a89",lnapprox:"\u2a89",lnE:"\u2268",lne:"\u2a87",lneq:"\u2a87",lneqq:"\u2268",lnsim:"\u22e6",loang:"\u27ec",loarr:"\u21fd",lobrk:"\u27e6",LongLeftArrow:"\u27f5",Longleftarrow:"\u27f8",longleftarrow:"\u27f5",LongLeftRightArrow:"\u27f7",Longleftrightarrow:"\u27fa",longleftrightarrow:"\u27f7",longmapsto:"\u27fc",LongRightArrow:"\u27f6",Longrightarrow:"\u27f9",longrightarrow:"\u27f6",looparrowleft:"\u21ab",looparrowright:"\u21ac",lopar:"\u2985",Lopf:"\u{1d543}",lopf:"\u{1d55d}",loplus:"\u2a2d",lotimes:"\u2a34",lowast:"\u2217",lowbar:"_",LowerLeftArrow:"\u2199",LowerRightArrow:"\u2198",loz:"\u25ca",lozenge:"\u25ca",lozf:"\u29eb",lpar:"(",lparlt:"\u2993",lrarr:"\u21c6",lrcorner:"\u231f",lrhar:"\u21cb",lrhard:"\u296d",lrm:"\u200e",lrtri:"\u22bf",lsaquo:"\u2039",Lscr:"\u2112",lscr:"\u{1d4c1}",Lsh:"\u21b0",lsh:"\u21b0",lsim:"\u2272",lsime:"\u2a8d",lsimg:"\u2a8f",lsqb:"[",lsquo:"\u2018",lsquor:"\u201a",Lstrok:"\u0141",lstrok:"\u0142",Lt:"\u226a",LT:"<",lt:"<",ltcc:"\u2aa6",ltcir:"\u2a79",ltdot:"\u22d6",lthree:"\u22cb",ltimes:"\u22c9",ltlarr:"\u2976",ltquest:"\u2a7b",ltri:"\u25c3",ltrie:"\u22b4",ltrif:"\u25c2",ltrPar:"\u2996",lurdshar:"\u294a",luruhar:"\u2966",lvertneqq:"\u2268\ufe00",lvnE:"\u2268\ufe00",macr:"\xaf",male:"\u2642",malt:"\u2720",maltese:"\u2720",Map:"\u2905",map:"\u21a6",mapsto:"\u21a6",mapstodown:"\u21a7",mapstoleft:"\u21a4",mapstoup:"\u21a5",marker:"\u25ae",mcomma:"\u2a29",Mcy:"\u041c",mcy:"\u043c",mdash:"\u2014",mDDot:"\u223a",measuredangle:"\u2221",MediumSpace:"\u205f",Mellintrf:"\u2133",Mfr:"\u{1d510}",mfr:"\u{1d52a}",mho:"\u2127",micro:"\xb5",mid:"\u2223",midast:"*",midcir:"\u2af0",middot:"\xb7",minus:"\u2212",minusb:"\u229f",minusd:"\u2238",minusdu:"\u2a2a",MinusPlus:"\u2213",mlcp:"\u2adb",mldr:"\u2026",mnplus:"\u2213",models:"\u22a7",Mopf:"\u{1d544}",mopf:"\u{1d55e}",mp:"\u2213",Mscr:"\u2133",mscr:"\u{1d4c2}",mstpos:"\u223e",Mu:"\u039c",mu:"\u03bc",multimap:"\u22b8",mumap:"\u22b8",nabla:"\u2207",Nacute:"\u0143",nacute:"\u0144",nang:"\u2220\u20d2",nap:"\u2249",napE:"\u2a70\u0338",napid:"\u224b\u0338",napos:"\u0149",napprox:"\u2249",natur:"\u266e",natural:"\u266e",naturals:"\u2115",nbsp:"\xa0",nbump:"\u224e\u0338",nbumpe:"\u224f\u0338",ncap:"\u2a43",Ncaron:"\u0147",ncaron:"\u0148",Ncedil:"\u0145",ncedil:"\u0146",ncong:"\u2247",ncongdot:"\u2a6d\u0338",ncup:"\u2a42",Ncy:"\u041d",ncy:"\u043d",ndash:"\u2013",ne:"\u2260",nearhk:"\u2924",neArr:"\u21d7",nearr:"\u2197",nearrow:"\u2197",nedot:"\u2250\u0338",NegativeMediumSpace:"\u200b",NegativeThickSpace:"\u200b",NegativeThinSpace:"\u200b",NegativeVeryThinSpace:"\u200b",nequiv:"\u2262",nesear:"\u2928",nesim:"\u2242\u0338",NestedGreaterGreater:"\u226b",NestedLessLess:"\u226a",NewLine:"\n",nexist:"\u2204",nexists:"\u2204",Nfr:"\u{1d511}",nfr:"\u{1d52b}",ngE:"\u2267\u0338",nge:"\u2271",ngeq:"\u2271",ngeqq:"\u2267\u0338",ngeqslant:"\u2a7e\u0338",nges:"\u2a7e\u0338",nGg:"\u22d9\u0338",ngsim:"\u2275",nGt:"\u226b\u20d2",ngt:"\u226f",ngtr:"\u226f",nGtv:"\u226b\u0338",nhArr:"\u21ce",nharr:"\u21ae",nhpar:"\u2af2",ni:"\u220b",nis:"\u22fc",nisd:"\u22fa",niv:"\u220b",NJcy:"\u040a",njcy:"\u045a",nlArr:"\u21cd",nlarr:"\u219a",nldr:"\u2025",nlE:"\u2266\u0338",nle:"\u2270",nLeftarrow:"\u21cd",nleftarrow:"\u219a",nLeftrightarrow:"\u21ce",nleftrightarrow:"\u21ae",nleq:"\u2270",nleqq:"\u2266\u0338",nleqslant:"\u2a7d\u0338",nles:"\u2a7d\u0338",nless:"\u226e",nLl:"\u22d8\u0338",nlsim:"\u2274",nLt:"\u226a\u20d2",nlt:"\u226e",nltri:"\u22ea",nltrie:"\u22ec",nLtv:"\u226a\u0338",nmid:"\u2224",NoBreak:"\u2060",NonBreakingSpace:"\xa0",Nopf:"\u2115",nopf:"\u{1d55f}",Not:"\u2aec",not:"\xac",NotCongruent:"\u2262",NotCupCap:"\u226d",NotDoubleVerticalBar:"\u2226",NotElement:"\u2209",NotEqual:"\u2260",NotEqualTilde:"\u2242\u0338",NotExists:"\u2204",NotGreater:"\u226f",NotGreaterEqual:"\u2271",NotGreaterFullEqual:"\u2267\u0338",NotGreaterGreater:"\u226b\u0338",NotGreaterLess:"\u2279",NotGreaterSlantEqual:"\u2a7e\u0338",NotGreaterTilde:"\u2275",NotHumpDownHump:"\u224e\u0338",NotHumpEqual:"\u224f\u0338",notin:"\u2209",notindot:"\u22f5\u0338",notinE:"\u22f9\u0338",notinva:"\u2209",notinvb:"\u22f7",notinvc:"\u22f6",NotLeftTriangle:"\u22ea",NotLeftTriangleBar:"\u29cf\u0338",NotLeftTriangleEqual:"\u22ec",NotLess:"\u226e",NotLessEqual:"\u2270",NotLessGreater:"\u2278",NotLessLess:"\u226a\u0338",NotLessSlantEqual:"\u2a7d\u0338",NotLessTilde:"\u2274",NotNestedGreaterGreater:"\u2aa2\u0338",NotNestedLessLess:"\u2aa1\u0338",notni:"\u220c",notniva:"\u220c",notnivb:"\u22fe",notnivc:"\u22fd",NotPrecedes:"\u2280",NotPrecedesEqual:"\u2aaf\u0338",NotPrecedesSlantEqual:"\u22e0",NotReverseElement:"\u220c",NotRightTriangle:"\u22eb",NotRightTriangleBar:"\u29d0\u0338",NotRightTriangleEqual:"\u22ed",NotSquareSubset:"\u228f\u0338",NotSquareSubsetEqual:"\u22e2",NotSquareSuperset:"\u2290\u0338",NotSquareSupersetEqual:"\u22e3",NotSubset:"\u2282\u20d2",NotSubsetEqual:"\u2288",NotSucceeds:"\u2281",NotSucceedsEqual:"\u2ab0\u0338",NotSucceedsSlantEqual:"\u22e1",NotSucceedsTilde:"\u227f\u0338",NotSuperset:"\u2283\u20d2",NotSupersetEqual:"\u2289",NotTilde:"\u2241",NotTildeEqual:"\u2244",NotTildeFullEqual:"\u2247",NotTildeTilde:"\u2249",NotVerticalBar:"\u2224",npar:"\u2226",nparallel:"\u2226",nparsl:"\u2afd\u20e5",npart:"\u2202\u0338",npolint:"\u2a14",npr:"\u2280",nprcue:"\u22e0",npre:"\u2aaf\u0338",nprec:"\u2280",npreceq:"\u2aaf\u0338",nrArr:"\u21cf",nrarr:"\u219b",nrarrc:"\u2933\u0338",nrarrw:"\u219d\u0338",nRightarrow:"\u21cf",nrightarrow:"\u219b",nrtri:"\u22eb",nrtrie:"\u22ed",nsc:"\u2281",nsccue:"\u22e1",nsce:"\u2ab0\u0338",Nscr:"\u{1d4a9}",nscr:"\u{1d4c3}",nshortmid:"\u2224",nshortparallel:"\u2226",nsim:"\u2241",nsime:"\u2244",nsimeq:"\u2244",nsmid:"\u2224",nspar:"\u2226",nsqsube:"\u22e2",nsqsupe:"\u22e3",nsub:"\u2284",nsubE:"\u2ac5\u0338",nsube:"\u2288",nsubset:"\u2282\u20d2",nsubseteq:"\u2288",nsubseteqq:"\u2ac5\u0338",nsucc:"\u2281",nsucceq:"\u2ab0\u0338",nsup:"\u2285",nsupE:"\u2ac6\u0338",nsupe:"\u2289",nsupset:"\u2283\u20d2",nsupseteq:"\u2289",nsupseteqq:"\u2ac6\u0338",ntgl:"\u2279",Ntilde:"\xd1",ntilde:"\xf1",ntlg:"\u2278",ntriangleleft:"\u22ea",ntrianglelefteq:"\u22ec",ntriangleright:"\u22eb",ntrianglerighteq:"\u22ed",Nu:"\u039d",nu:"\u03bd",num:"#",numero:"\u2116",numsp:"\u2007",nvap:"\u224d\u20d2",nVDash:"\u22af",nVdash:"\u22ae",nvDash:"\u22ad",nvdash:"\u22ac",nvge:"\u2265\u20d2",nvgt:">\u20d2",nvHarr:"\u2904",nvinfin:"\u29de",nvlArr:"\u2902",nvle:"\u2264\u20d2",nvlt:"<\u20d2",nvltrie:"\u22b4\u20d2",nvrArr:"\u2903",nvrtrie:"\u22b5\u20d2",nvsim:"\u223c\u20d2",nwarhk:"\u2923",nwArr:"\u21d6",nwarr:"\u2196",nwarrow:"\u2196",nwnear:"\u2927",Oacute:"\xd3",oacute:"\xf3",oast:"\u229b",ocir:"\u229a",Ocirc:"\xd4",ocirc:"\xf4",Ocy:"\u041e",ocy:"\u043e",odash:"\u229d",Odblac:"\u0150",odblac:"\u0151",odiv:"\u2a38",odot:"\u2299",odsold:"\u29bc",OElig:"\u0152",oelig:"\u0153",ofcir:"\u29bf",Ofr:"\u{1d512}",ofr:"\u{1d52c}",ogon:"\u02db",Ograve:"\xd2",ograve:"\xf2",ogt:"\u29c1",ohbar:"\u29b5",ohm:"\u03a9",oint:"\u222e",olarr:"\u21ba",olcir:"\u29be",olcross:"\u29bb",oline:"\u203e",olt:"\u29c0",Omacr:"\u014c",omacr:"\u014d",Omega:"\u03a9",omega:"\u03c9",Omicron:"\u039f",omicron:"\u03bf",omid:"\u29b6",ominus:"\u2296",Oopf:"\u{1d546}",oopf:"\u{1d560}",opar:"\u29b7",OpenCurlyDoubleQuote:"\u201c",OpenCurlyQuote:"\u2018",operp:"\u29b9",oplus:"\u2295",Or:"\u2a54",or:"\u2228",orarr:"\u21bb",ord:"\u2a5d",order:"\u2134",orderof:"\u2134",ordf:"\xaa",ordm:"\xba",origof:"\u22b6",oror:"\u2a56",orslope:"\u2a57",orv:"\u2a5b",oS:"\u24c8",Oscr:"\u{1d4aa}",oscr:"\u2134",Oslash:"\xd8",oslash:"\xf8",osol:"\u2298",Otilde:"\xd5",otilde:"\xf5",Otimes:"\u2a37",otimes:"\u2297",otimesas:"\u2a36",Ouml:"\xd6",ouml:"\xf6",ovbar:"\u233d",OverBar:"\u203e",OverBrace:"\u23de",OverBracket:"\u23b4",OverParenthesis:"\u23dc",par:"\u2225",para:"\xb6",parallel:"\u2225",parsim:"\u2af3",parsl:"\u2afd",part:"\u2202",PartialD:"\u2202",Pcy:"\u041f",pcy:"\u043f",percnt:"%",period:".",permil:"\u2030",perp:"\u22a5",pertenk:"\u2031",Pfr:"\u{1d513}",pfr:"\u{1d52d}",Phi:"\u03a6",phi:"\u03c6",phiv:"\u03d5",phmmat:"\u2133",phone:"\u260e",Pi:"\u03a0",pi:"\u03c0",pitchfork:"\u22d4",piv:"\u03d6",planck:"\u210f",planckh:"\u210e",plankv:"\u210f",plus:"+",plusacir:"\u2a23",plusb:"\u229e",pluscir:"\u2a22",plusdo:"\u2214",plusdu:"\u2a25",pluse:"\u2a72",PlusMinus:"\xb1",plusmn:"\xb1",plussim:"\u2a26",plustwo:"\u2a27",pm:"\xb1",Poincareplane:"\u210c",pointint:"\u2a15",Popf:"\u2119",popf:"\u{1d561}",pound:"\xa3",Pr:"\u2abb",pr:"\u227a",prap:"\u2ab7",prcue:"\u227c",prE:"\u2ab3",pre:"\u2aaf",prec:"\u227a",precapprox:"\u2ab7",preccurlyeq:"\u227c",Precedes:"\u227a",PrecedesEqual:"\u2aaf",PrecedesSlantEqual:"\u227c",PrecedesTilde:"\u227e",preceq:"\u2aaf",precnapprox:"\u2ab9",precneqq:"\u2ab5",precnsim:"\u22e8",precsim:"\u227e",Prime:"\u2033",prime:"\u2032",primes:"\u2119",prnap:"\u2ab9",prnE:"\u2ab5",prnsim:"\u22e8",prod:"\u220f",Product:"\u220f",profalar:"\u232e",profline:"\u2312",profsurf:"\u2313",prop:"\u221d",Proportion:"\u2237",Proportional:"\u221d",propto:"\u221d",prsim:"\u227e",prurel:"\u22b0",Pscr:"\u{1d4ab}",pscr:"\u{1d4c5}",Psi:"\u03a8",psi:"\u03c8",puncsp:"\u2008",Qfr:"\u{1d514}",qfr:"\u{1d52e}",qint:"\u2a0c",Qopf:"\u211a",qopf:"\u{1d562}",qprime:"\u2057",Qscr:"\u{1d4ac}",qscr:"\u{1d4c6}",quaternions:"\u210d",quatint:"\u2a16",quest:"?",questeq:"\u225f",QUOT:'"',quot:'"',rAarr:"\u21db",race:"\u223d\u0331",Racute:"\u0154",racute:"\u0155",radic:"\u221a",raemptyv:"\u29b3",Rang:"\u27eb",rang:"\u27e9",rangd:"\u2992",range:"\u29a5",rangle:"\u27e9",raquo:"\xbb",Rarr:"\u21a0",rArr:"\u21d2",rarr:"\u2192",rarrap:"\u2975",rarrb:"\u21e5",rarrbfs:"\u2920",rarrc:"\u2933",rarrfs:"\u291e",rarrhk:"\u21aa",rarrlp:"\u21ac",rarrpl:"\u2945",rarrsim:"\u2974",Rarrtl:"\u2916",rarrtl:"\u21a3",rarrw:"\u219d",rAtail:"\u291c",ratail:"\u291a",ratio:"\u2236",rationals:"\u211a",RBarr:"\u2910",rBarr:"\u290f",rbarr:"\u290d",rbbrk:"\u2773",rbrace:"}",rbrack:"]",rbrke:"\u298c",rbrksld:"\u298e",rbrkslu:"\u2990",Rcaron:"\u0158",rcaron:"\u0159",Rcedil:"\u0156",rcedil:"\u0157",rceil:"\u2309",rcub:"}",Rcy:"\u0420",rcy:"\u0440",rdca:"\u2937",rdldhar:"\u2969",rdquo:"\u201d",rdquor:"\u201d",rdsh:"\u21b3",Re:"\u211c",real:"\u211c",realine:"\u211b",realpart:"\u211c",reals:"\u211d",rect:"\u25ad",REG:"\xae",reg:"\xae",ReverseElement:"\u220b",ReverseEquilibrium:"\u21cb",ReverseUpEquilibrium:"\u296f",rfisht:"\u297d",rfloor:"\u230b",Rfr:"\u211c",rfr:"\u{1d52f}",rHar:"\u2964",rhard:"\u21c1",rharu:"\u21c0",rharul:"\u296c",Rho:"\u03a1",rho:"\u03c1",rhov:"\u03f1",RightAngleBracket:"\u27e9",RightArrow:"\u2192",Rightarrow:"\u21d2",rightarrow:"\u2192",RightArrowBar:"\u21e5",RightArrowLeftArrow:"\u21c4",rightarrowtail:"\u21a3",RightCeiling:"\u2309",RightDoubleBracket:"\u27e7",RightDownTeeVector:"\u295d",RightDownVector:"\u21c2",RightDownVectorBar:"\u2955",RightFloor:"\u230b",rightharpoondown:"\u21c1",rightharpoonup:"\u21c0",rightleftarrows:"\u21c4",rightleftharpoons:"\u21cc",rightrightarrows:"\u21c9",rightsquigarrow:"\u219d",RightTee:"\u22a2",RightTeeArrow:"\u21a6",RightTeeVector:"\u295b",rightthreetimes:"\u22cc",RightTriangle:"\u22b3",RightTriangleBar:"\u29d0",RightTriangleEqual:"\u22b5",RightUpDownVector:"\u294f",RightUpTeeVector:"\u295c",RightUpVector:"\u21be",RightUpVectorBar:"\u2954",RightVector:"\u21c0",RightVectorBar:"\u2953",ring:"\u02da",risingdotseq:"\u2253",rlarr:"\u21c4",rlhar:"\u21cc",rlm:"\u200f",rmoust:"\u23b1",rmoustache:"\u23b1",rnmid:"\u2aee",roang:"\u27ed",roarr:"\u21fe",robrk:"\u27e7",ropar:"\u2986",Ropf:"\u211d",ropf:"\u{1d563}",roplus:"\u2a2e",rotimes:"\u2a35",RoundImplies:"\u2970",rpar:")",rpargt:"\u2994",rppolint:"\u2a12",rrarr:"\u21c9",Rrightarrow:"\u21db",rsaquo:"\u203a",Rscr:"\u211b",rscr:"\u{1d4c7}",Rsh:"\u21b1",rsh:"\u21b1",rsqb:"]",rsquo:"\u2019",rsquor:"\u2019",rthree:"\u22cc",rtimes:"\u22ca",rtri:"\u25b9",rtrie:"\u22b5",rtrif:"\u25b8",rtriltri:"\u29ce",RuleDelayed:"\u29f4",ruluhar:"\u2968",rx:"\u211e",Sacute:"\u015a",sacute:"\u015b",sbquo:"\u201a",Sc:"\u2abc",sc:"\u227b",scap:"\u2ab8",Scaron:"\u0160",scaron:"\u0161",sccue:"\u227d",scE:"\u2ab4",sce:"\u2ab0",Scedil:"\u015e",scedil:"\u015f",Scirc:"\u015c",scirc:"\u015d",scnap:"\u2aba",scnE:"\u2ab6",scnsim:"\u22e9",scpolint:"\u2a13",scsim:"\u227f",Scy:"\u0421",scy:"\u0441",sdot:"\u22c5",sdotb:"\u22a1",sdote:"\u2a66",searhk:"\u2925",seArr:"\u21d8",searr:"\u2198",searrow:"\u2198",sect:"\xa7",semi:";",seswar:"\u2929",setminus:"\u2216",setmn:"\u2216",sext:"\u2736",Sfr:"\u{1d516}",sfr:"\u{1d530}",sfrown:"\u2322",sharp:"\u266f",SHCHcy:"\u0429",shchcy:"\u0449",SHcy:"\u0428",shcy:"\u0448",ShortDownArrow:"\u2193",ShortLeftArrow:"\u2190",shortmid:"\u2223",shortparallel:"\u2225",ShortRightArrow:"\u2192",ShortUpArrow:"\u2191",shy:"\xad",Sigma:"\u03a3",sigma:"\u03c3",sigmaf:"\u03c2",sigmav:"\u03c2",sim:"\u223c",simdot:"\u2a6a",sime:"\u2243",simeq:"\u2243",simg:"\u2a9e",simgE:"\u2aa0",siml:"\u2a9d",simlE:"\u2a9f",simne:"\u2246",simplus:"\u2a24",simrarr:"\u2972",slarr:"\u2190",SmallCircle:"\u2218",smallsetminus:"\u2216",smashp:"\u2a33",smeparsl:"\u29e4",smid:"\u2223",smile:"\u2323",smt:"\u2aaa",smte:"\u2aac",smtes:"\u2aac\ufe00",SOFTcy:"\u042c",softcy:"\u044c",sol:"/",solb:"\u29c4",solbar:"\u233f",Sopf:"\u{1d54a}",sopf:"\u{1d564}",spades:"\u2660",spadesuit:"\u2660",spar:"\u2225",sqcap:"\u2293",sqcaps:"\u2293\ufe00",sqcup:"\u2294",sqcups:"\u2294\ufe00",Sqrt:"\u221a",sqsub:"\u228f",sqsube:"\u2291",sqsubset:"\u228f",sqsubseteq:"\u2291",sqsup:"\u2290",sqsupe:"\u2292",sqsupset:"\u2290",sqsupseteq:"\u2292",squ:"\u25a1",Square:"\u25a1",square:"\u25a1",SquareIntersection:"\u2293",SquareSubset:"\u228f",SquareSubsetEqual:"\u2291",SquareSuperset:"\u2290",SquareSupersetEqual:"\u2292",SquareUnion:"\u2294",squarf:"\u25aa",squf:"\u25aa",srarr:"\u2192",Sscr:"\u{1d4ae}",sscr:"\u{1d4c8}",ssetmn:"\u2216",ssmile:"\u2323",sstarf:"\u22c6",Star:"\u22c6",star:"\u2606",starf:"\u2605",straightepsilon:"\u03f5",straightphi:"\u03d5",strns:"\xaf",Sub:"\u22d0",sub:"\u2282",subdot:"\u2abd",subE:"\u2ac5",sube:"\u2286",subedot:"\u2ac3",submult:"\u2ac1",subnE:"\u2acb",subne:"\u228a",subplus:"\u2abf",subrarr:"\u2979",Subset:"\u22d0",subset:"\u2282",subseteq:"\u2286",subseteqq:"\u2ac5",SubsetEqual:"\u2286",subsetneq:"\u228a",subsetneqq:"\u2acb",subsim:"\u2ac7",subsub:"\u2ad5",subsup:"\u2ad3",succ:"\u227b",succapprox:"\u2ab8",succcurlyeq:"\u227d",Succeeds:"\u227b",SucceedsEqual:"\u2ab0",SucceedsSlantEqual:"\u227d",SucceedsTilde:"\u227f",succeq:"\u2ab0",succnapprox:"\u2aba",succneqq:"\u2ab6",succnsim:"\u22e9",succsim:"\u227f",SuchThat:"\u220b",Sum:"\u2211",sum:"\u2211",sung:"\u266a",Sup:"\u22d1",sup:"\u2283",sup1:"\xb9",sup2:"\xb2",sup3:"\xb3",supdot:"\u2abe",supdsub:"\u2ad8",supE:"\u2ac6",supe:"\u2287",supedot:"\u2ac4",Superset:"\u2283",SupersetEqual:"\u2287",suphsol:"\u27c9",suphsub:"\u2ad7",suplarr:"\u297b",supmult:"\u2ac2",supnE:"\u2acc",supne:"\u228b",supplus:"\u2ac0",Supset:"\u22d1",supset:"\u2283",supseteq:"\u2287",supseteqq:"\u2ac6",supsetneq:"\u228b",supsetneqq:"\u2acc",supsim:"\u2ac8",supsub:"\u2ad4",supsup:"\u2ad6",swarhk:"\u2926",swArr:"\u21d9",swarr:"\u2199",swarrow:"\u2199",swnwar:"\u292a",szlig:"\xdf",Tab:"\t",target:"\u2316",Tau:"\u03a4",tau:"\u03c4",tbrk:"\u23b4",Tcaron:"\u0164",tcaron:"\u0165",Tcedil:"\u0162",tcedil:"\u0163",Tcy:"\u0422",tcy:"\u0442",tdot:"\u20db",telrec:"\u2315",Tfr:"\u{1d517}",tfr:"\u{1d531}",there4:"\u2234",Therefore:"\u2234",therefore:"\u2234",Theta:"\u0398",theta:"\u03b8",thetasym:"\u03d1",thetav:"\u03d1",thickapprox:"\u2248",thicksim:"\u223c",ThickSpace:"\u205f\u200a",thinsp:"\u2009",ThinSpace:"\u2009",thkap:"\u2248",thksim:"\u223c",THORN:"\xde",thorn:"\xfe",Tilde:"\u223c",tilde:"\u02dc",TildeEqual:"\u2243",TildeFullEqual:"\u2245",TildeTilde:"\u2248",times:"\xd7",timesb:"\u22a0",timesbar:"\u2a31",timesd:"\u2a30",tint:"\u222d",toea:"\u2928",top:"\u22a4",topbot:"\u2336",topcir:"\u2af1",Topf:"\u{1d54b}",topf:"\u{1d565}",topfork:"\u2ada",tosa:"\u2929",tprime:"\u2034",TRADE:"\u2122",trade:"\u2122",triangle:"\u25b5",triangledown:"\u25bf",triangleleft:"\u25c3",trianglelefteq:"\u22b4",triangleq:"\u225c",triangleright:"\u25b9",trianglerighteq:"\u22b5",tridot:"\u25ec",trie:"\u225c",triminus:"\u2a3a",TripleDot:"\u20db",triplus:"\u2a39",trisb:"\u29cd",tritime:"\u2a3b",trpezium:"\u23e2",Tscr:"\u{1d4af}",tscr:"\u{1d4c9}",TScy:"\u0426",tscy:"\u0446",TSHcy:"\u040b",tshcy:"\u045b",Tstrok:"\u0166",tstrok:"\u0167",twixt:"\u226c",twoheadleftarrow:"\u219e",twoheadrightarrow:"\u21a0",Uacute:"\xda",uacute:"\xfa",Uarr:"\u219f",uArr:"\u21d1",uarr:"\u2191",Uarrocir:"\u2949",Ubrcy:"\u040e",ubrcy:"\u045e",Ubreve:"\u016c",ubreve:"\u016d",Ucirc:"\xdb",ucirc:"\xfb",Ucy:"\u0423",ucy:"\u0443",udarr:"\u21c5",Udblac:"\u0170",udblac:"\u0171",udhar:"\u296e",ufisht:"\u297e",Ufr:"\u{1d518}",ufr:"\u{1d532}",Ugrave:"\xd9",ugrave:"\xf9",uHar:"\u2963",uharl:"\u21bf",uharr:"\u21be",uhblk:"\u2580",ulcorn:"\u231c",ulcorner:"\u231c",ulcrop:"\u230f",ultri:"\u25f8",Umacr:"\u016a",umacr:"\u016b",uml:"\xa8",UnderBar:"_",UnderBrace:"\u23df",UnderBracket:"\u23b5",UnderParenthesis:"\u23dd",Union:"\u22c3",UnionPlus:"\u228e",Uogon:"\u0172",uogon:"\u0173",Uopf:"\u{1d54c}",uopf:"\u{1d566}",UpArrow:"\u2191",Uparrow:"\u21d1",uparrow:"\u2191",UpArrowBar:"\u2912",UpArrowDownArrow:"\u21c5",UpDownArrow:"\u2195",Updownarrow:"\u21d5",updownarrow:"\u2195",UpEquilibrium:"\u296e",upharpoonleft:"\u21bf",upharpoonright:"\u21be",uplus:"\u228e",UpperLeftArrow:"\u2196",UpperRightArrow:"\u2197",Upsi:"\u03d2",upsi:"\u03c5",upsih:"\u03d2",Upsilon:"\u03a5",upsilon:"\u03c5",UpTee:"\u22a5",UpTeeArrow:"\u21a5",upuparrows:"\u21c8",urcorn:"\u231d",urcorner:"\u231d",urcrop:"\u230e",Uring:"\u016e",uring:"\u016f",urtri:"\u25f9",Uscr:"\u{1d4b0}",uscr:"\u{1d4ca}",utdot:"\u22f0",Utilde:"\u0168",utilde:"\u0169",utri:"\u25b5",utrif:"\u25b4",uuarr:"\u21c8",Uuml:"\xdc",uuml:"\xfc",uwangle:"\u29a7",vangrt:"\u299c",varepsilon:"\u03f5",varkappa:"\u03f0",varnothing:"\u2205",varphi:"\u03d5",varpi:"\u03d6",varpropto:"\u221d",vArr:"\u21d5",varr:"\u2195",varrho:"\u03f1",varsigma:"\u03c2",varsubsetneq:"\u228a\ufe00",varsubsetneqq:"\u2acb\ufe00",varsupsetneq:"\u228b\ufe00",varsupsetneqq:"\u2acc\ufe00",vartheta:"\u03d1",vartriangleleft:"\u22b2",vartriangleright:"\u22b3",Vbar:"\u2aeb",vBar:"\u2ae8",vBarv:"\u2ae9",Vcy:"\u0412",vcy:"\u0432",VDash:"\u22ab",Vdash:"\u22a9",vDash:"\u22a8",vdash:"\u22a2",Vdashl:"\u2ae6",Vee:"\u22c1",vee:"\u2228",veebar:"\u22bb",veeeq:"\u225a",vellip:"\u22ee",Verbar:"\u2016",verbar:"|",Vert:"\u2016",vert:"|",VerticalBar:"\u2223",VerticalLine:"|",VerticalSeparator:"\u2758",VerticalTilde:"\u2240",VeryThinSpace:"\u200a",Vfr:"\u{1d519}",vfr:"\u{1d533}",vltri:"\u22b2",vnsub:"\u2282\u20d2",vnsup:"\u2283\u20d2",Vopf:"\u{1d54d}",vopf:"\u{1d567}",vprop:"\u221d",vrtri:"\u22b3",Vscr:"\u{1d4b1}",vscr:"\u{1d4cb}",vsubnE:"\u2acb\ufe00",vsubne:"\u228a\ufe00",vsupnE:"\u2acc\ufe00",vsupne:"\u228b\ufe00",Vvdash:"\u22aa",vzigzag:"\u299a",Wcirc:"\u0174",wcirc:"\u0175",wedbar:"\u2a5f",Wedge:"\u22c0",wedge:"\u2227",wedgeq:"\u2259",weierp:"\u2118",Wfr:"\u{1d51a}",wfr:"\u{1d534}",Wopf:"\u{1d54e}",wopf:"\u{1d568}",wp:"\u2118",wr:"\u2240",wreath:"\u2240",Wscr:"\u{1d4b2}",wscr:"\u{1d4cc}",xcap:"\u22c2",xcirc:"\u25ef",xcup:"\u22c3",xdtri:"\u25bd",Xfr:"\u{1d51b}",xfr:"\u{1d535}",xhArr:"\u27fa",xharr:"\u27f7",Xi:"\u039e",xi:"\u03be",xlArr:"\u27f8",xlarr:"\u27f5",xmap:"\u27fc",xnis:"\u22fb",xodot:"\u2a00",Xopf:"\u{1d54f}",xopf:"\u{1d569}",xoplus:"\u2a01",xotime:"\u2a02",xrArr:"\u27f9",xrarr:"\u27f6",Xscr:"\u{1d4b3}",xscr:"\u{1d4cd}",xsqcup:"\u2a06",xuplus:"\u2a04",xutri:"\u25b3",xvee:"\u22c1",xwedge:"\u22c0",Yacute:"\xdd",yacute:"\xfd",YAcy:"\u042f",yacy:"\u044f",Ycirc:"\u0176",ycirc:"\u0177",Ycy:"\u042b",ycy:"\u044b",yen:"\xa5",Yfr:"\u{1d51c}",yfr:"\u{1d536}",YIcy:"\u0407",yicy:"\u0457",Yopf:"\u{1d550}",yopf:"\u{1d56a}",Yscr:"\u{1d4b4}",yscr:"\u{1d4ce}",YUcy:"\u042e",yucy:"\u044e",Yuml:"\u0178",yuml:"\xff",Zacute:"\u0179",zacute:"\u017a",Zcaron:"\u017d",zcaron:"\u017e",Zcy:"\u0417",zcy:"\u0437",Zdot:"\u017b",zdot:"\u017c",zeetrf:"\u2128",ZeroWidthSpace:"\u200b",Zeta:"\u0396",zeta:"\u03b6",Zfr:"\u2128",zfr:"\u{1d537}",ZHcy:"\u0416",zhcy:"\u0436",zigrarr:"\u21dd",Zopf:"\u2124",zopf:"\u{1d56b}",Zscr:"\u{1d4b5}",zscr:"\u{1d4cf}",zwj:"\u200d",zwnj:"\u200c"}),e.entityMap=e.HTML_ENTITIES},767(t,e,s){"use strict";function i(t,e){t.prototype=Object.create(Error.prototype,{constructor:{value:t},name:{value:t.name,enumerable:!0,writable:e}})}var r=s(870).freeze({Error:"Error",IndexSizeError:"IndexSizeError",DomstringSizeError:"DomstringSizeError",HierarchyRequestError:"HierarchyRequestError",WrongDocumentError:"WrongDocumentError",InvalidCharacterError:"InvalidCharacterError",NoDataAllowedError:"NoDataAllowedError",NoModificationAllowedError:"NoModificationAllowedError",NotFoundError:"NotFoundError",NotSupportedError:"NotSupportedError",InUseAttributeError:"InUseAttributeError",InvalidStateError:"InvalidStateError",SyntaxError:"SyntaxError",InvalidModificationError:"InvalidModificationError",NamespaceError:"NamespaceError",InvalidAccessError:"InvalidAccessError",ValidationError:"ValidationError",TypeMismatchError:"TypeMismatchError",SecurityError:"SecurityError",NetworkError:"NetworkError",AbortError:"AbortError",URLMismatchError:"URLMismatchError",QuotaExceededError:"QuotaExceededError",TimeoutError:"TimeoutError",InvalidNodeTypeError:"InvalidNodeTypeError",DataCloneError:"DataCloneError",EncodingError:"EncodingError",NotReadableError:"NotReadableError",UnknownError:"UnknownError",ConstraintError:"ConstraintError",DataError:"DataError",TransactionInactiveError:"TransactionInactiveError",ReadOnlyError:"ReadOnlyError",VersionError:"VersionError",OperationError:"OperationError",NotAllowedError:"NotAllowedError",OptOutError:"OptOutError"}),n=Object.keys(r);function o(t){return"number"==typeof t&&t>=1&&t<=25}function a(t,e){var s;o(t)?(this.name=n[t],this.message=e||""):(this.message=t,this.name="string"==typeof(s=e)&&s.substring(s.length-r.Error.length)===r.Error?e:r.Error),Error.captureStackTrace&&Error.captureStackTrace(this,a)}i(a,!0),Object.defineProperties(a.prototype,{code:{enumerable:!0,get:function(){var t=n.indexOf(this.name);return o(t)?t:0}}});for(var l={INDEX_SIZE_ERR:1,DOMSTRING_SIZE_ERR:2,HIERARCHY_REQUEST_ERR:3,WRONG_DOCUMENT_ERR:4,INVALID_CHARACTER_ERR:5,NO_DATA_ALLOWED_ERR:6,NO_MODIFICATION_ALLOWED_ERR:7,NOT_FOUND_ERR:8,NOT_SUPPORTED_ERR:9,INUSE_ATTRIBUTE_ERR:10,INVALID_STATE_ERR:11,SYNTAX_ERR:12,INVALID_MODIFICATION_ERR:13,NAMESPACE_ERR:14,INVALID_ACCESS_ERR:15,VALIDATION_ERR:16,TYPE_MISMATCH_ERR:17,SECURITY_ERR:18,NETWORK_ERR:19,ABORT_ERR:20,URL_MISMATCH_ERR:21,QUOTA_EXCEEDED_ERR:22,TIMEOUT_ERR:23,INVALID_NODE_TYPE_ERR:24,DATA_CLONE_ERR:25},c=Object.entries(l),h=0;h/),A=/[\x20\x0D\x0Aa-zA-Z0-9-'()+,./:=?;!*#@$_%]/,R=a('"',A,'*"',"|","'",n(A,"'"),"*'"),S="\x3c!--",M=o(S,a(n(l,"-"),"|",o("-",n(l,"-"))),"*","--\x3e"),I="#PCDATA",O=a(o(/\(/,u,I,a(u,/\|/,u,w),"*",u,/\)\*/),"|",o(/\(/,u,I,u,/\)/)),D=a("EMPTY","|","ANY","|",O,"|",o(/\([^>]+\)/,/[?*+]?/)),P=o(""),B=o("NOTATION",d,/\(/,u,f,a(u,/\|/,u,f),"*",u,/\)/),F=o(/\(/,u,g,a(u,/\|/,u,g),"*",u,/\)/),j=a(B,"|",F),U=a(/CDATA|ID|IDREF|IDREFS|ENTITY|ENTITIES|NMTOKEN|NMTOKENS/,"|",j),H=a(/#REQUIRED|#IMPLIED/,"|",a(a("#FIXED",d),"?",v)),q=o(""),W="about:legacy-compat",z=a('"'+W+'"',"|","'"+W+"'"),V="SYSTEM",X="PUBLIC",G=a(a(V,d,_),"|",a(X,d,R,d,_)),J=o("^",a(a(V,d,"(?",_,")"),"|",a(X,d,"(?",R,")",d,"(?",_,")"))),K=a(d,"NDATA",d,f),$=""),Q=a(N,"|",G),Z=a(Y,"|",o($,d,"%",d,f,d,Q,u,">")),tt=o(X,d,R),et=o(""),st=o(u,"=",u),it=/1[.]\d+/,rt=o(d,"version",st,a("'",it,"'","|",'"',it,'"')),nt=/[A-Za-z][-A-Za-z0-9._]*/,ot=o(/^<\?xml/,rt,a(d,"encoding",st,a('"',nt,'"',"|","'",nt,"'")),"?",a(d,"standalone",st,a("'",a("yes","|","no"),"'","|",'"',a("yes","|","no"),'"')),"?",u,/\?>/),at=o(l,"*?",/\]\]>/),lt=o(/",e.CDSect=lt,e.Char=l,e.Comment=M,e.COMMENT_START=S,e.COMMENT_END="--\x3e",e.DOCTYPE_DECL_START="=0&&o.warning("Unicode replacement character detected, source encoding issues?");function h(t){if(t>65535){var e=55296+((t-=65536)>>10),s=56320+(1023&t);return String.fromCharCode(e,s)}return String.fromCharCode(t)}function p(t){var e=";"===t[t.length-1]?t:t+";";if(!l&&e!==t)return o.error("EntityRef: expecting ;"),t;var i=r.Reference.exec(e);if(!i||i[0].length!==e.length)return o.error("entity not matching Reference production: "+t),t;var n=e.slice(1,-1);return c(s,n)?s[n]:"#"===n.charAt(0)?h(parseInt(n.substring(1).replace("x","0x"))):(o.error("entity not found:"+t),t)}function x(e){if(e>R){var s=t.substring(R,e).replace(m,p);k&&_(R),n.characters(s,0,e-R),R=e}}var y=0,w=0,C=/\r\n?|\n|$/g,k=n.locator;function _(e,s){for(;e>=w&&(s=C.exec(t));)y=w,w=s.index+s[0].length,k.lineNumber++;k.columnNumber=e-y+1}var L=[{currentNSMap:e}],A=[],R=0;for(;;){try{var S=t.indexOf("<",R);if(S<0){if(!l&&A.length>0)return o.fatalError("unclosed xml tag(s): "+A.join(", "));if(!t.substring(R).match(/^\s*$/)){var M=n.doc,I=M.createTextNode(t.substring(R));if(M.documentElement)return o.error("Extra content at the end of the document");M.appendChild(I),n.currentElement=I}return}if(S>R){var O=t.substring(R,S);l||0!==A.length||(O=O.replace(new RegExp(r.S_OPT.source,"g"),""))&&o.error("Unexpected content outside root element: '"+O+"'"),x(S)}switch(t.charAt(S+1)){case"/":var D=t.indexOf(">",S+2),P=t.substring(S+2,D>0?D:void 0);if(!P)return o.fatalError("end tag name missing");var B=D>0&&r.reg("^",r.QName_group,r.S_OPT,"$").exec(P);if(!B)return o.fatalError('end tag name contains invalid characters: "'+P+'"');if(!n.currentElement&&!n.doc.documentElement)return;var F=A[A.length-1]||n.currentElement.tagName||n.doc.documentElement.tagName||"";if(F!==B[1]){var j=B[1].toLowerCase();if(!l||F.toLowerCase()!==j)return o.fatalError('Opening and ending tag mismatch: "'+F+'" != "'+P+'"')}var U=L.pop();A.pop();var H=U.localNSMap;if(n.endElement(U.uri,U.localName,F),H)for(var q in H)c(H,q)&&n.endPrefixMapping(q);D++;break;case"?":k&&_(S),D=v(t,S,n,o);break;case"!":k&&_(S),D=N(t,S,n,o,l);break;default:k&&_(S);var W=new T,z=L[L.length-1].currentNSMap,V=(D=g(t,S,W,z,p,o,l),W.length);if(W.closed||(l&&i.isHTMLVoidElement(W.tagName)?W.closed=!0:A.push(W.tagName)),k&&V){for(var X=f(k,{}),G=0;GR?R=D:x(Math.max(S,R)+1)}}(t,e,s,n,this.errorHandler),n.endDocument()}};var m=/&#?\w+;?/g;function f(t,e){return e.lineNumber=t.lineNumber,e.columnNumber=t.columnNumber,e}function g(t,e,s,i,r,n,o){function a(t,e,i){return c(s.attributeNames,t)?n.fatalError("Attribute "+t+" redefined"):!o&&e.indexOf("<")>=0?n.fatalError("Unescaped '<' not allowed in attributes values"):void s.addValue(t,e.replace(/[\t\n\r]/g," ").replace(m,r),i)}for(var l,h=++e,d=0;;){var u=t.charAt(h);switch(u){case"=":if(1===d)l=t.slice(e,h),d=3;else{if(2!==d)throw new Error("attribute equal must after attrName");d=3}break;case"'":case'"':if(3===d||1===d){if(1===d&&(n.warning('attribute value must after "="'),l=t.slice(e,h)),e=h+1,!((h=t.indexOf(u,e))>0))throw new Error("attribute value no end '"+u+"' match");a(l,p=t.slice(e,h),e-1),d=5}else{if(4!=d)throw new Error('attribute value must after "="');a(l,p=t.slice(e,h),e),n.warning('attribute "'+l+'" missed start quot('+u+")!!"),e=h+1,d=5}break;case"/":switch(d){case 0:s.setTagName(t.slice(e,h));case 5:case 6:case 7:d=7,s.closed=!0;case 4:case 1:break;case 2:s.closed=!0;break;default:throw new Error("attribute invalid close char('/')")}break;case"":return n.error("unexpected end of input"),0==d&&s.setTagName(t.slice(e,h)),h;case">":switch(d){case 0:s.setTagName(t.slice(e,h));case 5:case 6:case 7:break;case 4:case 1:"/"===(p=t.slice(e,h)).slice(-1)&&(s.closed=!0,p=p.slice(0,-1));case 2:2===d&&(p=l),4==d?(n.warning('attribute "'+p+'" missed quot(")!'),a(l,p,e)):(o||n.warning('attribute "'+p+'" missed value!! "'+p+'" instead!!'),a(p,p,e));break;case 3:if(!o)return n.fatalError("AttValue: ' or \" expected")}return h;case"\x80":u=" ";default:if(u<=" ")switch(d){case 0:s.setTagName(t.slice(e,h)),d=6;break;case 1:l=t.slice(e,h),d=2;break;case 4:var p=t.slice(e,h);n.warning('attribute "'+p+'" missed quot(")!!'),a(l,p,e);case 5:d=6}else switch(d){case 2:o||n.warning('attribute "'+l+'" missed value!! "'+l+'" instead2!!'),a(l,l,e),e=h,d=1;break;case 5:n.warning('attribute space is required"'+l+'"!!');case 6:d=1,e=h;break;case 3:d=4,e=h;break;case 7:throw new Error("elements closed character '/' and '>' must be connected to")}}h++}}function b(t,e,s){for(var i=t.tagName,r=null,n=t.length;n--;){var o=t[n],a=o.qName,l=o.value;if((m=a.indexOf(":"))>0)var d=o.prefix=a.slice(0,m),u=a.slice(m+1),p="xmlns"===d&&u;else u=a,d=null,p="xmlns"===a&&"";o.localName=u,!1!==p&&(null==r&&(r=Object.create(null),x(s,s=Object.create(null))),s[p]=r[p]=l,o.uri=h.XMLNS,e.startPrefixMapping(p,l))}for(n=t.length;n--;)(o=t[n]).prefix&&("xml"===o.prefix&&(o.uri=h.XML),"xmlns"!==o.prefix&&(o.uri=s[o.prefix]));var m;(m=i.indexOf(":"))>0?(d=t.prefix=i.slice(0,m),u=t.localName=i.slice(m+1)):(d=null,u=t.localName=i);var f=t.uri=s[d||""];if(e.startElement(f,u,i,t),!t.closed)return t.currentNSMap=s,t.localNSMap=r,!0;if(e.endElement(f,u,i),r)for(d in r)c(r,d)&&e.endPrefixMapping(d)}function E(t,e,s,i,r){var n=o(s);if(n||l(s)){var a=t.indexOf("",e),c=t.substring(e+1,a);return n&&(c=c.replace(m,i)),r.characters(c,0,c.length),a}return e+1}function x(t,e){for(var s in t)c(t,s)&&(e[s]=t[s])}function y(t,e){var s=e;function i(e){return e=e||0,t.charAt(s+e)}function n(t){s+=t=t||1}function o(){return t.substring(s)}return{char:i,getIndex:function(){return s},getMatch:function(t){var e=r.reg("^",t).exec(o());return e?(n(e[0].length),e[0]):null},getSource:function(){return t},skip:n,skipBlanks:function(){for(var e=0;s"!==o.char()?i.fatalError("doctype not terminated with > at position "+o.getIndex()):(o.skip(1),s.startDTD(c.name,c.publicId,c.systemId,c.internalSubset),s.endDTD(),o.getIndex());default:return i.fatalError('Not well-formed XML starting with "0)return i.fatalError("processing instruction at position "+e+" is an xml declaration which is only at the start of the document");if(!r.XMLDecl.test(t.substring(e)))return i.fatalError("xml declaration is not well-formed")}return s.processingInstruction(n[1],n[2]),e+n[0].length}function T(){this.attributeNames=Object.create(null)}T.prototype={setTagName:function(t){if(!r.QName_exact.test(t))throw new Error("invalid tagName:"+t);this.tagName=t},addValue:function(t,e,s){if(!r.QName_exact.test(t))throw new Error("invalid attribute:"+t);this.attributeNames[t]=this.length,this[this.length++]={qName:t,value:e,offset:s}},length:0,getLocalName:function(t){return this[t].localName},getLocator:function(t){return this[t].locator},getQName:function(t){return this[t].qName},getURI:function(t){return this[t].uri},getValue:function(t){return this[t].value}},e.XMLReader=p,e.parseUtils=y,e.parseDoctypeCommentOrCData=N},999(t,e,s){(function(){"use strict";var e=this;function s(t){return"string"==typeof t}function i(t,e,s){return t.call.apply(t.bind,arguments)}function r(t,e,s){if(!t)throw Error();if(2e?1:0}var h,d=Array.prototype.indexOf?function(t,e,s){return Array.prototype.indexOf.call(t,e,s)}:function(t,e,i){if(i=null==i?0:0>i?Math.max(0,t.length+i):i,s(t))return s(e)&&1==e.length?t.indexOf(e,i):-1;for(;iparseFloat(k)){E=String(L);break t}}E=k}var A={};function R(t){if(!A[t]){for(var e=0,s=a(String(E)).split("."),i=a(String(t)).split("."),r=Math.max(s.length,i.length),n=0;0==e&&n",4,2,function(t,e,s){return mt(function(t,e){return t>e},t,e,s)}),bt("<=",4,2,function(t,e,s){return mt(function(t,e){return t<=e},t,e,s)}),bt(">=",4,2,function(t,e,s){return mt(function(t,e){return t>=e},t,e,s)});var Et=bt("=",3,2,function(t,e,s){return mt(function(t,e){return t==e},t,e,s,!0)});function xt(t,e,s){this.a=t,this.b=e||1,this.f=s||1}function yt(t,e){if(e.a.length&&4!=t.i)throw Error("Primary expression must evaluate to nodeset if filter has predicate(s).");ot.call(this,t.i),this.c=t,this.h=e,this.g=t.g,this.b=t.b}function Nt(t,e){if(e.lengtht.v)throw Error("Function "+t.j+" expects at most "+t.v+" arguments, "+e.length+" given");t.B&&u(e,function(e,s){if(4!=e.i)throw Error("Argument "+s+" to function "+t.j+" is not of type Nodeset: "+e)}),ot.call(this,t.i),this.h=t,this.c=e,lt(this,t.g||f(e,function(t){return t.g})),ct(this,t.D&&!e.length||t.C&&!!e.length||f(e,function(t){return t.b}))}function vt(t,e,s,i,r,n,o,a,l){this.j=t,this.i=e,this.g=s,this.D=i,this.C=r,this.m=n,this.A=o,this.v=void 0!==a?a:o,this.B=!!l}bt("!=",3,2,function(t,e,s){return mt(function(t,e){return t!=e},t,e,s,!0)}),bt("and",2,2,function(t,e,s){return ut(t,s)&&ut(e,s)}),bt("or",1,2,function(t,e,s){return ut(t,s)||ut(e,s)}),o(yt),yt.prototype.a=function(t){return t=this.c.a(t),Ht(this.h,t)},yt.prototype.toString=function(){return"Filter:"+at(this.c)+at(this.h)},o(Nt),Nt.prototype.a=function(t){return this.h.m.apply(null,function(t){return Array.prototype.concat.apply(Array.prototype,arguments)}(t,this.c))},Nt.prototype.toString=function(){var t="Function: "+this.h;if(this.c.length){var e=m(this.c,function(t,e){return t+at(e)},"Arguments:");t=t+at(e)}return t},vt.prototype.toString=function(){return this.j};var Tt={};function wt(t,e,s,i,r,n,o,a){if(Tt.hasOwnProperty(t))throw Error("Function already created: "+t+".");Tt[t]=new vt(t,e,s,i,!1,r,n,o,a)}function Ct(t,e){switch(this.h=t,this.c=void 0!==e?e:null,this.b=null,t){case"comment":this.b=8;break;case"text":this.b=3;break;case"processing-instruction":this.b=7;break;case"node":break;default:throw Error("Unexpected argument")}}function kt(t){return"comment"==t||"text"==t||"processing-instruction"==t||"node"==t}function _t(t){this.b=t,this.a=0}wt("boolean",2,!1,!1,function(t,e){return ut(e,t)},1),wt("ceiling",1,!1,!1,function(t,e){return Math.ceil(ht(e,t))},1),wt("concat",3,!1,!1,function(t,e){return m(function(t,e,s){return 2>=arguments.length?Array.prototype.slice.call(t,e):Array.prototype.slice.call(t,e,s)}(arguments,1),function(e,s){return e+dt(s,t)},"")},2,null),wt("contains",2,!1,!1,function(t,e,s){return l(dt(e,t),dt(s,t))},2),wt("count",1,!1,!1,function(t,e){return e.a(t).l},1,1,!0),wt("false",2,!1,!1,function(){return!1},0),wt("floor",1,!1,!1,function(t,e){return Math.floor(ht(e,t))},1),wt("id",4,!1,!1,function(t,e){function i(t){if(I){var e=r.all[t];if(e){if(e.nodeType&&t==e.id)return e;if(e.length)return function(t,e){var i;t:{i=t.length;for(var r=s(t)?t.split(""):t,n=0;ni?null:s(t)?t.charAt(i):t[i]}(e,function(e){return t==e.id})}return null}return r.getElementById(t)}var r=9==(n=t.a).nodeType?n:n.ownerDocument,n=dt(e,t).split(/\s+/),o=[];u(n,function(t){!(t=i(t))||0<=d(o,t)||o.push(t)}),o.sort(G);var a=new $;return u(o,function(t){tt(a,t)}),a},1),wt("lang",2,!1,!1,function(){return!1},1),wt("last",1,!0,!1,function(t){if(1!=arguments.length)throw Error("Function last expects ()");return t.f},0),wt("local-name",3,!1,!0,function(t,e){var s=e?et(e.a(t)):t.a;return s?s.localName||s.nodeName.toLowerCase():""},0,1,!0),wt("name",3,!1,!0,function(t,e){var s=e?et(e.a(t)):t.a;return s?s.nodeName.toLowerCase():""},0,1,!0),wt("namespace-uri",3,!0,!1,function(){return""},0,1,!0),wt("normalize-space",3,!1,!0,function(t,e){return(e?dt(e,t):B(t.a)).replace(/[\s\xa0]+/g," ").replace(/^\s+|\s+$/g,"")},0,1),wt("not",2,!1,!1,function(t,e){return!ut(e,t)},1),wt("number",1,!1,!0,function(t,e){return e?ht(e,t):+B(t.a)},0,1),wt("position",1,!0,!1,function(t){return t.b},0),wt("round",1,!1,!1,function(t,e){return Math.round(ht(e,t))},1),wt("starts-with",2,!1,!1,function(t,e,s){return e=dt(e,t),t=dt(s,t),0==e.lastIndexOf(t,0)},2),wt("string",3,!1,!0,function(t,e){return e?dt(e,t):B(t.a)},0,1),wt("string-length",1,!1,!0,function(t,e){return(e?dt(e,t):B(t.a)).length},0,1),wt("substring",3,!1,!1,function(t,e,s,i){if(s=ht(s,t),isNaN(s)||1/0==s||-1/0==s)return"";if(i=i?ht(i,t):1/0,isNaN(i)||-1/0===i)return"";s=Math.round(s)-1;var r=Math.max(s,0);return t=dt(e,t),1/0==i?t.substring(r):t.substring(r,s+Math.round(i))},2,3),wt("substring-after",3,!1,!1,function(t,e,s){return e=dt(e,t),t=dt(s,t),-1==(s=e.indexOf(t))?"":e.substring(s+t.length)},2),wt("substring-before",3,!1,!1,function(t,e,s){return e=dt(e,t),t=dt(s,t),-1==(t=e.indexOf(t))?"":e.substring(0,t)},2),wt("sum",1,!1,!1,function(t,e){for(var s=it(e.a(t)),i=0,r=nt(s);r;r=nt(s))i+=+B(r);return i},1,1,!0),wt("translate",3,!1,!1,function(t,e,s,i){e=dt(e,t),s=dt(s,t);var r=dt(i,t);for(t={},i=0;i]=|\s+|./g,At=/^\s/;function Rt(t,e){return t.b[t.a+(e||0)]}function St(t){return t.b[t.a++]}function Mt(t){return t.b.length<=t.a}function It(t){ot.call(this,3),this.c=t.substring(1,t.length-1)}function Ot(t,e){var s;this.j=t.toLowerCase(),s="*"==this.j?"*":"http://www.w3.org/1999/xhtml",this.c=e?e.toLowerCase():s}function Dt(t,e){if(ot.call(this,t.i),this.h=t,this.c=e,this.g=t.g,this.b=t.b,1==this.c.length){var s=this.c[0];s.u||s.c!=Xt||"*"!=(s=s.o).f()&&(this.f={name:s.f(),s:null})}}function Pt(){ot.call(this,4)}function Bt(){ot.call(this,4)}function Ft(t){return"/"==t||"//"==t}function jt(t){ot.call(this,4),this.c=t,lt(this,f(this.c,function(t){return t.g})),ct(this,f(this.c,function(t){return t.b}))}function Ut(t,e){this.a=t,this.b=!!e}function Ht(t,e,s){for(s=s||0;s(t=St(t.a)).length)throw Error("Unclosed literal string");return new It(t)}function ae(t){var e,s,i=[];if(Ft(Rt(t.a))){if(e=St(t.a),s=Rt(t.a),"/"==e&&(Mt(t.a)||"."!=s&&".."!=s&&"@"!=s&&"*"!=s&&!/(?![0-9])[\w]/.test(s)))return new Pt;s=new Pt,ie(t,"Missing next location step."),e=le(t,e),i.push(e)}else{t:{switch(s=(e=Rt(t.a)).charAt(0)){case"$":throw Error("Variable reference not allowed in HTML XPath");case"(":St(t.a),e=se(t),ie(t,'unclosed "("'),re(t,")");break;case'"':case"'":e=oe(t);break;default:if(isNaN(+e)){if(kt(e)||!/(?![0-9])[\w]/.test(s)||"("!=Rt(t.a,1)){e=null;break t}for(e=St(t.a),e=Tt[e]||null,St(t.a),s=[];")"!=Rt(t.a)&&(ie(t,"Missing function argument list."),s.push(se(t)),","==Rt(t.a));)St(t.a);ie(t,"Unclosed function argument list."),ne(t),e=new Nt(e,s)}else e=new te(+St(t.a))}"["==Rt(t.a)&&(e=new yt(e,s=new Ut(ce(t))))}if(e){if(!Ft(Rt(t.a)))return e;s=e}else e=le(t,"/"),s=new Bt,i.push(e)}for(;Ft(Rt(t.a));)e=St(t.a),ie(t,"Missing next location step."),e=le(t,e),i.push(e);return new Dt(s,i)}function le(t,e){var s,i,r,n;if("/"!=e&&"//"!=e)throw Error('Step op should be "/" or "//"');if("."==Rt(t.a))return i=new qt(Qt,new Ct("node")),St(t.a),i;if(".."==Rt(t.a))return i=new qt($t,new Ct("node")),St(t.a),i;if("@"==Rt(t.a))n=Xt,St(t.a),ie(t,"Missing attribute name");else if("::"==Rt(t.a,1)){if(!/(?![0-9])[\w]/.test(Rt(t.a).charAt(0)))throw Error("Bad token: "+St(t.a));if(s=St(t.a),!(n=zt[s]||null))throw Error("No axis with name: "+s);St(t.a),ie(t,"Missing node name")}else n=Gt;if(s=Rt(t.a),!/(?![0-9])[\w\*]/.test(s.charAt(0)))throw Error("Bad token: "+St(t.a));if("("==Rt(t.a,1)){if(!kt(s))throw Error("Invalid node type: "+s);if(!kt(s=St(t.a)))throw Error("Invalid type name: "+s);re(t,"("),ie(t,"Bad nodetype");var o=null;'"'!=(r=Rt(t.a).charAt(0))&&"'"!=r||(o=oe(t)),ie(t,"Bad nodetype"),ne(t),s=new Ct(s,o)}else if(-1==(r=(s=St(t.a)).indexOf(":")))s=new Ot(s);else{var a;if("*"==(o=s.substring(0,r)))a="*";else if(!(a=t.b(o)))throw Error("Namespace prefix not declared: "+o);s=new Ot(s=s.substr(r+1),a)}return r=new Ut(ce(t),n.a),i||new qt(n,s,r,"//"==e)}function ce(t){for(var e=[];"["==Rt(t.a);){St(t.a),ie(t,"Missing predicate expression.");var s=se(t);e.push(s),ie(t,"Unclosed predicate expression."),re(t,"]")}return e}function he(t){if("-"==Rt(t.a))return St(t.a),new Zt(he(t));var e=ae(t);if("|"!=Rt(t.a))t=e;else{for(e=[e];"|"==St(t.a);)ie(t,"Missing next union location path."),e.push(ae(t));t.a.a--,t=new jt(e)}return t}function de(t){switch(t.nodeType){case 1:return function(t,e){var s=Array.prototype.slice.call(arguments,1);return function(){var e=s.slice();return e.push.apply(e,arguments),t.apply(this,e)}}(pe,t);case 9:return de(t.documentElement);case 11:case 10:case 6:case 12:return ue;default:return t.parentNode?de(t.parentNode):ue}}function ue(){return null}function pe(t,e){if(t.prefix==e)return t.namespaceURI||"http://www.w3.org/1999/xhtml";var s=t.getAttributeNode("xmlns:"+e);return s&&s.specified?s.value||null:t.parentNode&&9!=t.parentNode.nodeType?pe(t.parentNode,e):null}function me(t,e){if(!t.length)throw Error("Empty XPath expression.");var s=function(t){t=t.match(Lt);for(var e=0;e=s.length?null:s[n++]},this.snapshotItem=function(t){if(6!=e&&7!=e)throw Error("snapshotItem called with wrong result type");return t>=s.length||0>t?null:s[t]}}function ge(t){this.lookupNamespaceURI=de(t)}function be(t,s){var i=t||e,r=i.Document&&i.Document.prototype||i.document;r.evaluate&&!s||(i.XPathResult=fe,r.evaluate=function(t,e,s,i){return new me(t,s).evaluate(e,i)},r.createExpression=function(t,e){return new me(t,e)},r.createNSResolver=function(t){return new ge(t)})}o(Zt),Zt.prototype.a=function(t){return-ht(this.c,t)},Zt.prototype.toString=function(){return"Unary Expression: -"+at(this.c)},o(te),te.prototype.a=function(){return this.c},te.prototype.toString=function(){return"Number: "+this.c},fe.ANY_TYPE=0,fe.NUMBER_TYPE=1,fe.STRING_TYPE=2,fe.BOOLEAN_TYPE=3,fe.UNORDERED_NODE_ITERATOR_TYPE=4,fe.ORDERED_NODE_ITERATOR_TYPE=5,fe.UNORDERED_NODE_SNAPSHOT_TYPE=6,fe.ORDERED_NODE_SNAPSHOT_TYPE=7,fe.ANY_UNORDERED_NODE_TYPE=8,fe.FIRST_ORDERED_NODE_TYPE=9;var Ee,xe=["wgxpath","install"],ye=e;xe[0]in ye||!ye.execScript||ye.execScript("var "+xe[0]);for(;xe.length&&(Ee=xe.shift());)xe.length||void 0===be?ye=ye[Ee]?ye[Ee]:ye[Ee]={}:ye[Ee]=be;t.exports.install=be,t.exports.XPathResultType={ANY_TYPE:0,NUMBER_TYPE:1,STRING_TYPE:2,BOOLEAN_TYPE:3,UNORDERED_NODE_ITERATOR_TYPE:4,ORDERED_NODE_ITERATOR_TYPE:5,UNORDERED_NODE_SNAPSHOT_TYPE:6,ORDERED_NODE_SNAPSHOT_TYPE:7,ANY_UNORDERED_NODE_TYPE:8,FIRST_ORDERED_NODE_TYPE:9}}).call(s.g)},855(t,e,s){"use strict";var i,r;s.d(e,{Al:()=>l,Gb:()=>a,Oe:()=>d});var n=s(546),o=s(999);const a=i||(i=s.t(n,2)),l=(new a.DOMImplementation).createDocument("",""),c=(null===(r||(r=s.t(o,2)))||void 0===(r||(r=s.t(o,2)))?void 0:o.install)||window.wgxpath.install,h=function(){const t={document:{},XPathResult:{}};return c(t),t.document.XPathResult=t.XPathResult,t.document}(),d={currentDocument:l,evaluate:h.evaluate,result:h.XPathResult,createNSResolver:h.createNSResolver}},679(__unused_webpack___webpack_module__,__webpack_exports__,__webpack_require__){"use strict";__webpack_require__.d(__webpack_exports__,{f:()=>SystemExternal});var _variables_js__WEBPACK_IMPORTED_MODULE_0__=__webpack_require__(439),_lib_external_js__WEBPACK_IMPORTED_MODULE_1__=__webpack_require__(855);const windowSupported=!("undefined"==typeof window),documentSupported=windowSupported&&!(void 0===window.document),webworker=!("undefined"==typeof DedicatedWorkerGlobalScope),nodeRequire=()=>{try{return eval("require")}catch(t){return t=>null}},SystemExternal={extRequire:t=>"undefined"!=typeof process&&"undefined"!=typeof require?nodeRequire()(t):null,windowSupported,documentSupported,webworker,xmldom:_lib_external_js__WEBPACK_IMPORTED_MODULE_1__.Gb,document:_lib_external_js__WEBPACK_IMPORTED_MODULE_1__.Al,fs:documentSupported||webworker?null:nodeRequire()("fs"),url:_variables_js__WEBPACK_IMPORTED_MODULE_0__.u.url,jsonPath:function(){if(documentSupported||webworker)return _variables_js__WEBPACK_IMPORTED_MODULE_0__.u.url;if(process.env.SRE_JSON_PATH||__webpack_require__.g.SRE_JSON_PATH)return process.env.SRE_JSON_PATH||__webpack_require__.g.SRE_JSON_PATH;try{return nodeRequire().resolve("speech-rule-engine").replace(/sre\.js$/,"")+"mathmaps"}catch(t){}try{return nodeRequire().resolve(".").replace(/sre\.js$/,"")+"mathmaps"}catch(t){}return"undefined"!=typeof __dirname?__dirname+(__dirname.match(/lib?$/)?"/mathmaps":"/lib/mathmaps"):process.cwd()+"/lib/mathmaps"}(),xpath:_lib_external_js__WEBPACK_IMPORTED_MODULE_1__.Oe}},439(t,e,s){"use strict";s.d(e,{u:()=>i});class i{static ensureLocale(t,e){return i.LOCALES.get(t)?t:(console.error(`Locale ${t} does not exist! Using ${i.LOCALES.get(e)} instead.`),e)}}i.VERSION="5.0.0-beta.6",i.LOCALES=new Map([["af","Afrikaans"],["ca","Catalan"],["da","Danish"],["de","German"],["en","English"],["es","Spanish"],["euro","Euro"],["fr","French"],["hi","Hindi"],["it","Italian"],["ko","Korean"],["nb","Bokm\xe5l"],["nn","Nynorsk"],["sv","Swedish"],["nemeth","Nemeth"]]),i.mathjaxVersion="4.0.0",i.url="https://cdn.jsdelivr.net/npm/speech-rule-engine@"+i.VERSION+"/lib/mathmaps"}},__webpack_module_cache__={},leafPrototypes,getProto;function __webpack_require__(t){var e=__webpack_module_cache__[t];if(void 0!==e)return e.exports;var s=__webpack_module_cache__[t]={exports:{}};return __webpack_modules__[t](s,s.exports,__webpack_require__),s.exports}getProto=Object.getPrototypeOf?t=>Object.getPrototypeOf(t):t=>t.__proto__,__webpack_require__.t=function(t,e){if(1&e&&(t=this(t)),8&e)return t;if("object"==typeof t&&t){if(4&e&&t.__esModule)return t;if(16&e&&"function"==typeof t.then)return t}var s=Object.create(null);__webpack_require__.r(s);var i={};leafPrototypes=leafPrototypes||[null,getProto({}),getProto([]),getProto(getProto)];for(var r=2&e&&t;("object"==typeof r||"function"==typeof r)&&!~leafPrototypes.indexOf(r);r=getProto(r))Object.getOwnPropertyNames(r).forEach(e=>i[e]=()=>t[e]);return i.default=()=>t,__webpack_require__.d(s,i),s},__webpack_require__.d=(t,e)=>{for(var s in e)__webpack_require__.o(e,s)&&!__webpack_require__.o(t,s)&&Object.defineProperty(t,s,{enumerable:!0,get:e[s]})},__webpack_require__.g=function(){if("object"==typeof globalThis)return globalThis;try{return this||new Function("return this")()}catch(t){if("object"==typeof window)return window}}(),__webpack_require__.o=(t,e)=>Object.prototype.hasOwnProperty.call(t,e),__webpack_require__.r=t=>{"undefined"!=typeof Symbol&&Symbol.toStringTag&&Object.defineProperty(t,Symbol.toStringTag,{value:"Module"}),Object.defineProperty(t,"__esModule",{value:!0})};var __webpack_exports__={};(()=>{"use strict";var t={};__webpack_require__.r(t),__webpack_require__.d(t,{GLOBAL:()=>ni,MathJax:()=>hi,combineConfig:()=>ai,combineDefaults:()=>li,combineWithMathJax:()=>ci,isObject:()=>oi});var e={};__webpack_require__.r(e),__webpack_require__.d(e,{context:()=>ui,hasWindow:()=>di});var s={};__webpack_require__.r(s),__webpack_require__.d(s,{Package:()=>mi,PackageError:()=>pi});var i={};__webpack_require__.r(i),__webpack_require__.d(i,{PrioritizedList:()=>fi});var r={};__webpack_require__.r(r),__webpack_require__.d(r,{FunctionList:()=>gi});var n={};__webpack_require__.r(n),__webpack_require__.d(n,{CONFIG:()=>Ti,Loader:()=>Ni,MathJax:()=>vi,PathFilters:()=>xi});var o={};__webpack_require__.r(o),__webpack_require__.d(o,{APPEND:()=>ki,Expandable:()=>Ai,OPTIONS:()=>Li,REMOVE:()=>_i,copy:()=>Ii,defaultOptions:()=>Di,expandable:()=>Ri,insert:()=>Oi,isObject:()=>Ci,keys:()=>Mi,lookup:()=>Ui,makeArray:()=>Si,selectOptions:()=>Bi,selectOptionsFromKeys:()=>Fi,separateOptions:()=>ji,userOptions:()=>Pi});var a={};__webpack_require__.r(a),__webpack_require__.d(a,{CONFIG:()=>zi,MathJax:()=>Wi,Startup:()=>qi});var l={};__webpack_require__.r(l),__webpack_require__.d(l,{AbstractDOMAdaptor:()=>Xi});var c={};__webpack_require__.r(c),__webpack_require__.d(c,{HTMLAdaptor:()=>Ji});var h={};__webpack_require__.r(h),__webpack_require__.d(h,{browserAdaptor:()=>$i});var d={};__webpack_require__.r(d),__webpack_require__.d(d,{AbstractFindMath:()=>Yi});var u={};__webpack_require__.r(u),__webpack_require__.d(u,{AbstractInputJax:()=>Qi});var p={};__webpack_require__.r(p),__webpack_require__.d(p,{AbstractOutputJax:()=>Zi});var m={};__webpack_require__.r(m),__webpack_require__.d(m,{END:()=>tr,LinkedList:()=>sr,ListItem:()=>er});var f={};__webpack_require__.r(f),__webpack_require__.d(f,{AbstractMathList:()=>ir});var g={};__webpack_require__.r(g),__webpack_require__.d(g,{AbstractMathItem:()=>nr,STATE:()=>or,newState:()=>ar,protoItem:()=>rr});var b={};__webpack_require__.r(b),__webpack_require__.d(b,{AbstractFactory:()=>lr});var E={};__webpack_require__.r(E),__webpack_require__.d(E,{AbstractNodeFactory:()=>cr});var x={};__webpack_require__.r(x),__webpack_require__.d(x,{Attributes:()=>dr,INHERIT:()=>hr});var y={};__webpack_require__.r(y),__webpack_require__.d(y,{AbstractEmptyNode:()=>pr,AbstractNode:()=>ur});var N={};__webpack_require__.r(N),__webpack_require__.d(N,{AbstractMmlBaseNode:()=>Tr,AbstractMmlEmptyNode:()=>wr,AbstractMmlLayoutNode:()=>vr,AbstractMmlNode:()=>yr,AbstractMmlTokenNode:()=>Nr,MATHVARIANTS:()=>Er,TEXCLASS:()=>mr,TEXCLASSNAMES:()=>fr,TextNode:()=>Cr,XMLNode:()=>kr,indentAttributes:()=>xr});var v={};__webpack_require__.r(v),__webpack_require__.d(v,{MmlMath:()=>_r});var T={};__webpack_require__.r(T),__webpack_require__.d(T,{MmlMi:()=>Lr});var w={};__webpack_require__.r(w),__webpack_require__.d(w,{MmlMn:()=>Ar});var C={};__webpack_require__.r(C),__webpack_require__.d(C,{MMLSPACING:()=>Or,MO:()=>Sr,OPDEF:()=>Rr,OPTABLE:()=>Dr,RANGES:()=>Mr,getRange:()=>Ir});var k={};__webpack_require__.r(k),__webpack_require__.d(k,{isPercent:()=>Ur,quotePattern:()=>Br,replaceUnicode:()=>qr,sortLength:()=>Pr,split:()=>Hr,toEntity:()=>Wr,unicodeChars:()=>Fr,unicodeString:()=>jr});var _={};__webpack_require__.r(_),__webpack_require__.d(_,{MmlMo:()=>zr});var L={};__webpack_require__.r(L),__webpack_require__.d(L,{MmlMtext:()=>Vr});var A={};__webpack_require__.r(A),__webpack_require__.d(A,{MmlMspace:()=>Xr});var R={};__webpack_require__.r(R),__webpack_require__.d(R,{MmlMs:()=>Gr});var S={};__webpack_require__.r(S),__webpack_require__.d(S,{MmlInferredMrow:()=>Kr,MmlMrow:()=>Jr});var M={};__webpack_require__.r(M),__webpack_require__.d(M,{MmlMfrac:()=>$r});var I={};__webpack_require__.r(I),__webpack_require__.d(I,{MmlMsqrt:()=>Yr});var O={};__webpack_require__.r(O),__webpack_require__.d(O,{MmlMroot:()=>Qr});var D={};__webpack_require__.r(D),__webpack_require__.d(D,{MmlMstyle:()=>Zr});var P={};__webpack_require__.r(P),__webpack_require__.d(P,{MmlMerror:()=>tn});var B={};__webpack_require__.r(B),__webpack_require__.d(B,{MmlMpadded:()=>en});var F={};__webpack_require__.r(F),__webpack_require__.d(F,{MmlMphantom:()=>sn});var j={};__webpack_require__.r(j),__webpack_require__.d(j,{MmlMfenced:()=>rn});var U={};__webpack_require__.r(U),__webpack_require__.d(U,{MmlMenclose:()=>nn});var H={};__webpack_require__.r(H),__webpack_require__.d(H,{MmlMaction:()=>on});var q={};__webpack_require__.r(q),__webpack_require__.d(q,{MmlMsub:()=>ln,MmlMsubsup:()=>an,MmlMsup:()=>cn});var W={};__webpack_require__.r(W),__webpack_require__.d(W,{MmlMover:()=>un,MmlMunder:()=>dn,MmlMunderover:()=>hn});var z={};__webpack_require__.r(z),__webpack_require__.d(z,{MmlMmultiscripts:()=>pn,MmlMprescripts:()=>mn,MmlNone:()=>fn});var V={};__webpack_require__.r(V),__webpack_require__.d(V,{MmlMtable:()=>gn});var X={};__webpack_require__.r(X),__webpack_require__.d(X,{MmlMlabeledtr:()=>En,MmlMtr:()=>bn});var G={};__webpack_require__.r(G),__webpack_require__.d(G,{MmlMtd:()=>xn});var J={};__webpack_require__.r(J),__webpack_require__.d(J,{MmlMaligngroup:()=>yn});var K={};__webpack_require__.r(K),__webpack_require__.d(K,{MmlMalignmark:()=>Nn});var $={};__webpack_require__.r($),__webpack_require__.d($,{MmlMglyph:()=>vn});var Y={};__webpack_require__.r(Y),__webpack_require__.d(Y,{MmlAnnotation:()=>Cn,MmlAnnotationXML:()=>wn,MmlSemantics:()=>Tn});var Q={};__webpack_require__.r(Q),__webpack_require__.d(Q,{TeXAtom:()=>kn});var Z={};__webpack_require__.r(Z),__webpack_require__.d(Z,{MathChoice:()=>_n});var tt={};__webpack_require__.r(tt),__webpack_require__.d(tt,{HtmlNode:()=>Ln});var et={};__webpack_require__.r(et),__webpack_require__.d(et,{MML:()=>An});var st={};__webpack_require__.r(st),__webpack_require__.d(st,{MmlFactory:()=>Rn});var it={};__webpack_require__.r(it),__webpack_require__.d(it,{BitField:()=>Sn,BitFieldClass:()=>Mn});var rt={};__webpack_require__.r(rt),__webpack_require__.d(rt,{handleRetriesFor:()=>In,retryAfter:()=>On});var nt={};__webpack_require__.r(nt),__webpack_require__.d(nt,{AbstractMathDocument:()=>qn,RenderList:()=>Pn,resetAllOptions:()=>Fn,resetOptions:()=>Bn});var ot={};__webpack_require__.r(ot),__webpack_require__.d(ot,{AbstractHandler:()=>zn});var at={};__webpack_require__.r(at),__webpack_require__.d(at,{HandlerList:()=>Vn});var lt={};__webpack_require__.r(lt),__webpack_require__.d(lt,{AbstractVisitor:()=>Xn});var ct={};__webpack_require__.r(ct),__webpack_require__.d(ct,{DATAMJX:()=>Gn,MmlVisitor:()=>Jn});var ht={};__webpack_require__.r(ht),__webpack_require__.d(ht,{MathMLVisitor:()=>Kn});var dt={};__webpack_require__.r(dt),__webpack_require__.d(dt,{SerializedMmlVisitor:()=>$n});var ut={};__webpack_require__.r(ut),__webpack_require__.d(ut,{AbstractWrapper:()=>Yn});var pt={};__webpack_require__.r(pt),__webpack_require__.d(pt,{AbstractWrapperFactory:()=>Qn});var mt={};__webpack_require__.r(mt),__webpack_require__.d(mt,{mathjax:()=>Zn});var ft={};__webpack_require__.r(ft),__webpack_require__.d(ft,{HTMLMathItem:()=>to});var gt={};__webpack_require__.r(gt),__webpack_require__.d(gt,{HTMLMathList:()=>eo});var bt={};__webpack_require__.r(bt),__webpack_require__.d(bt,{HTMLDomStrings:()=>so});var Et={};__webpack_require__.r(Et),__webpack_require__.d(Et,{HTMLDocument:()=>io});var xt={};__webpack_require__.r(xt),__webpack_require__.d(xt,{HTMLHandler:()=>ro});var yt={};__webpack_require__.r(yt),__webpack_require__.d(yt,{RegisterHTMLHandler:()=>no});var Nt={};__webpack_require__.r(Nt),__webpack_require__.d(Nt,{StyleJsonSheet:()=>oo});var vt={};__webpack_require__.r(vt),__webpack_require__.d(vt,{DraggableDialog:()=>co,isDialog:()=>lo});var Tt={};__webpack_require__.r(Tt),__webpack_require__.d(Tt,{InfoDialog:()=>ho});var wt={};__webpack_require__.r(wt),__webpack_require__.d(wt,{asyncLoad:()=>uo});var Ct={};__webpack_require__.r(Ct),__webpack_require__.d(Ct,{BIGDIMEN:()=>po,MATHSPACE:()=>go,RELUNITS:()=>fo,UNITS:()=>mo,em:()=>xo,length2em:()=>bo,percent:()=>Eo,px:()=>yo});var kt={};__webpack_require__.r(kt),__webpack_require__.d(kt,{BBox:()=>No});var _t={};__webpack_require__.r(_t),__webpack_require__.d(_t,{add:()=>Co,entities:()=>To,numeric:()=>Ao,options:()=>vo,remove:()=>ko,translate:()=>_o});var Lt={};__webpack_require__.r(Lt),__webpack_require__.d(Lt,{Styles:()=>Wo,TRBL:()=>Ro,WSC:()=>So});var At={};__webpack_require__.r(At),__webpack_require__.d(At,{max:()=>Vo,sum:()=>zo});var Rt={};__webpack_require__.r(Rt),__webpack_require__.d(Rt,{FindTeX:()=>Xo});var St={};__webpack_require__.r(St),__webpack_require__.d(St,{default:()=>Jo});var Mt={};__webpack_require__.r(Mt),__webpack_require__.d(Mt,{TexConstant:()=>Ko});var It={};__webpack_require__.r(It),__webpack_require__.d(It,{default:()=>ea});var Ot={};__webpack_require__.r(Ot),__webpack_require__.d(Ot,{ConfigurationType:()=>sa,HandlerType:()=>ia});var Dt={};__webpack_require__.r(Dt),__webpack_require__.d(Dt,{UnitUtil:()=>na});var Pt={};__webpack_require__.r(Pt),__webpack_require__.d(Pt,{default:()=>oa});var Bt={};__webpack_require__.r(Bt),__webpack_require__.d(Bt,{default:()=>la});var Ft={};__webpack_require__.r(Ft),__webpack_require__.d(Ft,{BaseItem:()=>ha,MmlStack:()=>ca});var jt={};__webpack_require__.r(jt),__webpack_require__.d(jt,{default:()=>da});var Ut={};__webpack_require__.r(Ut),__webpack_require__.d(Ut,{default:()=>ma});var Ht={};__webpack_require__.r(Ht),__webpack_require__.d(Ht,{NodeFactory:()=>fa});var qt={};__webpack_require__.r(qt),__webpack_require__.d(qt,{KeyValueDef:()=>ga,KeyValueTypes:()=>ba,ParseUtil:()=>ya});var Wt={};__webpack_require__.r(Wt),__webpack_require__.d(Wt,{ColumnParser:()=>Na});var zt={};__webpack_require__.r(zt),__webpack_require__.d(zt,{default:()=>wa});var Vt={};__webpack_require__.r(Vt),__webpack_require__.d(Vt,{AbstractTags:()=>_a,AllTags:()=>Aa,Label:()=>Ca,NoTags:()=>La,TagInfo:()=>ka,TagsFactory:()=>Ma});var Xt={};__webpack_require__.r(Xt),__webpack_require__.d(Xt,{Macro:()=>Oa,Token:()=>Ia});var Gt={};__webpack_require__.r(Gt),__webpack_require__.d(Gt,{AbstractParseMap:()=>Fa,AbstractTokenMap:()=>Pa,CharacterMap:()=>ja,CommandMap:()=>qa,DelimiterMap:()=>Ua,EnvironmentMap:()=>Wa,MacroMap:()=>Ha,RegExpMap:()=>Ba,parseResult:()=>Da});var Jt={};__webpack_require__.r(Jt),__webpack_require__.d(Jt,{MapHandler:()=>Va,SubHandler:()=>Xa,SubHandlers:()=>Ga});var Kt={};__webpack_require__.r(Kt),__webpack_require__.d(Kt,{Configuration:()=>Ja,ConfigurationHandler:()=>$a,ParserConfiguration:()=>Ya});var $t={};__webpack_require__.r($t),__webpack_require__.d($t,{ArrayItem:()=>yl,BeginItem:()=>hl,BreakItem:()=>cl,CellItem:()=>ml,CloseItem:()=>el,DotsItem:()=>xl,EndItem:()=>dl,EqnArrayItem:()=>Nl,EquationItem:()=>Tl,FnItem:()=>gl,LeftItem:()=>ol,Middle:()=>al,MmlItem:()=>fl,MstyleItem:()=>vl,NonscriptItem:()=>El,NotItem:()=>bl,NullItem:()=>sl,OpenItem:()=>tl,OverItem:()=>nl,PositionItem:()=>pl,PrimeItem:()=>il,RightItem:()=>ll,StartItem:()=>Qa,StopItem:()=>Za,StyleItem:()=>ul,SubsupItem:()=>rl});var Yt={};__webpack_require__.r(Yt),__webpack_require__.d(Yt,{default:()=>Al,splitAlignArray:()=>kl});var Qt={};__webpack_require__.r(Qt),__webpack_require__.d(Qt,{default:()=>Ml});var Zt={};__webpack_require__.r(Zt),__webpack_require__.d(Zt,{BaseConfiguration:()=>Fl,BaseTags:()=>Bl,Other:()=>Pl});var te={};__webpack_require__.r(te),__webpack_require__.d(te,{TeX:()=>jl});var ee={};__webpack_require__.r(ee),__webpack_require__.d(ee,{FlalignItem:()=>Hl,MultlineItem:()=>Ul});var se={};__webpack_require__.r(se),__webpack_require__.d(se,{NewcommandPriority:()=>Wl,NewcommandTables:()=>ql,NewcommandUtil:()=>zl});var ie={};__webpack_require__.r(ie),__webpack_require__.d(ie,{AmsMethods:()=>Gl});var re={};__webpack_require__.r(re),__webpack_require__.d(re,{BeginEnvItem:()=>Jl});var ne={};__webpack_require__.r(ne),__webpack_require__.d(ne,{default:()=>$l});var oe={};__webpack_require__.r(oe),__webpack_require__.d(oe,{NewcommandConfig:()=>Yl,NewcommandConfiguration:()=>Ql});var ae={};__webpack_require__.r(ae),__webpack_require__.d(ae,{AmsConfiguration:()=>tc,AmsTags:()=>Zl});var le={};__webpack_require__.r(le),__webpack_require__.d(le,{RequireConfiguration:()=>ac,RequireLoad:()=>rc,RequireMethods:()=>nc,options:()=>oc});var ce={};__webpack_require__.r(ce),__webpack_require__.d(ce,{AutoloadConfiguration:()=>dc});var he={};__webpack_require__.r(he),__webpack_require__.d(he,{ConfigMacrosConfiguration:()=>gc});var de={};__webpack_require__.r(de),__webpack_require__.d(de,{NoUndefinedConfiguration:()=>bc});var ue={};__webpack_require__.r(ue),__webpack_require__.d(ue,{TextParser:()=>Ec});var pe={};__webpack_require__.r(pe),__webpack_require__.d(pe,{TextMacrosMethods:()=>xc});var me={};__webpack_require__.r(me),__webpack_require__.d(me,{TextBaseConfiguration:()=>Nc,TextMacrosConfiguration:()=>Tc});var fe={};__webpack_require__.r(fe),__webpack_require__.d(fe,{FindMathML:()=>Cc});var ge={};__webpack_require__.r(ge),__webpack_require__.d(ge,{MathMLCompile:()=>kc});var be={};__webpack_require__.r(be),__webpack_require__.d(be,{MathML:()=>_c});var Ee={};__webpack_require__.r(Ee),__webpack_require__.d(Ee,{DIRECTION:()=>Lc,H:()=>Rc,V:()=>Ac});var xe={};__webpack_require__.r(xe),__webpack_require__.d(xe,{DIRECTION:()=>Lc,FontData:()=>Oc,NOSTRETCH:()=>Mc,mergeOptions:()=>Ic});var ye={};__webpack_require__.r(ye),__webpack_require__.d(ye,{LineBBox:()=>Dc});var Ne={};__webpack_require__.r(Ne),__webpack_require__.d(Ne,{LinebreakVisitor:()=>Fc,Linebreaks:()=>Bc,NOBREAK:()=>Pc});var ve={};__webpack_require__.r(ve),__webpack_require__.d(ve,{CommonOutputJax:()=>Uc,FONTPATH:()=>jc});var Te={};__webpack_require__.r(Te),__webpack_require__.d(Te,{CommonWrapperFactory:()=>Hc});var we={};__webpack_require__.r(we),__webpack_require__.d(we,{CommonWrapper:()=>Xc,SPACE:()=>Vc});var Ce={};__webpack_require__.r(Ce),__webpack_require__.d(Ce,{ChtmlWrapper:()=>Jc,FONTSIZE:()=>Gc});var ke={};__webpack_require__.r(ke),__webpack_require__.d(ke,{CommonMathMixin:()=>Kc});var _e={};__webpack_require__.r(_e),__webpack_require__.d(_e,{ChtmlMath:()=>$c});var Le={};__webpack_require__.r(Le),__webpack_require__.d(Le,{CommonMiMixin:()=>Yc});var Ae={};__webpack_require__.r(Ae),__webpack_require__.d(Ae,{ChtmlMi:()=>Qc});var Re={};__webpack_require__.r(Re),__webpack_require__.d(Re,{CommonMoMixin:()=>Zc});var Se={};__webpack_require__.r(Se),__webpack_require__.d(Se,{Usage:()=>th});var Me={};__webpack_require__.r(Me),__webpack_require__.d(Me,{AddCSS:()=>sh,ChtmlFontData:()=>eh,DIRECTION:()=>Lc,FontData:()=>Oc,NOSTRETCH:()=>Mc,mergeOptions:()=>Ic});var Ie={};__webpack_require__.r(Ie),__webpack_require__.d(Ie,{ChtmlMo:()=>ih});var Oe={};__webpack_require__.r(Oe),__webpack_require__.d(Oe,{CommonMnMixin:()=>rh});var De={};__webpack_require__.r(De),__webpack_require__.d(De,{ChtmlMn:()=>nh});var Pe={};__webpack_require__.r(Pe),__webpack_require__.d(Pe,{CommonMsMixin:()=>oh});var Be={};__webpack_require__.r(Be),__webpack_require__.d(Be,{ChtmlMs:()=>ah});var Fe={};__webpack_require__.r(Fe),__webpack_require__.d(Fe,{CommonMtextMixin:()=>lh});var je={};__webpack_require__.r(je),__webpack_require__.d(je,{ChtmlMtext:()=>ch});var Ue={};__webpack_require__.r(Ue),__webpack_require__.d(Ue,{CommonMspaceMixin:()=>hh});var He={};__webpack_require__.r(He),__webpack_require__.d(He,{ChtmlMspace:()=>dh});var qe={};__webpack_require__.r(qe),__webpack_require__.d(qe,{CommonMpaddedMixin:()=>uh});var We={};__webpack_require__.r(We),__webpack_require__.d(We,{ChtmlMpadded:()=>ph});var ze={};__webpack_require__.r(ze),__webpack_require__.d(ze,{ARROWDX:()=>fh,ARROWX:()=>mh,ARROWY:()=>gh,CommonArrow:()=>Dh,CommonBorder:()=>Sh,CommonBorder2:()=>Mh,CommonDiagonalArrow:()=>Oh,CommonDiagonalStrike:()=>Ih,PADDING:()=>Eh,SOLID:()=>xh,THICKNESS:()=>bh,arrowBBox:()=>Rh,arrowBBoxHD:()=>kh,arrowBBoxW:()=>_h,arrowDef:()=>Lh,arrowHead:()=>Ch,diagonalArrowDef:()=>Ah,fullBBox:()=>vh,fullBorder:()=>wh,fullPadding:()=>Th,sideIndex:()=>yh,sideNames:()=>Nh});var Ve={};__webpack_require__.r(Ve),__webpack_require__.d(Ve,{CommonMencloseMixin:()=>Ph});var Xe={};__webpack_require__.r(Xe),__webpack_require__.d(Xe,{ARROWDX:()=>fh,ARROWX:()=>mh,ARROWY:()=>gh,Arrow:()=>qh,Border:()=>Fh,Border2:()=>jh,CommonArrow:()=>Dh,CommonBorder:()=>Sh,CommonBorder2:()=>Mh,CommonDiagonalArrow:()=>Oh,CommonDiagonalStrike:()=>Ih,DiagonalArrow:()=>Hh,DiagonalStrike:()=>Uh,PADDING:()=>Eh,RenderElement:()=>Bh,SOLID:()=>xh,THICKNESS:()=>bh,arrowBBox:()=>Rh,arrowBBoxHD:()=>kh,arrowBBoxW:()=>_h,arrowDef:()=>Lh,arrowHead:()=>Ch,diagonalArrowDef:()=>Ah,fullBBox:()=>vh,fullBorder:()=>wh,fullPadding:()=>Th,sideIndex:()=>yh,sideNames:()=>Nh});var Ge={};__webpack_require__.r(Ge),__webpack_require__.d(Ge,{ChtmlMenclose:()=>Vh});var Je={};__webpack_require__.r(Je),__webpack_require__.d(Je,{CommonInferredMrowMixin:()=>Gh,CommonMrowMixin:()=>Xh});var Ke={};__webpack_require__.r(Ke),__webpack_require__.d(Ke,{ChtmlInferredMrow:()=>Kh,ChtmlMrow:()=>Jh});var $e={};__webpack_require__.r($e),__webpack_require__.d($e,{CommonMfencedMixin:()=>$h});var Ye={};__webpack_require__.r(Ye),__webpack_require__.d(Ye,{ChtmlMfenced:()=>Yh});var Qe={};__webpack_require__.r(Qe),__webpack_require__.d(Qe,{CommonMfracMixin:()=>Qh});var Ze={};__webpack_require__.r(Ze),__webpack_require__.d(Ze,{ChtmlMfrac:()=>Zh});var ts={};__webpack_require__.r(ts),__webpack_require__.d(ts,{CommonMsqrtMixin:()=>td});var es={};__webpack_require__.r(es),__webpack_require__.d(es,{ChtmlMsqrt:()=>ed});var ss={};__webpack_require__.r(ss),__webpack_require__.d(ss,{CommonMrootMixin:()=>sd});var is={};__webpack_require__.r(is),__webpack_require__.d(is,{ChtmlMroot:()=>id});var rs={};__webpack_require__.r(rs),__webpack_require__.d(rs,{CommonMsubMixin:()=>rd,CommonMsubsupMixin:()=>od,CommonMsupMixin:()=>nd});var ns={};__webpack_require__.r(ns),__webpack_require__.d(ns,{CommonScriptbaseMixin:()=>ad});var os={};__webpack_require__.r(os),__webpack_require__.d(os,{ChtmlScriptbase:()=>ld});var as={};__webpack_require__.r(as),__webpack_require__.d(as,{ChtmlMsub:()=>cd,ChtmlMsubsup:()=>dd,ChtmlMsup:()=>hd});var ls={};__webpack_require__.r(ls),__webpack_require__.d(ls,{CommonMoverMixin:()=>pd,CommonMunderMixin:()=>ud,CommonMunderoverMixin:()=>md});var cs={};__webpack_require__.r(cs),__webpack_require__.d(cs,{ChtmlMover:()=>gd,ChtmlMunder:()=>fd,ChtmlMunderover:()=>bd});var hs={};__webpack_require__.r(hs),__webpack_require__.d(hs,{CommonMmultiscriptsMixin:()=>yd,NextScript:()=>Ed,ScriptNames:()=>xd});var ds={};__webpack_require__.r(ds),__webpack_require__.d(ds,{ChtmlMmultiscripts:()=>Nd});var us={};__webpack_require__.r(us),__webpack_require__.d(us,{BREAK_BELOW:()=>vd,CommonMtableMixin:()=>Td});var ps={};__webpack_require__.r(ps),__webpack_require__.d(ps,{ChtmlMtable:()=>wd});var ms={};__webpack_require__.r(ms),__webpack_require__.d(ms,{CommonMlabeledtrMixin:()=>kd,CommonMtrMixin:()=>Cd});var fs={};__webpack_require__.r(fs),__webpack_require__.d(fs,{ChtmlMlabeledtr:()=>Ld,ChtmlMtr:()=>_d});var gs={};__webpack_require__.r(gs),__webpack_require__.d(gs,{CommonMtdMixin:()=>Ad});var bs={};__webpack_require__.r(bs),__webpack_require__.d(bs,{ChtmlMtd:()=>Rd});var Es={};__webpack_require__.r(Es),__webpack_require__.d(Es,{CommonMactionMixin:()=>Md,TooltipData:()=>Sd});var xs={};__webpack_require__.r(xs),__webpack_require__.d(xs,{ChtmlMaction:()=>Id});var ys={};__webpack_require__.r(ys),__webpack_require__.d(ys,{CommonMglyphMixin:()=>Od});var Ns={};__webpack_require__.r(Ns),__webpack_require__.d(Ns,{ChtmlMglyph:()=>Dd});var vs={};__webpack_require__.r(vs),__webpack_require__.d(vs,{CommonSemanticsMixin:()=>Pd});var Ts={};__webpack_require__.r(Ts),__webpack_require__.d(Ts,{CommonXmlNodeMixin:()=>Bd});var ws={};__webpack_require__.r(ws),__webpack_require__.d(ws,{ChtmlAnnotation:()=>jd,ChtmlAnnotationXML:()=>Ud,ChtmlSemantics:()=>Fd,ChtmlXmlNode:()=>Hd});var Cs={};__webpack_require__.r(Cs),__webpack_require__.d(Cs,{CommonTeXAtomMixin:()=>qd});var ks={};__webpack_require__.r(ks),__webpack_require__.d(ks,{ChtmlTeXAtom:()=>Wd});var _s={};__webpack_require__.r(_s),__webpack_require__.d(_s,{CommonTextNodeMixin:()=>zd});var Ls={};__webpack_require__.r(Ls),__webpack_require__.d(Ls,{ChtmlTextNode:()=>Vd});var As={};__webpack_require__.r(As),__webpack_require__.d(As,{ChtmlHtmlNode:()=>Xd});var Rs={};__webpack_require__.r(Rs),__webpack_require__.d(Rs,{ChtmlWrappers:()=>Gd});var Ss={};__webpack_require__.r(Ss),__webpack_require__.d(Ss,{ChtmlWrapperFactory:()=>Jd});var Ms={};__webpack_require__.r(Ms),__webpack_require__.d(Ms,{DefaultFont:()=>tu,fontName:()=>Zd});var Is={};__webpack_require__.r(Is),__webpack_require__.d(Is,{CHTML:()=>eu});var Os={};__webpack_require__.r(Os),__webpack_require__.d(Os,{AddFontIds:()=>su});var Ds={};__webpack_require__.r(Ds),__webpack_require__.d(Ds,{MJContextMenu:()=>ep});var Ps={};__webpack_require__.r(Ps),__webpack_require__.d(Ps,{addPreference:()=>vb,engineSetup:()=>xb,fromPreference:()=>Tb,locales:()=>bb,parseDOM:()=>Nb,setupEngine:()=>Eb,toEnriched:()=>yb,toPreference:()=>wb});var Bs={};__webpack_require__.r(Bs),__webpack_require__.d(Bs,{clearspeakMenu:()=>Ib,localeMenu:()=>Db});var Fs={};__webpack_require__.r(Fs),__webpack_require__.d(Fs,{copyToClipboard:()=>Bb,isMac:()=>Pb});var js={};__webpack_require__.r(js),__webpack_require__.d(js,{annotation:()=>Hb,copyAnnotations:()=>jb,showAnnotations:()=>Fb});var Us={};__webpack_require__.r(Us),__webpack_require__.d(Us,{RadioCompare:()=>zb});var Hs={};__webpack_require__.r(Hs),__webpack_require__.d(Hs,{MmlVisitor:()=>Vb});var qs={};__webpack_require__.r(qs),__webpack_require__.d(qs,{Menu:()=>Jb});var Ws={};__webpack_require__.r(Ws),__webpack_require__.d(Ws,{MenuHandler:()=>Yb,MenuMathDocumentMixin:()=>$b,MenuMathItemMixin:()=>Kb});var zs={};__webpack_require__.r(zs),__webpack_require__.d(zs,{EnrichHandler:()=>eE,EnrichedMathDocumentMixin:()=>tE,EnrichedMathItemMixin:()=>Zb,enrichVisitor:()=>Qb});var Vs={};__webpack_require__.r(Vs),__webpack_require__.d(Vs,{InPlace:()=>uE,SemAttr:()=>pE,buildLabel:()=>cE,buildSpeech:()=>hE,honk:()=>dE,ssmlParsing:()=>iE});var Xs={};__webpack_require__.r(Xs),__webpack_require__.d(Xs,{GeneratorPool:()=>mE});var Gs={};__webpack_require__.r(Gs),__webpack_require__.d(Gs,{WorkerHandler:()=>bE});var Js={};__webpack_require__.r(Js),__webpack_require__.d(Js,{SpeechHandler:()=>TE,SpeechMathDocumentMixin:()=>vE,SpeechMathItemMixin:()=>NE});var Ks={};__webpack_require__.r(Ks),__webpack_require__.d(Ks,{AbstractRegion:()=>wE,DummyRegion:()=>CE,HoverRegion:()=>RE,LiveRegion:()=>LE,SpeechRegion:()=>AE,StringRegion:()=>kE,ToolTip:()=>_E});var $s={};__webpack_require__.r($s),__webpack_require__.d($s,{AbstractExplorer:()=>SE});var Ys={};__webpack_require__.r(Ys),__webpack_require__.d(Ys,{SpeechExplorer:()=>FE,hasModifiers:()=>BE,isContainer:()=>PE});var Qs={};__webpack_require__.r(Qs),__webpack_require__.d(Qs,{AbstractMouseExplorer:()=>UE,ContentHoverer:()=>WE,FlameHoverer:()=>zE,Hoverer:()=>HE,ValueHoverer:()=>qE});var Zs={};__webpack_require__.r(Zs),__webpack_require__.d(Zs,{AbstractTreeExplorer:()=>VE,ContrastPicker:()=>JE,FlameColorer:()=>XE,TreeColorer:()=>GE});var ti={};__webpack_require__.r(ti),__webpack_require__.d(ti,{ATTR:()=>YE,getHighlighter:()=>ex});var ei={};__webpack_require__.r(ei),__webpack_require__.d(ei,{ExplorerPool:()=>nx,RegionPool:()=>ix});var si={};__webpack_require__.r(si),__webpack_require__.d(si,{ExplorerHandler:()=>cx,ExplorerMathDocumentMixin:()=>lx,ExplorerMathItemMixin:()=>ax,setA11yOption:()=>dx,setA11yOptions:()=>hx});const ii="4.1.1",ri={},ni="undefined"!=typeof window?window:void 0!==__webpack_require__.g?__webpack_require__.g:"undefined"!=typeof globalThis?globalThis:ri;function oi(t){return"object"==typeof t&&null!==t}function ai(t,e,s=!1){var i;for(const r of Object.keys(e))"__esModule"!==r&&t[r]!==e[r]&&null!==e[r]&&void 0!==e[r]&&(oi(t[r])&&oi(e[r])?ai(t[r],e[r],s||"_"===r):s&&(null===(i=Object.getOwnPropertyDescriptor(t,r))||void 0===i?void 0:i.get)||(t[r]=e[r]));return t}function li(t,e,s){t[e]||(t[e]={}),t=t[e];for(const e of Object.keys(s))oi(t[e])&&oi(s[e])?li(t,e,s[e]):null==t[e]&&null!=s[e]&&(t[e]=s[e]);return t}function ci(t){return ai(hi,t)}void 0!==ni.MathJax&&ni.MathJax.constructor==={}.constructor||(ni.MathJax={}),ni.MathJax.version||(ni.MathJax={version:ii,_:{},config:ni.MathJax});const hi=ni.MathJax;!Object.hasOwn&&hi.config.startup.polyfillHasOwn&&(Object.hasOwn=function(t,e){if(null==t)throw new TypeError("Cannot convert undefined or null to object");return Object.prototype.hasOwnProperty.call(Object(t),e)});const di="undefined"!=typeof window,ui={window:di?window:null,document:di?window.document:null,os:(()=>{if(di&&window.navigator){const t=window.navigator.appVersion,e=[["Win","Windows"],["Mac","MacOS"],["X11","Unix"],["Linux","Unix"]];for(const[s,i]of e)if(t.includes(s))return i;if(window.navigator.userAgent.includes("Android"))return"Unix"}else if("undefined"!=typeof process)return{linux:"Unix",android:"Unix",aix:"Unix",freebsd:"Unix",netbsd:"Unix",openbsd:"Unix",sunos:"Unix",darwin:"MacOS",win32:"Windows",cygwin:"Windows"}[process.platform]||process.platform;return"unknown"})(),path:t=>t};"Windows"===ui.os&&(ui.path=t=>t.match(/^[/\\]?[a-zA-Z]:[/\\]/)?"file://"+t.replace(/\\/g,"/").replace(/^\//,""):t.replace(/^\//,"file:///"));class pi extends Error{constructor(t,e){super(t),this.package=e}}class mi{get canLoad(){return 0===this.dependencyCount&&!this.noLoad&&!this.isLoading&&!this.hasFailed}static loadPromise(t){const e=Ti[t]||{},s=e.extraLoads?Ni.load(...e.extraLoads):Promise.resolve(),i=e.checkReady||(()=>Promise.resolve());return s.then(()=>i())}static resolvePath(t,e=!0){const s={name:t,original:t,addExtension:e};return Ni.pathFilters.execute(s),s.name}static loadAll(){for(const t of this.packages.values())t.canLoad&&t.load()}constructor(t,e=!1){this.isLoaded=!1,this.result={},this.isLoading=!1,this.hasFailed=!1,this.dependents=[],this.dependencies=[],this.dependencyCount=0,this.provided=[],this.name=t,this.noLoad=e,mi.packages.set(t,this),this.promise=this.makePromise(this.makeDependencies())}makeDependencies(){const t=[],e=mi.packages,s=this.noLoad,i=this.name,r=[];Object.hasOwn(Ti.dependencies,i)?r.push(...Ti.dependencies[i]):"core"!==i&&r.push("core");for(const i of r){const r=e.get(i)||new mi(i,s);this.dependencies.includes(r)||(r.addDependent(this,s),this.dependencies.push(r),r.isLoaded||(this.dependencyCount++,t.push(r.promise)))}return t}makePromise(t){let e=new Promise((t,e)=>{this.resolve=t,this.reject=e});const s=Ti[this.name]||{};return s.ready&&(e=e.then(t=>s.ready(this.name))),t.length&&(t.push(e),e=Promise.all(t).then(t=>t.join(", "))),s.failed&&e.catch(t=>s.failed(new pi(t,this.name))),e}load(){if(!this.isLoaded&&!this.isLoading&&!this.noLoad){this.isLoading=!0;const t=mi.resolvePath(this.name);Ti.require?this.loadCustom(t):this.loadScript(t)}}loadCustom(t){try{const e=Ti.require(t);e instanceof Promise?e.then(t=>this.result=t).then(()=>this.checkLoad()).catch(e=>this.failed("Can't load \""+t+'"\n'+e.message.trim())):(this.result=e,this.checkLoad())}catch(t){this.failed(t.message)}}loadScript(t){const e=ui.document.createElement("script");e.src=t,e.charset="UTF-8",e.onload=t=>this.checkLoad(),e.onerror=e=>this.failed("Can't load \""+t+'"'),ui.document.head.appendChild(e)}loaded(){this.isLoaded=!0,this.isLoading=!1;for(const t of this.dependents)t.requirementSatisfied();for(const t of this.provided)t.loaded();this.resolve(this.name)}failed(t){this.hasFailed=!0,this.isLoading=!1,this.reject(new pi(t,this.name))}checkLoad(){mi.loadPromise(this.name).then(()=>this.loaded()).catch(t=>this.failed(t))}requirementSatisfied(){this.dependencyCount&&(this.dependencyCount--,this.canLoad&&this.load())}provides(t=[]){for(const e of t){let t=mi.packages.get(e);t||(Ti.dependencies[e]||(Ti.dependencies[e]=[]),Ti.dependencies[e].push(e),t=new mi(e,!0),t.isLoading=!0),this.provided.push(t)}}addDependent(t,e){this.dependents.push(t),e||this.checkNoLoad()}checkNoLoad(){if(this.noLoad){this.noLoad=!1;for(const t of this.dependencies)t.checkNoLoad()}}}mi.packages=new Map;class fi{constructor(){this.items=[],this.items=[]}[Symbol.iterator](){let t=0;const e=this.items;return{next:()=>({value:e[t++],done:t>e.length})}}add(t,e=fi.DEFAULTPRIORITY){let s=this.items.length;do{s--}while(s>=0&&e=0&&this.items[e].item!==t);return e>=0&&this.items.splice(e,1),this}}fi.DEFAULTPRIORITY=5;class gi extends fi{constructor(t=null){super(),t&&this.addList(t)}addList(t){for(const e of t)Array.isArray(e)?this.add(e[0],e[1]):this.add(e)}execute(...t){for(const e of this){if(!1===e.item(...t))return!1}return!0}asyncExecute(...t){let e=-1;const s=this.items;return new Promise((i,r)=>{!function n(){for(;++er(t));if(!1===o)return void i(!1)}i(!0)}()})}}const bi=hi.config||{};var Ei=function(t,e,s,i){return new(s||(s=Promise))(function(r,n){function o(t){try{l(i.next(t))}catch(t){n(t)}}function a(t){try{l(i.throw(t))}catch(t){n(t)}}function l(t){var e;t.done?r(t.value):(e=t.value,e instanceof s?e:new s(function(t){t(e)})).then(o,a)}l((i=i.apply(t,e||[])).next())})};const xi={source:t=>(Object.hasOwn(Ti.source,t.name)&&(t.name=Ti.source[t.name]),!0),normalize:t=>{const e=t.name;return e.match(/^(?:[a-z]+:\/)?\/|[a-z]:[/\\]|\[/i)||(t.name="[mathjax]/"+e.replace(/^\.\//,"")),!0},prefix:t=>{let e;for(;(e=t.name.match(/^\[([^\]]*)\]/))&&Object.hasOwn(Ti.paths,e[1]);)t.name=Ti.paths[e[1]]+t.name.substring(e[0].length);return!0},addExtension:t=>(t.addExtension&&!t.name.match(/\.[^/]+$/)&&(t.name+=".js"),!0)},yi=hi.version,Ni={versions:new Map,nestedLoads:[],ready(...t){0===t.length&&(t=Array.from(mi.packages.keys()));const e=[];for(const s of t){const t=mi.packages.get(s)||new mi(s,!0);e.push(t.promise)}return Promise.all(e)},load(...t){if(0===t.length)return Promise.resolve([]);let e=[];this.nestedLoads.unshift(e);const s=Promise.resolve().then(()=>Ei(this,void 0,void 0,function*(){const s=[];for(const e of t){let t=mi.packages.get(e);t||(t=new mi(e),t.provides(Ti.provides[e])),t.checkNoLoad(),s.push(t.promise.then(()=>(Ti.versionWarnings&&t.isLoaded&&!Ni.versions.has(mi.resolvePath(e))&&console.warn(`No version information available for component ${e}`),t.result)))}mi.loadAll();const i=yield Promise.all(s);for(;e.length;){const t=Promise.all(e);e=this.nestedLoads[this.nestedLoads.indexOf(e)]=[],yield t}return this.nestedLoads.splice(this.nestedLoads.indexOf(e),1),i}));return this.nestedLoads.slice(1).forEach(t=>t.push(s)),s},preLoaded(...t){for(const e of t){let t=mi.packages.get(e);t||(t=new mi(e,!0),t.provides(Ti.provides[e])),t.loaded()}},addPackageData(t,e){let s=Ti[t];s||(s=Ti[t]={});for(const[t,i]of Object.entries(e))if(Array.isArray(i)){s[t]||(s[t]=[]);const e=new Set([...s[t],...i]);s[t]=[...e]}else s[t]=i},defaultReady(){void 0!==vi.startup&&vi.config.startup.ready()},getRoot(){if(ui.document){const t=ui.document.currentScript||ui.document.getElementById("MathJax-script");if(t&&t instanceof HTMLScriptElement)return t.src.replace(/\/[^/]*$/,"")}return bi?.loader?.paths?.mathjax||bi?.__dirname||"/"},checkVersion(t,e,s){return this.saveVersion(t),!(!Ti.versionWarnings||e===yi)&&(console.warn(`Component ${t} uses ${e} of MathJax; version in use is ${yi}`),!0)},saveVersion(t){Ni.versions.set(mi.resolvePath(t),yi)},pathFilters:new gi};Ni.pathFilters.add(xi.source,0),Ni.pathFilters.add(xi.normalize,10),Ni.pathFilters.add(xi.prefix,20),Ni.pathFilters.add(xi.addExtension,30);const vi=hi;if(void 0===vi.loader){li(vi.config,"loader",{paths:{mathjax:Ni.getRoot(),fonts:ui.window?"https://cdn.jsdelivr.net/npm/@mathjax":"@mathjax"},source:{},dependencies:{},provides:{},load:[],ready:Ni.defaultReady.bind(Ni),failed:t=>console.log(`MathJax(${t.package||"?"}): ${t.message}`),require:null,pathFilters:[],versionWarnings:!0}),ci({loader:Ni});for(const t of vi.config.loader.pathFilters)Array.isArray(t)?Ni.pathFilters.add(t[0],t[1]):Ni.pathFilters.add(t)}const Ti=vi.config.loader,wi={}.constructor;function Ci(t){return"object"==typeof t&&null!==t&&(t.constructor===wi||t.constructor===Ai)}const ki="[+]",_i="[-]",Li={invalidOption:"warn",optionError:(t,e)=>{if("fatal"===Li.invalidOption)throw new Error(t);console.warn("MathJax: "+t)}};class Ai{}function Ri(t){return Object.assign(Object.create(Ai.prototype),t)}function Si(t){return Array.isArray(t)?t:[t]}function Mi(t){return t?Object.keys(t).concat(Object.getOwnPropertySymbols(t)):[]}function Ii(t){const e={};for(const s of Mi(t)){const i=Object.getOwnPropertyDescriptor(t,s),r=i.value;Array.isArray(r)?i.value=Oi([],r,!1):Ci(r)&&(i.value=Ii(r)),i.enumerable&&(e[s]=i)}return Object.defineProperties(t.constructor===Ai?Ri({}):{},e)}function Oi(t,e,s=!0){for(let i of Mi(e)){if(s&&void 0===t[i]&&t.constructor!==Ai){"symbol"==typeof i&&(i=i.toString()),Li.optionError(`Invalid option "${i}" (no default value).`,i);continue}const r=e[i];let n=t[i];if(!Ci(r)||null===n||"object"!=typeof n&&"function"!=typeof n)Array.isArray(r)?(t[i]=[],Oi(t[i],r,!1)):Ci(r)?t[i]=Ii(r):t[i]=r;else{const e=Mi(r);Array.isArray(n)&&(1===e.length&&(e[0]===ki||e[0]===_i)&&Array.isArray(r[e[0]])||2===e.length&&e.sort().join(",")===ki+","+_i&&Array.isArray(r[ki])&&Array.isArray(r[_i]))?(r[_i]&&(n=t[i]=n.filter(t=>r[_i].indexOf(t)<0)),r[ki]&&(t[i]=[...n,...r[ki]])):Oi(n,r,s)}}return t}function Di(t,...e){return e.forEach(e=>Oi(t,e,!1)),t}function Pi(t,...e){return e.forEach(e=>Oi(t,e,!0)),t}function Bi(t,...e){const s={};for(const i of e)Object.hasOwn(t,i)&&(s[i]=t[i]);return s}function Fi(t,e){return Bi(t,...Object.keys(e))}function ji(t,...e){const s=[];for(const i of e){const e={},r={};for(const s of Object.keys(t||{}))(void 0===i[s]?r:e)[s]=t[s];s.push(e),t=r}return s.unshift(t),s}function Ui(t,e,s=null){return Object.hasOwn(e,t)?e[t]:s}var Hi=function(t,e,s,i){return new(s||(s=Promise))(function(r,n){function o(t){try{l(i.next(t))}catch(t){n(t)}}function a(t){try{l(i.throw(t))}catch(t){n(t)}}function l(t){var e;t.done?r(t.value):(e=t.value,e instanceof s?e:new s(function(t){t(e)})).then(o,a)}l((i=i.apply(t,e||[])).next())})};class qi{static toMML(t){return qi.visitor.visitTree(t,this.document)}static registerConstructor(t,e){qi.constructors[t]=e}static useHandler(t,e=!1){zi.handler&&!e||(zi.handler=t)}static useAdaptor(t,e=!1){zi.adaptor&&!e||(zi.adaptor=t)}static useInput(t,e=!1){Vi&&!e||zi.input.push(t)}static useOutput(t,e=!1){zi.output&&!e||(zi.output=t)}static extendHandler(t,e=10){qi.extensions.add(t,e)}static defaultReady(){qi.getComponents(),qi.makeMethods(),qi.pagePromise.then(()=>zi.pageReady()).then(()=>qi.promiseResolve()).catch(t=>qi.promiseReject(t))}static defaultPageReady(){return(zi.loadAllFontFiles&&qi.output.font?qi.output.font.loadDynamicFiles():Promise.resolve()).then(()=>{var t;return null===(t=qi.document.menu)||void 0===t?void 0:t.loadingPromise}).then(zi.typeset&&Wi.typesetPromise?()=>qi.typesetPromise(zi.elements):Promise.resolve()).then(()=>qi.promiseResolve())}static typesetPromise(t){return this.hasTypeset=!0,qi.document.whenReady(()=>Hi(this,void 0,void 0,function*(){qi.document.options.elements=t,qi.document.reset(),yield qi.document.renderPromise()}))}static getComponents(){qi.visitor=new Wi._.core.MmlTree.SerializedMmlVisitor.SerializedMmlVisitor,qi.mathjax=Wi._.mathjax.mathjax,qi.input=qi.getInputJax(),qi.output=qi.getOutputJax(),qi.adaptor=qi.getAdaptor(),qi.handler&&qi.mathjax.handlers.unregister(qi.handler),qi.handler=qi.getHandler(),qi.handler&&(qi.mathjax.handlers.register(qi.handler),qi.document=qi.getDocument())}static makeMethods(){qi.input&&qi.output&&qi.makeTypesetMethods();const t=qi.output?qi.output.name.toLowerCase():"";for(const e of qi.input){const s=e.name.toLowerCase();qi.makeMmlMethods(s,e),qi.makeResetMethod(s,e),qi.output&&qi.makeOutputMethods(s,t,e)}Wi.done=()=>qi.document.done(),Wi.whenReady=t=>qi.document.whenReady(t)}static makeTypesetMethods(){Wi.typeset=(t=null)=>{this.hasTypeset=!0,qi.document.options.elements=t,qi.document.reset(),qi.document.render()},Wi.typesetPromise=(t=null)=>qi.typesetPromise(t),Wi.typesetClear=(t=null)=>{t?qi.document.clearMathItemsWithin(t):qi.document.clear()}}static makeOutputMethods(t,e,s){const i=t+"2"+e;Wi[i]=(t,e={})=>(e=Object.assign(Object.assign({},e),{format:s.name}),qi.document.convert(t,e)),Wi[i+"Promise"]=(t,e={})=>(e=Object.assign(Object.assign({},e),{format:s.name}),qi.document.convertPromise(t,e)),Wi[e+"Stylesheet"]=()=>qi.output.styleSheet(qi.document),"getMetricsFor"in qi.output&&(Wi.getMetricsFor=(t,e)=>qi.output.getMetricsFor(t,e))}static makeMmlMethods(t,e){const s=Wi._.core.MathItem.STATE;Wi[t+"2mml"]=(t,i={})=>(i=Object.assign(Object.assign({},i),{end:s.CONVERT,format:e.name}),qi.toMML(qi.document.convert(t,i))),Wi[t+"2mmlPromise"]=(t,...i)=>Hi(this,[t,...i],void 0,function*(t,i={}){i=Object.assign(Object.assign({},i),{end:s.CONVERT,format:e.name});const r=yield qi.document.convertPromise(t,i);return qi.toMML(r)})}static makeResetMethod(t,e){Wi[t+"Reset"]=(...t)=>e.reset(...t)}static getInputJax(){const t=[];for(const e of zi.input){const s=qi.constructors[e];if(!s)throw Error('Input Jax "'+e+'" is not defined (has it been loaded?)');t[e]=new s(Wi.config[e]),t.push(t[e])}return t}static getOutputJax(){const t=zi.output;if(!t)return null;const e=qi.constructors[t];if(!e)throw Error('Output Jax "'+t+'" is not defined (has it been loaded?)');return new e(Wi.config[t])}static getAdaptor(){const t=zi.adaptor;if(!t||"none"===t)return null;const e=qi.constructors[t];if(!e)throw Error('DOMAdaptor "'+t+'" is not defined (has it been loaded?)');return e(Wi.config[t])}static getHandler(){const t=zi.handler;if(!t||"none"===t||!qi.adaptor)return null;const e=qi.constructors[t];if(!e)throw Error('Handler "'+t+'" is not defined (has it been loaded?)');let s=new e(qi.adaptor,5);for(const t of qi.extensions)s=t.item(s);return s}static getDocument(t=null){return qi.mathjax.document(t||zi.document,Object.assign(Object.assign({},Wi.config.options),{InputJax:qi.input,OutputJax:qi.output}))}}qi.extensions=new fi,qi.constructors={},qi.input=[],qi.output=null,qi.handler=null,qi.adaptor=null,qi.elements=null,qi.document=null,qi.promise=new Promise((t,e)=>{qi.promiseResolve=t,qi.promiseReject=e}),qi.pagePromise=new Promise((t,e)=>{const s=ni.document;if(s&&s.readyState&&"complete"!==s.readyState&&"interactive"!==s.readyState){const e=()=>t();s.defaultView.addEventListener("load",e,!0),s.defaultView.addEventListener("DOMContentLoaded",e,!0)}else t()}),qi.hasTypeset=!1,qi.defaultOptionError=Li.optionError;const Wi=hi;void 0===Wi._.startup&&(li(Wi.config,"startup",{input:[],output:"",handler:null,adaptor:null,document:ui.document||"",elements:null,typeset:!0,ready:qi.defaultReady.bind(qi),pageReady:qi.defaultPageReady.bind(qi),polyfillHasOwn:!0}),ci({startup:qi,options:{}}),Wi.config.startup.invalidOption&&(Li.invalidOption=Wi.config.startup.invalidOption),Wi.config.startup.optionError&&(Li.optionError=Wi.config.startup.optionError));const zi=Wi.config.startup,Vi=0!==zi.input.length;MathJax.loader&&MathJax.loader.checkVersion("startup",ii,"startup"),ci({_:{components:{loader:n,package:s,startup:a}}});Ni.preLoaded("loader","startup"),li(MathJax.config.loader,"dependencies",{"a11y/semantic-enrich":["input/mml","a11y/sre"],"a11y/speech":["a11y/semantic-enrich"],"a11y/complexity":["a11y/semantic-enrich"],"a11y/explorer":["a11y/speech"],"[mml]/mml3":["input/mml"],"[tex]/action":["input/tex-base"],"[tex]/ams":["input/tex-base","[tex]/newcommand"],"[tex]/amscd":["input/tex-base"],"[tex]/autoload":["input/tex-base","[tex]/require"],"[tex]/bbm":["input/tex-base"],"[tex]/bboldx":["input/tex-base","[tex]/textmacros"],"[tex]/bbox":["input/tex-base"],"[tex]/begingroup":["input/tex-base","[tex]/newcommand"],"[tex]/boldsymbol":["input/tex-base"],"[tex]/braket":["input/tex-base"],"[tex]/bussproofs":["input/tex-base"],"[tex]/cancel":["input/tex-base","[tex]/enclose"],"[tex]/cases":["[tex]/empheq"],"[tex]/centernot":["input/tex-base"],"[tex]/color":["input/tex-base"],"[tex]/colortbl":["input/tex-base","[tex]/color"],"[tex]/colorv2":["input/tex-base"],"[tex]/configmacros":["input/tex-base","[tex]/newcommand"],"[tex]/dsfont":["input/tex-base"],"[tex]/empheq":["input/tex-base","[tex]/ams"],"[tex]/enclose":["input/tex-base"],"[tex]/extpfeil":["input/tex-base","[tex]/newcommand","[tex]/ams"],"[tex]/gensymb":["input/tex-base"],"[tex]/html":["input/tex-base"],"[tex]/mathtools":["input/tex-base","[tex]/newcommand","[tex]/ams","[tex]/boldsymbol"],"[tex]/mhchem":["input/tex-base","[tex]/ams"],"[tex]/newcommand":["input/tex-base"],"[tex]/noerrors":["input/tex-base"],"[tex]/noundefined":["input/tex-base"],"[tex]/physics":["input/tex-base"],"[tex]/require":["input/tex-base"],"[tex]/setoptions":["input/tex-base"],"[tex]/tagformat":["input/tex-base"],"[tex]/texhtml":["input/tex-base"],"[tex]/textcomp":["input/tex-base","[tex]/textmacros"],"[tex]/textmacros":["input/tex-base"],"[tex]/unicode":["input/tex-base"],"[tex]/units":["input/tex-base"],"[tex]/upgreek":["input/tex-base"],"[tex]/verb":["input/tex-base"],"ui/menu":["a11y/sre"]}),li(MathJax.config.loader,"paths",{tex:"[mathjax]/input/tex/extensions",mml:"[mathjax]/input/mml/extensions",sre:"[mathjax]/sre",mathmaps:"[sre]/mathmaps"}),li(MathJax.config.loader,"provides",{startup:["loader"],"input/tex":["input/tex-base","[tex]/ams","[tex]/newcommand","[tex]/textmacros","[tex]/noundefined","[tex]/require","[tex]/autoload","[tex]/configmacros"]}),li(MathJax.config.loader,"source",{"[tex]/amsCd":"[tex]/amscd","[tex]/colorV2":"[tex]/colorv2","[tex]/configMacros":"[tex]/configmacros","[tex]/tagFormat":"[tex]/tagformat"});class Xi{constructor(t=null){this.canMeasureNodes=!0,this.document=t}node(t,e={},s=[],i){const r=this.create(t,i);this.setAttributes(r,e);for(const t of s)this.append(r,t);return r}setProperty(t,e,s){t[e]=s}getProperty(t,e){return t[e]}setAttributes(t,e){if(e.style&&"string"!=typeof e.style)for(const s of Object.keys(e.style))this.setStyle(t,s.replace(/-([a-z])/g,(t,e)=>e.toUpperCase()),e.style[s]);if(e.properties)for(const s of Object.keys(e.properties))t[s]=e.properties[s];for(const s of Object.keys(e))"style"===s&&"string"!=typeof e.style||"properties"===s||this.setAttribute(t,s,e[s])}replace(t,e){return this.insert(t,e),this.remove(e),e}childNode(t,e){return this.childNodes(t)[e]}allClasses(t){const e=this.getAttribute(t,"class");return e?e.replace(/  +/g," ").replace(/^ /,"").replace(/ $/,"").split(/ /):[]}cssText(t){return"style"===this.kind(t)?this.textContent(t):""}}var Gi=function(t,e,s,i){return new(s||(s=Promise))(function(r,n){function o(t){try{l(i.next(t))}catch(t){n(t)}}function a(t){try{l(i.throw(t))}catch(t){n(t)}}function l(t){var e;t.done?r(t.value):(e=t.value,e instanceof s?e:new s(function(t){t(e)})).then(o,a)}l((i=i.apply(t,e||[])).next())})};class Ji extends Xi{constructor(t){super(t.document),this.canMeasureNodes=!0,this.window=t,this.parser=new t.DOMParser}parse(t,e="text/html"){return this.parser.parseFromString(t,e)}create(t,e){return e?this.document.createElementNS(e,t):this.document.createElement(t)}text(t){return this.document.createTextNode(t)}head(t=this.document){return t.head||t}body(t=this.document){return t.body||t}root(t=this.document){return t.documentElement||t}doctype(t=this.document){return t.doctype?``:""}tags(t,e,s=null){const i=s?t.getElementsByTagNameNS(s,e):t.getElementsByTagName(e);return Array.from(i)}getElements(t,e){let s=[];for(const e of t)"string"==typeof e?s=s.concat(Array.from(this.document.querySelectorAll(e))):Array.isArray(e)||e instanceof this.window.NodeList||e instanceof this.window.HTMLCollection?s=s.concat(Array.from(e)):s.push(e);return s}getElement(t,e=this.document){return e.querySelector(t)}contains(t,e){return t.contains(e)}parent(t){return t.parentNode}append(t,e){return t.appendChild(e)}insert(t,e){return this.parent(e).insertBefore(t,e)}remove(t){return this.parent(t).removeChild(t)}replace(t,e){return this.parent(e).replaceChild(t,e)}clone(t,e=!0){return t.cloneNode(e)}split(t,e){return t.splitText(e)}next(t){return t.nextSibling}previous(t){return t.previousSibling}firstChild(t){return t.firstChild}lastChild(t){return t.lastChild}childNodes(t){return Array.from(t.childNodes)}childNode(t,e){return t.childNodes[e]}kind(t){const e=t.nodeType;return 1===e||3===e||8===e?t.nodeName.toLowerCase():""}value(t){return t.nodeValue||""}textContent(t){return t.textContent}innerHTML(t){return t.innerHTML}outerHTML(t){return t.outerHTML}serializeXML(t){return(new this.window.XMLSerializer).serializeToString(t)}setAttribute(t,e,s,i=null){return i?(e=i.replace(/.*\//,"")+":"+e.replace(/^.*:/,""),t.setAttributeNS(i,e,s)):("style"===e&&(s=s.replace(/\n/g," ")),t.setAttribute(e,s))}getAttribute(t,e){return t.getAttribute(e)}removeAttribute(t,e){return t.removeAttribute(e)}hasAttribute(t,e){return t.hasAttribute(e)}allAttributes(t){return Array.from(t.attributes).map(t=>({name:t.name,value:t.value}))}addClass(t,e){t.classList?t.classList.add(e):t.className=(t.className+" "+e).trim()}removeClass(t,e){t.classList?t.classList.remove(e):t.className=t.className.split(/ /).filter(t=>t!==e).join(" ")}hasClass(t,e){return t.classList?t.classList.contains(e):t.className.split(/ /).includes(e)}setStyle(t,e,s){t.style[e]=String(s).replace(/\n/g," ")}getStyle(t,e){return t.style[e]}allStyles(t){return t.style.cssText}insertRules(t,e){for(const s of e)try{t.sheet.insertRule(s,t.sheet.cssRules.length)}catch(t){console.warn(`MathJax: can't insert css rule '${s}': ${t.message}`)}}cssText(t){return"style"!==this.kind(t)?"":Array.from(t.sheet.cssRules).map(t=>t.cssText).join("\n")}fontSize(t){const e=this.window.getComputedStyle(t);return parseFloat(e.fontSize||String(this.constructor.DEFAULT_FONT_SIZE))}fontFamily(t){return this.window.getComputedStyle(t).fontFamily||""}nodeSize(t,e=1,s=!1){if(s&&t.getBBox){const{width:s,height:i}=t.getBBox();return[s/e,i/e]}return[t.offsetWidth/e,t.offsetHeight/e]}nodeBBox(t){const{left:e,right:s,top:i,bottom:r}=t.getBoundingClientRect();return{left:e,right:s,top:i,bottom:r}}createWorker(t,e){return Gi(this,void 0,void 0,function*(){const{path:s,maps:i,worker:r}=e,n=`${s}/${r}`,o=`\n      self.maps = '${Ki(i)}';\n      importScripts('${Ki(n)}');\n    `,a=URL.createObjectURL(new Blob([o],{type:"text/javascript"})),l=new Worker(a);return l.onmessage=t,URL.revokeObjectURL(a),l})}}function Ki(t){return[...t].map(t=>("\\"===t||"'"===t?t="\\"+t:(t<" "||t>"~")&&(t=`\\u{${t.codePointAt(0).toString(16)}}`),t)).join("")}function $i(){return new Ji(window)}Ji.DEFAULT_FONT_SIZE=16;class Yi{constructor(t){const e=this.constructor;this.options=Pi(Di({},e.OPTIONS),t)}}Yi.OPTIONS={};class Qi{constructor(t={}){this.adaptor=null,this.mmlFactory=null;const e=this.constructor;this.options=Pi(Di({},e.OPTIONS),t),this.preFilters=new gi(this.options.preFilters),this.postFilters=new gi(this.options.postFilters)}get name(){return this.constructor.NAME}setAdaptor(t){this.adaptor=t}setMmlFactory(t){this.mmlFactory=t}initialize(){}reset(...t){}get processStrings(){return!0}findMath(t,e){return[]}executeFilters(t,e,s,i){const r={math:e,document:s,data:i};return t.execute(r),r.data}}Qi.NAME="generic",Qi.OPTIONS={preFilters:[],postFilters:[]};class Zi{constructor(t={}){this.adaptor=null;const e=this.constructor;this.options=Pi(Di({},e.OPTIONS),t),this.preFilters=new gi(this.options.preFilters),this.postFilters=new gi(this.options.postFilters)}get name(){return this.constructor.NAME}setAdaptor(t){this.adaptor=t}initialize(){}reset(...t){}getMetrics(t){}styleSheet(t){return null}pageElements(t){return null}executeFilters(t,e,s,i){const r={math:e,document:s,data:i};return t.execute(r),r.data}}Zi.NAME="generic",Zi.OPTIONS={preFilters:[],postFilters:[]};const tr=Symbol();class er{constructor(t=null){this.next=null,this.prev=null,this.data=t}}class sr{constructor(...t){this.list=new er(tr),this.list.next=this.list.prev=this.list,this.push(...t)}isBefore(t,e){return t1;){const s=e.shift(),i=e.shift();s.merge(i,t),e.push(s)}return e.length&&(this.list=e[0].list),this}merge(t,e=null){null===e&&(e=this.isBefore.bind(this));let s=this.list.next,i=t.list.next;for(;s.data!==tr&&i.data!==tr;)e(i.data,s.data)?([i.prev.next,s.prev.next]=[s,i],[i.prev,s.prev]=[s.prev,i.prev],[this.list.prev.next,t.list.prev.next]=[t.list,this.list],[this.list.prev,t.list.prev]=[t.list.prev,this.list.prev],[s,i]=[i.next,s]):s=s.next;return i.data!==tr&&(this.list.prev.next=t.list.next,t.list.next.prev=this.list.prev,t.list.prev.next=this.list,this.list.prev=t.list.prev,t.list.next=t.list.prev=t.list),this}}class ir extends sr{isBefore(t,e){return t.start.i=e&&this.state(e-1),t.renderActions.renderMath(this,t,e)}convert(t,e=or.LAST){t.renderActions.renderConvert(this,t,e)}compile(t){this.state()=or.INSERTED&&this.removeFromDocument(e),t=or.TYPESET&&(this.outputData={}),t=or.COMPILED&&(this.inputData={}),this._state=t),this._state}reset(t=!1){this.state(or.UNPROCESSED,t)}clear(){}}const or={UNPROCESSED:0,FINDMATH:10,COMPILED:20,CONVERT:100,METRICS:110,RERENDER:125,TYPESET:150,INSERTED:200,LAST:1e4};function ar(t,e){if(t in or)throw Error("State "+t+" already exists");or[t]=e}class lr{constructor(t=null){this.defaultKind="unknown",this.nodeMap=new Map,this.node={},null===t&&(t=this.constructor.defaultNodes);for(const e of Object.keys(t))this.setNodeClass(e,t[e])}create(t,...e){return(this.node[t]||this.node[this.defaultKind])(...e)}setNodeClass(t,e){this.nodeMap.set(t,e);const s=this.nodeMap.get(t);this.node[t]=(...t)=>new s(this,...t)}getNodeClass(t){return this.nodeMap.get(t)}deleteNodeClass(t){this.nodeMap.delete(t),delete this.node[t]}nodeIsKind(t,e){return t instanceof this.getNodeClass(e)}getKinds(){return Array.from(this.nodeMap.keys())}}lr.defaultNodes={};class cr extends lr{create(t,e={},s=[]){return this.node[t](e,s)}}const hr="_inherit_";class dr{constructor(t,e){this.global=e,this.defaults=Object.create(e),this.inherited=Object.create(this.defaults),this.attributes=Object.create(this.inherited),Object.assign(this.defaults,t)}set(t,e){this.attributes[t]=e}setList(t){Object.assign(this.attributes,t)}unset(t){delete this.attributes[t]}get(t){let e=this.attributes[t];return e===hr&&(e=this.global[t]),e}getExplicit(t){return this.hasExplicit(t)?this.attributes[t]:void 0}hasExplicit(t){return Object.hasOwn(this.attributes,t)}hasOneOf(t){for(const e of t)if(this.hasExplicit(e))return!0;return!1}getList(...t){const e={};for(const s of t)e[s]=this.get(s);return e}setInherited(t,e){this.inherited[t]=e}getInherited(t){return this.inherited[t]}getDefault(t){return this.defaults[t]}isSet(t){return Object.hasOwn(this.attributes,t)||Object.hasOwn(this.inherited,t)}hasDefault(t){return t in this.defaults}getExplicitNames(){return Object.keys(this.attributes)}getInheritedNames(){return Object.keys(this.inherited)}getDefaultNames(){return Object.keys(this.defaults)}getGlobalNames(){return Object.keys(this.global)}getAllAttributes(){return this.attributes}getAllInherited(){return this.inherited}getAllDefaults(){return this.defaults}getAllGlobals(){return this.global}}class ur{constructor(t,e={},s=[]){this.factory=t,this.parent=null,this.properties={},this.childNodes=[];for(const t of Object.keys(e))this.setProperty(t,e[t]);s.length&&this.setChildren(s)}get kind(){return"unknown"}setProperty(t,e){this.properties[t]=e}getProperty(t){return this.properties[t]}getPropertyNames(){return Object.keys(this.properties)}getAllProperties(){return this.properties}removeProperty(...t){for(const e of t)delete this.properties[e]}isKind(t){return this.factory.nodeIsKind(this,t)}setChildren(t){this.childNodes=[];for(const e of t)this.appendChild(e)}appendChild(t){return this.childNodes.push(t),t.parent=this,t}replaceChild(t,e){const s=this.childIndex(e);return null!==s&&(this.childNodes[s]=t,t.parent=this,e.parent===this&&(e.parent=null)),t}removeChild(t){const e=this.childIndex(t);return null!==e&&(this.childNodes.splice(e,1),t.parent=null),t}childIndex(t){const e=this.childNodes.indexOf(t);return-1===e?null:e}copy(){const t=this.factory.create(this.kind);t.properties=Object.assign({},this.properties);for(const e of this.childNodes||[])e&&t.appendChild(e.copy());return t}findNodes(t){const e=[];return this.walkTree(s=>{s.isKind(t)&&e.push(s)}),e}walkTree(t,e){t(this,e);for(const s of this.childNodes)s&&s.walkTree(t,e);return e}toString(){return this.kind+"("+this.childNodes.join(",")+")"}}class pr extends ur{setChildren(t){}appendChild(t){return t}replaceChild(t,e){return e}childIndex(t){return null}walkTree(t,e){return t(this,e),e}toString(){return this.kind}}const mr={ORD:0,OP:1,BIN:2,REL:3,OPEN:4,CLOSE:5,PUNCT:6,INNER:7,NONE:-1},fr=["ORD","OP","BIN","REL","OPEN","CLOSE","PUNCT","INNER"],gr=["","thinmathspace","mediummathspace","thickmathspace"],br=[[0,-1,2,3,0,0,0,1],[-1,-1,0,3,0,0,0,1],[2,2,0,0,2,0,0,2],[3,3,0,0,3,0,0,3],[0,0,0,0,0,0,0,0],[0,-1,2,3,0,0,0,1],[1,1,0,1,1,1,1,1],[1,-1,2,3,1,0,1,1]],Er=new Set(["normal","bold","italic","bold-italic","double-struck","fraktur","bold-fraktur","script","bold-script","sans-serif","bold-sans-serif","sans-serif-italic","sans-serif-bold-italic","monospace","inital","tailed","looped","stretched"]),xr=["indentalign","indentalignfirst","indentshift","indentshiftfirst"];class yr extends ur{constructor(t,e={},s=[]){super(t),this.prevClass=null,this.prevLevel=null,this.texclass=null,this.arity<0&&(this.childNodes=[t.create("inferredMrow")],this.childNodes[0].parent=this),this.setChildren(s),this.attributes=new dr(t.getNodeClass(this.kind).defaults,t.getNodeClass("math").defaults),this.attributes.setList(e)}copy(t=!1){const e=this.factory.create(this.kind);if(e.properties=Object.assign({},this.properties),this.attributes){const s=this.attributes.getAllAttributes();for(const i of Object.keys(s))("id"!==i||t)&&e.attributes.set(i,s[i])}if(this.childNodes&&this.childNodes.length){let t=this.childNodes;1===t.length&&t[0].isInferred&&(t=t[0].childNodes);for(const s of t)s?e.appendChild(s.copy()):e.childNodes.push(null)}return e}get texClass(){return this.texclass}set texClass(t){this.texclass=t}get isToken(){return!1}get isEmbellished(){return!1}get isSpacelike(){return!1}get linebreakContainer(){return!1}get linebreakAlign(){return"data-align"}get isEmpty(){for(const t of this.childNodes)if(!t.isEmpty)return!1;return!0}get arity(){return 1/0}get isInferred(){return!1}get Parent(){let t=this.parent;for(;t&&t.notParent;)t=t.Parent;return t}get notParent(){return!1}setChildren(t){return this.arity<0?this.childNodes[0].setChildren(t):super.setChildren(t)}appendChild(t){if(this.arity<0)return this.childNodes[0].appendChild(t),t;if(t.isInferred){if(this.arity===1/0)return t.childNodes.forEach(t=>super.appendChild(t)),t;const e=t;(t=this.factory.create("mrow")).setChildren(e.childNodes),t.attributes=e.attributes;for(const s of e.getPropertyNames())t.setProperty(s,e.getProperty(s))}return super.appendChild(t)}replaceChild(t,e){return this.arity<0?(this.childNodes[0].replaceChild(t,e),t):super.replaceChild(t,e)}core(){return this}coreMO(){return this}coreIndex(){return 0}childPosition(){let t=null,e=this.parent;for(;e&&e.notParent;)t=e,e=e.parent;if(t=t||this,e){let s=0;for(const i of e.childNodes){if(i===t)return s;s++}}return null}setTeXclass(t){return this.getPrevClass(t),null!=this.texClass?this:t}updateTeXclass(t){t&&(this.prevClass=t.prevClass,this.prevLevel=t.prevLevel,t.prevClass=t.prevLevel=null,this.texClass=t.texClass)}getPrevClass(t){t&&(this.prevClass=t.texClass,this.prevLevel=t.attributes.get("scriptlevel"))}texSpacing(){const t=null!=this.prevClass?this.prevClass:mr.NONE,e=this.texClass||mr.ORD;if(t===mr.NONE||e===mr.NONE)return"";const s=br[t][e];return(this.prevLevel>0||this.attributes.get("scriptlevel")>0)&&s>=0?"":gr[Math.abs(s)]}hasSpacingAttributes(){return this.isEmbellished&&this.coreMO().hasSpacingAttributes()}setInheritedAttributes(t={},e=!1,s=0,i=!1){var r,n,o;const a=this.attributes.getAllDefaults();for(const e of Object.keys(t)){if(Object.hasOwn(a,e)||Object.hasOwn(yr.alwaysInherit,e)){const[s,i]=t[e];(null===(n=null===(r=yr.noInherit[s])||void 0===r?void 0:r[this.kind])||void 0===n?void 0:n[e])||this.attributes.setInherited(e,i)}(null===(o=yr.stopInherit[this.kind])||void 0===o?void 0:o[e])&&delete(t=Object.assign({},t))[e]}void 0===this.attributes.getExplicit("displaystyle")&&this.attributes.setInherited("displaystyle",e);void 0===this.attributes.getExplicit("scriptlevel")&&this.attributes.setInherited("scriptlevel",s),i&&this.setProperty("texprimestyle",i);const l=this.arity;if(l>=0&&l!==1/0&&(1===l&&0===this.childNodes.length||1!==l&&this.childNodes.length!==l))if(l=0&&e!==1/0&&(1===e&&0===this.childNodes.length||1!==e&&this.childNodes.length!==e)&&this.mError('Wrong number of children for "'+this.kind+'" node',t,!0),this.verifyChildren(t)}verifyAttributes(t){if(t.checkAttributes){const e=this.attributes,s=[];for(const t of e.getExplicitNames())"data-"===t.substring(0,5)||void 0!==e.getDefault(t)||t.match(/^(?:class|style|id|(?:xlink:)?href)$/)||s.push(t);s.length&&this.mError("Unknown attributes for "+this.kind+" node: "+s.join(", "),t)}if(t.checkMathvariants){const e=this.attributes.getExplicit("mathvariant");!e||Er.has(e)||this.getProperty("ignore-variant")||this.mError(`Invalid mathvariant: ${e}`,t,!0)}}verifyChildren(t){for(const e of this.childNodes)e.verifyTree(t)}mError(t,e,s=!1){if(this.parent&&this.parent.isKind("merror"))return null;const i=this.factory.create("merror");if(i.attributes.set("data-mjx-message",t),e.fullErrors||s){const s=this.factory.create("mtext"),r=this.factory.create("text");r.setText(e.fullErrors?t:this.kind),s.appendChild(r),i.appendChild(s),this.parent.replaceChild(i,this),e.fullErrors||i.attributes.set("title",t)}else this.parent.replaceChild(i,this),i.appendChild(this);return i}}yr.defaults={mathbackground:hr,mathcolor:hr,mathsize:hr,dir:hr},yr.noInherit={mstyle:{mpadded:{width:!0,height:!0,depth:!0,lspace:!0,voffset:!0},mtable:{width:!0,height:!0,depth:!0,align:!0}},maligngroup:{mrow:{groupalign:!0},mtable:{groupalign:!0}},mtr:{msqrt:{"data-vertical-align":!0},mroot:{"data-vertical-align":!0}},mlabeledtr:{msqrt:{"data-vertical-align":!0},mroot:{"data-vertical-align":!0}}},yr.stopInherit={mtd:{columnalign:!0,rowalign:!0,groupalign:!0}},yr.alwaysInherit={scriptminsize:!0,scriptsizemultiplier:!0,infixlinebreakstyle:!0},yr.verifyDefaults={checkArity:!0,checkAttributes:!1,checkMathvariants:!0,fullErrors:!1,fixMmultiscripts:!0,fixMtables:!0};class Nr extends yr{get isToken(){return!0}get isEmpty(){for(const t of this.childNodes)if(!(t instanceof Cr)||t.getText().length)return!1;return!0}getText(){let t="";for(const e of this.childNodes)e instanceof Cr?t+=e.getText():"textContent"in e&&(t+=e.textContent());return t}setChildInheritedAttributes(t,e,s,i){for(const r of this.childNodes)r instanceof yr&&r.setInheritedAttributes(t,e,s,i)}walkTree(t,e){t(this,e);for(const s of this.childNodes)s instanceof yr&&s.walkTree(t,e);return e}}Nr.defaults=Object.assign(Object.assign({},yr.defaults),{mathvariant:"normal",mathsize:hr});class vr extends yr{get isSpacelike(){return this.childNodes[0].isSpacelike}get isEmbellished(){return this.childNodes[0].isEmbellished}get arity(){return-1}core(){return this.childNodes[0]}coreMO(){return this.childNodes[0].coreMO()}setTeXclass(t){return t=this.childNodes[0].setTeXclass(t),this.updateTeXclass(this.childNodes[0]),t}}vr.defaults=yr.defaults;class Tr extends yr{get isEmbellished(){return this.childNodes[0].isEmbellished}core(){return this.childNodes[0]}coreMO(){return this.childNodes[0].coreMO()}setTeXclass(t){this.getPrevClass(t),this.texClass=mr.ORD;const e=this.childNodes[0];let s=null;e&&(this.isEmbellished||e.isKind("mi")?(s=e.setTeXclass(t),this.updateTeXclass(this.core())):(e.setTeXclass(null),e.isKind("TeXAtom")&&(this.texClass=e.texClass)));for(const t of this.childNodes.slice(1))t&&t.setTeXclass(null);return s||this}}Tr.defaults=yr.defaults;class wr extends pr{get isToken(){return!1}get isEmpty(){return!0}get isEmbellished(){return!1}get isSpacelike(){return!1}get linebreakContainer(){return!1}get linebreakAlign(){return""}get arity(){return 0}get isInferred(){return!1}get notParent(){return!1}get Parent(){return this.parent}get texClass(){return mr.NONE}get prevClass(){return mr.NONE}get prevLevel(){return 0}hasSpacingAttributes(){return!1}get attributes(){return null}core(){return this}coreMO(){return this}coreIndex(){return 0}childPosition(){return 0}setTeXclass(t){return t}texSpacing(){return""}setInheritedAttributes(t,e,s,i){}inheritAttributesFrom(t){}verifyTree(t){}mError(t,e,s=!1){return null}}class Cr extends wr{constructor(){super(...arguments),this.text=""}get kind(){return"text"}getText(){return this.text}setText(t){return this.text=t,this}copy(){return this.factory.create(this.kind).setText(this.getText())}toString(){return this.text}}class kr extends wr{constructor(){super(...arguments),this.xml=null,this.adaptor=null}get kind(){return"XML"}getXML(){return this.xml}setXML(t,e=null){return this.xml=t,this.adaptor=e,this}getSerializedXML(){return this.adaptor.serializeXML(this.xml)}copy(){return this.factory.create(this.kind).setXML(this.adaptor.clone(this.xml))}toString(){return"XML data"}}class _r extends vr{get kind(){return"math"}get linebreakContainer(){return!0}get linebreakAlign(){return""}setChildInheritedAttributes(t,e,s,i){"display"===this.attributes.get("mode")&&this.attributes.setInherited("display","block"),t=this.addInheritedAttributes(t,this.attributes.getAllAttributes()),e=!!this.attributes.get("displaystyle")||!this.attributes.get("displaystyle")&&"block"===this.attributes.get("display"),this.attributes.setInherited("displaystyle",e),s=this.attributes.get("scriptlevel")||this.constructor.defaults.scriptlevel,super.setChildInheritedAttributes(t,e,s,i)}verifyTree(t=null){super.verifyTree(t),this.parent&&this.mError("Improper nesting of math tags",t,!0)}}_r.defaults=Object.assign(Object.assign({},vr.defaults),{mathvariant:"normal",mathsize:"normal",mathcolor:"",mathbackground:"transparent",dir:"ltr",scriptlevel:0,displaystyle:!1,display:"inline",maxwidth:"",overflow:"linebreak",altimg:"","altimg-width":"","altimg-height":"","altimg-valign":"",alttext:"",cdgroup:"",scriptsizemultiplier:1/Math.sqrt(2),scriptminsize:".4em",infixlinebreakstyle:"before",lineleading:"100%",linebreakmultchar:"\u2062",indentshift:"auto",indentalign:"auto",indenttarget:"",indentalignfirst:"indentalign",indentshiftfirst:"indentshift",indentalignlast:"indentalign",indentshiftlast:"indentshift"});class Lr extends Nr{constructor(){super(...arguments),this.texclass=mr.ORD}get kind(){return"mi"}setInheritedAttributes(t={},e=!1,s=0,i=!1){super.setInheritedAttributes(t,e,s,i);this.getText().match(Lr.singleCharacter)&&!t.mathvariant&&this.attributes.setInherited("mathvariant","italic")}setTeXclass(t){this.getPrevClass(t);const e=this.getText();return e.length>1&&e.match(Lr.operatorName)&&"normal"===this.attributes.get("mathvariant")&&void 0===this.getProperty("autoOP")&&void 0===this.getProperty("texClass")&&(this.texClass=mr.OP,this.setProperty("autoOP",!0)),this}}Lr.defaults=Object.assign({},Nr.defaults),Lr.operatorName=/^[a-z][a-z0-9]*$/i,Lr.singleCharacter=/^[\uD800-\uDBFF]?.[\u0300-\u036F\u1AB0-\u1ABE\u1DC0-\u1DFF\u20D0-\u20EF]*$/;class Ar extends Nr{constructor(){super(...arguments),this.texclass=mr.ORD}get kind(){return"mn"}}function Rr(t,e,s=mr.BIN,i=null){return[t,e,s,i]}Ar.defaults=Object.assign({},Nr.defaults);const Sr={REL:Rr(5,5,mr.REL),WIDEREL:Rr(5,5,mr.REL,{accent:!0,stretchy:!0}),BIN4:Rr(4,4,mr.BIN),RELSTRETCH:Rr(5,5,mr.REL,{stretchy:!0}),ORD:Rr(0,0,mr.ORD),BIN3:Rr(3,3,mr.BIN),OPEN:Rr(0,0,mr.OPEN,{fence:!0,stretchy:!0,symmetric:!0}),CLOSE:Rr(0,0,mr.CLOSE,{fence:!0,stretchy:!0,symmetric:!0}),INTEGRAL:Rr(3,3,mr.OP,{largeop:!0,symmetric:!0}),ACCENT:Rr(0,0,mr.ORD,{accent:!0}),WIDEACCENT:Rr(0,0,mr.ORD,{accent:!0,stretchy:!0}),OP:Rr(3,3,mr.OP,{largeop:!0,movablelimits:!0,symmetric:!0}),RELACCENT:Rr(5,5,mr.REL,{accent:!0}),BIN0:Rr(0,0,mr.BIN),BIN5:Rr(5,5,mr.BIN),FENCE:Rr(0,0,mr.ORD,{fence:!0,stretchy:!0,symmetric:!0}),INNER:Rr(1,1,mr.INNER),ORD30:Rr(3,0,mr.ORD),NONE:Rr(0,0,mr.NONE),ORDSTRETCH0:Rr(0,0,mr.ORD,{stretchy:!0}),BINSTRETCH0:Rr(0,0,mr.BIN,{stretchy:!0}),RELSTRETCH0:Rr(0,0,mr.REL,{stretchy:!0}),CLOSE0:Rr(0,0,mr.CLOSE,{fence:!0}),ORD3:Rr(3,3,mr.ORD),PUNCT03:Rr(0,3,mr.PUNCT,{linebreakstyle:"after"}),OPEN0:Rr(0,0,mr.OPEN,{fence:!0}),STRETCH4:Rr(4,4,mr.BIN,{stretchy:!0})},Mr=[[32,127,mr.REL,"mo"],[160,191,mr.ORD,"mo"],[192,591,mr.ORD,"mi"],[688,879,mr.ORD,"mo"],[880,6688,mr.ORD,"mi"],[6832,6911,mr.ORD,"mo"],[6912,7615,mr.ORD,"mi"],[7616,7679,mr.ORD,"mo"],[7680,8191,mr.ORD,"mi"],[8192,8303,mr.ORD,"mo"],[8304,8351,mr.ORD,"mo"],[8448,8527,mr.ORD,"mi"],[8528,8591,mr.ORD,"mn"],[8592,8703,mr.REL,"mo"],[8704,8959,mr.BIN,"mo"],[8960,9215,mr.ORD,"mo"],[9312,9471,mr.ORD,"mn"],[9472,10223,mr.ORD,"mo"],[10224,10239,mr.REL,"mo"],[10240,10495,mr.ORD,"mtext"],[10496,10623,mr.REL,"mo"],[10624,10751,mr.ORD,"mo"],[10752,11007,mr.BIN,"mo"],[11008,11055,mr.ORD,"mo"],[11056,11087,mr.REL,"mo"],[11088,11263,mr.ORD,"mo"],[11264,11744,mr.ORD,"mi"],[11776,11903,mr.ORD,"mo"],[11904,12255,mr.ORD,"mi","normal"],[12272,12351,mr.ORD,"mo"],[12352,42143,mr.ORD,"mi","normal"],[42192,43055,mr.ORD,"mi"],[43056,43071,mr.ORD,"mn"],[43072,55295,mr.ORD,"mi"],[63744,64255,mr.ORD,"mi","normal"],[64256,65023,mr.ORD,"mi"],[65024,65135,mr.ORD,"mo"],[65136,65791,mr.ORD,"mi"],[65792,65935,mr.ORD,"mn"],[65936,74751,mr.ORD,"mi","normal"],[74752,74879,mr.ORD,"mn"],[74880,113823,mr.ORD,"mi","normal"],[113824,119391,mr.ORD,"mo"],[119648,119679,mr.ORD,"mn"],[119808,120781,mr.ORD,"mi"],[120782,120831,mr.ORD,"mn"],[122624,129023,mr.ORD,"mo"],[129024,129279,mr.REL,"mo"],[129280,129535,mr.ORD,"mo"],[131072,195103,mr.ORD,"mi","normal"]];function Ir(t){const e=Dr.infix[t]||Dr.prefix[t]||Dr.postfix[t];if(e)return[0,0,e[2],"mo"];const s=t.codePointAt(0);for(const t of Mr)if(s<=t[1]){if(s>=t[0])return t;break}return[0,0,mr.REL,"mo"]}const Or=[[0,0],[1,2],[3,3],[4,4],[0,0],[0,0],[0,3],[1,1]],Dr={prefix:{"!":Sr.ORD,"(":Sr.OPEN,"+":Sr.BIN0,"-":Sr.BIN0,"[":Sr.OPEN,"{":Sr.OPEN,"|":Sr.OPEN,"||":Sr.BIN0,"\xac":Sr.ORD,"\xb1":Sr.BIN0,"\u2016":Sr.FENCE,"\u2018":Sr.OPEN0,"\u201c":Sr.OPEN0,\u2145:Sr.ORD30,\u2146:Sr.ORD30,"\u2200":Sr.ORD,"\u2201":Sr.ORD,"\u2202":Sr.ORD30,"\u2203":Sr.ORD,"\u2204":Sr.ORD,"\u2207":Sr.ORD,"\u220f":Sr.OP,"\u2210":Sr.OP,"\u2211":Sr.OP,"\u2212":Sr.BIN0,"\u2213":Sr.BIN0,"\u221a":[3,0,mr.ORD,{stretchy:!0}],"\u221b":Sr.ORD30,"\u221c":Sr.ORD30,"\u221f":Sr.ORD,"\u2220":Sr.ORD,"\u2221":Sr.ORD,"\u2222":Sr.ORD,"\u222b":Sr.INTEGRAL,"\u222c":Sr.INTEGRAL,"\u222d":Sr.INTEGRAL,"\u222e":Sr.INTEGRAL,"\u222f":Sr.INTEGRAL,"\u2230":Sr.INTEGRAL,"\u2231":Sr.INTEGRAL,"\u2232":Sr.INTEGRAL,"\u2233":Sr.INTEGRAL,"\u2234":Sr.REL,"\u2235":Sr.REL,"\u223c":[0,0,mr.REL,{}],"\u22be":Sr.ORD,"\u22bf":Sr.ORD,"\u22c0":Sr.OP,"\u22c1":Sr.OP,"\u22c2":Sr.OP,"\u22c3":Sr.OP,"\u2308":Sr.OPEN,"\u230a":Sr.OPEN,"\u2310":Sr.ORD,"\u2319":Sr.ORD,"\u2772":Sr.OPEN,"\u2795":Sr.ORD,"\u2796":Sr.ORD,"\u27c0":Sr.ORD,"\u27e6":Sr.OPEN,"\u27e8":Sr.OPEN,"\u27ea":Sr.OPEN,"\u27ec":Sr.OPEN,"\u27ee":Sr.OPEN,"\u2980":Sr.FENCE,"\u2983":Sr.OPEN,"\u2985":Sr.OPEN,"\u2987":Sr.OPEN,"\u2989":Sr.OPEN,"\u298b":Sr.OPEN,"\u298d":Sr.OPEN,"\u298f":Sr.OPEN,"\u2991":Sr.OPEN,"\u2993":Sr.OPEN,"\u2995":Sr.OPEN,"\u2997":Sr.OPEN,"\u2999":Sr.FENCE,"\u299b":Sr.ORD,"\u299c":Sr.ORD,"\u299d":Sr.ORD,"\u299e":Sr.ORD,"\u299f":Sr.ORD,"\u29a0":Sr.ORD,"\u29a1":Sr.ORD,"\u29a2":Sr.ORD,"\u29a3":Sr.ORD,"\u29a4":Sr.ORD,"\u29a5":Sr.ORD,"\u29a6":Sr.ORD,"\u29a7":Sr.ORD,"\u29a8":Sr.ORD,"\u29a9":Sr.ORD,"\u29aa":Sr.ORD,"\u29ab":Sr.ORD,"\u29ac":Sr.ORD,"\u29ad":Sr.ORD,"\u29ae":Sr.ORD,"\u29af":Sr.ORD,"\u29d8":Sr.OPEN,"\u29da":Sr.OPEN,"\u29fc":Sr.OPEN,"\u2a00":Sr.OP,"\u2a01":Sr.OP,"\u2a02":Sr.OP,"\u2a03":Sr.OP,"\u2a04":Sr.OP,"\u2a05":Sr.OP,"\u2a06":Sr.OP,"\u2a07":Sr.OP,"\u2a08":Sr.OP,"\u2a09":Sr.OP,"\u2a0a":Sr.OP,"\u2a0b":Sr.INTEGRAL,"\u2a0c":Sr.INTEGRAL,"\u2a0d":Sr.INTEGRAL,"\u2a0e":Sr.INTEGRAL,"\u2a0f":Sr.INTEGRAL,"\u2a10":Sr.INTEGRAL,"\u2a11":Sr.INTEGRAL,"\u2a12":Sr.INTEGRAL,"\u2a13":Sr.INTEGRAL,"\u2a14":Sr.INTEGRAL,"\u2a15":Sr.INTEGRAL,"\u2a16":Sr.INTEGRAL,"\u2a17":Sr.INTEGRAL,"\u2a18":Sr.INTEGRAL,"\u2a19":Sr.INTEGRAL,"\u2a1a":Sr.INTEGRAL,"\u2a1b":Sr.INTEGRAL,"\u2a1c":Sr.INTEGRAL,"\u2a1d":Sr.OP,"\u2a1e":Sr.OP,"\u2aec":Sr.ORD,"\u2aed":Sr.ORD,"\u2afc":Sr.OP,"\u2aff":Sr.OP,"\u3008":Sr.OPEN},postfix:{"!!":Sr.BIN0,"!":Sr.CLOSE0,'"':Sr.ORD,"%":Sr.ORD,"&":Sr.ORD,"'":Sr.ACCENT,")":Sr.CLOSE,"++":Sr.BIN0,"--":Sr.BIN0,"]":Sr.CLOSE,"^":Sr.WIDEACCENT,_:Sr.WIDEACCENT,"`":Sr.ACCENT,"|":Sr.CLOSE,"||":Sr.BIN0,"}":Sr.CLOSE,"~":Sr.WIDEACCENT,"\xa8":Sr.ACCENT,"\xaf":Sr.WIDEACCENT,"\xb0":Sr.ACCENT,"\xb2":Sr.ORD,"\xb3":Sr.ORD,"\xb4":Sr.ACCENT,"\xb8":Sr.ACCENT,"\xb9":Sr.ORD,\u02c6:Sr.WIDEACCENT,\u02c7:Sr.WIDEACCENT,\u02c9:Sr.WIDEACCENT,\u02ca:Sr.ACCENT,\u02cb:Sr.ACCENT,\u02cd:Sr.WIDEACCENT,"\u02d8":Sr.ACCENT,"\u02d9":Sr.ACCENT,"\u02da":Sr.ACCENT,"\u02dc":Sr.WIDEACCENT,"\u02dd":Sr.ACCENT,"\u02f7":Sr.WIDEACCENT,"\u0302":Sr.WIDEACCENT,"\u0311":Sr.ACCENT,"\u2016":Sr.FENCE,"\u2019":Sr.CLOSE0,"\u201a":Sr.ORD,"\u201b":Sr.ORD,"\u201d":Sr.CLOSE0,"\u201e":Sr.ORD,"\u201f":Sr.ORD,"\u2032":Sr.ORD,"\u2033":Sr.ORD,"\u2034":Sr.ORD,"\u2035":Sr.ORD,"\u2036":Sr.ORD,"\u2037":Sr.ORD,"\u203e":Sr.WIDEACCENT,"\u2057":Sr.ORD,"\u20db":Sr.ACCENT,"\u20dc":Sr.ACCENT,"\u2309":Sr.CLOSE,"\u230b":Sr.CLOSE,"\u2322":Sr.RELSTRETCH0,"\u2323":Sr.RELSTRETCH0,"\u23b4":Sr.WIDEACCENT,"\u23b5":Sr.WIDEACCENT,"\u23cd":Sr.ORD,"\u23dc":Sr.WIDEACCENT,"\u23dd":Sr.WIDEACCENT,"\u23de":Sr.WIDEACCENT,"\u23df":Sr.WIDEACCENT,"\u23e0":Sr.WIDEACCENT,"\u23e1":Sr.WIDEACCENT,"\u2773":Sr.CLOSE,"\u27e7":Sr.CLOSE,"\u27e9":Sr.CLOSE,"\u27eb":Sr.CLOSE,"\u27ed":Sr.CLOSE,"\u27ef":Sr.CLOSE,"\u2980":Sr.FENCE,"\u2984":Sr.CLOSE,"\u2986":Sr.CLOSE,"\u2988":Sr.CLOSE,"\u298a":Sr.CLOSE,"\u298c":Sr.CLOSE,"\u298e":Sr.CLOSE,"\u2990":Sr.CLOSE,"\u2992":Sr.CLOSE,"\u2994":Sr.CLOSE,"\u2996":Sr.CLOSE,"\u2998":Sr.CLOSE,"\u2999":Sr.FENCE,"\u29d9":Sr.CLOSE,"\u29db":Sr.CLOSE,"\u29fd":Sr.CLOSE,"\u3009":Sr.CLOSE,"\u{1eef0}":Sr.BINSTRETCH0,"\u{1eef1}":Sr.BINSTRETCH0},infix:{"!":Sr.ORD,"!=":Sr.BIN5,"#":Sr.ORD,$:Sr.ORD,"%":Sr.ORD3,"&&":Sr.BIN4,"**":Sr.BIN3,"*":Sr.BIN3,"*=":Sr.BIN5,"+":Sr.BIN4,"+=":Sr.BIN5,",":Sr.PUNCT03,"":Sr.ORD,"-":Sr.BIN4,"-=":Sr.BIN5,"->":Sr.BIN5,".":Sr.ORD3,"..":Sr.BIN3,"...":Sr.INNER,"/":[4,4,mr.ORD,{}],"//":Sr.BIN5,"/=":Sr.BIN5,":":[0,3,mr.REL,{}],":=":Sr.BIN5,";":Sr.PUNCT03,"<":Sr.REL,"<=":Sr.REL,"<>":[3,3,mr.REL,{}],"=":Sr.REL,"==":Sr.REL,">":Sr.REL,">=":Sr.REL,"?":[3,3,mr.CLOSE,{fence:!0}],"@":Sr.ORD3,"\\":Sr.ORD,"^":[3,3,mr.ORD,{accent:!0,stretchy:!0}],_:Sr.WIDEACCENT,"|":[5,5,mr.ORD,{}],"||":Sr.BIN5,"\xb1":Sr.BIN4,"\xb7":Sr.BIN3,"\xd7":Sr.BIN3,"\xf7":Sr.BIN4,\u02b9:Sr.ORD,"\u0300":Sr.ACCENT,"\u0301":Sr.ACCENT,"\u0303":Sr.WIDEACCENT,"\u0304":Sr.ACCENT,"\u0306":Sr.ACCENT,"\u0307":Sr.ACCENT,"\u0308":Sr.ACCENT,"\u030c":Sr.ACCENT,"\u0332":Sr.WIDEACCENT,"\u0338":Sr.REL,"\u03f6":Sr.REL,"\u2015":Sr.ORDSTRETCH0,"\u2017":Sr.ORDSTRETCH0,"\u2020":Sr.BIN3,"\u2021":Sr.BIN3,"\u2022":Sr.BIN3,"\u2026":Sr.INNER,"\u2043":Sr.BIN3,"\u2044":Sr.STRETCH4,"\u2061":Sr.NONE,"\u2062":Sr.NONE,"\u2063":[0,0,mr.NONE,{linebreakstyle:"after"}],"\u2064":Sr.NONE,"\u20d7":Sr.ACCENT,\u2111:Sr.ORD,\u2113:Sr.ORD,\u2118:Sr.ORD,\u211c:Sr.ORD,"\u2190":Sr.WIDEREL,"\u2191":Sr.RELSTRETCH,"\u2192":Sr.WIDEREL,"\u2193":Sr.RELSTRETCH,"\u2194":Sr.WIDEREL,"\u2195":Sr.RELSTRETCH,"\u2196":Sr.REL,"\u2197":Sr.REL,"\u2198":Sr.REL,"\u2199":Sr.REL,"\u219a":Sr.WIDEREL,"\u219b":Sr.WIDEREL,"\u219c":Sr.WIDEREL,"\u219d":Sr.WIDEREL,"\u219e":Sr.WIDEREL,"\u219f":Sr.RELSTRETCH,"\u21a0":Sr.WIDEREL,"\u21a1":Sr.RELSTRETCH,"\u21a2":Sr.WIDEREL,"\u21a3":Sr.WIDEREL,"\u21a4":Sr.WIDEREL,"\u21a5":Sr.RELSTRETCH,"\u21a6":Sr.WIDEREL,"\u21a7":Sr.RELSTRETCH,"\u21a8":Sr.RELSTRETCH,"\u21a9":Sr.WIDEREL,"\u21aa":Sr.WIDEREL,"\u21ab":Sr.WIDEREL,"\u21ac":Sr.WIDEREL,"\u21ad":Sr.WIDEREL,"\u21ae":Sr.WIDEREL,"\u21af":Sr.REL,"\u21b0":Sr.RELSTRETCH,"\u21b1":Sr.RELSTRETCH,"\u21b2":Sr.RELSTRETCH,"\u21b3":Sr.RELSTRETCH,"\u21b4":Sr.RELSTRETCH,"\u21b5":Sr.RELSTRETCH,"\u21b6":Sr.REL,"\u21b7":Sr.REL,"\u21b8":Sr.REL,"\u21b9":Sr.WIDEREL,"\u21ba":Sr.REL,"\u21bb":Sr.REL,"\u21bc":Sr.WIDEREL,"\u21bd":Sr.WIDEREL,"\u21be":Sr.RELSTRETCH,"\u21bf":Sr.RELSTRETCH,"\u21c0":Sr.WIDEREL,"\u21c1":Sr.WIDEREL,"\u21c2":Sr.RELSTRETCH,"\u21c3":Sr.RELSTRETCH,"\u21c4":Sr.WIDEREL,"\u21c5":Sr.RELSTRETCH,"\u21c6":Sr.WIDEREL,"\u21c7":Sr.WIDEREL,"\u21c8":Sr.RELSTRETCH,"\u21c9":Sr.WIDEREL,"\u21ca":Sr.RELSTRETCH,"\u21cb":Sr.WIDEREL,"\u21cc":Sr.WIDEREL,"\u21cd":Sr.WIDEREL,"\u21ce":Sr.WIDEREL,"\u21cf":Sr.WIDEREL,"\u21d0":Sr.WIDEREL,"\u21d1":Sr.RELSTRETCH,"\u21d2":Sr.WIDEREL,"\u21d3":Sr.RELSTRETCH,"\u21d4":Sr.WIDEREL,"\u21d5":Sr.RELSTRETCH,"\u21d6":Sr.REL,"\u21d7":Sr.REL,"\u21d8":Sr.REL,"\u21d9":Sr.REL,"\u21da":Sr.WIDEREL,"\u21db":Sr.WIDEREL,"\u21dc":Sr.WIDEREL,"\u21dd":Sr.WIDEREL,"\u21de":Sr.RELSTRETCH,"\u21df":Sr.RELSTRETCH,"\u21e0":Sr.WIDEREL,"\u21e1":Sr.RELSTRETCH,"\u21e2":Sr.WIDEREL,"\u21e3":Sr.RELSTRETCH,"\u21e4":Sr.WIDEREL,"\u21e5":Sr.WIDEREL,"\u21e6":Sr.WIDEREL,"\u21e7":Sr.RELSTRETCH,"\u21e8":Sr.WIDEREL,"\u21e9":Sr.RELSTRETCH,"\u21ea":Sr.RELSTRETCH,"\u21eb":Sr.RELSTRETCH,"\u21ec":Sr.RELSTRETCH,"\u21ed":Sr.RELSTRETCH,"\u21ee":Sr.RELSTRETCH,"\u21ef":Sr.RELSTRETCH,"\u21f0":Sr.WIDEREL,"\u21f1":Sr.REL,"\u21f2":Sr.REL,"\u21f3":Sr.RELSTRETCH,"\u21f4":Sr.WIDEREL,"\u21f5":Sr.RELSTRETCH,"\u21f6":Sr.WIDEREL,"\u21f7":Sr.WIDEREL,"\u21f8":Sr.WIDEREL,"\u21f9":Sr.WIDEREL,"\u21fa":Sr.WIDEREL,"\u21fb":Sr.WIDEREL,"\u21fc":Sr.WIDEREL,"\u21fd":Sr.WIDEREL,"\u21fe":Sr.WIDEREL,"\u21ff":Sr.WIDEREL,"\u2205":Sr.ORD,"\u2206":Sr.ORD,"\u2208":Sr.REL,"\u2209":Sr.REL,"\u220a":Sr.REL,"\u220b":Sr.REL,"\u220c":Sr.REL,"\u220d":Sr.REL,"\u2212":Sr.BIN4,"\u2213":Sr.BIN4,"\u2214":Sr.BIN4,"\u2215":Sr.STRETCH4,"\u2216":Sr.BIN4,"\u2217":Sr.BIN3,"\u2218":Sr.BIN3,"\u2219":Sr.BIN3,"\u221d":Sr.REL,"\u221e":Sr.ORD,"\u2223":Sr.REL,"\u2224":Sr.REL,"\u2225":Sr.REL,"\u2226":Sr.REL,"\u2227":Sr.BIN4,"\u2228":Sr.BIN4,"\u2229":Sr.BIN4,"\u222a":Sr.BIN4,"\u2236":Sr.BIN4,"\u2237":Sr.REL,"\u2238":Sr.BIN4,"\u2239":Sr.REL,"\u223a":Sr.REL,"\u223b":Sr.REL,"\u223c":Sr.REL,"\u223d":Sr.REL,"\u223e":Sr.REL,"\u2240":Sr.BIN3,"\u2241":Sr.REL,"\u2242":Sr.REL,"\u2242\u0338":Sr.REL,"\u2243":Sr.REL,"\u2244":Sr.REL,"\u2245":Sr.REL,"\u2246":Sr.REL,"\u2247":Sr.REL,"\u2248":Sr.REL,"\u2249":Sr.REL,"\u224a":Sr.REL,"\u224b":Sr.REL,"\u224c":Sr.REL,"\u224d":Sr.REL,"\u224e":Sr.REL,"\u224f":Sr.REL,"\u2250":Sr.REL,"\u2251":Sr.REL,"\u2252":Sr.REL,"\u2253":Sr.REL,"\u2254":Sr.REL,"\u2255":Sr.REL,"\u2256":Sr.REL,"\u2257":Sr.REL,"\u2258":Sr.REL,"\u2259":Sr.REL,"\u225a":Sr.REL,"\u225b":Sr.REL,"\u225c":Sr.REL,"\u225d":Sr.REL,"\u225e":Sr.REL,"\u225f":Sr.REL,"\u2260":Sr.REL,"\u2261":Sr.REL,"\u2262":Sr.REL,"\u2263":Sr.REL,"\u2264":Sr.REL,"\u2265":Sr.REL,"\u2266":Sr.REL,"\u2266\u0338":Sr.REL,"\u2267":Sr.REL,"\u2267\u0338":Sr.REL,"\u2268":Sr.REL,"\u2269":Sr.REL,"\u226a":Sr.REL,"\u226a\u0338":Sr.REL,"\u226b":Sr.REL,"\u226b\u0338":Sr.REL,"\u226c":Sr.REL,"\u226d":Sr.REL,"\u226e":Sr.REL,"\u226f":Sr.REL,"\u2270":Sr.REL,"\u2271":Sr.REL,"\u2272":Sr.REL,"\u2273":Sr.REL,"\u2274":Sr.REL,"\u2275":Sr.REL,"\u2276":Sr.REL,"\u2277":Sr.REL,"\u2278":Sr.REL,"\u2279":Sr.REL,"\u227a":Sr.REL,"\u227b":Sr.REL,"\u227c":Sr.REL,"\u227d":Sr.REL,"\u227e":Sr.REL,"\u227e\u0338":Sr.REL,"\u227f":Sr.REL,"\u227f\u0338":Sr.REL,"\u2280":Sr.REL,"\u2281":Sr.REL,"\u2282":Sr.REL,"\u2283":Sr.REL,"\u2284":Sr.REL,"\u2285":Sr.REL,"\u2286":Sr.REL,"\u2287":Sr.REL,"\u2288":Sr.REL,"\u2289":Sr.REL,"\u228a":Sr.REL,"\u228b":Sr.REL,"\u228c":Sr.BIN4,"\u228d":Sr.BIN4,"\u228e":Sr.BIN4,"\u228f":Sr.REL,"\u228f\u0338":Sr.REL,"\u2290":Sr.REL,"\u2290\u0338":Sr.REL,"\u2291":Sr.REL,"\u2292":Sr.REL,"\u2293":Sr.BIN4,"\u2294":Sr.BIN4,"\u2295":Sr.BIN4,"\u2296":Sr.BIN4,"\u2297":Sr.BIN3,"\u2298":Sr.BIN4,"\u2299":Sr.BIN3,"\u229a":Sr.BIN3,"\u229b":Sr.BIN3,"\u229c":Sr.REL,"\u229d":Sr.BIN4,"\u229e":Sr.BIN4,"\u229f":Sr.BIN4,"\u22a0":Sr.BIN3,"\u22a1":Sr.BIN3,"\u22a2":Sr.REL,"\u22a3":Sr.REL,"\u22a4":Sr.ORD,"\u22a5":Sr.ORD,"\u22a6":Sr.REL,"\u22a7":Sr.REL,"\u22a8":Sr.REL,"\u22a9":Sr.REL,"\u22aa":Sr.REL,"\u22ab":Sr.REL,"\u22ac":Sr.REL,"\u22ad":Sr.REL,"\u22ae":Sr.REL,"\u22af":Sr.REL,"\u22b0":Sr.REL,"\u22b1":Sr.REL,"\u22b2":Sr.REL,"\u22b3":Sr.REL,"\u22b4":Sr.REL,"\u22b5":Sr.REL,"\u22b6":Sr.REL,"\u22b7":Sr.REL,"\u22b8":Sr.REL,"\u22ba":Sr.BIN3,"\u22bb":Sr.BIN4,"\u22bc":Sr.BIN4,"\u22bd":Sr.BIN4,"\u22c4":Sr.BIN3,"\u22c5":Sr.BIN3,"\u22c6":Sr.BIN3,"\u22c7":Sr.BIN3,"\u22c8":Sr.REL,"\u22c9":Sr.BIN3,"\u22ca":Sr.BIN3,"\u22cb":Sr.BIN3,"\u22cc":Sr.BIN3,"\u22cd":Sr.REL,"\u22ce":Sr.BIN4,"\u22cf":Sr.BIN4,"\u22d0":Sr.REL,"\u22d1":Sr.REL,"\u22d2":Sr.BIN4,"\u22d3":Sr.BIN4,"\u22d4":Sr.REL,"\u22d5":Sr.REL,"\u22d6":Sr.REL,"\u22d7":Sr.REL,"\u22d8":Sr.REL,"\u22d9":Sr.REL,"\u22da":Sr.REL,"\u22db":Sr.REL,"\u22dc":Sr.REL,"\u22dd":Sr.REL,"\u22de":Sr.REL,"\u22df":Sr.REL,"\u22e0":Sr.REL,"\u22e1":Sr.REL,"\u22e2":Sr.REL,"\u22e3":Sr.REL,"\u22e4":Sr.REL,"\u22e5":Sr.REL,"\u22e6":Sr.REL,"\u22e7":Sr.REL,"\u22e8":Sr.REL,"\u22e9":Sr.REL,"\u22ea":Sr.REL,"\u22eb":Sr.REL,"\u22ec":Sr.REL,"\u22ed":Sr.REL,"\u22ee":Sr.ORD,"\u22ef":Sr.INNER,"\u22f0":Sr.INNER,"\u22f1":Sr.INNER,"\u22f2":Sr.REL,"\u22f3":Sr.REL,"\u22f4":Sr.REL,"\u22f5":Sr.REL,"\u22f6":Sr.REL,"\u22f7":Sr.REL,"\u22f8":Sr.REL,"\u22f9":Sr.REL,"\u22fa":Sr.REL,"\u22fb":Sr.REL,"\u22fc":Sr.REL,"\u22fd":Sr.REL,"\u22fe":Sr.REL,"\u22ff":Sr.REL,"\u2301":Sr.REL,"\u2305":Sr.BIN3,"\u2306":Sr.BIN3,"\u2329":Sr.OPEN,"\u232a":Sr.CLOSE,"\u237c":Sr.REL,"\u238b":Sr.REL,"\u23aa":Sr.ORD,"\u23af":Sr.ORDSTRETCH0,"\u23b0":Sr.OPEN,"\u23b1":Sr.CLOSE,"\u2500":Sr.ORD,"\u25b3":Sr.BIN3,"\u25b5":Sr.BIN3,"\u25b9":Sr.BIN3,"\u25bd":Sr.BIN3,"\u25bf":Sr.BIN3,"\u25c3":Sr.BIN3,"\u25ef":Sr.BIN3,"\u2660":Sr.ORD,"\u2661":Sr.ORD,"\u2662":Sr.ORD,"\u2663":Sr.ORD,"\u266d":Sr.ORD,"\u266e":Sr.ORD,"\u266f":Sr.ORD,"\u2758":[5,5,mr.REL,{stretchy:!0,symmetric:!0}],"\u2794":Sr.WIDEREL,"\u2795":Sr.BIN4,"\u2796":Sr.BIN4,"\u2797":Sr.BIN4,"\u2798":Sr.REL,"\u2799":Sr.WIDEREL,"\u279a":Sr.REL,"\u279b":Sr.WIDEREL,"\u279c":Sr.WIDEREL,"\u279d":Sr.WIDEREL,"\u279e":Sr.WIDEREL,"\u279f":Sr.WIDEREL,"\u27a0":Sr.WIDEREL,"\u27a1":Sr.WIDEREL,"\u27a5":Sr.WIDEREL,"\u27a6":Sr.WIDEREL,"\u27a7":Sr.RELACCENT,"\u27a8":Sr.WIDEREL,"\u27a9":Sr.WIDEREL,"\u27aa":Sr.WIDEREL,"\u27ab":Sr.WIDEREL,"\u27ac":Sr.WIDEREL,"\u27ad":Sr.WIDEREL,"\u27ae":Sr.WIDEREL,"\u27af":Sr.WIDEREL,"\u27b1":Sr.WIDEREL,"\u27b2":Sr.RELACCENT,"\u27b3":Sr.WIDEREL,"\u27b4":Sr.REL,"\u27b5":Sr.WIDEREL,"\u27b6":Sr.REL,"\u27b7":Sr.REL,"\u27b8":Sr.WIDEREL,"\u27b9":Sr.REL,"\u27ba":Sr.WIDEREL,"\u27bb":Sr.WIDEREL,"\u27bc":Sr.WIDEREL,"\u27bd":Sr.WIDEREL,"\u27be":Sr.WIDEREL,"\u27c2":Sr.REL,"\u27c2\u0338":Sr.REL,"\u27cb":Sr.BIN3,"\u27cd":Sr.BIN3,"\u27f0":Sr.RELSTRETCH,"\u27f1":Sr.RELSTRETCH,"\u27f2":Sr.REL,"\u27f3":Sr.REL,"\u27f4":Sr.RELSTRETCH,"\u27f5":Sr.WIDEREL,"\u27f6":Sr.WIDEREL,"\u27f7":Sr.WIDEREL,"\u27f8":Sr.WIDEREL,"\u27f9":Sr.WIDEREL,"\u27fa":Sr.WIDEREL,"\u27fb":Sr.WIDEREL,"\u27fc":Sr.WIDEREL,"\u27fd":Sr.WIDEREL,"\u27fe":Sr.WIDEREL,"\u27ff":Sr.WIDEREL,"\u2900":Sr.WIDEREL,"\u2901":Sr.WIDEREL,"\u2902":Sr.WIDEREL,"\u2903":Sr.WIDEREL,"\u2904":Sr.WIDEREL,"\u2905":Sr.WIDEREL,"\u2906":Sr.WIDEREL,"\u2907":Sr.WIDEREL,"\u2908":Sr.RELSTRETCH,"\u2909":Sr.RELSTRETCH,"\u290a":Sr.RELSTRETCH,"\u290b":Sr.RELSTRETCH,"\u290c":Sr.WIDEREL,"\u290d":Sr.WIDEREL,"\u290e":Sr.WIDEREL,"\u290f":Sr.WIDEREL,"\u2910":Sr.WIDEREL,"\u2911":Sr.WIDEREL,"\u2912":Sr.RELSTRETCH,"\u2913":Sr.RELSTRETCH,"\u2914":Sr.WIDEREL,"\u2915":Sr.WIDEREL,"\u2916":Sr.WIDEREL,"\u2917":Sr.WIDEREL,"\u2918":Sr.WIDEREL,"\u2919":Sr.WIDEREL,"\u291a":Sr.WIDEREL,"\u291b":Sr.WIDEREL,"\u291c":Sr.WIDEREL,"\u291d":Sr.WIDEREL,"\u291e":Sr.WIDEREL,"\u291f":Sr.WIDEREL,"\u2920":Sr.WIDEREL,"\u2921":Sr.REL,"\u2922":Sr.REL,"\u2923":Sr.REL,"\u2924":Sr.REL,"\u2925":Sr.REL,"\u2926":Sr.REL,"\u2927":Sr.REL,"\u2928":Sr.REL,"\u2929":Sr.REL,"\u292a":Sr.REL,"\u292b":Sr.REL,"\u292c":Sr.REL,"\u292d":Sr.REL,"\u292e":Sr.REL,"\u292f":Sr.REL,"\u2930":Sr.REL,"\u2931":Sr.REL,"\u2932":Sr.REL,"\u2933":Sr.RELACCENT,"\u2934":Sr.RELSTRETCH,"\u2935":Sr.RELSTRETCH,"\u2936":Sr.RELSTRETCH,"\u2937":Sr.RELSTRETCH,"\u2938":Sr.REL,"\u2939":Sr.REL,"\u293a":Sr.RELACCENT,"\u293b":Sr.RELACCENT,"\u293c":Sr.RELACCENT,"\u293d":Sr.RELACCENT,"\u293e":Sr.REL,"\u293f":Sr.REL,"\u2940":Sr.REL,"\u2941":Sr.REL,"\u2942":Sr.WIDEREL,"\u2943":Sr.WIDEREL,"\u2944":Sr.WIDEREL,"\u2945":Sr.RELSTRETCH,"\u2946":Sr.RELSTRETCH,"\u2947":Sr.WIDEREL,"\u2948":Sr.WIDEREL,"\u2949":Sr.RELSTRETCH,"\u294a":Sr.WIDEREL,"\u294b":Sr.WIDEREL,"\u294c":Sr.RELSTRETCH,"\u294d":Sr.RELSTRETCH,"\u294e":Sr.WIDEREL,"\u294f":Sr.RELSTRETCH,"\u2950":Sr.WIDEREL,"\u2951":Sr.RELSTRETCH,"\u2952":Sr.WIDEREL,"\u2953":Sr.WIDEREL,"\u2954":Sr.RELSTRETCH,"\u2955":Sr.RELSTRETCH,"\u2956":Sr.WIDEREL,"\u2957":Sr.WIDEREL,"\u2958":Sr.RELSTRETCH,"\u2959":Sr.RELSTRETCH,"\u295a":Sr.WIDEREL,"\u295b":Sr.WIDEREL,"\u295c":Sr.RELSTRETCH,"\u295d":Sr.RELSTRETCH,"\u295e":Sr.WIDEREL,"\u295f":Sr.WIDEREL,"\u2960":Sr.RELSTRETCH,"\u2961":Sr.RELSTRETCH,"\u2962":Sr.WIDEREL,"\u2963":Sr.RELSTRETCH,"\u2964":Sr.WIDEREL,"\u2965":Sr.RELSTRETCH,"\u2966":Sr.WIDEREL,"\u2967":Sr.WIDEREL,"\u2968":Sr.WIDEREL,"\u2969":Sr.WIDEREL,"\u296a":Sr.WIDEREL,"\u296b":Sr.WIDEREL,"\u296c":Sr.WIDEREL,"\u296d":Sr.WIDEREL,"\u296e":Sr.RELSTRETCH,"\u296f":Sr.RELSTRETCH,"\u2970":Sr.WIDEREL,"\u2971":Sr.WIDEREL,"\u2972":Sr.WIDEREL,"\u2973":Sr.WIDEREL,"\u2974":Sr.WIDEREL,"\u2975":Sr.WIDEREL,"\u2976":Sr.RELACCENT,"\u2977":Sr.RELACCENT,"\u2978":Sr.RELACCENT,"\u2979":Sr.RELACCENT,"\u297a":Sr.RELACCENT,"\u297b":Sr.RELACCENT,"\u297c":Sr.WIDEREL,"\u297d":Sr.WIDEREL,"\u297e":Sr.RELSTRETCH,"\u297f":Sr.RELSTRETCH,"\u2981":Sr.REL,"\u2982":Sr.REL,"\u29b6":Sr.REL,"\u29b7":Sr.REL,"\u29b8":Sr.BIN4,"\u29b9":Sr.REL,"\u29bc":Sr.BIN4,"\u29c0":Sr.REL,"\u29c1":Sr.REL,"\u29c4":Sr.BIN4,"\u29c5":Sr.BIN4,"\u29c6":Sr.BIN3,"\u29c7":Sr.BIN3,"\u29c8":Sr.BIN3,"\u29ce":Sr.REL,"\u29cf":Sr.REL,"\u29d0":Sr.REL,"\u29d1":Sr.REL,"\u29d2":Sr.REL,"\u29d3":Sr.REL,"\u29d4":Sr.BIN3,"\u29d5":Sr.BIN3,"\u29d6":Sr.BIN3,"\u29d7":Sr.BIN3,"\u29df":Sr.REL,"\u29e1":Sr.REL,"\u29e2":Sr.BIN3,"\u29e3":Sr.REL,"\u29e4":Sr.REL,"\u29e5":Sr.REL,"\u29e6":Sr.REL,"\u29f4":Sr.REL,"\u29f5":Sr.BIN4,"\u29f6":Sr.BIN4,"\u29f7":Sr.BIN4,"\u29f8":Sr.BIN4,"\u29f9":Sr.BIN4,"\u29fa":Sr.BIN4,"\u29fb":Sr.BIN4,"\u2a1d":Sr.BIN3,"\u2a1e":Sr.BIN3,"\u2a1f":Sr.BIN4,"\u2a20":Sr.BIN4,"\u2a21":Sr.BIN4,"\u2a22":Sr.BIN4,"\u2a23":Sr.BIN4,"\u2a24":Sr.BIN4,"\u2a25":Sr.BIN4,"\u2a26":Sr.BIN4,"\u2a27":Sr.BIN4,"\u2a28":Sr.BIN4,"\u2a29":Sr.BIN4,"\u2a2a":Sr.BIN4,"\u2a2b":Sr.BIN4,"\u2a2c":Sr.BIN4,"\u2a2d":Sr.BIN4,"\u2a2e":Sr.BIN4,"\u2a2f":Sr.BIN3,"\u2a30":Sr.BIN3,"\u2a31":Sr.BIN3,"\u2a32":Sr.BIN3,"\u2a33":Sr.BIN3,"\u2a34":Sr.BIN3,"\u2a35":Sr.BIN3,"\u2a36":Sr.BIN3,"\u2a37":Sr.BIN3,"\u2a38":Sr.BIN4,"\u2a39":Sr.BIN4,"\u2a3a":Sr.BIN4,"\u2a3b":Sr.BIN3,"\u2a3c":Sr.BIN3,"\u2a3d":Sr.BIN3,"\u2a3e":Sr.BIN4,"\u2a3f":Sr.BIN3,"\u2a40":Sr.BIN4,"\u2a41":Sr.BIN4,"\u2a42":Sr.BIN4,"\u2a43":Sr.BIN4,"\u2a44":Sr.BIN4,"\u2a45":Sr.BIN4,"\u2a46":Sr.BIN4,"\u2a47":Sr.BIN4,"\u2a48":Sr.BIN4,"\u2a49":Sr.BIN4,"\u2a4a":Sr.BIN4,"\u2a4b":Sr.BIN4,"\u2a4c":Sr.BIN4,"\u2a4d":Sr.BIN4,"\u2a4e":Sr.BIN4,"\u2a4f":Sr.BIN4,"\u2a50":Sr.BIN3,"\u2a51":Sr.BIN4,"\u2a52":Sr.BIN4,"\u2a53":Sr.BIN4,"\u2a54":Sr.BIN4,"\u2a55":Sr.BIN4,"\u2a56":Sr.BIN4,"\u2a57":Sr.BIN4,"\u2a58":Sr.BIN4,"\u2a59":Sr.BIN4,"\u2a5a":Sr.BIN4,"\u2a5b":Sr.BIN4,"\u2a5c":Sr.BIN4,"\u2a5d":Sr.BIN4,"\u2a5e":Sr.BIN4,"\u2a5f":Sr.BIN4,"\u2a60":Sr.BIN4,"\u2a61":Sr.BIN4,"\u2a62":Sr.BIN4,"\u2a63":Sr.BIN4,"\u2a64":Sr.BIN3,"\u2a65":Sr.BIN3,"\u2a66":Sr.REL,"\u2a67":Sr.REL,"\u2a68":Sr.REL,"\u2a69":Sr.REL,"\u2a6a":Sr.REL,"\u2a6b":Sr.REL,"\u2a6c":Sr.REL,"\u2a6d":Sr.REL,"\u2a6e":Sr.REL,"\u2a6f":Sr.REL,"\u2a70":Sr.REL,"\u2a71":Sr.REL,"\u2a72":Sr.REL,"\u2a73":Sr.REL,"\u2a74":Sr.REL,"\u2a75":Sr.REL,"\u2a76":Sr.REL,"\u2a77":Sr.REL,"\u2a78":Sr.REL,"\u2a79":Sr.REL,"\u2a7a":Sr.REL,"\u2a7b":Sr.REL,"\u2a7c":Sr.REL,"\u2a7d":Sr.REL,"\u2a7d\u0338":Sr.REL,"\u2a7e":Sr.REL,"\u2a7e\u0338":Sr.REL,"\u2a7f":Sr.REL,"\u2a80":Sr.REL,"\u2a81":Sr.REL,"\u2a82":Sr.REL,"\u2a83":Sr.REL,"\u2a84":Sr.REL,"\u2a85":Sr.REL,"\u2a86":Sr.REL,"\u2a87":Sr.REL,"\u2a88":Sr.REL,"\u2a89":Sr.REL,"\u2a8a":Sr.REL,"\u2a8b":Sr.REL,"\u2a8c":Sr.REL,"\u2a8d":Sr.REL,"\u2a8e":Sr.REL,"\u2a8f":Sr.REL,"\u2a90":Sr.REL,"\u2a91":Sr.REL,"\u2a92":Sr.REL,"\u2a93":Sr.REL,"\u2a94":Sr.REL,"\u2a95":Sr.REL,"\u2a96":Sr.REL,"\u2a97":Sr.REL,"\u2a98":Sr.REL,"\u2a99":Sr.REL,"\u2a9a":Sr.REL,"\u2a9b":Sr.REL,"\u2a9c":Sr.REL,"\u2a9d":Sr.REL,"\u2a9e":Sr.REL,"\u2a9f":Sr.REL,"\u2aa0":Sr.REL,"\u2aa1":Sr.REL,"\u2aa2":Sr.REL,"\u2aa3":Sr.REL,"\u2aa4":Sr.REL,"\u2aa5":Sr.REL,"\u2aa6":Sr.REL,"\u2aa7":Sr.REL,"\u2aa8":Sr.REL,"\u2aa9":Sr.REL,"\u2aaa":Sr.REL,"\u2aab":Sr.REL,"\u2aac":Sr.REL,"\u2aad":Sr.REL,"\u2aae":Sr.REL,"\u2aaf":Sr.REL,"\u2aaf\u0338":Sr.REL,"\u2ab0":Sr.REL,"\u2ab0\u0338":Sr.REL,"\u2ab1":Sr.REL,"\u2ab2":Sr.REL,"\u2ab3":Sr.REL,"\u2ab4":Sr.REL,"\u2ab5":Sr.REL,"\u2ab6":Sr.REL,"\u2ab7":Sr.REL,"\u2ab8":Sr.REL,"\u2ab9":Sr.REL,"\u2aba":Sr.REL,"\u2abb":Sr.REL,"\u2abc":Sr.REL,"\u2abd":Sr.REL,"\u2abe":Sr.REL,"\u2abf":Sr.REL,"\u2ac0":Sr.REL,"\u2ac1":Sr.REL,"\u2ac2":Sr.REL,"\u2ac3":Sr.REL,"\u2ac4":Sr.REL,"\u2ac5":Sr.REL,"\u2ac6":Sr.REL,"\u2ac7":Sr.REL,"\u2ac8":Sr.REL,"\u2ac9":Sr.REL,"\u2aca":Sr.REL,"\u2acb":Sr.REL,"\u2acc":Sr.REL,"\u2acd":Sr.REL,"\u2ace":Sr.REL,"\u2acf":Sr.REL,"\u2ad0":Sr.REL,"\u2ad1":Sr.REL,"\u2ad2":Sr.REL,"\u2ad3":Sr.REL,"\u2ad4":Sr.REL,"\u2ad5":Sr.REL,"\u2ad6":Sr.REL,"\u2ad7":Sr.REL,"\u2ad8":Sr.REL,"\u2ad9":Sr.REL,"\u2ada":Sr.REL,"\u2adb":Sr.BIN4,"\u2add":Sr.BIN3,"\u2add\u0338":Sr.REL,"\u2ade":Sr.REL,"\u2adf":Sr.REL,"\u2ae0":Sr.REL,"\u2ae1":Sr.REL,"\u2ae2":Sr.REL,"\u2ae3":Sr.REL,"\u2ae4":Sr.REL,"\u2ae5":Sr.REL,"\u2ae6":Sr.REL,"\u2ae7":Sr.REL,"\u2ae8":Sr.REL,"\u2ae9":Sr.REL,"\u2aea":Sr.REL,"\u2aeb":Sr.REL,"\u2aee":Sr.REL,"\u2af2":Sr.REL,"\u2af3":Sr.REL,"\u2af4":Sr.REL,"\u2af5":Sr.REL,"\u2af6":Sr.BIN4,"\u2af7":Sr.REL,"\u2af8":Sr.REL,"\u2af9":Sr.REL,"\u2afa":Sr.REL,"\u2afb":Sr.BIN4,"\u2afd":Sr.BIN4,"\u2afe":Sr.BIN3,"\u2b00":Sr.REL,"\u2b01":Sr.REL,"\u2b02":Sr.REL,"\u2b03":Sr.REL,"\u2b04":Sr.WIDEREL,"\u2b05":Sr.WIDEREL,"\u2b06":Sr.RELSTRETCH,"\u2b07":Sr.RELSTRETCH,"\u2b08":Sr.REL,"\u2b09":Sr.REL,"\u2b0a":Sr.REL,"\u2b0b":Sr.REL,"\u2b0c":Sr.WIDEREL,"\u2b0d":Sr.RELSTRETCH,"\u2b0e":Sr.RELSTRETCH,"\u2b0f":Sr.RELSTRETCH,"\u2b10":Sr.RELSTRETCH,"\u2b11":Sr.RELSTRETCH,"\u2b30":Sr.WIDEREL,"\u2b31":Sr.WIDEREL,"\u2b32":Sr.RELSTRETCH,"\u2b33":Sr.WIDEREL,"\u2b34":Sr.WIDEREL,"\u2b35":Sr.WIDEREL,"\u2b36":Sr.WIDEREL,"\u2b37":Sr.WIDEREL,"\u2b38":Sr.WIDEREL,"\u2b39":Sr.WIDEREL,"\u2b3a":Sr.WIDEREL,"\u2b3b":Sr.WIDEREL,"\u2b3c":Sr.WIDEREL,"\u2b3d":Sr.WIDEREL,"\u2b3e":Sr.WIDEREL,"\u2b3f":Sr.RELACCENT,"\u2b40":Sr.WIDEREL,"\u2b41":Sr.WIDEREL,"\u2b42":Sr.WIDEREL,"\u2b43":Sr.WIDEREL,"\u2b44":Sr.WIDEREL,"\u2b45":Sr.WIDEREL,"\u2b46":Sr.WIDEREL,"\u2b47":Sr.WIDEREL,"\u2b48":Sr.WIDEREL,"\u2b49":Sr.WIDEREL,"\u2b4a":Sr.WIDEREL,"\u2b4b":Sr.WIDEREL,"\u2b4c":Sr.WIDEREL,"\u2b4d":Sr.REL,"\u2b4e":Sr.REL,"\u2b4f":Sr.REL,"\u2b5a":Sr.REL,"\u2b5b":Sr.REL,"\u2b5c":Sr.REL,"\u2b5d":Sr.REL,"\u2b5e":Sr.REL,"\u2b5f":Sr.REL,"\u2b60":Sr.WIDEREL,"\u2b61":Sr.RELSTRETCH,"\u2b62":Sr.WIDEREL,"\u2b63":Sr.RELSTRETCH,"\u2b64":Sr.WIDEREL,"\u2b65":Sr.RELSTRETCH,"\u2b66":Sr.REL,"\u2b67":Sr.REL,"\u2b68":Sr.REL,"\u2b69":Sr.REL,"\u2b6a":Sr.WIDEREL,"\u2b6b":Sr.RELSTRETCH,"\u2b6c":Sr.WIDEREL,"\u2b6d":Sr.RELSTRETCH,"\u2b6e":Sr.REL,"\u2b6f":Sr.REL,"\u2b70":Sr.WIDEREL,"\u2b71":Sr.RELSTRETCH,"\u2b72":Sr.WIDEREL,"\u2b73":Sr.RELSTRETCH,"\u2b76":Sr.REL,"\u2b77":Sr.REL,"\u2b78":Sr.REL,"\u2b79":Sr.REL,"\u2b7a":Sr.WIDEREL,"\u2b7b":Sr.RELSTRETCH,"\u2b7c":Sr.WIDEREL,"\u2b7d":Sr.RELSTRETCH,"\u2b80":Sr.WIDEREL,"\u2b81":Sr.RELSTRETCH,"\u2b82":Sr.WIDEREL,"\u2b83":Sr.RELSTRETCH,"\u2b84":Sr.WIDEREL,"\u2b85":Sr.RELSTRETCH,"\u2b86":Sr.WIDEREL,"\u2b87":Sr.RELSTRETCH,"\u2b88":Sr.RELACCENT,"\u2b89":Sr.REL,"\u2b8a":Sr.RELACCENT,"\u2b8b":Sr.REL,"\u2b8c":Sr.REL,"\u2b8d":Sr.REL,"\u2b8e":Sr.REL,"\u2b8f":Sr.REL,"\u2b94":Sr.REL,"\u2b95":Sr.WIDEREL,"\u2ba0":Sr.RELSTRETCH,"\u2ba1":Sr.RELSTRETCH,"\u2ba2":Sr.RELSTRETCH,"\u2ba3":Sr.RELSTRETCH,"\u2ba4":Sr.RELSTRETCH,"\u2ba5":Sr.RELSTRETCH,"\u2ba6":Sr.RELSTRETCH,"\u2ba7":Sr.RELSTRETCH,"\u2ba8":Sr.WIDEREL,"\u2ba9":Sr.WIDEREL,"\u2baa":Sr.WIDEREL,"\u2bab":Sr.WIDEREL,"\u2bac":Sr.RELSTRETCH,"\u2bad":Sr.RELSTRETCH,"\u2bae":Sr.RELSTRETCH,"\u2baf":Sr.RELSTRETCH,"\u2bb0":Sr.REL,"\u2bb1":Sr.REL,"\u2bb2":Sr.REL,"\u2bb3":Sr.REL,"\u2bb4":Sr.REL,"\u2bb5":Sr.REL,"\u2bb6":Sr.REL,"\u2bb7":Sr.REL,"\u2bb8":Sr.RELSTRETCH,"\u2bd1":Sr.REL,\u3adc:Sr.BIN3,"\ufe37":Sr.WIDEACCENT,"\ufe38":Sr.WIDEACCENT}};function Pr(t,e){return t.length!==e.length?e.length-t.length:t===e?0:tt.codePointAt(0))}function jr(t){return String.fromCodePoint(...t)}function Ur(t){return!!t.match(/%\s*$/)}function Hr(t){return t.trim().split(/\s+/)}function qr(t){return t.replace(/\\U(?:([0-9A-Fa-f]{4})|\{\s*([0-9A-Fa-f]{1,6})\s*\})|\\./g,(t,e,s)=>"\\\\"===t?"\\":String.fromCodePoint(parseInt(e||s,16)))}function Wr(t){return`&#x${t.codePointAt(0).toString(16).toUpperCase()};`}class zr extends Nr{constructor(){super(...arguments),this._texClass=null,this.lspace=5/18,this.rspace=5/18}get texClass(){return null===this._texClass?this.getOperatorDef(this.getText())[2]:this._texClass}set texClass(t){this._texClass=t}get kind(){return"mo"}get isEmbellished(){return!0}coreParent(){let t=null,e=this;const s=this.factory.getNodeClass("math");for(;e&&e.isEmbellished&&e.coreMO()===this&&!(e instanceof s);)t=e,e=e.parent;return t||this}coreText(t){if(!t)return"";if(t.isEmbellished)return t.coreMO().getText();for(;((t.isKind("mrow")||t.isKind("TeXAtom")||t.isKind("mstyle")||t.isKind("mphantom"))&&1===t.childNodes.length||t.isKind("munderover"))&&t.childNodes[0];)t=t.childNodes[0];return t.isToken?t.getText():""}hasSpacingAttributes(){return this.attributes.isSet("lspace")||this.attributes.isSet("rspace")}get isAccent(){let t=!1;const e=this.coreParent().parent;if(e){const s=e.isKind("mover")?e.childNodes[e.over].coreMO()?"accent":"":e.isKind("munder")?e.childNodes[e.under].coreMO()?"accentunder":"":e.isKind("munderover")?this===e.childNodes[e.over].coreMO()?"accent":this===e.childNodes[e.under].coreMO()?"accentunder":"":"";if(s){t=void 0!==e.attributes.getExplicit(s)?t:this.attributes.get("accent")}}return t}setTeXclass(t){const{form:e,fence:s}=this.attributes.getList("form","fence");return void 0===this.getProperty("texClass")&&this.hasSpacingAttributes()?null:(s&&this.texClass===mr.REL&&("prefix"===e&&(this.texClass=mr.OPEN),"postfix"===e&&(this.texClass=mr.CLOSE)),this.adjustTeXclass(t))}adjustTeXclass(t){const e=this.texClass;let s=this.prevClass;if(e===mr.NONE)return t;if(t?(!t.getProperty("autoOP")||e!==mr.BIN&&e!==mr.REL||(s=t.texClass=mr.ORD),s=this.prevClass=t.texClass||mr.ORD,this.prevLevel=this.attributes.getInherited("scriptlevel")):s=this.prevClass=mr.NONE,e!==mr.BIN||s!==mr.NONE&&s!==mr.BIN&&s!==mr.OP&&s!==mr.REL&&s!==mr.OPEN&&s!==mr.PUNCT)if(s!==mr.BIN||e!==mr.REL&&e!==mr.CLOSE&&e!==mr.PUNCT){if(e===mr.BIN){let t=null,e=this.parent;for(;e&&e.parent&&e.isEmbellished&&(1===e.childNodes.length||!e.isKind("mrow")&&e.core()===t);)t=e,e=e.parent;t=t||this,e.childNodes[e.childNodes.length-1]===t&&(this.texClass=mr.ORD)}}else t.texClass=this.prevClass=mr.ORD;else this.texClass=mr.ORD;return this}setInheritedAttributes(t={},e=!1,s=0,i=!1){super.setInheritedAttributes(t,e,s,i);const r=this.getText();this.checkOperatorTable(r),this.checkPseudoScripts(r),this.checkPrimes(r),this.checkMathAccent(r)}getOperatorDef(t){const[e,s,i]=this.handleExplicitForm(this.getForms());this.attributes.setInherited("form",e);const r=this.constructor,n=r.OPTABLE,o=n[e][t]||n[s][t]||n[i][t];if(o)return o;this.setProperty("noDictDef",!0);const a=this.attributes.get("movablelimits");if((!!t.match(r.opPattern)||a)&&void 0===this.getProperty("texClass"))return Rr(1,2,mr.OP);const l=Ir(t),[c,h]=r.MMLSPACING[l[2]];return Rr(c,h,l[2])}checkOperatorTable(t){const e=this.getOperatorDef(t);void 0===this.getProperty("texClass")&&(this.texClass=e[2]);for(const t of Object.keys(e[3]||{}))this.attributes.setInherited(t,e[3][t]);this.lspace=e[0]/18,this.rspace=e[1]/18}getForms(){let t=null,e=this.parent,s=this.Parent;for(;s&&s.isEmbellished;)t=e,e=s.parent,s=s.Parent;if(t=t||this,e&&e.isKind("mrow")&&1!==e.nonSpaceLength()){if(e.firstNonSpace()===t)return["prefix","infix","postfix"];if(e.lastNonSpace()===t)return["postfix","infix","prefix"]}return["infix","prefix","postfix"]}handleExplicitForm(t){if(this.attributes.isSet("form")){const e=this.attributes.get("form");t=[e].concat(t.filter(t=>t!==e))}return t}checkPseudoScripts(t){const e=this.constructor.pseudoScripts;if(!t.match(e))return;const s=this.coreParent().Parent,i=!s||!(s.isKind("msubsup")&&!s.isKind("msub"));this.setProperty("pseudoscript",i),i&&(this.attributes.setInherited("lspace",0),this.attributes.setInherited("rspace",0))}checkPrimes(t){const e=this.constructor.primes;if(!t.match(e))return;const s=this.constructor.remapPrimes,i=jr(Fr(t).map(t=>s[t]));this.setProperty("primes",i)}checkMathAccent(t){const e=this.Parent;if(void 0!==this.getProperty("mathaccent")||!e||!e.isKind("munderover"))return;const[s,i,r]=e.childNodes;if(s.isEmbellished&&s.coreMO()===this)return;const n=!(!i||!i.isEmbellished||i.coreMO()!==this),o=!(!r||!r.isEmbellished||i.coreMO()!==this);(n||o)&&(this.isMathAccent(t)?this.setProperty("mathaccent",!0):this.isMathAccentWithWidth(t)&&this.setProperty("mathaccent",!1))}isMathAccent(t=this.getText()){const e=this.constructor.mathaccents;return!!t.match(e)}isMathAccentWithWidth(t=this.getText()){const e=this.constructor.mathaccentsWithWidth;return!!t.match(e)}}zr.defaults=Object.assign(Object.assign({},Nr.defaults),{form:"infix",fence:!1,separator:!1,lspace:"thickmathspace",rspace:"thickmathspace",stretchy:!1,symmetric:!1,maxsize:"infinity",minsize:"0em",largeop:!1,movablelimits:!1,accent:!1,linebreak:"auto",lineleading:"100%",linebreakstyle:"before",indentalign:"auto",indentshift:"0",indenttarget:"",indentalignfirst:"indentalign",indentshiftfirst:"indentshift",indentalignlast:"indentalign",indentshiftlast:"indentshift"}),zr.MMLSPACING=Or,zr.OPTABLE=Dr,zr.pseudoScripts=new RegExp(["^[\"'*`","\xaa","\xb0","\xb2-\xb4","\xb9","\xba","\u2018-\u201f","\u2032-\u2037\u2057","\u2070\u2071","\u2074-\u207f","\u2080-\u208e","]+$"].join("")),zr.primes=new RegExp(["^[\"'","\u2018-\u201f","]+$"].join("")),zr.opPattern=/^[a-zA-Z]{2,}$/,zr.remapPrimes={34:8243,39:8242,8216:8245,8217:8242,8218:8242,8219:8245,8220:8246,8221:8243,8222:8243,8223:8246},zr.mathaccents=new RegExp(["^[","\xb4\u0301\u02ca","`\u0300\u02cb","\xa8\u0308","~\u0303\u02dc","\xaf\u0304\u02c9","\u02d8\u0306","\u02c7\u030c","^\u0302\u02c6","\u20d0\u20d1","\u20d6\u20d7\u20e1","\u02d9\u0307","\u02da\u030a","\u20db","\u20dc","]$"].join("")),zr.mathaccentsWithWidth=new RegExp(["^[","\u2190\u2192\u2194","\u23dc\u23dd","\u23de\u23df","]$"].join(""));class Vr extends Nr{constructor(){super(...arguments),this.texclass=mr.ORD}get kind(){return"mtext"}get isSpacelike(){return!!this.getText().match(/^\s*$/)&&!this.attributes.hasOneOf(Vr.NONSPACELIKE)}}Vr.NONSPACELIKE=["style","mathbackground","background"],Vr.defaults=Object.assign({},Nr.defaults);class Xr extends Nr{constructor(){super(...arguments),this.texclass=mr.NONE}setTeXclass(t){return t}get kind(){return"mspace"}get arity(){return 0}get isSpacelike(){return!this.attributes.hasExplicit("linebreak")&&this.canBreak}get hasNewline(){const t=this.attributes.get("linebreak");return this.canBreak&&("newline"===t||"indentingnewline"===t)}get canBreak(){return!this.attributes.hasOneOf(Xr.NONSPACELIKE)&&"-"!==String(this.attributes.get("width")).trim().charAt(0)}}Xr.NONSPACELIKE=["height","depth","style","mathbackground","background"],Xr.defaults=Object.assign(Object.assign({},Nr.defaults),{width:"0em",height:"0ex",depth:"0ex",linebreak:"auto",indentshift:"auto",indentalign:"auto",indenttarget:"",indentalignfirst:"indentalign",indentshiftfirst:"indentshift",indentalignlast:"indentalign",indentshiftlast:"indentshift"});class Gr extends Nr{constructor(){super(...arguments),this.texclass=mr.ORD}get kind(){return"ms"}}Gr.defaults=Object.assign(Object.assign({},Nr.defaults),{lquote:'"',rquote:'"'});class Jr extends yr{constructor(){super(...arguments),this._core=null}get kind(){return"mrow"}get isSpacelike(){for(const t of this.childNodes)if(!t.isSpacelike)return!1;return!0}get isEmbellished(){let t=!1,e=0;for(const s of this.childNodes){if(s)if(s.isEmbellished){if(t)return!1;t=!0,this._core=e}else if(!s.isSpacelike)return!1;e++}return t}core(){return this.isEmbellished&&null!=this._core?this.childNodes[this._core]:this}coreMO(){return this.isEmbellished&&null!=this._core?this.childNodes[this._core].coreMO():this}nonSpaceLength(){let t=0;for(const e of this.childNodes)e&&!e.isSpacelike&&t++;return t}firstNonSpace(){for(const t of this.childNodes)if(t&&!t.isSpacelike)return t;return null}lastNonSpace(){let t=this.childNodes.length;for(;--t>=0;){const e=this.childNodes[t];if(e&&!e.isSpacelike)return e}return null}setTeXclass(t){if(null!=this.getProperty("open")||null!=this.getProperty("close")){this.getPrevClass(t),t=null;for(const e of this.childNodes)t=e.setTeXclass(t);return null==this.texClass&&(this.texClass=mr.INNER),this}for(const e of this.childNodes)t=e.setTeXclass(t);return this.childNodes[0]&&this.updateTeXclass(this.childNodes[0]),t}}Jr.defaults=Object.assign({},yr.defaults);class Kr extends Jr{get kind(){return"inferredMrow"}get isInferred(){return!0}get notParent(){return!0}toString(){return"["+this.childNodes.join(",")+"]"}}Kr.defaults=Jr.defaults;class $r extends Tr{get kind(){return"mfrac"}get arity(){return 2}get linebreakContainer(){return!0}get linebreakAlign(){return""}setTeXclass(t){this.getPrevClass(t);for(const t of this.childNodes)t.setTeXclass(null);return this}setChildInheritedAttributes(t,e,s,i){(!e||s>0)&&s++;const r=this.attributes.get("numalign"),n=this.attributes.get("denomalign"),o=this.addInheritedAttributes(Object.assign({},t),{numalign:r,indentshift:"0",indentalignfirst:r,indentshiftfirst:"0",indentalignlast:"indentalign",indentshiftlast:"indentshift"}),a=this.addInheritedAttributes(Object.assign({},t),{denalign:n,indentshift:"0",indentalignfirst:n,indentshiftfirst:"0",indentalignlast:"indentalign",indentshiftlast:"indentshift"});this.childNodes[0].setInheritedAttributes(o,!1,s,i),this.childNodes[1].setInheritedAttributes(a,!1,s,!0)}}$r.defaults=Object.assign(Object.assign({},Tr.defaults),{linethickness:"medium",numalign:"center",denomalign:"center",bevelled:!1});class Yr extends yr{constructor(){super(...arguments),this.texclass=mr.ORD}get kind(){return"msqrt"}get arity(){return-1}get linebreakContainer(){return!0}setTeXclass(t){return this.getPrevClass(t),this.childNodes[0].setTeXclass(null),this}setChildInheritedAttributes(t,e,s,i){this.childNodes[0].setInheritedAttributes(t,e,s,!0)}}Yr.defaults=Object.assign(Object.assign({},yr.defaults),{"data-vertical-align":"bottom"});class Qr extends yr{constructor(){super(...arguments),this.texclass=mr.ORD}get kind(){return"mroot"}get arity(){return 2}get linebreakContainer(){return!0}setTeXclass(t){return this.getPrevClass(t),this.childNodes[0].setTeXclass(null),this.childNodes[1].setTeXclass(null),this}setChildInheritedAttributes(t,e,s,i){this.childNodes[0].setInheritedAttributes(t,e,s,!0),this.childNodes[1].setInheritedAttributes(t,!1,s+2,i)}}Qr.defaults=Object.assign(Object.assign({},yr.defaults),{"data-vertical-align":"bottom"});class Zr extends vr{get kind(){return"mstyle"}get notParent(){return this.childNodes[0]&&1===this.childNodes[0].childNodes.length}setInheritedAttributes(t={},e=!1,s=0,i=!1){this.attributes.setInherited("displaystyle",e),this.attributes.setInherited("scriptlevel",s),super.setInheritedAttributes(t,e,s,i)}setChildInheritedAttributes(t,e,s,i){let r=this.attributes.getExplicit("scriptlevel");null!=r&&(r=r.toString(),r.match(/^\s*[-+]/)?s+=parseInt(r):s=parseInt(r),i=!1);const n=this.attributes.getExplicit("displaystyle");null!=n&&(e=!0===n,i=!1);const o=this.attributes.getExplicit("data-cramped");null!=o&&(i=o),t=this.addInheritedAttributes(t,this.attributes.getAllAttributes()),this.childNodes[0].setInheritedAttributes(t,e,s,i)}}Zr.defaults=Object.assign(Object.assign({},vr.defaults),{scriptlevel:hr,displaystyle:hr,scriptsizemultiplier:1/Math.sqrt(2),scriptminsize:".4em",mathbackground:hr,mathcolor:hr,dir:hr,infixlinebreakstyle:"before"});class tn extends yr{constructor(){super(...arguments),this.texclass=mr.ORD}get kind(){return"merror"}get arity(){return-1}get linebreakContainer(){return!0}}tn.defaults=Object.assign({},yr.defaults);class en extends vr{get kind(){return"mpadded"}get linebreakContainer(){return!0}setTeXclass(t){return this.getProperty("vbox")?(this.getPrevClass(t),this.texClass=mr.ORD,this.childNodes[0].setTeXclass(null),this):super.setTeXclass(t)}}en.defaults=Object.assign(Object.assign({},vr.defaults),{width:"",height:"",depth:"",lspace:0,voffset:0});class sn extends vr{constructor(){super(...arguments),this.texclass=mr.ORD}get kind(){return"mphantom"}}sn.defaults=Object.assign({},vr.defaults);class rn extends yr{constructor(){super(...arguments),this.texclass=mr.INNER,this.separators=[],this.open=null,this.close=null}get kind(){return"mfenced"}setTeXclass(t){this.getPrevClass(t),this.open&&(t=this.open.setTeXclass(t)),this.childNodes[0]&&(t=this.childNodes[0].setTeXclass(t));for(let e=1,s=this.childNodes.length;ethis.childNodes.length&&(t=1),this.attributes.set("selection",t)}setChildInheritedAttributes(t,e,s,i){var r,n;"tooltip"===this.attributes.get("actiontype").toLowerCase()?(null===(r=this.childNodes[0])||void 0===r||r.setInheritedAttributes(t,e,s,i),null===(n=this.childNodes[1])||void 0===n||n.setInheritedAttributes(t,!1,1,!1)):super.setChildInheritedAttributes(t,e,s,i)}}on.defaults=Object.assign(Object.assign({},yr.defaults),{actiontype:"toggle",selection:1});class an extends Tr{get kind(){return"msubsup"}get arity(){return 3}get base(){return 0}get sub(){return 1}get sup(){return 2}setChildInheritedAttributes(t,e,s,i){const r=this.childNodes;r[0].setInheritedAttributes(t,e,s,i),r[1].setInheritedAttributes(t,!1,s+1,i||1===this.sub),r[2]&&r[2].setInheritedAttributes(t,!1,s+1,i||2===this.sub)}}an.defaults=Object.assign(Object.assign({},Tr.defaults),{subscriptshift:"",superscriptshift:""});class ln extends an{get kind(){return"msub"}get arity(){return 2}}ln.defaults=Object.assign({},an.defaults);class cn extends an{get kind(){return"msup"}get arity(){return 2}get sup(){return 1}get sub(){return 2}}cn.defaults=Object.assign({},an.defaults);class hn extends Tr{get kind(){return"munderover"}get arity(){return 3}get base(){return 0}get under(){return 1}get over(){return 2}get linebreakContainer(){return!0}setChildInheritedAttributes(t,e,s,i){const r=this.childNodes;r[0].setInheritedAttributes(t,e,s,i||!!r[this.over]);const n=!(e||!r[0].coreMO().attributes.get("movablelimits")),o=this.constructor.ACCENTS;r[1].setInheritedAttributes(t,!1,this.getScriptlevel(o[1],n,s),i||1===this.under),this.setInheritedAccent(1,o[1],e,s,i,n),r[2]&&(r[2].setInheritedAttributes(t,!1,this.getScriptlevel(o[2],n,s),i||2===this.under),this.setInheritedAccent(2,o[2],e,s,i,n))}getScriptlevel(t,e,s){return!e&&this.attributes.get(t)||s++,s}setInheritedAccent(t,e,s,i,r,n){const o=this.childNodes[t];if(!this.attributes.hasExplicit(e)&&o.isEmbellished){const t=o.coreMO().attributes.get("accent");this.attributes.setInherited(e,t),t!==this.attributes.getDefault(e)&&o.setInheritedAttributes({},s,this.getScriptlevel(e,n,i),r)}}}hn.defaults=Object.assign(Object.assign({},Tr.defaults),{accent:!1,accentunder:!1,align:"center"}),hn.ACCENTS=["","accentunder","accent"];class dn extends hn{get kind(){return"munder"}get arity(){return 2}}dn.defaults=Object.assign({},hn.defaults);class un extends hn{get kind(){return"mover"}get arity(){return 2}get over(){return 1}get under(){return 2}}un.defaults=Object.assign({},hn.defaults),un.ACCENTS=["","accent","accentunder"];class pn extends an{get kind(){return"mmultiscripts"}get arity(){return 1}setChildInheritedAttributes(t,e,s,i){this.childNodes[0].setInheritedAttributes(t,e,s,i);let r=!1;for(let e=1,n=0;e...`}verifyTree(t){!this.parent||this.parent.isToken||this.mError("HTML can only be a child of a token element",t,!0)}}const An={[_r.prototype.kind]:_r,[Lr.prototype.kind]:Lr,[Ar.prototype.kind]:Ar,[zr.prototype.kind]:zr,[Vr.prototype.kind]:Vr,[Xr.prototype.kind]:Xr,[Gr.prototype.kind]:Gr,[Jr.prototype.kind]:Jr,[Kr.prototype.kind]:Kr,[$r.prototype.kind]:$r,[Yr.prototype.kind]:Yr,[Qr.prototype.kind]:Qr,[Zr.prototype.kind]:Zr,[tn.prototype.kind]:tn,[en.prototype.kind]:en,[sn.prototype.kind]:sn,[rn.prototype.kind]:rn,[nn.prototype.kind]:nn,[on.prototype.kind]:on,[ln.prototype.kind]:ln,[cn.prototype.kind]:cn,[an.prototype.kind]:an,[dn.prototype.kind]:dn,[un.prototype.kind]:un,[hn.prototype.kind]:hn,[pn.prototype.kind]:pn,[mn.prototype.kind]:mn,[fn.prototype.kind]:fn,[gn.prototype.kind]:gn,[En.prototype.kind]:En,[bn.prototype.kind]:bn,[xn.prototype.kind]:xn,[yn.prototype.kind]:yn,[Nn.prototype.kind]:Nn,[vn.prototype.kind]:vn,[Tn.prototype.kind]:Tn,[Cn.prototype.kind]:Cn,[wn.prototype.kind]:wn,[kn.prototype.kind]:kn,[_n.prototype.kind]:_n,[Cr.prototype.kind]:Cr,[kr.prototype.kind]:kr,[Ln.prototype.kind]:Ln};class Rn extends cr{get MML(){return this.node}}Rn.defaultNodes=An;class Sn{constructor(){this.bits=0}static allocate(...t){for(const e of t){if(this.has(e))throw new Error("Bit already allocated for "+e);if(this.next===Sn.MAXBIT)throw new Error("Maximum number of bits already allocated");this.names.set(e,this.next),this.next<<=1}}static has(t){return this.names.has(t)}set(t){this.bits|=this.getBit(t)}clear(t){this.bits&=~this.getBit(t)}isSet(t){return!!(this.bits&this.getBit(t))}reset(){this.bits=0}getBit(t){const e=this.constructor.names.get(t);if(!e)throw new Error("Unknown bit-field name: "+t);return e}}function Mn(...t){const e=class extends Sn{};return e.allocate(...t),e}function In(t){return new Promise(function e(s,i){const r=t=>{var r;t.retry instanceof Promise?t.retry.then(()=>e(s,i)).catch(t=>i(t)):(null===(r=t.restart)||void 0===r?void 0:r.isCallback)?MathJax.Callback.After(()=>e(s,i),t.restart):i(t)};try{const e=t();e instanceof Promise?e.then(t=>s(t)).catch(t=>r(t)):s(e)}catch(t){r(t)}})}function On(t){const e=new Error("MathJax retry -- an asynchronous action is required; try using one of the promise-based functions and await its resolution.");throw e.retry=t,e}Sn.MAXBIT=1<<31,Sn.next=1,Sn.names=new Map;var Dn=function(t,e,s,i){return new(s||(s=Promise))(function(r,n){function o(t){try{l(i.next(t))}catch(t){n(t)}}function a(t){try{l(i.throw(t))}catch(t){n(t)}}function l(t){var e;t.done?r(t.value):(e=t.value,e instanceof s?e:new s(function(t){t(e)})).then(o,a)}l((i=i.apply(t,e||[])).next())})};class Pn extends fi{static create(t){const e=new this;for(const s of Object.keys(t)){const[i,r]=this.action(s,t[s]);r&&e.add(i,r)}return e}static action(t,e){let s,i,r=!0;const n=e[0];if(1===e.length||"boolean"==typeof e[1])2===e.length&&(r=e[1]),[s,i]=this.methodActions(t);else if("string"==typeof e[1])if("string"==typeof e[2]){4===e.length&&(r=e[3]);const[t,n]=e.slice(1);[s,i]=this.methodActions(t,n)}else 3===e.length&&(r=e[2]),[s,i]=this.methodActions(e[1]);else 4===e.length&&(r=e[3]),[s,i]=e.slice(1);return[{id:t,renderDoc:s,renderMath:i,convert:r},n]}static methodActions(t,e=t){return[e=>(t&&e[t](),!1),(t,s)=>(e&&t[e](s),!1)]}renderDoc(t,e=or.UNPROCESSED){for(const s of this.items)if(s.priority>=e&&s.item.renderDoc(t))return}renderMath(t,e,s=or.UNPROCESSED){for(const i of this.items)if(i.priority>=s&&i.item.renderMath(t,e))return}renderConvert(t,e,s=or.LAST){for(const i of this.items){if(i.priority>s)return;if(i.item.convert&&i.item.renderMath(t,e))return}}findID(t){for(const e of this.items)if(e.item.id===t)return e.item;return null}}const Bn={all:!1,processed:!1,inputJax:null,outputJax:null},Fn={all:!0,processed:!0,inputJax:[],outputJax:[]};class jn extends Qi{compile(t){return null}}class Un extends Zi{typeset(t,e=null){return null}escaped(t,e){return null}}class Hn extends ir{}class qn{constructor(t,e,s){const i=this.constructor;this.document=t,this.options=Pi(Di({},i.OPTIONS),s),this.math=new(this.options.MathList||Hn),this.renderActions=Pn.create(this.options.renderActions),this._actionPromises=[],this._readyPromise=Promise.resolve(),this.processed=new qn.ProcessBits,this.outputJax=this.options.OutputJax||new Un;let r=this.options.InputJax||[new jn];Array.isArray(r)||(r=[r]),this.inputJax=r,this.adaptor=e,this.outputJax.setAdaptor(e),this.inputJax.map(t=>t.setAdaptor(e)),this.mmlFactory=this.options.MmlFactory||new Rn,this.inputJax.map(t=>t.setMmlFactory(this.mmlFactory)),this.outputJax.initialize(),this.inputJax.map(t=>t.initialize())}get kind(){return this.constructor.KIND}addRenderAction(t,...e){const[s,i]=Pn.action(t,e);this.renderActions.add(s,i)}removeRenderAction(t){const e=this.renderActions.findID(t);e&&this.renderActions.remove(e)}render(){return this.clearPromises(),this.renderActions.renderDoc(this),this}renderPromise(){return this.whenReady(()=>In(()=>Dn(this,void 0,void 0,function*(){return this.render(),yield this.actionPromises(),this.clearPromises(),this})))}rerender(t=or.RERENDER){return this.state(t-1),this.render(),this}rerenderPromise(t=or.RERENDER){return this.whenReady(()=>In(()=>Dn(this,void 0,void 0,function*(){return this.rerender(t),yield this.actionPromises(),this.clearPromises(),this})))}convert(t,e={}){let{format:s,display:i,end:r,ex:n,em:o,containerWidth:a,scale:l,family:c}=Pi({format:this.inputJax[0].name,display:!0,end:or.LAST,em:16,ex:8,containerWidth:null,scale:1,family:""},e);null===a&&(a=80*n);const h=this.inputJax.reduce((t,e)=>e.name===s?e:t,null),d=new this.options.MathItem(t,h,i);return d.start.node=this.adaptor.body(this.document),d.setMetrics(o,n,a,l),c&&this.outputJax.options.mtextInheritFont&&(d.outputData.mtextFamily=c),c&&this.outputJax.options.merrorInheritFont&&(d.outputData.merrorFamily=c),this.clearPromises(),d.convert(this,r),d.typesetRoot||d.root}convertPromise(t,e={}){return this.whenReady(()=>In(()=>Dn(this,void 0,void 0,function*(){const s=this.convert(t,e);return yield this.actionPromises(),this.clearPromises(),s})))}whenReady(t){return this._readyPromise=this._readyPromise.catch(t=>{}).then(()=>{const e=this._readyPromise;this._readyPromise=Promise.resolve();const s=t(),i=this._readyPromise.then(()=>s);return this._readyPromise=e,i})}actionPromises(){return Promise.all(this._actionPromises)}clearPromises(){this._actionPromises=[]}savePromise(t){this._actionPromises.push(t)}findMath(t=null){return this.processed.set("findMath"),this}compile(){if(!this.processed.isSet("compile")){const t=[];for(const e of this.math)this.compileMath(e),void 0!==e.inputData.recompile&&t.push(e);for(const e of t){const t=e.inputData.recompile;e.state(t.state),e.inputData.recompile=t,this.compileMath(e)}this.processed.set("compile")}return this}compileMath(t){try{t.compile(this)}catch(e){if(e.retry||e.restart)throw e;this.options.compileError(this,t,e),t.inputData.error=e}}compileError(t,e){t.root=this.mmlFactory.create("math",null,[this.mmlFactory.create("merror",{"data-mjx-error":e.message,title:e.message},[this.mmlFactory.create("mtext",null,[this.mmlFactory.create("text").setText("Math input error")])])]),t.display&&t.root.attributes.set("display","block"),t.inputData.error=e.message}typeset(){if(!this.processed.isSet("typeset")){for(const t of this.math)try{t.typeset(this)}catch(e){if(e.retry||e.restart)throw e;this.options.typesetError(this,t,e),t.outputData.error=e}this.processed.set("typeset")}return this}typesetError(t,e){t.typesetRoot=this.adaptor.node("mjx-container",{class:"MathJax mjx-output-error",jax:this.outputJax.name},[this.adaptor.node("span",{"data-mjx-error":e.message,title:e.message,style:{color:"red","background-color":"yellow","line-height":"normal"}},[this.adaptor.text("Math output error")])]),t.display&&this.adaptor.setAttributes(t.typesetRoot,{style:{display:"block",margin:"1em 0","text-align":"center"}}),t.outputData.error=e.message}getMetrics(){return this.processed.isSet("getMetrics")||(this.outputJax.getMetrics(this),this.processed.set("getMetrics")),this}updateDocument(){if(!this.processed.isSet("updateDocument")){for(const t of this.math.reversed())t.updateDocument(this);this.processed.set("updateDocument")}return this}removeFromDocument(t=!1){return this}state(t,e=!1){for(const s of this.math)s.state(t,e);return te.reset(...t.inputJax)),t.outputJax&&this.outputJax.reset(...t.outputJax),this}clear(){return this.reset(),this.math.clear(),this}done(){return Promise.resolve()}concat(t){return this.math.merge(t),this}clearMathItemsWithin(t){const e=this.getMathItemsWithin(t);for(const t of e.slice(0).reverse())t.clear();return this.math.remove(...e),e}getMathItemsWithin(t){Array.isArray(t)||(t=[t]);const e=this.adaptor,s=[],i=e.getElements(t,this.document);t:for(const t of this.math)for(const r of i)if(t.start.node&&e.contains(r,t.start.node)){s.push(t);continue t}return s}}qn.KIND="MathDocument",qn.OPTIONS={OutputJax:null,InputJax:null,MmlFactory:null,MathList:Hn,MathItem:class extends nr{},compileError:(t,e,s)=>{t.compileError(e,s)},typesetError:(t,e,s)=>{t.typesetError(e,s)},renderActions:Ri({find:[or.FINDMATH,"findMath","",!1],compile:[or.COMPILED],metrics:[or.METRICS,"getMetrics","",!1],typeset:[or.TYPESET],update:[or.INSERTED,"updateDocument",!1]})},qn.ProcessBits=Mn("findMath","compile","getMetrics","typeset","updateDocument");class Wn extends qn{}class zn{constructor(t,e=5){this.documentClass=Wn,this.adaptor=t,this.priority=e}get name(){return this.constructor.NAME}handlesDocument(t){return!1}create(t,e){return new this.documentClass(t,this.adaptor,e)}}zn.NAME="generic";class Vn extends fi{register(t){return this.add(t,t.priority)}unregister(t){this.remove(t)}handlesDocument(t){for(const e of this){const s=e.item;if(s.handlesDocument(t))return s}throw new Error("Can't find handler for document")}document(t,e=null){return this.handlesDocument(t).create(t,e)}}class Xn{static methodName(t){return"visit"+(t.charAt(0).toUpperCase()+t.substring(1)).replace(/[^a-z0-9_]/gi,"_")+"Node"}constructor(t){this.nodeHandlers=new Map;for(const e of t.getKinds()){const t=this[Xn.methodName(e)];t&&this.nodeHandlers.set(e,t)}}visitTree(t,...e){return this.visitNode(t,...e)}visitNode(t,...e){return(this.nodeHandlers.get(t.kind)||this.visitDefault).call(this,t,...e)}visitDefault(t,...e){if("childNodes"in t)for(const s of t.childNodes)this.visitNode(s,...e)}setNodeHandler(t,e){this.nodeHandlers.set(t,e)}removeNodeHandler(t){this.nodeHandlers.delete(t)}}const Gn="data-mjx-";class Jn extends Xn{constructor(t=null){t||(t=new Rn),super(t)}visitTextNode(t,...e){}visitXMLNode(t,...e){}visitHtmlNode(t,...e){}getKind(t){const e=t.kind;return Ui(e,this.constructor.rename,e)}getAttributeList(t){const e=this.constructor,s=Ui(t.kind,e.defaultAttributes,{}),i=Object.assign({},s,this.getDataAttributes(t),t.attributes.getAllAttributes()),r=e.variants;return Object.hasOwn(i,"mathvariant")&&(Object.hasOwn(r,i.mathvariant)?i.mathvariant=r[i.mathvariant]:t.getProperty("ignore-variant")&&delete i.mathvariant),i}getDataAttributes(t){const e={},s=t.attributes.getExplicit("mathvariant"),i=this.constructor.variants;s&&(t.getProperty("ignore-variant")||Object.hasOwn(i,s))&&this.setDataAttribute(e,"variant",s),t.getProperty("variantForm")&&this.setDataAttribute(e,"alternate","1"),t.getProperty("pseudoscript")&&this.setDataAttribute(e,"pseudoscript","true"),!1===t.getProperty("autoOP")&&this.setDataAttribute(e,"auto-op","false");const r=t.getProperty("vbox");r&&this.setDataAttribute(e,"vbox",r);const n=t.getProperty("scriptalign");n&&this.setDataAttribute(e,"script-align",n);const o=t.getProperty("mathaccent");void 0!==o&&(o&&!t.isMathAccent()||!o&&!t.isMathAccentWithWidth())&&this.setDataAttribute(e,"mathaccent",o.toString());const a=t.getProperty("texClass");if(void 0!==a){let s=!0;if(a===mr.OP&&t.isKind("mi")){const e=t.getText();s=!(e.length>1&&e.match(Lr.operatorName))}s&&this.setDataAttribute(e,"texclass",a<0?"NONE":fr[a])}return t.getProperty("smallmatrix")&&this.setDataAttribute(e,"smallmatrix","true"),e}setDataAttribute(t,e,s){t[Gn+e]=s}}Jn.rename={TeXAtom:"mrow"},Jn.variants={"-tex-calligraphic":"script","-tex-bold-calligraphic":"bold-script","-tex-oldstyle":"normal","-tex-bold-oldstyle":"bold","-tex-mathit":"italic"},Jn.defaultAttributes={math:{xmlns:"http://www.w3.org/1998/Math/MathML"}};class Kn extends Jn{constructor(){super(...arguments),this.document=null}visitTree(t,e){this.document=e;const s=e.createElement("top");return this.visitNode(t,s),this.document=null,s.firstChild}visitTextNode(t,e){e.appendChild(this.document.createTextNode(t.getText()))}visitXMLNode(t,e){e.appendChild(t.getXML().cloneNode(!0))}visitHtmlNode(t,e){e.appendChild(t.getHTML().cloneNode(!0))}visitInferredMrowNode(t,e){for(const s of t.childNodes)this.visitNode(s,e)}visitDefault(t,e){const s=this.document.createElement(this.getKind(t));this.addAttributes(t,s);for(const e of t.childNodes)this.visitNode(e,s);e.appendChild(s)}addAttributes(t,e){const s=this.getAttributeList(t);for(const t of Object.keys(s))e.setAttribute(t,s[t].toString())}}class $n extends Jn{visitTree(t){return this.visitNode(t,"")}visitTextNode(t,e){return this.quoteHTML(t.getText())}visitXMLNode(t,e){return e+t.getSerializedXML()}visitHtmlNode(t,e){return t.getSerializedHTML()}visitInferredMrowNode(t,e){const s=[];for(const i of t.childNodes)s.push(this.visitNode(i,e));return s.join("\n")}visitAnnotationNode(t,e){const s=this.childNodeMml(t,"","");return`${e}${s}`}visitDefault(t,e){const s=this.getKind(t),[i,r]=t.isToken||0===t.childNodes.length?["",""]:["\n",e],n=this.childNodeMml(t,e+"  ",i),o=n.match(/\S/)?i+n+r:"";return`${e}<${s}${this.getAttributes(t)}>${o}`}childNodeMml(t,e,s){let i="";for(const r of t.childNodes)i+=this.visitNode(r,e)+s;return i}getAttributes(t){const e=[],s=this.getAttributeList(t);for(const t of Object.keys(s)){const i=String(s[t]);void 0!==i&&e.push(t+'="'+this.quoteHTML(i)+'"')}return e.length?" "+e.join(" "):""}quoteHTML(t){return t.replace(/&/g,"&").replace(//g,">").replace(/"/g,""").replace(/[\uD800-\uDBFF]./g,this.toEntity).replace(/[\u0080-\uD7FF\uE000-\uFFFF]/g,this.toEntity)}toEntity(t){return Wr(t)}}class Yn{get kind(){return this.node.kind}constructor(t,e){this.factory=t,this.node=e}wrap(t){return this.factory.wrap(t)}walkTree(t,e){if(t(this,e),"childNodes"in this)for(const s of this.childNodes)s&&s.walkTree(t,e);return e}}class Qn extends lr{wrap(t,...e){return this.create(t.kind,t,...e)}}const Zn={version:ii,context:ui,handlers:new Vn,document:function(t,e){return Zn.handlers.document(t,e)},handleRetriesFor:In,retryAfter:On,asyncLoad:null,asyncIsSynchronous:!1};class to extends nr{get adaptor(){return this.inputJax.adaptor}constructor(t,e,s=!0,i={node:null,n:0,delim:""},r={node:null,n:0,delim:""}){super(t,e,s,i,r)}updateDocument(t){if(this.state()=or.TYPESET){const e=this.adaptor,s=this.start.node;let i=e.text("");if(t){const t=this.start.delim+this.math+this.end.delim;if(this.inputJax.processStrings)i=e.text(t);else{const s=e.parse(t,"text/html");i=e.firstChild(e.body(s))}}e.parent(s)&&e.replace(i,s),this.start.node=this.end.node=i,this.start.n=this.end.n=0}}}class eo extends ir{}class so{constructor(t=null){const e=this.constructor;this.options=Pi(Di({},e.OPTIONS),t),this.init(),this.getPatterns()}init(){this.strings=[],this.string="",this.snodes=[],this.nodes=[],this.stack=[]}getPatterns(){const t=Si(this.options.skipHtmlTags),e=Si(this.options.ignoreHtmlClass),s=Si(this.options.processHtmlClass);this.skipHtmlTags=new RegExp("^(?:"+t.join("|")+")$","i"),this.ignoreHtmlClass=new RegExp("(?:^| )(?:"+e.join("|")+")(?: |$)"),this.processHtmlClass=new RegExp("(?:^| )(?:"+s+")(?: |$)")}pushString(){this.string.match(/\S/)&&(this.strings.push(this.string),this.nodes.push(this.snodes)),this.string="",this.snodes=[]}extendString(t,e){this.snodes.push([t,e.length]),this.string+=e}handleText(t,e){return e||this.extendString(t,this.adaptor.value(t)),this.adaptor.next(t)}handleTag(t,e){if(!e){const e=this.options.includeHtmlTags[this.adaptor.kind(t)];e instanceof Function?this.extendString(t,e(t,this.adaptor)):this.extendString(t,e)}return this.adaptor.next(t)}handleContainer(t,e){this.pushString();const s=this.adaptor.getAttribute(t,"class")||"",i=this.adaptor.kind(t)||"",r=this.processHtmlClass.exec(s);let n=t;return!this.adaptor.firstChild(t)||this.adaptor.getAttribute(t,"data-MJX")||!r&&this.skipHtmlTags.exec(i)?n=this.adaptor.next(t):(this.adaptor.next(t)&&this.stack.push([this.adaptor.next(t),e]),n=this.adaptor.firstChild(t),e=(e||this.ignoreHtmlClass.exec(s))&&!r),[n,e]}handleOther(t,e){return this.pushString(),this.adaptor.next(t)}find(t){this.init();const e=this.adaptor.next(t);let s=!1;const i=this.options.includeHtmlTags;for(;t&&t!==e;){const e=this.adaptor.kind(t);"#text"===e?t=this.handleText(t,s):Object.hasOwn(i,e)?t=this.handleTag(t,s):e?[t,s]=this.handleContainer(t,s):t=this.handleOther(t,s),!t&&this.stack.length&&(this.pushString(),[t,s]=this.stack.pop())}this.pushString();const r=[this.strings,this.nodes];return this.init(),r}}so.OPTIONS={skipHtmlTags:["script","noscript","style","textarea","pre","code","math","select","option","mjx-container"],includeHtmlTags:Ri({br:"\n",wbr:"","#comment":""}),ignoreHtmlClass:"mathjax_ignore",processHtmlClass:"mathjax_process"},ar("STYLES",or.INSERTED+1);class io extends qn{constructor(t,e,s){const[i,r]=ji(s,so.OPTIONS);super(t,e,i),this.domStrings=this.options.DomStrings||new so(r),this.domStrings.adaptor=e,this.styles=[]}findPosition(t,e,s,i){const r=this.adaptor,n=1/(i[t].length||1);let o=t;for(const[a,l]of i[t]){if(e<=l&&"#text"===r.kind(a))return{i:o,node:a,n:Math.max(e,0),delim:s};e-=l,o+=n}return{node:null,n:0,delim:s}}mathItem(t,e,s){const i=t.math,r=this.findPosition(t.n,t.start.n,t.open,s),n=this.findPosition(t.n,t.end.n,t.close,s);return new this.options.MathItem(i,e,t.display,r,n)}findMath(t){if(!this.processed.isSet("findMath")){this.adaptor.document=this.document,t=Pi({elements:this.options.elements||[this.adaptor.body(this.document)]},t);const e=this.adaptor.getElements(t.elements,this.document);for(const t of this.inputJax){const s=t.processStrings?this.findMathFromStrings(t,e):this.findMathFromDOM(t,e);this.math.merge(s)}this.processed.set("findMath")}return this}findMathFromStrings(t,e){const s=[],i=[];for(const t of e){const[e,r]=this.domStrings.find(t);s.push(...e),i.push(...r)}const r=new this.options.MathList;for(const e of t.findMath(s))r.push(this.mathItem(e,t,i));return r}findMathFromDOM(t,e){const s=[];for(const i of e)for(const e of t.findMath(i))s.push(new this.options.MathItem(e.math,t,e.display,e.start,e.end));return new this.options.MathList(...s)}updateDocument(){return this.processed.isSet("updateDocument")||(this.addPageElements(),this.addStyleSheet(),super.updateDocument(),this.processed.set("updateDocument")),this}addPageElements(){const t=this.adaptor,e=t.body(this.document),s=this.documentPageElements();if(s){const i=t.firstChild(e);i?t.insert(s,i):t.append(e,s)}}addStyleSheet(){const t=this.documentStyleSheet(),e=this.adaptor;if(t&&!e.parent(t)){const s=e.head(this.document),i=this.findSheet(s,e.getAttribute(t,"id"));i?e.replace(t,i):e.append(s,t)}}findSheet(t,e){if(e)for(const s of this.adaptor.tags(t,"style"))if(this.adaptor.getAttribute(s,"id")===e)return s;return null}removeFromDocument(t=!1){if(this.processed.isSet("updateDocument"))for(const e of this.math)e.state()>=or.INSERTED&&e.state(or.TYPESET,t);return this.processed.clear("updateDocument"),this}documentStyleSheet(){return this.outputJax.styleSheet(this)}documentPageElements(){return this.outputJax.pageElements(this)}addStyles(t){this.styles.push(t),"insertStyles"in this.outputJax&&this.outputJax.insertStyles(t)}getStyles(){return this.styles}}io.KIND="HTML",io.OPTIONS=Object.assign(Object.assign({},qn.OPTIONS),{renderActions:Ri(Object.assign(Object.assign({},qn.OPTIONS.renderActions),{styles:[or.STYLES,"","updateStyleSheet",!1]})),MathList:eo,MathItem:to,DomStrings:null});class ro extends zn{constructor(){super(...arguments),this.documentClass=io}handlesDocument(t){const e=this.adaptor;if("string"==typeof t)try{t=e.parse(t,"text/html")}catch(t){}return t instanceof e.window.Document||t instanceof e.window.HTMLElement||t instanceof e.window.DocumentFragment}create(t,e){const s=this.adaptor;if("string"==typeof t)t=s.parse(t,"text/html");else if(t instanceof s.window.HTMLElement||t instanceof s.window.DocumentFragment){const e=t;t=s.parse("","text/html"),s.append(s.body(t),e)}return super.create(t,e)}}function no(t){const e=new ro(t);return Zn.handlers.register(e),e}class oo{get cssText(){return this.getStyleString()}constructor(t=null){this.styles={},this.addStyles(t)}addStyles(t){if(t)for(const e of Object.keys(t))this.styles[e]||(this.styles[e]={}),Object.assign(this.styles[e],t[e])}removeStyles(...t){for(const e of t)delete this.styles[e]}clear(){this.styles={}}getStyleString(){return this.getStyleRules().join("\n\n")}getStyleRules(t=this.styles,e=""){const s=Object.keys(t),i=new Array(s.length);let r=0;for(const n of s){const s=t[n];i[r++]=`${e}${n} {\n${this.getStyleDefString(s,e)}\n${e}}`}return i}getStyleDefString(t,e){const s=Object.keys(t),i=new Array(s.length);let r=0;for(const n of s)i[r++]=t[n]instanceof Object?e+this.getStyleRules({[n]:t[n]},e+"  ").join("\n"+e):"  "+e+n+": "+t[n]+";";return i.join("\n"+e)}}var ao;const lo=!!(null===(ao=ui.window)||void 0===ao?void 0:ao.HTMLDialogElement);class co{constructor(t){this.minW=200,this.minH=80,this.tx=0,this.ty=0,this.dragging=!1,this.events=[["mousemove",this.MouseMove.bind(this)],["mouseup",this.MouseUp.bind(this)]],this.mode="",this.actions={down:{move:t=>{t.dialog.classList.add("mjx-moving")}},move:{move:(t,e)=>[e.x-t.x,e.y-t.y,0,0],top:(t,e)=>[0,(e.y-t.y)/2,0,t.y-e.y],bottom:(t,e)=>[0,(e.y-t.y)/2,0,e.y-t.y],left:(t,e)=>[(e.x-t.x)/2,0,t.x-e.x,0],right:(t,e)=>[(e.x-t.x)/2,0,e.x-t.x,0],topleft:(t,e)=>[(e.x-t.x)/2,(e.y-t.y)/2,t.x-e.x,t.y-e.y],topright:(t,e)=>[(e.x-t.x)/2,(e.y-t.y)/2,e.x-t.x,t.y-e.y],botleft:(t,e)=>[(e.x-t.x)/2,(e.y-t.y)/2,t.x-e.x,e.y-t.y],botright:(t,e)=>[(e.x-t.x)/2,(e.y-t.y)/2,e.x-t.x,e.y-t.y]},up:{move:t=>{t.dialog.classList.remove("mjx-moving")}},keymove:{left:()=>[-5,0,0,0],right:()=>[5,0,0,0],up:()=>[0,-5,0,0],down:()=>[0,5,0,0]},bigmove:{left:()=>[-20,0,0,0],right:()=>[20,0,0,0],up:()=>[0,-20,0,0],down:()=>[0,20,0,0]},keysize:{left:()=>[-3,0,-6,0],right:()=>[3,0,6,0],up:()=>[0,-3,0,-6],down:()=>[0,3,0,6]},bigsize:{left:()=>[-10,0,-20,0],right:()=>[10,0,20,0],up:()=>[0,-10,0,-20],down:()=>[0,10,0,20]}};const{adaptor:e,node:s=null}=t;this.init(e),this.node=s,this.background=lo?null:e.node("mjx-dialog-background"),this.x=this.y=0,this.dragging=!1,this.action="",this.dialog=this.html(t),this.title=this.dialog.firstChild.firstChild.firstChild,this.content=this.dialog.firstChild.firstChild.nextSibling;const i=this.dialog.lastChild;i.addEventListener("click",this.closeDialog.bind(this)),i.addEventListener("keydown",this.actionKey.bind(this,this.closeDialog.bind(this)));const r=this.dialog.lastChild.previousSibling;r.addEventListener("click",this.helpDialog.bind(this,e)),r.addEventListener("keydown",this.actionKey.bind(this,this.helpDialog.bind(this,e))),this.noDrag=Array.from(this.dialog.querySelectorAll('[data-drag="none"]'))}init(t){const e=this.constructor;if(!t.document.head.querySelector("#"+e.styleId)){const s=t.node("style",{id:e.styleId});s.textContent=new oo(e.styles).cssText,t.document.head.append(s)}}html(t){const{title:e,message:s,adaptor:i,styles:r=null,extraNodes:n=[],className:o=co.className}=t;if(r){const t=i.node("style");t.textContent=new oo(r).cssText,n.unshift(t)}const a="mjx-dialog-label-"+co.id++,l=i.node("dialog",{closedby:"any",class:("mjx-dialog "+o).trim()},[i.node("mjx-dialog",{"aria-labeledby":a},[i.node("mjx-title",{},[i.node("h1",{id:a,tabIndex:0})]),i.node("div",{"data-drag":"none",tabIndex:0})]),...n,i.node("mjx-dialog-spacer",{"aria-hidden":!0}),i.node("mjx-dialog-drag",{"data-drag":"top","aria-hidden":!0}),i.node("mjx-dialog-drag",{"data-drag":"bottom","aria-hidden":!0}),i.node("mjx-dialog-drag",{"data-drag":"left","aria-hidden":!0}),i.node("mjx-dialog-drag",{"data-drag":"right","aria-hidden":!0}),i.node("mjx-dialog-drag",{"data-drag":"topleft","aria-hidden":!0}),i.node("mjx-dialog-drag",{"data-drag":"topright","aria-hidden":!0}),i.node("mjx-dialog-drag",{"data-drag":"botleft","aria-hidden":!0}),i.node("mjx-dialog-drag",{"data-drag":"botright","aria-hidden":!0}),i.node("mjx-dialog-help",{class:"mjx-dialog-button","data-drag":"none",tabIndex:0,role:"button","aria-label":"Dialog Help"},[i.node("mjx-dialog-icon",{"aria-hidden":!0},[i.text("?")])]),i.node("mjx-dialog-close",{class:"mjx-dialog-button","data-drag":"none",tabIndex:0,role:"button","aria-label":"Close Dialog Box"},[i.node("mjx-dialog-icon",{"aria-hidden":!0},[i.text("\xd7")])])]);return l.firstChild.firstChild.firstChild.innerHTML=e,l.firstChild.childNodes[1].innerHTML=s,l}attach(){lo?(this.dialog.addEventListener("mousedown",this.MouseDown.bind(this)),this.dialog.addEventListener("keydown",this.KeyDown.bind(this),!0),document.body.append(this.dialog),this.dialog.showModal()):(this.background.addEventListener("mousedown",this.MouseDown.bind(this)),this.background.addEventListener("keydown",this.KeyDown.bind(this),!0),this.dialog.setAttribute("tabindex","0"),this.dialog.addEventListener("click",this.stop),this.background.append(this.dialog),document.body.append(this.background)),ui.window.addEventListener("visibilitychange",this.Visibility.bind(this)),this.minW=Math.min(this.minW,this.dialog.clientWidth-8),this.minH=Math.min(this.minH,this.dialog.clientHeight-this.title.offsetHeight-8),this.title.focus()}dragAction(t,e=null){e&&this.stop(e);const s=this.actions[t][this.action],i=s?s(this,e):null;if(!i)return;let[r,n,o,a]=i;if(o){const t=this.w+o;t>=this.minW?(this.x=null==e?void 0:e.x,this.w=t,this.dialog.style.maxWidth=this.dialog.style.width=t+"px"):r=0}if(a){const t=this.h+a;t>=this.minH+this.title.offsetHeight?(this.y=null==e?void 0:e.y,this.h=t,this.dialog.style.maxHeight=this.dialog.style.height=t+"px"):n=0}(r||n)&&(r&&(this.x=null==e?void 0:e.x,this.tx+=r||0),n&&(this.y=null==e?void 0:e.y,this.ty+=n||0),this.dialog.style.transform=`translate(${this.tx}px, ${this.ty}px)`)}MouseDown(t){const e=t.target;if(!(1!==t.buttons||t.shiftKey||t.metaKey||t.altKey||t.ctrlKey))if(this.inDialog(t)){for(const t of this.noDrag)if(e===t||t.contains(e))return;this.action=e.getAttribute("data-drag")||"move",this.startDrag(t),this.dragAction("down",t)}else this.closeDialog(t)}MouseMove(t){1!==t.buttons&&this.endDrag(),this.dragging&&this.dragAction("move",t)}MouseUp(t){this.dragging&&(this.dragAction("up",t),this.endDrag())}Visibility(){ui.document.hidden&&this.closeDialog()}KeyDown(t){const e=this.constructor.keyActions.get(t.key);e&&e(this,t)}escKey(t){this.closeDialog(t)}aKey(t){(t.ctrlKey||t.metaKey)&&(this.selectAll(),this.stop(t))}mKey(t){this.mode="move"===this.mode?"":"move",this.stop(t)}sKey(t){this.mode="size"===this.mode?"":"size",this.stop(t)}arrowKey(t,e){t.ctrlKey||this.dragging||(this.action=e,this.getWH(),t.altKey||"move"===this.mode?(this.dragAction(t.shiftKey?"bigmove":"keymove"),this.stop(t)):(t.metaKey||"size"===this.mode)&&(this.dragAction(t.shiftKey?"bigsize":"keysize"),this.stop(t)),this.action="")}actionKey(t,e){"Enter"!==e.code&&"Space"!==e.code||t(e)}selectAll(){document.getSelection().selectAllChildren(this.content)}copyToClipboard(){this.selectAll();try{document.execCommand("copy")}catch(t){alert(`Can't copy to clipboard: ${t.message}`)}document.getSelection().removeAllRanges()}startDrag(t){this.x=t.x,this.y=t.y,this.getWH(),this.dragging=!0;const e=this.background||this.dialog;for(const[t,s]of this.events)e.addEventListener(t,s)}getWH(){this.w=this.dialog.clientWidth-8,this.h=this.dialog.clientHeight-8}endDrag(){this.action="",this.dragging=!1;const t=this.background||this.dialog;for(const[e,s]of this.events)t.removeEventListener(e,s)}closeDialog(t){var e;lo?(this.dialog.close(),this.dialog.remove()):this.background.remove(),null===(e=this.node)||void 0===e||e.focus(),t&&this.stop(t)}helpDialog(t,e){new co({title:"MathJax Dialog Help",message:this.constructor.helpMessage,adaptor:t,className:"mjx-dialog-help",styles:{".mjx-dialog-help":{"max-width":"calc(min(50em, 80%))"}}}).attach(),this.stop(e)}inDialog(t){if(!this.dialog.contains(t.target))return!1;const{x:e,y:s}=t,{left:i,right:r,top:n,bottom:o}=this.dialog.getBoundingClientRect();return e>=i&&e<=r&&s>=n&&s<=o}stop(t){t.preventDefault&&t.preventDefault(),t.stopImmediatePropagation?t.stopImmediatePropagation():t.stopPropagation&&t.stopPropagation()}}co.keyActions=new Map([["Escape",(t,e)=>t.escKey(e)],["a",(t,e)=>t.aKey(e)],["m",(t,e)=>t.mKey(e)],["s",(t,e)=>t.sKey(e)],["ArrowRight",(t,e)=>t.arrowKey(e,"right")],["ArrowLeft",(t,e)=>t.arrowKey(e,"left")],["ArrowUp",(t,e)=>t.arrowKey(e,"up")],["ArrowDown",(t,e)=>t.arrowKey(e,"down")]]),co.styleId="MJX-DIALOG-styles",co.className="",co.id=0,co.styles={"mjx-dialog-background":{display:"flex","flex-direction":"column","justify-content":"center",position:"fixed",top:0,left:0,right:0,bottom:0,"z-index":1001},".mjx-dialog":{"max-width":"calc(min(60em, 90%))","max-height":"calc(min(50em, 85%))",border:"3px outset","border-radius":"15px",color:"black","background-color":"#DDDDDD","box-shadow":"0px 10px 20px #808080",padding:"4px 4px",cursor:"grab",overflow:"visible",display:"flex","flex-direction":"column","align-items":"center",position:"fixed",top:"-4%"},".mjx-dialog.mjx-moving":{cursor:"grabbing"},'.mjx-dialog > input[type="button"]':{width:"fit-content"},".mjx-dialog > mjx-dialog-spacer":{display:"block",height:".75em","flex-shrink":0},".mjx-dialog::backdrop":{opacity:0,cursor:"default"},"mjx-dialog":{all:"initial",cursor:"inherit",width:"100%",display:"flex","flex-direction":"column","flex-grow":1,"flex-shrink":1,overflow:"hidden"},"mjx-dialog > mjx-title":{display:"block","text-align":"center",margin:".25em 1.75em",overflow:"hidden","white-space":"nowrap","-webkit-user-select":"none","user-select":"none","flex-shrink":0},"mjx-dialog > mjx-title > h1":{"font-size":"125%",margin:0},"mjx-dialog > div":{margin:"0 1em .5em",padding:"8px 18px",overflow:"auto",border:"2px inset black","background-color":"white","text-align":"left",cursor:"default","flex-grow":1,"flex-shrink":1},"mjx-dialog > div > pre":{margin:0},".mjx-dialog-button":{position:"absolute",top:"6px",height:"17px",width:"17px",cursor:"default",display:"block",border:"2px solid #AAA","border-radius":"18px","font-family":'"Courier New", Courier',"text-align":"center",color:"#F0F0F0","-webkit-user-select":"none","user-select":"none"},".mjx-dialog-button:hover":{color:"white !important",border:"2px solid #CCC !important"},".mjx-dialog-button > mjx-dialog-icon":{display:"block","background-color":"#AAA",border:"1.5px solid","border-radius":"18px","line-height":0,padding:"8px 0 6px"},".mjx-dialog-button > mjx-dialog-icon:hover":{"background-color":"#CCC !important"},"mjx-dialog-close":{right:"6px","font-size":"20px;"},"mjx-dialog-help":{left:"6px","font-size":"14px;","font-weight":"bold"},".mjx-dialog-help mjx-dialog-help":{display:"none"},"mjx-dialog kbd":{display:"inline-block",padding:"3px 5px","font-size":"11px","line-height":"10px",color:"#444d56","vertical-align":"middle","background-color":"#fafbfc",border:"solid 1.5px #c6cbd1","border-bottom-color":"#959da5","border-radius":"3px","box-shadow":"inset -.5px -1px 0 #959da5"},'mjx-dialog-drag[data-drag="top"]':{height:"5px",position:"absolute",top:"-3px",left:"10px",right:"10px",cursor:"ns-resize"},'mjx-dialog-drag[data-drag="bottom"]':{height:"5px",position:"absolute",bottom:"-3px",left:"10px",right:"10px",cursor:"ns-resize"},'mjx-dialog-drag[data-drag="left"]':{width:"5px",position:"absolute",left:"-3px",top:"10px",bottom:"10px",cursor:"ew-resize"},'mjx-dialog-drag[data-drag="right"]':{width:"5px",position:"absolute",right:"-3px",top:"10px",bottom:"10px",cursor:"ew-resize"},'mjx-dialog-drag[data-drag="topleft"]':{width:"13px",height:"13px",position:"absolute",left:"-3px",top:"-3px",cursor:"nwse-resize"},'mjx-dialog-drag[data-drag="topright"]':{width:"13px",height:"13px",position:"absolute",right:"-3px",top:"-3px",cursor:"nesw-resize"},'mjx-dialog-drag[data-drag="botleft"]':{width:"13px",height:"13px",position:"absolute",left:"-3px",bottom:"-3px",cursor:"nesw-resize"},'mjx-dialog-drag[data-drag="botright"]':{width:"13px",height:"13px",position:"absolute",right:"-3px",bottom:"-3px",cursor:"nwse-resize"},"@media (prefers-color-scheme: dark)":{".mjx-dialog":{"background-color":"#303030","box-shadow":"0px 10px 20px #000",border:"3px outset #7C7C7C"},"mjx-dialog":{color:"#E0E0E0"},"mjx-dialog > div":{border:"2px inset #7C7C7C","background-color":"#222025"},".mjx-dialog a[href]":{color:"#86A7F5"},".mjx-dialog a[href]:visited":{color:"#DD98E2"},"mjx-dialog kbd":{color:"#F8F8F8","background-color":"#545454",border:"solid 1.5px #7A7C7E","border-bottom-color":"#707070","box-shadow":"inset -.5px -1px 0 #818589"},".mjx-dialog-button":{border:"2px solid #686868",color:"#A4A4A4"},".mjx-dialog-button:hover":{color:"#CBCBCB !important",border:"2px solid #888888 !important"},".mjx-dialog-button > mjx-dialog-icon":{"background-color":"#646464"},".mjx-dialog-button > mjx-dialog-icon:hover":{"background-color":"#888888 !important"}}},co.helpMessage='\n    

The dialog boxes in MathJax are movable and sizeable.

\n\n

For mouse users, dragging any of the edges will enlarge or shrink\n the dialog box by moving that side. Dragging any of the corners\n changes the two sides that meet at that corner. Dragging elsewhere on\n the dialog frame will move the dialog without changing its size.

\n\n

For keyboard users, there are two ways to adjust the position\n and size of the dialog box. The first is to hold the\n Alt or Option key and press any of the arrow\n keys to move the dialog box in the given direction. Hold the\n Win or Command key and press any of the\n arrow keys to enlarge or shrink the dialog box. Left and right\n move the right-hand edge of the dialog, while up and down move the\n bottom edge of the dialog.\n

\n\n

For some users, holding two keys down at once may be difficult,\n so the second way is to press the m to start "move"\n mode, then use the arrow keys to move the dialog box in the given\n direction. Press m again to stop moving the dialog.\n Similarly, press s to start and stop "sizing" mode,\n where the arrows will change the size of the dialog box.

\n\n

Holding a shift key along with the arrow key will\n make larger changes in the size or position, for either method\n described above.

\n\n

Use Tab to move among the text, buttons, and links\n within the dialog. The Enter or Space key\n activates the focused item. The Escape key closes the\n dialog, as does clicking outside the dialog box, or clicking the\n "\xd7" icon in the upper right-hand corner of the dialog.

\n ';class ho extends co{static post(t){const e=new this(t);return e.attach(),e}}function uo(t){return Zn.asyncLoad?new Promise((e,s)=>{const i=Zn.asyncLoad(t);i instanceof Promise?i.then(t=>e(t)).catch(t=>s(t)):e(i)}):Promise.reject(`Can't load '${t}': No mathjax.asyncLoad method specified`)}const po=1e6,mo={px:1,in:96,cm:96/2.54,mm:96/25.4},fo={em:1,ex:.431,pt:.1,pc:1.2,mu:1/18},go={veryverythinmathspace:1/18,verythinmathspace:2/18,thinmathspace:3/18,mediummathspace:4/18,thickmathspace:5/18,verythickmathspace:6/18,veryverythickmathspace:7/18,negativeveryverythinmathspace:-1/18,negativeverythinmathspace:-2/18,negativethinmathspace:-3/18,negativemediummathspace:-4/18,negativethickmathspace:-5/18,negativeverythickmathspace:-6/18,negativeveryverythickmathspace:-7/18,thin:.04,medium:.06,thick:.1,normal:1,big:2,small:1/Math.sqrt(2),infinity:po};function bo(t,e=0,s=1,i=16){if("string"!=typeof t&&(t=String(t)),""===t||null==t)return e;if(go[t])return go[t];const r=t.match(/^\s*([-+]?(?:\.\d+|\d+(?:\.\d*)?))?(pt|em|ex|mu|px|pc|in|mm|cm|%)?/);if(!r||""===r[0])return e;const n=parseFloat(r[1]||"1"),o=r[2];return Object.hasOwn(mo,o)?n*mo[o]/i/s:Object.hasOwn(fo,o)?n*fo[o]:"%"===o?n/100*e:n*e}function Eo(t){return(100*t).toFixed(1).replace(/\.?0+$/,"")+"%"}function xo(t){return Math.abs(t)<.001?"0":t.toFixed(3).replace(/\.?0+$/,"")+"em"}function yo(t,e=-po,s=16){return t*=s,e&&tthis.w&&(this.w=r),n>this.h&&(this.h=n),o>this.d&&(this.d=o)}append(t){const e=t.rscale;this.w+=e*(t.w+t.L+t.R),e*t.h>this.h&&(this.h=e*t.h),e*t.d>this.d&&(this.d=e*t.d)}updateFrom(t){this.h=t.h,this.d=t.d,this.w=t.w,t.pwidth&&(this.pwidth=t.pwidth)}copy(){const t=new No;return Object.assign(t,this),t}}No.fullWidth="100%",No.boxSides=[["Top",0,"h"],["Right",1,"w"],["Bottom",2,"d"],["Left",3,"w"]];const vo={loadMissingEntities:!0},To={ApplyFunction:"\u2061",Backslash:"\u2216",Because:"\u2235",Breve:"\u02d8",Cap:"\u22d2",CenterDot:"\xb7",CircleDot:"\u2299",CircleMinus:"\u2296",CirclePlus:"\u2295",CircleTimes:"\u2297",Congruent:"\u2261",ContourIntegral:"\u222e",Coproduct:"\u2210",Cross:"\u2a2f",Cup:"\u22d3",CupCap:"\u224d",Dagger:"\u2021",Del:"\u2207",Delta:"\u0394",Diamond:"\u22c4",DifferentialD:"\u2146",DotEqual:"\u2250",DoubleDot:"\xa8",DoubleRightTee:"\u22a8",DoubleVerticalBar:"\u2225",DownArrow:"\u2193",DownLeftVector:"\u21bd",DownRightVector:"\u21c1",DownTee:"\u22a4",Downarrow:"\u21d3",Element:"\u2208",EqualTilde:"\u2242",Equilibrium:"\u21cc",Exists:"\u2203",ExponentialE:"\u2147",FilledVerySmallSquare:"\u25aa",ForAll:"\u2200",Gamma:"\u0393",Gg:"\u22d9",GreaterEqual:"\u2265",GreaterEqualLess:"\u22db",GreaterFullEqual:"\u2267",GreaterLess:"\u2277",GreaterSlantEqual:"\u2a7e",GreaterTilde:"\u2273",Hacek:"\u02c7",Hat:"^",HumpDownHump:"\u224e",HumpEqual:"\u224f",Im:"\u2111",ImaginaryI:"\u2148",Integral:"\u222b",Intersection:"\u22c2",InvisibleComma:"\u2063",InvisibleTimes:"\u2062",Lambda:"\u039b",Larr:"\u219e",LeftAngleBracket:"\u27e8",LeftArrow:"\u2190",LeftArrowRightArrow:"\u21c6",LeftCeiling:"\u2308",LeftDownVector:"\u21c3",LeftFloor:"\u230a",LeftRightArrow:"\u2194",LeftTee:"\u22a3",LeftTriangle:"\u22b2",LeftTriangleEqual:"\u22b4",LeftUpVector:"\u21bf",LeftVector:"\u21bc",Leftarrow:"\u21d0",Leftrightarrow:"\u21d4",LessEqualGreater:"\u22da",LessFullEqual:"\u2266",LessGreater:"\u2276",LessSlantEqual:"\u2a7d",LessTilde:"\u2272",Ll:"\u22d8",Lleftarrow:"\u21da",LongLeftArrow:"\u27f5",LongLeftRightArrow:"\u27f7",LongRightArrow:"\u27f6",Longleftarrow:"\u27f8",Longleftrightarrow:"\u27fa",Longrightarrow:"\u27f9",Lsh:"\u21b0",MinusPlus:"\u2213",NestedGreaterGreater:"\u226b",NestedLessLess:"\u226a",NotDoubleVerticalBar:"\u2226",NotElement:"\u2209",NotEqual:"\u2260",NotExists:"\u2204",NotGreater:"\u226f",NotGreaterEqual:"\u2271",NotLeftTriangle:"\u22ea",NotLeftTriangleEqual:"\u22ec",NotLess:"\u226e",NotLessEqual:"\u2270",NotPrecedes:"\u2280",NotPrecedesSlantEqual:"\u22e0",NotRightTriangle:"\u22eb",NotRightTriangleEqual:"\u22ed",NotSubsetEqual:"\u2288",NotSucceeds:"\u2281",NotSucceedsSlantEqual:"\u22e1",NotSupersetEqual:"\u2289",NotTilde:"\u2241",NotVerticalBar:"\u2224",Omega:"\u03a9",OverBar:"\u203e",OverBrace:"\u23de",PartialD:"\u2202",Phi:"\u03a6",Pi:"\u03a0",PlusMinus:"\xb1",Precedes:"\u227a",PrecedesEqual:"\u2aaf",PrecedesSlantEqual:"\u227c",PrecedesTilde:"\u227e",Product:"\u220f",Proportional:"\u221d",Psi:"\u03a8",Rarr:"\u21a0",Re:"\u211c",ReverseEquilibrium:"\u21cb",RightAngleBracket:"\u27e9",RightArrow:"\u2192",RightArrowLeftArrow:"\u21c4",RightCeiling:"\u2309",RightDownVector:"\u21c2",RightFloor:"\u230b",RightTee:"\u22a2",RightTeeArrow:"\u21a6",RightTriangle:"\u22b3",RightTriangleEqual:"\u22b5",RightUpVector:"\u21be",RightVector:"\u21c0",Rightarrow:"\u21d2",Rrightarrow:"\u21db",Rsh:"\u21b1",Sigma:"\u03a3",SmallCircle:"\u2218",Sqrt:"\u221a",Square:"\u25a1",SquareIntersection:"\u2293",SquareSubset:"\u228f",SquareSubsetEqual:"\u2291",SquareSuperset:"\u2290",SquareSupersetEqual:"\u2292",SquareUnion:"\u2294",Star:"\u22c6",Subset:"\u22d0",SubsetEqual:"\u2286",Succeeds:"\u227b",SucceedsEqual:"\u2ab0",SucceedsSlantEqual:"\u227d",SucceedsTilde:"\u227f",SuchThat:"\u220b",Sum:"\u2211",Superset:"\u2283",SupersetEqual:"\u2287",Supset:"\u22d1",Therefore:"\u2234",Theta:"\u0398",Tilde:"\u223c",TildeEqual:"\u2243",TildeFullEqual:"\u2245",TildeTilde:"\u2248",UnderBar:"_",UnderBrace:"\u23df",Union:"\u22c3",UnionPlus:"\u228e",UpArrow:"\u2191",UpDownArrow:"\u2195",UpTee:"\u22a5",Uparrow:"\u21d1",Updownarrow:"\u21d5",Upsilon:"\u03a5",Vdash:"\u22a9",Vee:"\u22c1",VerticalBar:"\u2223",VerticalTilde:"\u2240",Vvdash:"\u22aa",Wedge:"\u22c0",Xi:"\u039e",amp:"&",acute:"\xb4",aleph:"\u2135",alpha:"\u03b1",amalg:"\u2a3f",and:"\u2227",ang:"\u2220",angmsd:"\u2221",angsph:"\u2222",ape:"\u224a",backprime:"\u2035",backsim:"\u223d",backsimeq:"\u22cd",beta:"\u03b2",beth:"\u2136",between:"\u226c",bigcirc:"\u25ef",bigodot:"\u2a00",bigoplus:"\u2a01",bigotimes:"\u2a02",bigsqcup:"\u2a06",bigstar:"\u2605",bigtriangledown:"\u25bd",bigtriangleup:"\u25b3",biguplus:"\u2a04",blacklozenge:"\u29eb",blacktriangle:"\u25b4",blacktriangledown:"\u25be",blacktriangleleft:"\u25c2",bowtie:"\u22c8",boxdl:"\u2510",boxdr:"\u250c",boxminus:"\u229f",boxplus:"\u229e",boxtimes:"\u22a0",boxul:"\u2518",boxur:"\u2514",bsol:"\\",bull:"\u2022",cap:"\u2229",check:"\u2713",chi:"\u03c7",circ:"\u02c6",circeq:"\u2257",circlearrowleft:"\u21ba",circlearrowright:"\u21bb",circledR:"\xae",circledS:"\u24c8",circledast:"\u229b",circledcirc:"\u229a",circleddash:"\u229d",clubs:"\u2663",colon:":",comp:"\u2201",ctdot:"\u22ef",cuepr:"\u22de",cuesc:"\u22df",cularr:"\u21b6",cup:"\u222a",curarr:"\u21b7",curlyvee:"\u22ce",curlywedge:"\u22cf",dagger:"\u2020",daleth:"\u2138",ddarr:"\u21ca",deg:"\xb0",delta:"\u03b4",digamma:"\u03dd",div:"\xf7",divideontimes:"\u22c7",dot:"\u02d9",doteqdot:"\u2251",dotplus:"\u2214",dotsquare:"\u22a1",dtdot:"\u22f1",ecir:"\u2256",efDot:"\u2252",egs:"\u2a96",ell:"\u2113",els:"\u2a95",empty:"\u2205",epsi:"\u03b5",epsiv:"\u03f5",erDot:"\u2253",eta:"\u03b7",eth:"\xf0",flat:"\u266d",fork:"\u22d4",frown:"\u2322",gEl:"\u2a8c",gamma:"\u03b3",gap:"\u2a86",gimel:"\u2137",gnE:"\u2269",gnap:"\u2a8a",gne:"\u2a88",gnsim:"\u22e7",gt:">",gtdot:"\u22d7",harrw:"\u21ad",hbar:"\u210f",hellip:"\u2026",hookleftarrow:"\u21a9",hookrightarrow:"\u21aa",imath:"\u0131",infin:"\u221e",intcal:"\u22ba",iota:"\u03b9",jmath:"\u0237",kappa:"\u03ba",kappav:"\u03f0",lEg:"\u2a8b",lambda:"\u03bb",lap:"\u2a85",larrlp:"\u21ab",larrtl:"\u21a2",lbrace:"{",lbrack:"[",le:"\u2264",leftleftarrows:"\u21c7",leftthreetimes:"\u22cb",lessdot:"\u22d6",lmoust:"\u23b0",lnE:"\u2268",lnap:"\u2a89",lne:"\u2a87",lnsim:"\u22e6",longmapsto:"\u27fc",looparrowright:"\u21ac",lowast:"\u2217",loz:"\u25ca",lt:"<",ltimes:"\u22c9",ltri:"\u25c3",macr:"\xaf",malt:"\u2720",mho:"\u2127",mu:"\u03bc",multimap:"\u22b8",nLeftarrow:"\u21cd",nLeftrightarrow:"\u21ce",nRightarrow:"\u21cf",nVDash:"\u22af",nVdash:"\u22ae",natur:"\u266e",nearr:"\u2197",nharr:"\u21ae",nlarr:"\u219a",not:"\xac",nrarr:"\u219b",nu:"\u03bd",nvDash:"\u22ad",nvdash:"\u22ac",nwarr:"\u2196",omega:"\u03c9",omicron:"\u03bf",or:"\u2228",osol:"\u2298",period:".",phi:"\u03c6",phiv:"\u03d5",pi:"\u03c0",piv:"\u03d6",prap:"\u2ab7",precnapprox:"\u2ab9",precneqq:"\u2ab5",precnsim:"\u22e8",prime:"\u2032",psi:"\u03c8",quot:'"',rarrtl:"\u21a3",rbrace:"}",rbrack:"]",rho:"\u03c1",rhov:"\u03f1",rightrightarrows:"\u21c9",rightthreetimes:"\u22cc",ring:"\u02da",rmoust:"\u23b1",rtimes:"\u22ca",rtri:"\u25b9",scap:"\u2ab8",scnE:"\u2ab6",scnap:"\u2aba",scnsim:"\u22e9",sdot:"\u22c5",searr:"\u2198",sect:"\xa7",sharp:"\u266f",sigma:"\u03c3",sigmav:"\u03c2",simne:"\u2246",smile:"\u2323",spades:"\u2660",sub:"\u2282",subE:"\u2ac5",subnE:"\u2acb",subne:"\u228a",supE:"\u2ac6",supnE:"\u2acc",supne:"\u228b",swarr:"\u2199",tau:"\u03c4",theta:"\u03b8",thetav:"\u03d1",tilde:"\u02dc",times:"\xd7",triangle:"\u25b5",triangleq:"\u225c",upsi:"\u03c5",upuparrows:"\u21c8",veebar:"\u22bb",vellip:"\u22ee",weierp:"\u2118",xi:"\u03be",yen:"\xa5",zeta:"\u03b6",zigrarr:"\u21dd",nbsp:"\xa0",rsquo:"\u2019",lsquo:"\u2018"},wo={};function Co(t,e){Object.assign(To,t),wo[e]=!0}function ko(t){delete To[t]}function _o(t){return t.replace(/&([a-z][a-z0-9]*|#(?:[0-9]+|x[0-9a-f]+));/gi,Lo)}function Lo(t,e){if("#"===e.charAt(0))return Ao(e.slice(1));if(To[e])return To[e];if(vo.loadMissingEntities){const t=e.match(/^[a-zA-Z](fr|scr|opf)$/)?RegExp.$1:e.charAt(0).toLowerCase();wo[t]||(wo[t]=!0,On(uo("./util/entities/"+t+".js")))}return t}function Ao(t){const e="x"===t.charAt(0)?parseInt(t.slice(1),16):parseInt(t);return String.fromCodePoint(e)}const Ro=["top","right","bottom","left"],So=["width","style","color"];function Mo(t){const e=t.split(/((?:'[^'\n]*'|"[^"\n]*"|,[\s\n]|[^\s\n])*)/g),s=[];for(;e.length>1;)e.shift(),s.push(e.shift());return s}function Io(t){const e=Mo(this.styles[t]);0===e.length&&e.push(""),1===e.length&&e.push(e[0]),2===e.length&&e.push(e[0]),3===e.length&&e.push(e[1]);for(const s of Wo.connect[t].children)this.setStyle(this.childName(t,s),e.shift())}function Oo(t){const e=Wo.connect[t].children,s=[];for(const i of e){const e=this.styles[this.childName(t,i)];if(!e)return void delete this.styles[t];s.push(e)}s[3]===s[1]&&(s.pop(),s[2]===s[0]&&(s.pop(),s[1]===s[0]&&s.pop())),this.styles[t]=s.join(" ")}function Do(t){Oo.call(this,t),this.combineChildren(t),Po.call(this,t),this.combineParent(t)}function Po(t){if(!Wo.connect[t])return;const e=[...Wo.connect[t].children],s=this.styles[this.childName(t,e.shift())];for(const i of e)if(this.styles[this.childName(t,i)]!==s)return void delete this.styles[t];s&&(this.styles[t]=s)}const Bo=/^(?:[\d.]+(?:[a-z]+)|thin|medium|thick|inherit|initial|unset)$/,Fo=/^(?:none|hidden|dotted|dashed|solid|double|groove|ridge|inset|outset|inherit|initial|unset)$/;function jo(t){const e={width:"",style:"",color:""};for(const s of Mo(this.styles[t]))s.match(Bo)&&""===e.width?e.width=s:s.match(Fo)&&""===e.style?e.style=s:e.color=s;for(const s of Wo.connect[t].children)this.setStyle(this.childName(t,s),e[s])}function Uo(t){const e=[];for(const s of Wo.connect[t].children){const i=this.styles[this.childName(t,s)];i&&e.push(i)}e.length>1?this.styles[t]=e.join(" "):delete this.styles[t]}const Ho={style:/^(?:normal|italic|oblique|inherit|initial|unset)$/,variant:new RegExp("^(?:"+["normal|none","inherit|initial|unset","common-ligatures|no-common-ligatures","discretionary-ligatures|no-discretionary-ligatures","historical-ligatures|no-historical-ligatures","contextual|no-contextual","(?:stylistic|character-variant|swash|ornaments|annotation)\\([^)]*\\)","small-caps|all-small-caps|petite-caps|all-petite-caps|unicase|titling-caps","lining-nums|oldstyle-nums|proportional-nums|tabular-nums","diagonal-fractions|stacked-fractions","ordinal|slashed-zero","jis78|jis83|jis90|jis04|simplified|traditional","full-width|proportional-width","ruby"].join("|")+")$"),weight:/^(?:normal|bold|bolder|lighter|[1-9]00|inherit|initial|unset)$/,stretch:new RegExp("^(?:"+["normal","(?:(?:ultra|extra|semi)-)?(?:condensed|expanded)","inherit|initial|unset"].join("|")+")$"),size:new RegExp("^(?:"+["xx-small|x-small|small|medium|large|x-large|xx-large|larger|smaller","[\\d.]+%|[\\d.]+[a-z]+","inherit|initial|unset"].join("|")+")(?:/(?:normal|[\\d.]+(?:%|[a-z]+)?))?$")};function qo(t,e){for(const s of Wo.connect[t].children){const i=this.childName(t,s);if(Array.isArray(e[s])){const t=e[s];t.length&&(this.styles[i]=t.join(" "))}else""!==e[s]&&(this.styles[i]=e[s])}}class Wo{constructor(t=""){this.parse(t)}sanitizeValue(t){const e=this.constructor.pattern;if(!t.match(e.sanitize))return t;const s=(t=t.replace(e.value,"$1")).replace(/\\./g,"").replace(/(['"]).*?\1/g,"").replace(/[^'"]/g,"");return s.length&&(t+=s.charAt(0)),t}get cssText(){var t,e;const s=[];for(const i of Object.keys(this.styles)){const r=this.parentName(i),n=i.replace(/.*-/,""),o=this.childName(this.parentName(r),n);!this.styles[i]||this.styles[o]||this.styles[r]&&(null===(e=null===(t=Wo.connect[r])||void 0===t?void 0:t.children)||void 0===e?void 0:e.includes(n))||s.push(`${i}: ${this.styles[i]};`)}return s.join(" ")}get styleList(){return Object.assign({},this.styles)}set(t,e){t=this.normalizeName(t),this.setStyle(t,String(e));const s=Wo.connect[t];if(null==s?void 0:s.subPart)s.combine.call(this,t);else if(this.combineParent(t),t.match(/-.*-/)){const e=t.replace(/-.*-/,"-");Po.call(this,e)}}combineParent(t){for(var e;t.match(/-/);){const s=t;t=this.parentName(t);const i=Wo.connect[t];if(!Wo.connect[s]&&!(null===(e=null==i?void 0:i.children)||void 0===e?void 0:e.includes(s.substring(t.length+1))))break;i.combine.call(this,t)}if(!this.styles[t])return;const s=Wo.connect[t];for(const e of(null==s?void 0:s.parts)||[])delete this.styles[this.childName(t,e)]}get(t){return t=this.normalizeName(t),Object.hasOwn(this.styles,t)?this.styles[t]:""}setStyle(t,e){var s;this.styles[t]=this.sanitizeValue(e),(null===(s=Wo.connect[t])||void 0===s?void 0:s.children)&&Wo.connect[t].split.call(this,t),""===e&&delete this.styles[t]}combineChildren(t){const e=this.parentName(t);for(const s of Wo.connect[t].children){const t=this.childName(e,s);Wo.connect[t].combine.call(this,t)}}parentName(t){const e=t.replace(/-[^-]*$/,"");return t===e?"":e}childName(t,e){var s;return e.match(/-/)?e:((null===(s=Wo.connect[t])||void 0===s?void 0:s.subPart)&&(e+=t.replace(/.*-/,"-"),t=this.parentName(t)),t+"-"+e)}normalizeName(t){return t.replace(/[A-Z]/g,t=>"-"+t.toLowerCase())}parse(t=""){const e=this.constructor.pattern;this.styles={};const s=t.replace(/\n/g," ").replace(e.comment,"").split(e.style);for(;s.length>1;){const[t,e,i]=s.splice(0,3);if(t.match(/[^\s\n;]/))return;this.set(e,i)}}}function zo(t){return t.reduce((t,e)=>t+e,0)}function Vo(t){return t.reduce((t,e)=>Math.max(t,e),0)}if(Wo.pattern={sanitize:/['";]/,value:/^((:?'(?:\\.|[^'])*(?:'|$)|"(?:\\.|[^"])*(?:"|$)|\n|\\.|[^'";])*?)[\s\n]*(?:;|$).*/,style:/([-a-z]+)[\s\n]*:[\s\n]*((?:'(?:\\.|[^'])*(?:'|$)|"(?:\\.|[^"])*(?:"|$)|\n|\\.|[^'";])*?)[\s\n]*(?:;|$)/g,comment:/\/\*[^]*?\*\//g},Wo.connect={padding:{children:Ro,split:Io,combine:Oo},margin:{children:Ro,split:Io,combine:Oo},border:{children:Ro,parts:So,split:function(t){for(const e of Wo.connect[t].children)this.setStyle(this.childName(t,e),this.styles[t])},combine:Po},"border-top":{children:So,split:jo,combine:Uo},"border-right":{children:So,split:jo,combine:Uo},"border-bottom":{children:So,split:jo,combine:Uo},"border-left":{children:So,split:jo,combine:Uo},"border-width":{children:Ro,split:Io,combine:Do,subPart:!0},"border-style":{children:Ro,split:Io,combine:Do,subPart:!0},"border-color":{children:Ro,split:Io,combine:Do,subPart:!0},font:{children:["style","variant","weight","stretch","line-height","size","family"],split:function(t){const e=Mo(this.styles[t]),s={style:"",variant:[],weight:"",stretch:"",size:"",family:"","line-height":""};for(const t of e){s.family||(s.family=t);for(const e of Object.keys(Ho))if((Array.isArray(s[e])||""===s[e])&&t.match(Ho[e]))if(s.family===t&&(s.family=""),"size"===e){const[i,r]=t.split(/\//);s[e]=i,r&&(s["line-height"]=r)}else""===s.size&&(Array.isArray(s[e])?s[e].push(t):""===s[e]&&(s[e]=t))}qo.call(this,t,s),delete this.styles[t]},combine:function(t){}}},MathJax.loader&&MathJax.loader.checkVersion("core",ii,"core"),ci({_:{adaptors:{HTMLAdaptor:c,browserAdaptor:h},components:{global:t},core:{DOMAdaptor:l,FindMath:d,Handler:ot,HandlerList:at,InputJax:u,MathDocument:nt,MathItem:g,MathList:f,MmlTree:{Attributes:x,MML:et,MathMLVisitor:ht,MmlFactory:st,MmlNode:N,MmlNodes:{HtmlNode:tt,TeXAtom:Q,maction:H,maligngroup:J,malignmark:K,math:v,mathchoice:Z,menclose:U,merror:P,mfenced:j,mfrac:M,mglyph:$,mi:T,mmultiscripts:z,mn:w,mo:_,mpadded:B,mphantom:F,mroot:O,mrow:S,ms:R,mspace:A,msqrt:I,mstyle:D,msubsup:q,mtable:V,mtd:G,mtext:L,mtr:X,munderover:W,semantics:Y},MmlVisitor:ct,OperatorDictionary:C,SerializedMmlVisitor:dt},OutputJax:p,Tree:{Factory:b,Node:y,NodeFactory:E,Visitor:lt,Wrapper:ut,WrapperFactory:pt}},handlers:{html_ts:yt,html:{HTMLDocument:Et,HTMLDomStrings:bt,HTMLHandler:xt,HTMLMathItem:ft,HTMLMathList:gt}},mathjax:mt,ui:{dialog:{DraggableDialog:vt,InfoDialog:Tt}},util:{AsyncLoad:wt,BBox:kt,BitField:it,Entities:_t,FunctionList:r,LinkedList:m,Options:o,PrioritizedList:i,Retries:rt,StyleJson:Nt,Styles:Lt,context:e,lengths:Ct,numeric:At,string:k}}}),MathJax.startup&&(MathJax.startup.registerConstructor("HTMLHandler",ro),MathJax.startup.registerConstructor("browserAdaptor",$i),MathJax.startup.useHandler("HTMLHandler"),MathJax.startup.useAdaptor("browserAdaptor")),MathJax.loader){const t=MathJax.config.loader;MathJax._.mathjax.mathjax.asyncLoad=e=>"node:"===e.substring(0,5)?t.require(e):MathJax.loader.load(e).then(t=>t[0])}class Xo extends Yi{constructor(t){super(t),this.getPatterns()}getPatterns(){const t=this.options,e=[],s=[],i=[];this.end={},this.env=this.sub=0;let r=1;t.inlineMath.forEach(t=>this.addPattern(e,t,!1)),t.displayMath.forEach(t=>this.addPattern(e,t,!0)),e.length&&s.push(e.sort(Pr).join("|")),t.processEnvironments&&(s.push("\\\\begin\\s*\\{([^}]*)\\}"),this.env=r,r++),t.processEscapes&&i.push("\\\\([\\\\$])"),t.processRefs&&i.push("(\\\\(?:eq)?ref\\s*\\{[^}]*\\})"),i.length&&(s.push("("+i.join("|")+")"),this.sub=r),this.start=new RegExp(s.join("|"),"g"),this.hasPatterns=s.length>0}addPattern(t,e,s){const[i,r]=e;t.push(Br(i)),this.end[i]=[r,s,this.endPattern(r)]}endPattern(t,e){return new RegExp((e||Br(t))+"|\\\\(?:[a-zA-Z]|.)|[{}]","g")}findEnd(t,e,s,i){const[r,n,o]=i,a=o.lastIndex=s.index+s[0].length;let l,c=0;for(;l=o.exec(t);){if((l[1]||l[0])===r&&0===c)return rr(s[0],t.substring(a,l.index),l[0],e,s.index,l.index+l[0].length,n);"{"===l[0]?c++:"}"===l[0]&&c&&c--}return null}findMathInString(t,e,s){let i,r;for(this.start.lastIndex=0;i=this.start.exec(s);){if(void 0!==i[this.env]&&this.env){const t="\\\\end\\s*(\\{"+Br(i[this.env])+"\\})";r=this.findEnd(s,e,i,["{"+i[this.env]+"}",!0,this.endPattern(null,t)]),r&&(r.math=r.open+r.math+r.close,r.open=r.close="")}else if(void 0!==i[this.sub]&&this.sub){const t=i[this.sub],s=i.index+i[this.sub].length;r=2===t.length?rr("\\",t.substring(1),"",e,i.index,s):rr("",t,"",e,i.index,s,!1)}else r=this.findEnd(s,e,i,this.end[i[0]]);r&&(t.push(r),this.start.lastIndex=r.end.n)}}findMath(t){const e=[];if(this.hasPatterns)for(let s=0,i=t.length;sString.fromCodePoint(parseInt(t,16)),getChildren:t=>t.childNodes,getText:t=>t.getText(),appendChildren(t,e){for(const s of e)t.appendChild(s)},setAttribute(t,e,s){t.attributes.set(e,s)},setProperty(t,e,s){t.setProperty(e,s)},setProperties(t,e){for(const s of Object.keys(e)){const i=e[s];"texClass"===s?(t.texClass=i,t.setProperty(s,i)):"movablelimits"===s?(t.setProperty("movablelimits",i),(t.isKind("mo")||t.isKind("mstyle"))&&t.attributes.set("movablelimits",i)):"inferred"===s||(Go.attrs.has(s)?t.setProperty(s,i):t.attributes.set(s,i))}},getProperty:(t,e)=>t.getProperty(e),getAttribute:(t,e)=>t.attributes.get(e),removeAttribute(t,e){t.attributes.unset(e)},removeProperties(t,...e){t.removeProperty(...e)},getChildAt:(t,e)=>t.childNodes[e],setChild(t,e,s){t.childNodes[e]=s,s&&(s.parent=t)},copyChildren(t,e){const s=t.childNodes;for(let t=0;tt.isKind(e),isEmbellished:t=>t.isEmbellished,getTexClass:t=>t.texClass,getCoreMO:t=>t.coreMO(),isNode:t=>t instanceof yr||t instanceof wr,isInferred:t=>t.isInferred,getForm(t){if(!t.isKind("mo"))return null;const e=t,s=e.getForms();for(const t of s){const s=this.getOp(e,t);if(s)return s}return null},getOp:(t,e="infix")=>zr.OPTABLE[e][t.getText()]||null,getMoAttribute(t,e){var s,i;if(!t.attributes.isSet(e))for(const r of["infix","postfix","prefix"]){const n=null===(i=null===(s=this.getOp(t,r))||void 0===s?void 0:s[3])||void 0===i?void 0:i[e];if(void 0!==n)return n}return t.attributes.get(e)}},Jo=Go,Ko={Variant:{NORMAL:"normal",BOLD:"bold",ITALIC:"italic",BOLDITALIC:"bold-italic",DOUBLESTRUCK:"double-struck",FRAKTUR:"fraktur",BOLDFRAKTUR:"bold-fraktur",SCRIPT:"script",BOLDSCRIPT:"bold-script",SANSSERIF:"sans-serif",BOLDSANSSERIF:"bold-sans-serif",SANSSERIFITALIC:"sans-serif-italic",SANSSERIFBOLDITALIC:"sans-serif-bold-italic",MONOSPACE:"monospace",INITIAL:"inital",TAILED:"tailed",LOOPED:"looped",STRETCHED:"stretched",CALLIGRAPHIC:"-tex-calligraphic",BOLDCALLIGRAPHIC:"-tex-bold-calligraphic",OLDSTYLE:"-tex-oldstyle",BOLDOLDSTYLE:"-tex-bold-oldstyle",MATHITALIC:"-tex-mathit"},Form:{PREFIX:"prefix",INFIX:"infix",POSTFIX:"postfix"},LineBreak:{AUTO:"auto",NEWLINE:"newline",NOBREAK:"nobreak",GOODBREAK:"goodbreak",BADBREAK:"badbreak"},LineBreakStyle:{BEFORE:"before",AFTER:"after",DUPLICATE:"duplicate",INFIXLINBREAKSTYLE:"infixlinebreakstyle"},IndentAlign:{LEFT:"left",CENTER:"center",RIGHT:"right",AUTO:"auto",ID:"id",INDENTALIGN:"indentalign"},IndentShift:{INDENTSHIFT:"indentshift"},LineThickness:{THIN:"thin",MEDIUM:"medium",THICK:"thick"},Notation:{LONGDIV:"longdiv",ACTUARIAL:"actuarial",PHASORANGLE:"phasorangle",RADICAL:"radical",BOX:"box",ROUNDEDBOX:"roundedbox",CIRCLE:"circle",LEFT:"left",RIGHT:"right",TOP:"top",BOTTOM:"bottom",UPDIAGONALSTRIKE:"updiagonalstrike",DOWNDIAGONALSTRIKE:"downdiagonalstrike",VERTICALSTRIKE:"verticalstrike",HORIZONTALSTRIKE:"horizontalstrike",NORTHEASTARROW:"northeastarrow",MADRUWB:"madruwb",UPDIAGONALARROW:"updiagonalarrow"},Align:{TOP:"top",BOTTOM:"bottom",CENTER:"center",BASELINE:"baseline",AXIS:"axis",LEFT:"left",RIGHT:"right"},Lines:{NONE:"none",SOLID:"solid",DASHED:"dashed"},Side:{LEFT:"left",RIGHT:"right",LEFTOVERLAP:"leftoverlap",RIGHTOVERLAP:"rightoverlap"},Width:{AUTO:"auto",FIT:"fit"},Actiontype:{TOGGLE:"toggle",STATUSLINE:"statusline",TOOLTIP:"tooltip",INPUT:"input"},Overflow:{LINBREAK:"linebreak",SCROLL:"scroll",ELIDE:"elide",TRUNCATE:"truncate",SCALE:"scale"},Unit:{EM:"em",EX:"ex",PX:"px",IN:"in",CM:"cm",MM:"mm",PT:"pt",PC:"pc"},Attr:{LATEX:"data-latex",LATEXITEM:"data-latex-item"}};function $o(t,e,s){const i=e.attributes,r=s.attributes;t.forEach(t=>{const e=r.getExplicit(t);null!=e&&i.set(t,e)})}function Yo(t,e){const s=(t,e)=>t.getExplicitNames().filter(s=>s!==e&&("stretchy"!==s||t.getExplicit("stretchy"))&&"data-latex"!==s&&"data-latex-item"!==s),i=t.attributes,r=e.attributes,n=s(i,"lspace"),o=s(r,"rspace");if(n.length!==o.length)return!1;for(const t of n)if(i.getExplicit(t)!==r.getExplicit(t))return!1;return!0}function Qo(t,e,s){const i=[];for(const r of t.getList("m"+e+s)){const n=r.childNodes;if(n[r[e]]&&n[r[s]])continue;const o=r.parent,a=n[r[e]]?t.nodeFactory.create("node","m"+e,[n[r.base],n[r[e]]]):t.nodeFactory.create("node","m"+s,[n[r.base],n[r[s]]]);Jo.copyAttributes(r,a),o.replaceChild(a,r),i.push(r)}t.removeFromList("m"+e+s,i)}function Zo(t,e,s){const i=[];for(const r of t.getList(e)){if(r.attributes.get("displaystyle"))continue;const e=r.childNodes[r.base],n=e.coreMO();if(e.getProperty("movablelimits")&&!n.attributes.hasExplicit("movablelimits")){const e=t.nodeFactory.create("node",s,r.childNodes);Jo.copyAttributes(r,e),r.parent.replaceChild(e,r),i.push(r)}}t.removeFromList(e,i)}const ta={cleanStretchy(t){var e;const s=t.data;for(const t of s.getList("fixStretchy"))if(Jo.getProperty(t,"fixStretchy")){const s=Jo.getForm(t);(null===(e=null==s?void 0:s[3])||void 0===e?void 0:e.stretchy)&&Jo.setAttribute(t,"stretchy",!1),Jo.removeProperties(t,"fixStretchy")}},cleanAttributes(t){t.data.root.walkTree(t=>{const e=new Set((t.getProperty("keep-attrs")||"").split(/ /)),s=t.attributes;s.unset(Ko.Attr.LATEXITEM);for(const t of s.getExplicitNames())e.has(t)||s.get(t)!==s.getInherited(t)||s.unset(t)})},combineRelations(t){const e=[];for(const s of t.data.getList("mo")){if(s.getProperty("relationsCombined")||!s.parent||s.parent&&!Jo.isType(s.parent,"mrow")||Jo.getTexClass(s)!==mr.REL)continue;let t;const i=s.parent.childNodes,r=i.indexOf(s)+1,n=Jo.getProperty(s,"variantForm");for(;r"data-latex"!==t.substring(0,10)).length){const r=t.childNodes[0].childNodes[0];i.forEach(t=>r.attributes.set(t,e.get(t))),t.parent.replaceChild(r,t),s.push(t)}}e.removeFromList("mstyle",s)}},ea=ta;var sa,ia;!function(t){t.HANDLER="handler",t.FALLBACK="fallback",t.ITEMS="items",t.TAGS="tags",t.OPTIONS="options",t.NODES="nodes",t.PREPROCESSORS="preprocessors",t.POSTPROCESSORS="postprocessors",t.INIT="init",t.CONFIG="config",t.PRIORITY="priority",t.PARSER="parser"}(sa||(sa={})),function(t){t.DELIMITER="delimiter",t.MACRO="macro",t.CHARACTER="character",t.ENVIRONMENT="environment"}(ia||(ia={}));const ra=7.2;const na={UNIT_CASES:new class{constructor(t){this.num="([-+]?([.,]\\d+|\\d+([.,]\\d*)?))",this.unit="",this.dimenEnd=/./,this.dimenRest=/./,this.map=new Map(t),this.updateDimen()}updateDimen(){this.unit=`(${Array.from(this.map.keys()).join("|")})`,this.dimenEnd=RegExp("^\\s*"+this.num+"\\s*"+this.unit+"\\s*$"),this.dimenRest=RegExp("^\\s*"+this.num+"\\s*"+this.unit+" ?")}set(t,e){return this.map.set(t,e),this.updateDimen(),this}get(t){return this.map.get(t)||this.map.get("pt")}delete(t){return!!this.map.delete(t)&&(this.updateDimen(),!0)}}([["em",1],["ex",.43],["pt",.1],["pc",1.2],["px",.1],["in",ra],["cm",ra/2.54],["mm",ra/25.4],["mu",1/18]]),matchDimen(t,e=!1){const s=t.match(e?na.UNIT_CASES.dimenRest:na.UNIT_CASES.dimenEnd);return s?function([t,e,s]){return"mu"!==e?[t,e,s]:[na.em(na.UNIT_CASES.get(e)*parseFloat(t)).slice(0,-2),"em",s]}([s[1].replace(/,/,"."),s[4],s[0].length]):[null,null,0]},dimen2em(t){const[e,s]=na.matchDimen(t),i=parseFloat(e||"1");return na.UNIT_CASES.get(s)*i},em:t=>Math.abs(t)<6e-4?"0em":t.toFixed(3).replace(/\.?0+$/,"")+"em",trimSpaces(t){if("string"!=typeof t)return t;let e=t.trim();return e.match(/\\$/)&&t.match(/ $/)&&(e+=" "),e}};class oa{constructor(t,e,s){this._factory=t,this._env=e,this.global={},this.stack=[],this.global={isInner:s},this.stack=[this._factory.create("start",this.global)],e&&(this.stack[0].env=e),this.env=this.stack[0].env}set env(t){this._env=t}get env(){return this._env}Push(...t){for(const e of t){if(!e)continue;const t=Jo.isNode(e)?this._factory.create("mml",e):e;t.global=this.global;const[s,i]=this.stack.length?this.Top().checkItem(t):[null,!0];i&&(s?(this.Pop(),this.Push(...s)):(t.isKind("null")||this.stack.push(t),t.env?(t.copyEnv&&Object.assign(t.env,this.env),this.env=t.env):t.env=this.env))}}Pop(){const t=this.stack.pop();return t.isOpen||delete t.env,this.env=this.stack.length?this.Top().env:{},t}Top(t=1){return this.stack.length="0"&&i<="9")s[t]=e[parseInt(s[t],10)-1],"number"==typeof s[t]&&(s[t]=s[t].toString());else if("{"===i)if(i=s[t].substring(1),i>="0"&&i<="9")s[t]=e[parseInt(s[t].substring(1,s[t].length-1),10)-1],"number"==typeof s[t]&&(s[t]=s[t].toString());else{s[t].match(/^\{([a-z]+):%(\d+)\|(.*)\}$/)&&(s[t]="%"+s[t])}}return s.join("")}constructor(t,e,...s){this.id=t,this.message=aa.processString(e,s)}}aa.pattern=/%(\d+|\{\d+\}|\{[a-z]+:%\d+(?:\|(?:%\{\d+\}|%.|[^}])*)+\}|.)/g;const la=aa;class ca{constructor(t){this._nodes=t,this.startStr="",this.startI=0,this.stopI=0}get nodes(){return this._nodes}Push(...t){this._nodes.push(...t)}Pop(){return this._nodes.pop()}get First(){return this._nodes[this.Size()-1]}set First(t){this._nodes[this.Size()-1]=t}get Last(){return this._nodes[0]}set Last(t){this._nodes[0]=t}Peek(t){return null==t&&(t=1),this._nodes.slice(this.Size()-t)}Size(){return this._nodes.length}Clear(){this._nodes=[]}toMml(t=!0,e){return 1!==this._nodes.length||e?this.create("node",t?"inferredMrow":"mrow",this._nodes,{}):this.First}create(t,...e){return this.factory.configuration.nodeFactory.create(t,...e)}}class ha extends ca{constructor(t,...e){super(e),this.factory=t,this.global={},this._properties={},this.isOpen&&(this._env={})}get kind(){return"base"}get env(){return this._env}set env(t){this._env=t}get copyEnv(){return!0}getProperty(t){return this._properties[t]}setProperty(t,e){return this._properties[t]=e,this}get isOpen(){return!1}get isClose(){return!1}get isFinal(){return!1}isKind(t){return t===this.kind}checkItem(t){if(t.isKind("over")&&this.isOpen&&(t.setProperty("num",this.toMml(!1)),this.Clear()),t.isKind("cell")&&this.isOpen){if(t.getProperty("linebreak"))return ha.fail;throw new la("Misplaced","Misplaced %1",t.getName())}if(t.isClose&&this.getErrors(t.kind)){const[e,s]=this.getErrors(t.kind);throw new la(e,s,t.getName())}return t.isFinal?(this.Push(t.First),ha.fail):ha.success}clearEnv(){for(const t of Object.keys(this.env))delete this.env[t]}setProperties(t){return Object.assign(this._properties,t),this}getName(){return this.getProperty("name")}toString(){return this.kind+"["+this.nodes.join("; ")+"]"}getErrors(t){return this.constructor.errors[t]||ha.errors[t]}addLatexItem(t,e=""){const s=this.startStr.slice(this.startI,this.stopI);if(s){const i=e?e+s:s;t.attributes.set(Ko.Attr.LATEXITEM,i),"}"!==i&&t.attributes.set(Ko.Attr.LATEX,i)}}}ha.fail=[null,!1],ha.success=[null,!0],ha.errors={end:["MissingBeginExtraEnd","Missing \\begin{%1} or extra \\end{%1}"],close:["ExtraCloseMissingOpen","Extra close brace or missing open brace"],right:["MissingLeftExtraRight","Missing \\left or extra \\right"],middle:["ExtraMiddle","Extra \\middle"]};class da{constructor(t,e,s){this._string=t,this.configuration=s,this.macroCount=0,this.i=0,this.currentCS="",this.saveI=0;const i=Object.hasOwn(e,"isInner"),r=e.isInner;let n;if(delete e.isInner,e){n={};for(const t of Object.keys(e))n[t]=e[t]}this.configuration.pushParser(this),this.stack=new oa(this.itemFactory,n,!i||r),this.Parse(),this.Push(this.itemFactory.create("stop")),this.stack.env=n}get options(){return this.configuration.options}get itemFactory(){return this.configuration.itemFactory}get tags(){return this.configuration.tags}set string(t){this._string=t}get string(){return this._string}parse(t,e){const s=this.saveI;this.saveI=this.i-("character"===t&&"&"!==e[1]?1:0);const i=this.configuration.handlers.get(t).parse(e);return"macro"!==t&&this.updateResult(e[1],s),this.saveI=s,i}lookup(t,e){return this.configuration.handlers.get(t).lookup(e)}contains(t,e){return this.configuration.handlers.get(t).contains(e)}toString(){let t="";for(const e of Array.from(this.configuration.handlers.keys()))t+=e+": "+this.configuration.handlers.get(e)+"\n";return t}Parse(){let t;for(;this.it.includes(e),t=>t)}constructor(t,e,s){this.name=t,this.verify=e,this.convert=s}}const ba={boolean:new ga("boolean",t=>"true"===t||"false"===t,t=>"true"===t),number:new ga("number",t=>!!t.match(/^[-+]?(?:\d+(?:\.\d*)?|\.\d+)(?:e[-+]?\d+)?$/),t=>parseFloat(t)),integer:new ga("integer",t=>!!t.match(/^[-+]?\d+$/),t=>parseInt(t)),string:new ga("string",t=>!0,t=>t),dimen:new ga("dimen",t=>null!==na.matchDimen(t)[0],t=>t)};function Ea(t,e){if(0===e)return t.replace(/^\s+/,"").replace(/([^\\\s]|^)((?:\\\\)*(?:\\\s)?)?\s+$/,"$1$2");for(;e>0;)t=t.trim().slice(1,-1),e--;return t}function xa(t,e,s=!1,i=!1){const r=t.length;let n=0,o="",a=0,l=0,c=!0;for(;an&&(l=n),c=!1}o+=i}if(n)throw new la("ExtraOpenMissingClose","Extra open brace or missing close brace");return i&&l?["","",Ea(o,1)]:[Ea(o,s?Math.min(1,l):l),"",t.slice(a)]}const ya={cols:(...t)=>t.map(t=>na.em(t)).join(" "),fenced(t,e,s,i,r="",n=""){const o=t.nodeFactory,a=o.create("node","mrow",[],{open:e,close:i,texClass:mr.INNER});let l;if(r)l=new da("\\"+r+"l"+e,t.parser.stack.env,t).mml();else{const t=o.create("text",e);l=o.create("node","mo",[],{fence:!0,stretchy:!0,symmetric:!0,texClass:mr.OPEN},t)}if(Jo.appendChildren(a,[l,s]),r)l=new da("\\"+r+"r"+i,t.parser.stack.env,t).mml();else{const t=o.create("text",i);l=o.create("node","mo",[],{fence:!0,stretchy:!0,symmetric:!0,texClass:mr.CLOSE},t)}return n&&l.attributes.set("mathcolor",n),Jo.appendChildren(a,[l]),a},fixedFence(t,e,s,i){const r=t.nodeFactory.create("node","mrow",[],{open:e,close:i,texClass:mr.ORD});return e&&Jo.appendChildren(r,[ya.mathPalette(t,e,"l")]),Jo.isType(s,"mrow")?Jo.appendChildren(r,Jo.getChildren(s)):Jo.appendChildren(r,[s]),i&&Jo.appendChildren(r,[ya.mathPalette(t,i,"r")]),r},mathPalette(t,e,s){"{"!==e&&"}"!==e||(e="\\"+e);const i="{\\big"+s+" "+e+"}";return new da("\\mathchoice"+("{\\bigg"+s+" "+e+"}")+i+i+i,{},t).mml()},fixInitialMO(t,e){for(let s=0,i=e.length;s1&&(l=[t.create("node","mrow",l)]),l},internalText(t,e,s){e=e.replace(/\n+/g," ").replace(/^ +/,To.nbsp).replace(/ +$/,To.nbsp);const i=t.create("text",e);return t.create("node","mtext",[],s,i)},underOver(t,e,s,i,r){if(ya.checkMovableLimits(e),Jo.isType(e,"munderover")&&Jo.isEmbellished(e)){Jo.setProperties(Jo.getCoreMO(e),{lspace:0,rspace:0});const s=t.create("node","mo",[],{rspace:0});e=t.create("node","mrow",[s,e])}const n=t.create("node","munderover",[e]);Jo.setChild(n,"over"===i?n.over:n.under,s);let o=n;return r&&(o=t.create("node","TeXAtom",[t.create("node","mstyle",[n],{displaystyle:!0,scriptlevel:0})],{texClass:mr.OP,movesupsub:!0})),Jo.setProperty(o,"subsupOK",!0),o},checkMovableLimits(t){const e=Jo.isType(t,"mo")?Jo.getForm(t):null;(Jo.getProperty(t,"movablelimits")||e&&e[3]&&e[3].movablelimits)&&Jo.setProperties(t,{movablelimits:!1})},setArrayAlign:(t,e,s)=>(s||(e=na.trimSpaces(e||"")),"t"===e?t.arraydef.align="baseline 1":"b"===e?t.arraydef.align="baseline -1":"c"===e?t.arraydef.align="axis":e&&(s?(s.string=`[${e}]`+s.string.slice(s.i),s.i=0):t.arraydef.align=e),t),substituteArgs(t,e,s){let i="",r="",n=0;for(;ne.length)throw new la("IllegalMacroParam","Illegal macro parameter reference");r=ya.addArgs(t,ya.addArgs(t,r,i),e[parseInt(o,10)-1]),i=""}else i+=o}return ya.addArgs(t,r,i)},addArgs(t,e,s){if(s.match(/^[a-z]/i)&&e.match(/(^|[^\\])(\\\\)*\\[a-z]+$/i)&&(e+=" "),e.length+s.length>t.configuration.options.maxBuffer)throw new la("MaxBufferSize","MathJax internal buffer size exceeded; is there a recursive macro call?");return e+s},checkMaxMacros(t,e=!0){if(!(++t.macroCount<=t.configuration.options.maxMacros))throw e?new la("MaxMacroSub1","MathJax maximum macro substitution count exceeded; is here a recursive macro call?"):new la("MaxMacroSub2","MathJax maximum substitution count exceeded; is there a recursive latex environment?")},checkEqnEnv(t,e=!0){const s=t.stack.Top(),i=s.First;if(!(s.getProperty("nestable")&&e&&!i||s.getProperty("nestStart"))&&(!s.isKind("start")||i))throw new la("ErroneousNestingEq","Erroneous nesting of equation structures")},copyNode(t,e){const s=t.copy(),i=e.configuration;return s.walkTree(t=>{i.addNode(t.kind,t);const e=(t.getProperty("in-lists")||"").split(/,/);for(const s of e)s&&i.addNode(s,t)}),s},mmlFilterAttribute:(t,e,s)=>s,getFontDef(t){const e=t.stack.env.font;return e?{mathvariant:e}:{}},keyvalOptions(t,e=null,s=!1,i=!1){const r=function(t,e=!1){const s={};let i,r,n,o=t,a=!0;for(;o;)[r,i,o]=xa(o,["=",","],e,a),a=!1,"="===i?([n,i,o]=xa(o,[","],e),n="false"===n||"true"===n?JSON.parse(n):n,s[r]=n):r&&(s[r]=!0);return s}(t,i);if(e)for(const t of Object.keys(r))if(Object.hasOwn(e,t)){if(e[t]instanceof ga){const s=e[t],i=String(r[t]);if(!s.verify(i))throw new la("InvalidValue","Value for key '%1' is not of the expected type",t);r[t]=s.convert(i)}}else{if(s)throw new la("InvalidOption","Invalid option: %1",t);delete r[t]}return r},isLatinOrGreekChar:t=>!!t.normalize("NFD").match(/[a-zA-Z\u0370-\u03F0]/)};class Na{constructor(){this.columnHandler={l:t=>t.calign[t.j++]="left",c:t=>t.calign[t.j++]="center",r:t=>t.calign[t.j++]="right",p:t=>this.getColumn(t,"top"),m:t=>this.getColumn(t,"middle"),b:t=>this.getColumn(t,"bottom"),w:t=>this.getColumn(t,"top",""),W:t=>this.getColumn(t,"top",""),"|":t=>this.addRule(t,"solid"),":":t=>this.addRule(t,"dashed"),">":t=>t.cstart[t.j]=(t.cstart[t.j]||"")+this.getBraces(t),"<":t=>t.cend[t.j-1]=(t.cend[t.j-1]||"")+this.getBraces(t),"@":t=>this.addAt(t,this.getBraces(t)),"!":t=>this.addBang(t,this.getBraces(t)),"*":t=>this.repeat(t),P:t=>this.macroColumn(t,">{$}p{#1}<{$}",1),M:t=>this.macroColumn(t,">{$}m{#1}<{$}",1),B:t=>this.macroColumn(t,">{$}b{#1}<{$}",1)," ":t=>{}},this.MAXCOLUMNS=1e4}process(t,e,s){const i={parser:t,template:e,i:0,j:0,c:"",cwidth:[],calign:[],cspace:[],clines:[],cstart:s.cstart,cend:s.cend,ralign:s.ralign,cextra:s.cextra};let r=0;for(;i.ithis.MAXCOLUMNS)throw new la("MaxColumns","Too many column specifiers (perhaps looping column definitions?)");const t=i.template.codePointAt(i.i),e=i.c=String.fromCodePoint(t);if(i.i+=e.length,!Object.hasOwn(this.columnHandler,e))throw new la("BadPreamToken","Illegal pream-token (%1)",e);this.columnHandler[e](i)}this.setColumnAlign(i,s),this.setColumnWidths(i,s),this.setColumnSpacing(i,s),this.setColumnLines(i,s),this.setPadding(i,s)}setColumnAlign(t,e){e.arraydef.columnalign=t.calign.join(" ")}setColumnWidths(t,e){if(!t.cwidth.length)return;const s=[...t.cwidth];s.lengtht||"auto").join(" ")}setColumnSpacing(t,e){if(!t.cspace.length)return;const s=[...t.cspace];s.lengtht||"1em").join(" ")}setColumnLines(t,e){if(!t.clines.length)return;const s=[...t.clines];s[0]&&e.frame.push(["left",s[0]]),s.length>t.calign.length?e.frame.push(["right",s.pop()]):s.length1&&(e.arraydef.columnlines=s.slice(1).map(t=>t||"none").join(" "))}setPadding(t,e){if(!t.cextra[0]&&!t.cextra[t.calign.length-1])return;const s=t.calign.length-1,i=t.cspace,r=t.cextra[s]?i[s]:null;e.arraydef["data-array-padding"]=`${i[0]||".5em"} ${r||".5em"}`}getColumn(t,e,s="left"){t.calign[t.j]=s||this.getAlign(t),t.cwidth[t.j]=this.getDimen(t),t.ralign[t.j]=[e,t.cwidth[t.j],t.calign[t.j]],t.j++}getDimen(t){const e=this.getBraces(t);if(!na.matchDimen(e)[0])throw new la("MissingColumnDimOrUnits","Missing dimension or its units for %1 column declaration",t.c);return e}getAlign(t){return Ui(this.getBraces(t).toLowerCase(),{l:"left",c:"center",r:"right"},"")}getBraces(t){for(;" "===t.template[t.i];)t.i++;if(t.i>=t.template.length)throw new la("MissingArgForColumn","Missing argument for %1 column declaration",t.c);if("{"!==t.template[t.i])return t.template[t.i++];const e=++t.i;let s=1;for(;t.i0&&s--;)i.push(this.getBraces(t));t.template=ya.substituteArgs(t.parser,i,e)+t.template.slice(t.i),t.i=0}addRule(t,e){t.clines[t.j]&&this.addAt(t,"\\,"),t.clines[t.j]=e,"0"===t.cspace[t.j]&&(t.cstart[t.j]="\\hspace{.5em}")}addAt(t,e){const{cstart:s,cspace:i,j:r}=t;t.cextra[r]=!0,t.calign[r]="center",t.clines[r]&&(".5em"===i[r]?s[r-1]+="\\hspace{.25em}":i[r]||(t.cend[r-1]=(t.cend[r-1]||"")+"\\hspace{.5em}")),s[r]=e,i[r]="0",i[++t.j]="0"}addBang(t,e){const{cstart:s,cspace:i,j:r}=t;t.cextra[r]=!0,t.calign[r]="center",s[r]=("0"===i[r]&&t.clines[r]?"\\hspace{.25em}":"")+e,i[r]||(i[r]=".5em"),i[++t.j]=".5em"}repeat(t){const e=this.getBraces(t),s=this.getBraces(t),i=parseInt(e);if(String(i)!==e)throw new la("ColArgNotNum","First argument to %1 column specifier must be a number","*");t.template=new Array(i).fill(s).join("")+t.template.substring(t.i),t.i=0}}const va=Ko.Variant;class Ta{constructor(t,e=[]){this.options={},this.columnParser=new Na,this.packageData=new Map,this.parsers=[],this.root=null,this.nodeLists={},this.error=!1,this.handlers=t.handlers,this.nodeFactory=new fa,this.nodeFactory.configuration=this,this.nodeFactory.setCreators(t.nodes),this.itemFactory=new ma(t.items),this.itemFactory.configuration=this,Di(this.options,...e),Di(this.options,t.options),this.mathStyle=Ta.getVariant.get(this.options.mathStyle)||Ta.getVariant.get("TeX")}pushParser(t){this.parsers.unshift(t)}popParser(){this.parsers.shift()}get parser(){return this.parsers[0]}clear(){this.parsers=[],this.root=null,this.nodeLists={},this.error=!1,this.tags.resetTag()}addNode(t,e){let s=this.nodeLists[t];if(s||(s=this.nodeLists[t]=[]),s.push(e),e.kind!==t){const s=Jo.getProperty(e,"in-lists")||"",i=(s?s.split(/,/):[]).concat(t).join(",");Jo.setProperty(e,"in-lists",i)}}getList(t){const e=this.nodeLists[t]||[],s=[];for(const t of e)this.inTree(t)&&s.push(t);return this.nodeLists[t]=s,s}removeFromList(t,e){const s=this.nodeLists[t]||[];for(const t of e){const e=s.indexOf(t);e>=0&&s.splice(e,1)}}inTree(t){for(;t&&t!==this.root;)t=t.parent;return!!t}}Ta.getVariant=new Map([["TeX",(t,e)=>e&&t.match(/^[\u0391-\u03A9\u03F4]/)?va.NORMAL:""],["ISO",t=>va.ITALIC],["French",t=>t.normalize("NFD").match(/^[a-z]/)?va.ITALIC:va.NORMAL],["upright",t=>va.NORMAL]]);const wa=Ta;class Ca{constructor(t="???",e=""){this.tag=t,this.id=e}}class ka{constructor(t="",e=!1,s=!1,i=null,r="",n="",o=!1,a=""){this.env=t,this.taggable=e,this.defaultTags=s,this.tag=i,this.tagId=r,this.tagFormat=n,this.noTag=o,this.labelId=a}}class _a{constructor(){this.counter=0,this.allCounter=0,this.configuration=null,this.ids={},this.allIds={},this.labels={},this.allLabels={},this.redo=!1,this.refUpdate=!1,this.currentTag=new ka,this.history=[],this.stack=[],this.enTag=function(t,e){const s=this.configuration.nodeFactory,i=s.create("node","mtd",[t]),r=s.create("node","mlabeledtr",[e,i]);return s.create("node","mtable",[r],{side:this.configuration.options.tagSide,minlabelspacing:this.configuration.options.tagIndent,displaystyle:!0})}}start(t,e,s){this.currentTag&&this.stack.push(this.currentTag);const i=this.label;this.currentTag=new ka(t,e,s),this.label=i}get env(){return this.currentTag.env}end(){this.history.push(this.currentTag);const t=this.label;this.currentTag=this.stack.pop(),t&&!this.label&&(this.label=t)}tag(t,e){this.currentTag.tag=t,this.currentTag.tagFormat=e?t:this.formatTag(t),this.currentTag.noTag=!1}notag(){this.tag("",!0),this.currentTag.noTag=!0}get noTag(){return this.currentTag.noTag}set label(t){this.currentTag.labelId=t}get label(){return this.currentTag.labelId}formatUrl(t,e){return e+"#"+encodeURIComponent(t)}formatTag(t){return["(",t,")"]}formatRef(t){return this.formatTag(t)}formatId(t){return"mjx-eqn:"+t.replace(/\s/g,"_")}formatNumber(t){return t.toString()}autoTag(){null==this.currentTag.tag&&(this.counter++,this.tag(this.formatNumber(this.counter),!1))}clearTag(){this.tag(null,!0),this.currentTag.tagId=""}getTag(t=!1){if(t)return this.autoTag(),this.makeTag();const e=this.currentTag;return e.taggable&&!e.noTag&&(e.defaultTags&&this.autoTag(),e.tag)?this.makeTag():null}resetTag(){this.history=[],this.redo=!1,this.refUpdate=!1,this.clearTag()}reset(t=0){this.resetTag(),this.counter=this.allCounter=t,this.allLabels={},this.allIds={},this.label=""}startEquation(t){this.history=[],this.stack=[],this.clearTag(),this.currentTag=new ka("",void 0,void 0),this.labels={},this.ids={},this.counter=this.allCounter,this.redo=!1;const e=t.inputData.recompile;e&&(this.refUpdate=!0,this.counter=e.counter)}finishEquation(t){this.redo&&(t.inputData.recompile={state:t.state(),counter:this.allCounter}),this.refUpdate||(this.allCounter=this.counter),Object.assign(this.allIds,this.ids),Object.assign(this.allLabels,this.labels)}finalize(t,e){if(!e.display||this.currentTag.env||null==this.currentTag.tag)return t;const s=this.makeTag();return this.enTag(t,s)}makeId(){this.currentTag.tagId=this.formatId(this.configuration.options.useLabelIds&&this.label||this.currentTag.tag)}makeTag(){var t;this.makeId(),this.label&&(this.labels[this.label]=new Ca(this.currentTag.tag,this.currentTag.tagId),this.label="");const e=this.currentTag.tagFormat,s=Array.isArray(e)?e:(null===(t=e.match(/^(\(|\[|\{)(.*)(\}|\]|\))$/))||void 0===t?void 0:t.slice(1))||[e],i=new da(s.map(t=>t?`\\text{${t}}`:"").join(""),{},this.configuration).mml();return this.configuration.nodeFactory.create("node","mtd",[i],{id:this.currentTag.tagId,rowalign:this.configuration.options.tagAlign})}}class La extends _a{autoTag(){}getTag(){return this.currentTag.tag?super.getTag():null}}class Aa extends _a{finalize(t,e){if(!e.display||this.history.find(function(t){return t.taggable}))return t;const s=this.getTag(!0);return this.enTag(t,s)}}const Ra=new Map([["none",La],["all",Aa]]);let Sa="none";const Ma={OPTIONS:{tags:Sa,tagSide:"right",tagIndent:"0.8em",useLabelIds:!0,ignoreDuplicateLabels:!1,tagAlign:"baseline"},add(t,e){Ra.set(t,e)},addTags(t){for(const e of Object.keys(t))Ma.add(e,t[e])},create(t){const e=Ra.get(t)||Ra.get(Sa);if(!e)throw Error("Unknown tags class");return new e},setDefault(t){Sa=t},getDefault:()=>Ma.create(Sa)};class Ia{constructor(t,e,s){this._token=t,this._char=e,this._attributes=s}get token(){return this._token}get char(){return this._char}get attributes(){return this._attributes}}class Oa{constructor(t,e,s=[]){this._token=t,this._func=e,this._args=s}get token(){return this._token}get func(){return this._func}get args(){return this._args}}function Da(t){return void 0===t||t}class Pa{constructor(t,e){this._name=t,this._parser=e,Va.register(this)}get name(){return this._name}parserFor(t){return this.contains(t)?this.parser:null}parse([t,e]){const s=this.parserFor(e),i=this.lookup(e);return s&&i?Da(s(t,i)):null}set parser(t){this._parser=t}get parser(){return this._parser}}class Ba extends Pa{constructor(t,e,s){super(t,e),this._regExp=s}contains(t){return this._regExp.test(t)}lookup(t){return this.contains(t)?t:null}}class Fa extends Pa{constructor(){super(...arguments),this.map=new Map}lookup(t){return this.map.get(t)}contains(t){return this.map.has(t)}add(t,e){this.map.set(t,e)}remove(t){this.map.delete(t)}}class ja extends Fa{constructor(t,e,s){super(t,e);for(const t of Object.keys(s)){const e=s[t],[i,r]="string"==typeof e?[e,null]:e,n=new Ia(t,i,r);this.add(t,n)}}}class Ua extends ja{parse([t,e]){return super.parse([t,"\\"+e])}}class Ha extends Fa{constructor(t,e,s={}){super(t,null);const i=t=>"string"==typeof t?s[t]:t;for(const[t,s]of Object.entries(e)){let e,r;Array.isArray(s)?(e=i(s[0]),r=s.slice(1)):(e=i(s),r=[]);const n=new Oa(t,e,r);this.add(t,n)}}parserFor(t){const e=this.lookup(t);return e?e.func:null}parse([t,e]){const s=this.lookup(e),i=this.parserFor(e);return s&&i?Da(i(t,s.token,...s.args)):null}}class qa extends Ha{parse([t,e]){const s=this.lookup(e),i=this.parserFor(e);if(!s||!i)return null;const r=t.currentCS;t.currentCS="\\"+e;const n=i(t,"\\"+s.token,...s.args);return t.currentCS=r,Da(n)}}class Wa extends Ha{constructor(t,e,s,i={}){super(t,s,i),this.parser=e}parse([t,e]){const s=this.lookup(e),i=this.parserFor(e);return s&&i?Da(this.parser(t,s.token,i,s.args)):null}}const za=new Map,Va={register(t){za.set(t.name,t)},getMap:t=>za.get(t)};class Xa{constructor(){this._configuration=new fi,this._fallback=new gi}add(t,e,s=fi.DEFAULTPRIORITY){for(const e of t.slice().reverse()){const t=Va.getMap(e);if(!t)return void this.warn(`Configuration '${e}' not found! Omitted.`);this._configuration.add(t,s)}e&&this._fallback.add(e,s)}remove(t,e=null){for(const e of t){const t=this.retrieve(e);t&&this._configuration.remove(t)}e&&this._fallback.remove(e)}parse(t){for(const{item:e}of this._configuration){const s=e.parse(t);if(s===Xa.FALLBACK)break;if(s)return s}const[e,s]=t;Array.from(this._fallback)[0].item(e,s)}lookup(t){const e=this.applicable(t);return e?e.lookup(t):null}contains(t){const e=this.applicable(t);return!(!e||e instanceof ja&&null===e.lookup(t).char)}toString(){const t=[];for(const{item:e}of this._configuration)t.push(e.name);return t.join(", ")}applicable(t){for(const{item:e}of this._configuration)if(e.contains(t))return e;return null}retrieve(t){for(const{item:e}of this._configuration)if(e.name===t)return e;return null}warn(t){console.log("TexParser Warning: "+t)}}Xa.FALLBACK=Symbol("fallback");class Ga{constructor(){this.map=new Map}add(t,e,s=fi.DEFAULTPRIORITY){for(const i of Object.keys(t)){const r=i;let n=this.get(r);n||(n=new Xa,this.set(r,n)),n.add(t[r],e[r],s)}}remove(t,e){for(const s of Object.keys(t)){const i=this.get(s);i&&i.remove(t[s],e[s])}}set(t,e){this.map.set(t,e)}get(t){return this.map.get(t)}retrieve(t){for(const e of this.map.values()){const s=e.retrieve(t);if(s)return s}return null}keys(){return this.map.keys()}}class Ja{static makeProcessor(t,e){return Array.isArray(t)?t:[t,e]}static _create(t,e={}){var s;const i=null!==(s=e.priority)&&void 0!==s?s:fi.DEFAULTPRIORITY,r=e.init?this.makeProcessor(e.init,i):null,n=e.config?this.makeProcessor(e.config,i):null,o=(e.preprocessors||[]).map(t=>this.makeProcessor(t,i)),a=(e.postprocessors||[]).map(t=>this.makeProcessor(t,i)),l=e.parser||"tex";return new Ja(t,e[sa.HANDLER]||{},e[sa.FALLBACK]||{},e[sa.ITEMS]||{},e[sa.TAGS]||{},e[sa.OPTIONS]||{},e[sa.NODES]||{},o,a,r,n,i,l)}static create(t,e={}){const s=Ja._create(t,e);return $a.set(t,s),s}static local(t={}){return Ja._create("",t)}constructor(t,e={},s={},i={},r={},n={},o={},a=[],l=[],c=null,h=null,d,u){this.name=t,this.handler=e,this.fallback=s,this.items=i,this.tags=r,this.options=n,this.nodes=o,this.preprocessors=a,this.postprocessors=l,this.initMethod=c,this.configMethod=h,this.priority=d,this.parser=u,this.handler=Object.assign({[ia.CHARACTER]:[],[ia.DELIMITER]:[],[ia.MACRO]:[],[ia.ENVIRONMENT]:[]},e)}get init(){return this.initMethod?this.initMethod[0]:null}get config(){return this.configMethod?this.configMethod[0]:null}}const Ka=new Map,$a={set(t,e){Ka.set(t,e)},get:t=>Ka.get(t),keys:()=>Ka.keys()};class Ya{constructor(t,e=["tex"]){this.initMethod=new gi,this.configMethod=new gi,this.configurations=new fi,this.parsers=[],this.handlers=new Ga,this.items={},this.tags={},this.options={},this.nodes={},this.parsers=e;for(const e of t.slice().reverse())this.addPackage(e);for(const{item:t,priority:e}of this.configurations)this.append(t,e)}init(){this.initMethod.execute(this)}config(t){this.configMethod.execute(this,t);for(const e of this.configurations)this.addFilters(t,e.item)}addPackage(t){const e="string"==typeof t?t:t[0],s=this.getPackage(e);s&&this.configurations.add(s,"string"==typeof t?s.priority:t[1])}add(t,e,s={}){const i=this.getPackage(t);this.append(i),this.configurations.add(i,i.priority),this.init();const r=e.parseOptions;r.nodeFactory.setCreators(i.nodes);for(const t of Object.keys(i.items))r.itemFactory.setNodeClass(t,i.items[t]);Ma.addTags(i.tags),Di(r.options,i.options),Pi(r.options,s),this.addFilters(e,i),i.config&&i.config(this,e)}getPackage(t){const e=$a.get(t);if(e&&!this.parsers.includes(e.parser))throw Error(`Package '${t}' doesn't target the proper parser`);return e||this.warn(`Package '${t}' not found. Omitted.`),e}append(t,e){e=e||t.priority,t.initMethod&&this.initMethod.add(t.initMethod[0],t.initMethod[1]),t.configMethod&&this.configMethod.add(t.configMethod[0],t.configMethod[1]),this.handlers.add(t.handler,t.fallback,e),Object.assign(this.items,t.items),Object.assign(this.tags,t.tags),Di(this.options,t.options),Object.assign(this.nodes,t.nodes)}addFilters(t,e){for(const[s,i]of e.preprocessors)t.preFilters.add(s,i);for(const[s,i]of e.postprocessors)t.postFilters.add(s,i)}warn(t){console.warn("MathJax Warning: "+t)}}class Qa extends ha{constructor(t,e){super(t),this.global=e}get kind(){return"start"}get isOpen(){return!0}checkItem(t){if(t.isKind("stop")){let t=this.toMml();return this.global.isInner||(t=this.factory.configuration.tags.finalize(t,this.env)),[[this.factory.create("mml",t)],!0]}return super.checkItem(t)}}class Za extends ha{get kind(){return"stop"}get isClose(){return!0}}class tl extends ha{get kind(){return"open"}get isOpen(){return!0}checkItem(t){if(t.isKind("close")){const e=this.toMml(),s=this.create("node","TeXAtom",[e]);return t.addLatexItem(s),[[this.factory.create("mml",s)],!0]}return super.checkItem(t)}}tl.errors=Object.assign(Object.create(ha.errors),{stop:["ExtraOpenMissingClose","Extra open brace or missing close brace"]});class el extends ha{get kind(){return"close"}get isClose(){return!0}}class sl extends ha{get kind(){return"null"}}class il extends ha{get kind(){return"prime"}checkItem(t){const[e,s]=this.Peek(2),i=(Jo.isType(e,"msubsup")||Jo.isType(e,"msup"))&&!Jo.getChildAt(e,e.sup),r=(Jo.isType(e,"munderover")||Jo.isType(e,"mover"))&&!Jo.getChildAt(e,e.over)&&!Jo.getProperty(e,"subsupOK");if(!i&&!r){return[[this.create("node",e.getProperty("movesupsub")?"mover":"msup",[e,s]),t],!0]}const n=i?e.sup:e.over;return Jo.setChild(e,n,s),[[e,t],!0]}}class rl extends ha{get kind(){return"subsup"}checkItem(t){if(t.isKind("open")||t.isKind("left"))return ha.success;const e=this.First,s=this.getProperty("position");if(t.isKind("mml")){if(this.getProperty("primes"))if(2!==s)Jo.setChild(e,2,this.getProperty("primes"));else{Jo.setProperty(this.getProperty("primes"),"variantForm",!0);const e=this.create("node","mrow",[this.getProperty("primes"),t.First]);t.First=e}Jo.setChild(e,s,t.First),null!=this.getProperty("movesupsub")&&Jo.setProperty(e,"movesupsub",this.getProperty("movesupsub"));return[[this.factory.create("mml",e)],!0]}super.checkItem(t);const i=this.getErrors(["","sub","sup"][s]);throw new la(i[0],i[1],...i.splice(2))}}rl.errors=Object.assign(Object.create(ha.errors),{stop:["MissingScript","Missing superscript or subscript argument"],sup:["MissingOpenForSup","Missing open brace for superscript"],sub:["MissingOpenForSub","Missing open brace for subscript"]});class nl extends ha{constructor(t){super(t),this.setProperty("name","\\over")}get kind(){return"over"}get isClose(){return!0}checkItem(t){if(t.isKind("over"))throw new la("AmbiguousUseOf","Ambiguous use of %1",t.getName());if(t.isClose){let e=this.create("node","mfrac",[this.getProperty("num"),this.toMml(!1)]);return null!=this.getProperty("thickness")&&Jo.setAttribute(e,"linethickness",this.getProperty("thickness")),(this.getProperty("ldelim")||this.getProperty("rdelim"))&&(Jo.setProperty(e,"withDelims",!0),e=ya.fixedFence(this.factory.configuration,this.getProperty("ldelim"),e,this.getProperty("rdelim"))),e.attributes.set(Ko.Attr.LATEXITEM,this.getProperty("name")),[[this.factory.create("mml",e),t],!0]}return super.checkItem(t)}toString(){return"over["+this.getProperty("num")+" / "+this.nodes.join("; ")+"]"}}class ol extends ha{constructor(t,e){super(t),this.setProperty("delim",e)}get kind(){return"left"}get isOpen(){return!0}checkItem(t){if(t.isKind("right")){const e=ya.fenced(this.factory.configuration,this.getProperty("delim"),this.toMml(),t.getProperty("delim"),"",t.getProperty("color")),s=e.childNodes[0],i=e.childNodes[e.childNodes.length-1],r=this.factory.create("mml",e);return this.addLatexItem(s,"\\left"),t.addLatexItem(i,"\\right"),r.Peek()[0].attributes.set(Ko.Attr.LATEXITEM,"\\left"+t.startStr.slice(this.startI,t.stopI)),[[r],!0]}if(t.isKind("middle")){const e={stretchy:!0};t.getProperty("color")&&(e.mathcolor=t.getProperty("color"));const s=this.create("token","mo",e,t.getProperty("delim"));return t.addLatexItem(s,"\\middle"),this.Push(this.create("node","TeXAtom",[],{texClass:mr.CLOSE}),s,this.create("node","TeXAtom",[],{texClass:mr.OPEN})),this.env={},[[this],!0]}return super.checkItem(t)}}ol.errors=Object.assign(Object.create(ha.errors),{stop:["ExtraLeftMissingRight","Extra \\left or missing \\right"]});class al extends ha{constructor(t,e,s){super(t),this.setProperty("delim",e),s&&this.setProperty("color",s)}get kind(){return"middle"}get isClose(){return!0}}class ll extends ha{constructor(t,e,s){super(t),this.setProperty("delim",e),s&&this.setProperty("color",s)}get kind(){return"right"}get isClose(){return!0}}class cl extends ha{get kind(){return"break"}constructor(t,e,s){super(t),this.setProperty("linebreak",e),this.setProperty("insert",s)}checkItem(t){var e,s;const i=this.getProperty("linebreak");if(t.isKind("mml")){const r=t.First;if(r.isKind("mo")){if("after"!==((null===(s=null===(e=Jo.getOp(r))||void 0===e?void 0:e[3])||void 0===s?void 0:s.linebreakstyle)||Jo.getAttribute(r,"linebreakstyle")))return Jo.setAttribute(r,"linebreak",i),[[t],!0];if(!this.getProperty("insert"))return[[t],!0]}}const r=this.create("token","mspace",{linebreak:i});return[[this.factory.create("mml",r),t],!0]}}class hl extends ha{get kind(){return"begin"}get isOpen(){return!0}checkItem(t){if(t.isKind("end")){if(t.getName()!==this.getName())throw new la("EnvBadEnd","\\begin{%1} ended with \\end{%2}",this.getName(),t.getName());const e=this.toMml();return t.addLatexItem(e),[[this.factory.create("mml",e)],!0]}if(t.isKind("stop"))throw new la("EnvMissingEnd","Missing \\end{%1}",this.getName());return super.checkItem(t)}}class dl extends ha{get kind(){return"end"}get isClose(){return!0}}class ul extends ha{get kind(){return"style"}checkItem(t){if(!t.isClose)return super.checkItem(t);const e=this.create("node","mstyle",this.nodes,this.getProperty("styles"));return[[this.factory.create("mml",e),t],!0]}}class pl extends ha{get kind(){return"position"}checkItem(t){if(t.isClose)throw new la("MissingBoxFor","Missing box for %1",this.getName());if(t.isFinal){let e=t.toMml();switch(this.getProperty("move")){case"vertical":return e=this.create("node","mpadded",[e],{height:this.getProperty("dh"),depth:this.getProperty("dd"),voffset:this.getProperty("dh")}),[[this.factory.create("mml",e)],!0];case"horizontal":return[[this.factory.create("mml",this.getProperty("left")),t,this.factory.create("mml",this.getProperty("right"))],!0]}}return super.checkItem(t)}}class ml extends ha{get kind(){return"cell"}get isClose(){return!0}}class fl extends ha{get isFinal(){return!0}get kind(){return"mml"}}class gl extends ha{get kind(){return"fn"}checkItem(t){const e=this.First;if(e){if(t.isOpen)return ha.success;if(!t.isKind("fn")){let s=t.First;if(!t.isKind("mml")||!s)return[[e,t],!0];if(Jo.isType(s,"mstyle")&&s.childNodes.length&&Jo.isType(s.childNodes[0].childNodes[0],"mspace")||Jo.isType(s,"mspace"))return[[e,t],!0];Jo.isEmbellished(s)&&(s=Jo.getCoreMO(s));const i=Jo.getForm(s);if(null!=i&&[0,0,1,1,0,1,1,0,0,0][i[2]])return[[e,t],!0]}if(e.isKind("TeXAtom")&&e.isEmpty)return[[e,t],!0];return[[e,this.create("token","mo",{texClass:mr.NONE},To.ApplyFunction),t],!0]}return super.checkItem(t)}}class bl extends ha{constructor(){super(...arguments),this.remap=Va.getMap("not_remap")}get kind(){return"not"}checkItem(t){let e,s,i;if(t.isKind("open")||t.isKind("left"))return ha.success;if(t.isKind("mml")&&(Jo.isType(t.First,"mo")||Jo.isType(t.First,"mi")||Jo.isType(t.First,"mtext"))&&(e=t.First,s=Jo.getText(e),1===s.length&&!Jo.getProperty(e,"movesupsub")&&1===Jo.getChildren(e).length))return this.remap.contains(s)?(i=this.create("text",this.remap.lookup(s).char),Jo.setChild(e,0,i)):(i=this.create("text","\u0338"),Jo.appendChildren(e,[i])),[[t],!0];i=this.create("text","\u29f8");const r=this.create("node","mtext",[],{},i),n=this.create("node","mpadded",[r],{width:0});return e=this.create("node","TeXAtom",[n],{texClass:mr.REL}),[[e,t],!0]}}class El extends ha{get kind(){return"nonscript"}checkItem(t){if(t.isKind("mml")&&1===t.Size()){let e=t.First;if(e.isKind("mstyle")&&e.notParent&&(e=Jo.getChildren(Jo.getChildren(e)[0])[0]),e.isKind("mspace")){if(e!==t.First){const e=this.create("node","mrow",[t.Pop()]);t.Push(e)}this.factory.configuration.addNode("nonscript",t.First)}}return[[t],!0]}}class xl extends ha{get kind(){return"dots"}checkItem(t){if(t.isKind("open")||t.isKind("left"))return ha.success;let e=this.getProperty("ldots");const s=t.First;if(t.isKind("mml")&&Jo.isEmbellished(s)){const t=Jo.getTexClass(Jo.getCoreMO(s));t!==mr.BIN&&t!==mr.REL||(e=this.getProperty("cdots"))}return[[e,t],!0]}}class yl extends ha{constructor(){super(...arguments),this.table=[],this.row=[],this.frame=[],this.hfill=[],this.arraydef={},this.cstart=[],this.cend=[],this.cextra=[],this.atEnd=!1,this.ralign=[],this.breakAlign={cell:"",row:"",table:""},this.templateSubs=0}get kind(){return"array"}get isOpen(){return!0}get copyEnv(){return!1}checkItem(t){if(t.isClose&&!t.isKind("over")){if(t.getProperty("isEntry"))return this.EndEntry(),this.clearEnv(),this.StartEntry(),ha.fail;if(t.getProperty("isCR"))return this.EndEntry(),this.EndRow(),this.clearEnv(),this.StartEntry(),ha.fail;this.EndTable(),this.clearEnv();const e=this.factory.create("mml",this.createMml());if(this.getProperty("requireClose")){if(t.isKind("close"))return[[e],!0];throw new la("MissingCloseBrace","Missing close brace")}return[[e,t],!0]}return super.checkItem(t)}createMml(){const t=this.arraydef.scriptlevel;delete this.arraydef.scriptlevel;let e=this.create("node","mtable",this.table,this.arraydef);return t&&e.setProperty("smallmatrix",!0),this.breakAlign.table&&Jo.setAttribute(e,"data-break-align",this.breakAlign.table),this.getProperty("arrayPadding")&&(Jo.setAttribute(e,"data-frame-styles",""),Jo.setAttribute(e,"framespacing",this.getProperty("arrayPadding"))),e=this.handleFrame(e),void 0!==t&&(e=this.create("node","mstyle",[e],{scriptlevel:t})),(this.getProperty("open")||this.getProperty("close"))&&(e=ya.fenced(this.factory.configuration,this.getProperty("open"),e,this.getProperty("close"))),e}handleFrame(t){if(!this.frame.length)return t;const e=new Map(this.frame),s=this.frame.reduce((t,[,e])=>e===t?e:"",this.frame[0][1]);if(s){if(4===this.frame.length)return Jo.setAttribute(t,"frame",s),Jo.removeAttribute(t,"data-frame-styles"),t;if("solid"===s)return Jo.setAttribute(t,"data-frame-styles",""),t=this.create("node","menclose",[t],{notation:Array.from(e.keys()).join(" "),"data-padding":0})}const i=Ro.map(t=>e.get(t)||"none").join(" ");return Jo.setAttribute(t,"data-frame-styles",i),t}StartEntry(){const t=this.row.length;let e=this.cstart[t],s=this.cend[t];const i=this.ralign[t],r=this.cextra;if(!(e||s||i||r[t]||r[t+1]))return;let[n,o,a,l]=this.getEntry();if(!r[t]||this.atEnd&&!r[t+1]||(e+="&"),"&"!==a&&(l=!!o.trim()||!!(t||a&&"\\end"!==a.substring(0,4)),r[t+1]&&!r[t]&&(s=(s||"")+"&",this.atEnd=!0)),!l&&!n)return;const c=this.parser;if(l&&(e&&(o=ya.addArgs(c,e,o)),s&&(o=ya.addArgs(c,o,s)),i&&(o="\\text{"+o.trim()+"}"),(e||s||i)&&++this.templateSubs>c.configuration.options.maxTemplateSubtitutions))throw new la("MaxTemplateSubs","Maximum template substitutions exceeded; is there an invalid use of \\\\ in the template?");n&&(o=ya.addArgs(c,n,o)),c.string=ya.addArgs(c,o,c.string),c.i=0}getEntry(){const t=this.parser,e=/^([^]*?)([&{}]|\\\\|\\(?:begin|end)\s*\{array\}|\\cr|\\)/;let s,i=0,r=0,n=t.i;const o=["","","",!1];for(;null!==(s=t.string.slice(n).match(e));)switch(n+=s[0].length,s[2]){case"\\":n++;break;case"{":i++;break;case"}":if(!i)return o;i--;break;case"\\begin{array}":i||r++;break;case"\\end{array}":if(!i&&r){r--;break}default:{if(i||r)continue;n-=s[2].length;let e=t.string.slice(t.i,n).trim();const o=e.match(/^(?:\s*\\(?:h(?:dash)?line|hfil{1,3}|rowcolor\s*\{.*?\}))+/);return o&&(e=e.slice(o[0].length)),t.string=t.string.slice(n),t.i=0,[(null==o?void 0:o[0])||"",e,s[2],!0]}}return o}EndEntry(){const t=this.create("node","mtd",this.nodes);this.hfill.length&&(0===this.hfill[0]&&Jo.setAttribute(t,"columnalign","right"),this.hfill[this.hfill.length-1]===this.Size()&&Jo.setAttribute(t,"columnalign",Jo.getAttribute(t,"columnalign")?"center":"left"));const e=this.ralign[this.row.length];if(e){const[s,i,r]=e,n=this.create("node","mpadded",t.childNodes[0].childNodes,{width:i,"data-overflow":"auto","data-align":r,"data-vertical-align":s});n.setProperty("vbox",s),t.childNodes[0].childNodes=[],t.appendChild(n)}else this.breakAlign.cell&&Jo.setAttribute(t,"data-vertical-align",this.breakAlign.cell);this.breakAlign.cell="",this.row.push(t),this.Clear(),this.hfill=[]}EndRow(){let t="mtr";this.getProperty("isNumbered")&&3===this.row.length?(this.row.unshift(this.row.pop()),t="mlabeledtr"):this.getProperty("isLabeled")&&(t="mlabeledtr",this.setProperty("isLabeled",!1));const e=this.create("node",t,this.row);this.breakAlign.row&&(Jo.setAttribute(e,"data-break-align",this.breakAlign.row),this.breakAlign.row=""),this.addLatexItem(e),this.table.push(e),this.row=[],this.atEnd=!1}EndTable(){(this.Size()||this.row.length)&&(this.EndEntry(),this.EndRow()),this.checkLines()}checkLines(){if(this.arraydef.rowlines){const t=this.arraydef.rowlines.split(/ /);t.length===this.table.length?(this.frame.push(["bottom",t.pop()]),t.length?this.arraydef.rowlines=t.join(" "):delete this.arraydef.rowlines):t.lengththis.maxrow&&(this.maxrow=this.row.length);const t=this.factory.configuration.tags.getTag();t&&(this.row=[t].concat(this.row),this.setProperty("isLabeled",!0)),this.factory.configuration.tags.clearTag(),super.EndRow()}EndTable(){super.EndTable(),this.factory.configuration.tags.end(),this.extendArray("columnalign",this.maxrow),this.extendArray("columnwidth",this.maxrow),this.extendArray("columnspacing",this.maxrow-1),this.extendArray("data-break-align",this.maxrow),this.addIndentshift()}extendArray(t,e){if(!this.arraydef[t])return;const s=this.arraydef[t].split(/ /),i=[...s];if(i.length>1){for(;i.length0){const t="center"===e?".7em":"2em";for(const e of this.table){const i=e.childNodes[e.isKind("mlabeledtr")?s+1:s];if(i){const e=this.create("node","mstyle",i.childNodes[0].childNodes,{indentshift:t});i.childNodes[0].childNodes=[],i.appendChild(e)}}}e=t[s]}}}class vl extends hl{get kind(){return"mstyle"}constructor(t,e,s){super(t),this.attrList=e,this.setProperty("name",s)}checkItem(t){if(t.isKind("end")&&t.getName()===this.getName()){return[[this.create("node","mstyle",[this.toMml()],this.attrList)],!0]}return super.checkItem(t)}}class Tl extends ha{constructor(t,...e){super(t),this.factory.configuration.tags.start("equation",!0,e[0])}get kind(){return"equation"}get isOpen(){return!0}checkItem(t){if(t.isKind("end")){const e=this.toMml(),s=this.factory.configuration.tags.getTag();return this.factory.configuration.tags.end(),[[s?this.factory.configuration.tags.enTag(e,s):e,t],!0]}if(t.isKind("stop"))throw new la("EnvMissingEnd","Missing \\end{%1}",this.getName());return super.checkItem(t)}}const wl=1.2/.85,Cl={fontfamily:1,fontsize:1,fontweight:1,fontstyle:1,color:1,background:1,id:1,class:1,href:1,style:1};function kl(t,e=1/0){const s=t.replace(/\s+/g,"").split("").map(t=>{const e={t:"top",b:"bottom",m:"middle",c:"center"}[t];if(!e)throw new la("BadBreakAlign","Invalid alignment character: %1",t);return e});if(s.length>e)throw new la("TooManyAligns","Too many alignment characters: %1",t);return 1===e?s[0]:s.join(" ")}function _l(t,e){const s=t.stack.env,i=s.inRoot;s.inRoot=!0;const r=new da(e,s,t.configuration);let n=r.mml();const o=r.stack.global;if(o.leftRoot||o.upRoot){const e={};o.leftRoot&&(e.width=o.leftRoot),o.upRoot&&(e.voffset=o.upRoot,e.height=o.upRoot),n=t.create("node","mpadded",[n],e)}return s.inRoot=i,n}const Ll={Open(t,e){t.Push(t.itemFactory.create("open"))},Close(t,e){t.Push(t.itemFactory.create("close"))},Bar(t,e){const s=t.create("token","mo",{stretchy:!1,texClass:mr.ORD},e);s.setProperty("keep-attrs","stretchy"),t.Push(s)},Tilde(t,e){t.Push(t.create("token","mtext",{},To.nbsp))},Space(t,e){},Superscript(t,e){let s,i;t.GetNext().match(/\d/)&&(t.string=t.string.substring(0,t.i+1)+" "+t.string.substring(t.i+1));const r=t.stack.Top();r.isKind("prime")?([i,s]=r.Peek(2),t.stack.Pop()):(i=t.stack.Prev(),i||(i=t.create("token","mi",{},"")));const n=Jo.getProperty(i,"movesupsub");let o=Jo.isType(i,"msubsup")?i.sup:i.over;if(Jo.isType(i,"msubsup")&&!Jo.isType(i,"msup")&&Jo.getChildAt(i,i.sup)||Jo.isType(i,"munderover")&&!Jo.isType(i,"mover")&&Jo.getChildAt(i,i.over)&&!Jo.getProperty(i,"subsupOK"))throw new la("DoubleExponent","Double exponent: use braces to clarify");Jo.isType(i,"msubsup")&&!Jo.isType(i,"msup")||(n?((!Jo.isType(i,"munderover")||Jo.isType(i,"mover")||Jo.getChildAt(i,i.over))&&(i=t.create("node","munderover",[i],{movesupsub:!0})),o=i.over):(i=t.create("node","msubsup",[i]),o=i.sup)),t.Push(t.itemFactory.create("subsup",i).setProperties({position:o,primes:s,movesupsub:n}))},Subscript(t,e){let s,i;t.GetNext().match(/\d/)&&(t.string=t.string.substring(0,t.i+1)+" "+t.string.substring(t.i+1));const r=t.stack.Top();r.isKind("prime")?([i,s]=r.Peek(2),t.stack.Pop()):(i=t.stack.Prev(),i||(i=t.create("token","mi",{},"")));const n=Jo.getProperty(i,"movesupsub");let o=Jo.isType(i,"msubsup")?i.sub:i.under;if(Jo.isType(i,"msubsup")&&!Jo.isType(i,"msup")&&Jo.getChildAt(i,i.sub)||Jo.isType(i,"munderover")&&!Jo.isType(i,"mover")&&Jo.getChildAt(i,i.under)&&!Jo.getProperty(i,"subsupOK"))throw new la("DoubleSubscripts","Double subscripts: use braces to clarify");Jo.isType(i,"msubsup")&&!Jo.isType(i,"msup")||(n?((!Jo.isType(i,"munderover")||Jo.isType(i,"mover")||Jo.getChildAt(i,i.under))&&(i=t.create("node","munderover",[i],{movesupsub:!0})),o=i.under):(i=t.create("node","msubsup",[i]),o=i.sub)),t.Push(t.itemFactory.create("subsup",i).setProperties({position:o,primes:s,movesupsub:n}))},Prime(t,e){let s=t.stack.Prev();if(s||(s=t.create("token","mi")),Jo.isType(s,"msubsup")&&!Jo.isType(s,"msup")&&Jo.getChildAt(s,s.sup)||Jo.isType(s,"munderover")&&!Jo.isType(s,"mover")&&Jo.getChildAt(s,s.over)&&!Jo.getProperty(s,"subsupOK"))throw new la("DoubleExponentPrime","Prime causes double exponent: use braces to clarify");let i="";t.i--;do{i+=To.prime,t.i++,e=t.GetNext()}while("'"===e||e===To.rsquo);i=["","\u2032","\u2033","\u2034","\u2057"][i.length]||i;const r=t.create("token","mo",{variantForm:!0},i);t.Push(t.itemFactory.create("prime",s,r))},Comment(t,e){for(;t.in.macroColumn(t,r,parseInt(i)),t.Push(t.itemFactory.create("null"))},BeginEnd(t,e){const s=t.GetArgument(e);if(s.match(/\\/))throw new la("InvalidEnv","Invalid environment name '%1'",s);const i=t.configuration.handlers.get(ia.ENVIRONMENT).lookup(s);if(i&&"\\end"===e){if(!i.args[0]){const e=t.itemFactory.create("end").setProperty("name",s);return void t.Push(e)}t.stack.env.closing=s}ya.checkMaxMacros(t,!1),t.parse(ia.ENVIRONMENT,[t,s])},Array(t,e,s,i,r,n,o,a,l){r||(r=t.GetArgument("\\begin{"+e.getName()+"}"));const c=t.itemFactory.create("array");return"array"===e.getName()&&c.setProperty("arrayPadding",".5em .125em"),c.parser=t,c.arraydef={columnspacing:n||"1em",rowspacing:o||"4pt"},t.configuration.columnParser.process(t,r,c),s&&c.setProperty("open",t.convertDelimiter(s)),i&&c.setProperty("close",t.convertDelimiter(i)),"'"===(a||"").charAt(1)&&(c.arraydef["data-cramped"]=!0,a=a.charAt(0)),"D"===a?c.arraydef.displaystyle=!0:a&&(c.arraydef.displaystyle=!1),c.arraydef.scriptlevel="S"===a?1:0,l&&(c.arraydef.useHeight=!1),t.Push(e),c.StartEntry(),c},AlignedArray(t,e,s=""){const i=t.GetBrackets("\\begin{"+e.getName()+"}"),r=Ll.Array(t,e,null,null,null,null,null,s);return ya.setArrayAlign(r,i)},IndentAlign(t,e){const s=`\\begin{${e.getName()}}`,i=t.GetBrackets(s,""),r=t.GetBrackets(s,""),n=t.GetBrackets(s,"");if(i&&!na.matchDimen(i)[0]||r&&!na.matchDimen(r)[0]||n&&!na.matchDimen(n)[0])throw new la("BracketMustBeDimension","Bracket argument to %1 must be a dimension",s);const o=t.GetArgument(s);if(o&&!o.match(/^([lcr]{1,3})?$/))throw new la("BadAlignment","Alignment must be one to three copies of l, c, or r");const a=[...o].map(t=>({l:"left",c:"center",r:"right"}[t]));1===a.length&&a.push(a[0]);const l={};for(const[t,e]of[["indentshiftfirst",i],["indentshift",r||i],["indentshiftlast",n],["indentalignfirst",a[0]],["indentalign",a[1]],["indentalignlast",a[2]]])e&&(l[t]=e);t.Push(t.itemFactory.create("mstyle",l,e.getName()))},Equation:(t,e,s,i=!0)=>(t.configuration.mathItem.display=i,t.stack.env.display=i,ya.checkEqnEnv(t),t.Push(e),t.itemFactory.create("equation",s).setProperty("name",e.getName())),EqnArray(t,e,s,i,r,n,o){const a=e.getName(),l="gather"===a||"gather*"===a;i&&ya.checkEqnEnv(t,!l),t.Push(e),r=(r=r.replace(/[^clr]/g,"").split("").join(" ")).replace(/l/g,"left").replace(/r/g,"right").replace(/c/g,"center"),n=kl(n);const c=t.itemFactory.create("eqnarray",a,s,i,t.stack.global);return c.arraydef={displaystyle:!0,columnalign:r,columnspacing:o||"1em",rowspacing:"3pt","data-break-align":n,side:t.options.tagSide,minlabelspacing:t.options.tagIndent},l&&c.setProperty("nestable",!0),c},HandleNoTag(t,e){t.tags.notag()},HandleLabel(t,e){const s=t.GetArgument(e);if(""!==s&&!t.tags.refUpdate){if(t.tags.label)throw new la("MultipleCommand","Multiple %1",t.currentCS);if(t.tags.label=s,(t.tags.allLabels[s]||t.tags.labels[s])&&!t.options.ignoreDuplicateLabels)throw new la("MultipleLabel","Label '%1' multiply defined",s);t.tags.labels[s]=new Ca}},HandleRef(t,e,s){const i=t.GetArgument(e);let r=t.tags.allLabels[i]||t.tags.labels[i];r||(t.tags.refUpdate||(t.tags.redo=!0),r=new Ca);let n=r.tag;s&&(n=t.tags.formatRef(n));const o=t.create("node","mrow",ya.internalMath(t,Array.isArray(n)?n.join(""):n),{href:t.tags.formatUrl(r.id,t.options.baseURL),class:"MathJax_ref"});t.Push(o)},Macro(t,e,s,i,r){if(i){const n=[];if(null!=r){const s=t.GetBrackets(e);n.push(null==s?r:s)}for(let s=n.length;s1&&(i.autoOP=!1)),!i.mathvariant&&ya.isLatinOrGreekChar(e)){const s=t.configuration.mathStyle(e);s&&(i.mathvariant=s)}const n=t.create("token","mi",i,e);t.Push(n)},digit(t,e){const s=t.configuration.options.numberPattern,i=t.string.slice(t.i-1).match(s);if(!i)return!1;const r=ya.getFontDef(t),n=t.create("token","mn",r,i[0].replace(/[{}]/g,""));return t.i+=i[0].length-1,t.Push(n),!0},controlSequence(t,e){const s=t.GetCS();t.parse(ia.MACRO,[t,s])},lcGreek(t,e){const s={mathvariant:t.configuration.mathStyle(e.char)||Rl.ITALIC},i=t.create("token","mi",s,e.char);t.Push(i)},ucGreek(t,e){const s={mathvariant:t.stack.env.font||t.configuration.mathStyle(e.char,!0)||Rl.NORMAL},i=t.create("token","mi",s,e.char);t.Push(i)},mathchar0mi(t,e){const s=e.attributes||{mathvariant:Rl.ITALIC},i=t.create("token","mi",s,e.char);t.Push(i)},mathchar0mo(t,e){const s=e.attributes||{};s.stretchy=!1;const i=t.create("token","mo",s,e.char);Jo.setProperty(i,"fixStretchy",!0),t.configuration.addNode("fixStretchy",i),t.Push(i)},mathchar7(t,e){const s=e.attributes||{mathvariant:Rl.NORMAL};t.stack.env.font&&(s.mathvariant=t.stack.env.font);const i=t.create("token","mi",s,e.char);t.Push(i)},delimiter(t,e){let s=e.attributes||{};s=Object.assign({fence:!1,stretchy:!1},s);const i=t.create("token","mo",s,e.char);t.Push(i)},environment(t,e,s,i){const r=t.itemFactory.create("begin").setProperty("name",e);t.Push(s(t,r,...i.slice(1)))}},Ml=Sl,Il=xo(go.thickmathspace),Ol=Ko.Variant;new Ba("letter",Ml.variable,/[a-z]/i),new Ba("digit",Ml.digit,/[0-9.,]/),new Ba("command",Ml.controlSequence,/^\\/),new Ha("special",{"{":Al.Open,"}":Al.Close,"~":Al.Tilde,"^":Al.Superscript,_:Al.Subscript,"|":Al.Bar," ":Al.Space,"\t":Al.Space,"\r":Al.Space,"\n":Al.Space,"'":Al.Prime,"%":Al.Comment,"&":Al.Entry,"#":Al.Hash,"\xa0":Al.Space,"\u2019":Al.Prime}),new ja("lcGreek",Ml.lcGreek,{alpha:"\u03b1",beta:"\u03b2",gamma:"\u03b3",delta:"\u03b4",epsilon:"\u03f5",zeta:"\u03b6",eta:"\u03b7",theta:"\u03b8",iota:"\u03b9",kappa:"\u03ba",lambda:"\u03bb",mu:"\u03bc",nu:"\u03bd",xi:"\u03be",omicron:"\u03bf",pi:"\u03c0",rho:"\u03c1",sigma:"\u03c3",tau:"\u03c4",upsilon:"\u03c5",phi:"\u03d5",chi:"\u03c7",psi:"\u03c8",omega:"\u03c9",varepsilon:"\u03b5",vartheta:"\u03d1",varpi:"\u03d6",varrho:"\u03f1",varsigma:"\u03c2",varphi:"\u03c6"}),new ja("ucGreek",Ml.ucGreek,{Gamma:"\u0393",Delta:"\u0394",Theta:"\u0398",Lambda:"\u039b",Xi:"\u039e",Pi:"\u03a0",Sigma:"\u03a3",Upsilon:"\u03a5",Phi:"\u03a6",Psi:"\u03a8",Omega:"\u03a9"}),new ja("mathchar0mi",Ml.mathchar0mi,{AA:"\u212b",S:["\xa7",{mathvariant:Ol.NORMAL}],aleph:["\u2135",{mathvariant:Ol.NORMAL}],hbar:["\u210f",{variantForm:!0}],imath:"\u0131",jmath:"\u0237",ell:"\u2113",wp:["\u2118",{mathvariant:Ol.NORMAL}],Re:["\u211c",{mathvariant:Ol.NORMAL}],Im:["\u2111",{mathvariant:Ol.NORMAL}],partial:["\u2202",{mathvariant:Ol.ITALIC}],infty:["\u221e",{mathvariant:Ol.NORMAL}],prime:["\u2032",{variantForm:!0}],emptyset:["\u2205",{mathvariant:Ol.NORMAL}],nabla:["\u2207",{mathvariant:Ol.NORMAL}],top:["\u22a4",{mathvariant:Ol.NORMAL}],bot:["\u22a5",{mathvariant:Ol.NORMAL}],angle:["\u2220",{mathvariant:Ol.NORMAL}],triangle:["\u25b3",{mathvariant:Ol.NORMAL}],backslash:["\\",{mathvariant:Ol.NORMAL}],forall:["\u2200",{mathvariant:Ol.NORMAL}],exists:["\u2203",{mathvariant:Ol.NORMAL}],neg:["\xac",{mathvariant:Ol.NORMAL}],lnot:["\xac",{mathvariant:Ol.NORMAL}],flat:["\u266d",{mathvariant:Ol.NORMAL}],natural:["\u266e",{mathvariant:Ol.NORMAL}],sharp:["\u266f",{mathvariant:Ol.NORMAL}],clubsuit:["\u2663",{mathvariant:Ol.NORMAL}],diamondsuit:["\u2662",{mathvariant:Ol.NORMAL}],heartsuit:["\u2661",{mathvariant:Ol.NORMAL}],spadesuit:["\u2660",{mathvariant:Ol.NORMAL}]}),new ja("mathchar0mo",Ml.mathchar0mo,{surd:["\u221a",{symmetric:!0}],coprod:["\u2210",{movesupsub:!0}],bigvee:["\u22c1",{movesupsub:!0}],bigwedge:["\u22c0",{movesupsub:!0}],biguplus:["\u2a04",{movesupsub:!0}],bigcap:["\u22c2",{movesupsub:!0}],bigcup:["\u22c3",{movesupsub:!0}],int:"\u222b",intop:["\u222b",{movesupsub:!0,movablelimits:!0}],iint:"\u222c",iiint:"\u222d",prod:["\u220f",{movesupsub:!0}],sum:["\u2211",{movesupsub:!0}],bigotimes:["\u2a02",{movesupsub:!0}],bigoplus:["\u2a01",{movesupsub:!0}],bigodot:["\u2a00",{movesupsub:!0}],oint:"\u222e",ointop:["\u222e",{movesupsub:!0,movablelimits:!0}],oiint:"\u222f",oiiint:"\u2230",bigsqcup:["\u2a06",{movesupsub:!0}],smallint:["\u222b",{largeop:!1}],triangleleft:"\u25c3",triangleright:"\u25b9",bigtriangleup:"\u25b3",bigtriangledown:"\u25bd",wedge:"\u2227",land:"\u2227",vee:"\u2228",lor:"\u2228",cap:"\u2229",cup:"\u222a",ddagger:"\u2021",dagger:"\u2020",sqcap:"\u2293",sqcup:"\u2294",uplus:"\u228e",amalg:"\u2a3f",diamond:"\u22c4",bullet:"\u2219",wr:"\u2240",div:"\xf7",odot:["\u2299",{largeop:!1}],oslash:["\u2298",{largeop:!1}],otimes:["\u2297",{largeop:!1}],ominus:["\u2296",{largeop:!1}],oplus:["\u2295",{largeop:!1}],mp:"\u2213",pm:"\xb1",circ:"\u2218",bigcirc:"\u25ef",setminus:"\u2216",cdot:"\u22c5",ast:"\u2217",times:"\xd7",star:"\u22c6",propto:"\u221d",sqsubseteq:"\u2291",sqsupseteq:"\u2292",parallel:"\u2225",mid:"\u2223",dashv:"\u22a3",vdash:"\u22a2",leq:"\u2264",le:"\u2264",geq:"\u2265",ge:"\u2265",lt:"<",gt:">",succ:"\u227b",prec:"\u227a",approx:"\u2248",succeq:"\u2ab0",preceq:"\u2aaf",supset:"\u2283",subset:"\u2282",supseteq:"\u2287",subseteq:"\u2286",in:"\u2208",ni:"\u220b",notin:"\u2209",owns:"\u220b",gg:"\u226b",ll:"\u226a",sim:"\u223c",simeq:"\u2243",perp:"\u27c2",equiv:"\u2261",asymp:"\u224d",smile:"\u2323",frown:"\u2322",ne:"\u2260",neq:"\u2260",cong:"\u2245",doteq:"\u2250",bowtie:"\u22c8",models:"\u22a7",notChar:"\u29f8",Leftrightarrow:"\u21d4",Leftarrow:"\u21d0",Rightarrow:"\u21d2",leftrightarrow:"\u2194",leftarrow:"\u2190",gets:"\u2190",rightarrow:"\u2192",to:["\u2192",{accent:!1}],mapsto:"\u21a6",leftharpoonup:"\u21bc",leftharpoondown:"\u21bd",rightharpoonup:"\u21c0",rightharpoondown:"\u21c1",nearrow:"\u2197",searrow:"\u2198",nwarrow:"\u2196",swarrow:"\u2199",rightleftharpoons:"\u21cc",hookrightarrow:"\u21aa",hookleftarrow:"\u21a9",longleftarrow:"\u27f5",Longleftarrow:"\u27f8",longrightarrow:"\u27f6",Longrightarrow:"\u27f9",Longleftrightarrow:"\u27fa",longleftrightarrow:"\u27f7",longmapsto:"\u27fc",ldots:"\u2026",cdots:"\u22ef",vdots:"\u22ee",ddots:"\u22f1",iddots:"\u22f0",dotsc:"\u2026",dotsb:"\u22ef",dotsm:"\u22ef",dotsi:"\u22ef",dotso:"\u2026",ldotp:[".",{texClass:mr.PUNCT}],cdotp:["\u22c5",{texClass:mr.PUNCT}],colon:[":",{texClass:mr.PUNCT}]}),new ja("mathchar7",Ml.mathchar7,{_:"_","#":"#",$:"$","%":"%","&":"&",And:"&"}),new Ua("delimiter",Ml.delimiter,{"(":"(",")":")","[":"[","]":"]","<":"\u27e8",">":"\u27e9","\\lt":"\u27e8","\\gt":"\u27e9","/":"/","|":["|",{texClass:mr.ORD}],".":"","\\lmoustache":"\u23b0","\\rmoustache":"\u23b1","\\lgroup":"\u27ee","\\rgroup":"\u27ef","\\arrowvert":"\u23d0","\\Arrowvert":"\u2016","\\bracevert":"\u23aa","\\Vert":["\u2016",{texClass:mr.ORD}],"\\|":["\u2016",{texClass:mr.ORD}],"\\vert":["|",{texClass:mr.ORD}],"\\uparrow":"\u2191","\\downarrow":"\u2193","\\updownarrow":"\u2195","\\Uparrow":"\u21d1","\\Downarrow":"\u21d3","\\Updownarrow":"\u21d5","\\backslash":"\\","\\rangle":"\u27e9","\\langle":"\u27e8","\\rbrace":"}","\\lbrace":"{","\\}":"}","\\{":"{","\\rceil":"\u2309","\\lceil":"\u2308","\\rfloor":"\u230b","\\lfloor":"\u230a","\\lbrack":"[","\\rbrack":"]"}),new qa("macros",{displaystyle:[Al.SetStyle,"D",!0,0],textstyle:[Al.SetStyle,"T",!1,0],scriptstyle:[Al.SetStyle,"S",!1,1],scriptscriptstyle:[Al.SetStyle,"SS",!1,2],rm:[Al.SetFont,Ol.NORMAL],mit:[Al.SetFont,Ol.ITALIC],oldstyle:[Al.SetFont,Ol.OLDSTYLE],cal:[Al.SetFont,Ol.CALLIGRAPHIC],it:[Al.SetFont,Ol.MATHITALIC],bf:[Al.SetFont,Ol.BOLD],sf:[Al.SetFont,Ol.SANSSERIF],tt:[Al.SetFont,Ol.MONOSPACE],frak:[Al.MathFont,Ol.FRAKTUR],Bbb:[Al.MathFont,Ol.DOUBLESTRUCK],mathrm:[Al.MathFont,Ol.NORMAL],mathup:[Al.MathFont,Ol.NORMAL],mathnormal:[Al.MathFont,""],mathbf:[Al.MathFont,Ol.BOLD],mathbfup:[Al.MathFont,Ol.BOLD],mathit:[Al.MathFont,Ol.MATHITALIC],mathbfit:[Al.MathFont,Ol.BOLDITALIC],mathbb:[Al.MathFont,Ol.DOUBLESTRUCK],mathfrak:[Al.MathFont,Ol.FRAKTUR],mathbffrak:[Al.MathFont,Ol.BOLDFRAKTUR],mathscr:[Al.MathFont,Ol.SCRIPT],mathbfscr:[Al.MathFont,Ol.BOLDSCRIPT],mathsf:[Al.MathFont,Ol.SANSSERIF],mathsfup:[Al.MathFont,Ol.SANSSERIF],mathbfsf:[Al.MathFont,Ol.BOLDSANSSERIF],mathbfsfup:[Al.MathFont,Ol.BOLDSANSSERIF],mathsfit:[Al.MathFont,Ol.SANSSERIFITALIC],mathbfsfit:[Al.MathFont,Ol.SANSSERIFBOLDITALIC],mathtt:[Al.MathFont,Ol.MONOSPACE],mathcal:[Al.MathFont,Ol.CALLIGRAPHIC],mathbfcal:[Al.MathFont,Ol.BOLDCALLIGRAPHIC],symrm:[Al.MathFont,Ol.NORMAL],symup:[Al.MathFont,Ol.NORMAL],symnormal:[Al.MathFont,""],symbf:[Al.MathFont,Ol.BOLD,Ol.BOLDITALIC],symbfup:[Al.MathFont,Ol.BOLD],symit:[Al.MathFont,Ol.ITALIC],symbfit:[Al.MathFont,Ol.BOLDITALIC],symbb:[Al.MathFont,Ol.DOUBLESTRUCK],symfrak:[Al.MathFont,Ol.FRAKTUR],symbffrak:[Al.MathFont,Ol.BOLDFRAKTUR],symscr:[Al.MathFont,Ol.SCRIPT],symbfscr:[Al.MathFont,Ol.BOLDSCRIPT],symsf:[Al.MathFont,Ol.SANSSERIF,Ol.SANSSERIFITALIC],symsfup:[Al.MathFont,Ol.SANSSERIF],symbfsf:[Al.MathFont,Ol.BOLDSANSSERIF],symbfsfup:[Al.MathFont,Ol.BOLDSANSSERIF],symsfit:[Al.MathFont,Ol.SANSSERIFITALIC],symbfsfit:[Al.MathFont,Ol.SANSSERIFBOLDITALIC],symtt:[Al.MathFont,Ol.MONOSPACE],symcal:[Al.MathFont,Ol.CALLIGRAPHIC],symbfcal:[Al.MathFont,Ol.BOLDCALLIGRAPHIC],textrm:[Al.HBox,null,Ol.NORMAL],textup:[Al.HBox,null,Ol.NORMAL],textnormal:[Al.HBox],textit:[Al.HBox,null,Ol.ITALIC],textbf:[Al.HBox,null,Ol.BOLD],textsf:[Al.HBox,null,Ol.SANSSERIF],texttt:[Al.HBox,null,Ol.MONOSPACE],tiny:[Al.SetSize,.5],Tiny:[Al.SetSize,.6],scriptsize:[Al.SetSize,.7],small:[Al.SetSize,.85],normalsize:[Al.SetSize,1],large:[Al.SetSize,1.2],Large:[Al.SetSize,1.44],LARGE:[Al.SetSize,1.73],huge:[Al.SetSize,2.07],Huge:[Al.SetSize,2.49],arcsin:Al.NamedFn,arccos:Al.NamedFn,arctan:Al.NamedFn,arg:Al.NamedFn,cos:Al.NamedFn,cosh:Al.NamedFn,cot:Al.NamedFn,coth:Al.NamedFn,csc:Al.NamedFn,deg:Al.NamedFn,det:Al.NamedOp,dim:Al.NamedFn,exp:Al.NamedFn,gcd:Al.NamedOp,hom:Al.NamedFn,inf:Al.NamedOp,ker:Al.NamedFn,lg:Al.NamedFn,lim:Al.NamedOp,liminf:[Al.NamedOp,"lim inf"],limsup:[Al.NamedOp,"lim sup"],ln:Al.NamedFn,log:Al.NamedFn,max:Al.NamedOp,min:Al.NamedOp,Pr:Al.NamedOp,sec:Al.NamedFn,sin:Al.NamedFn,sinh:Al.NamedFn,sup:Al.NamedOp,tan:Al.NamedFn,tanh:Al.NamedFn,limits:[Al.Limits,!0],nolimits:[Al.Limits,!1],overline:[Al.UnderOver,"2015"],underline:[Al.UnderOver,"2015"],overbrace:[Al.UnderOver,"23DE",!0],underbrace:[Al.UnderOver,"23DF",!0],overparen:[Al.UnderOver,"23DC"],underparen:[Al.UnderOver,"23DD"],overrightarrow:[Al.UnderOver,"2192"],underrightarrow:[Al.UnderOver,"2192"],overleftarrow:[Al.UnderOver,"2190"],underleftarrow:[Al.UnderOver,"2190"],overleftrightarrow:[Al.UnderOver,"2194"],underleftrightarrow:[Al.UnderOver,"2194"],overset:Al.Overset,underset:Al.Underset,overunderset:Al.Overunderset,stackrel:[Al.Macro,"\\mathrel{\\mathop{#2}\\limits^{#1}}",2],stackbin:[Al.Macro,"\\mathbin{\\mathop{#2}\\limits^{#1}}",2],over:Al.Over,overwithdelims:Al.Over,atop:Al.Over,atopwithdelims:Al.Over,above:Al.Over,abovewithdelims:Al.Over,brace:[Al.Over,"{","}"],brack:[Al.Over,"[","]"],choose:[Al.Over,"(",")"],frac:Al.Frac,sqrt:Al.Sqrt,root:Al.Root,uproot:[Al.MoveRoot,"upRoot"],leftroot:[Al.MoveRoot,"leftRoot"],left:Al.LeftRight,right:Al.LeftRight,middle:Al.LeftRight,llap:Al.Lap,rlap:Al.Lap,raise:Al.RaiseLower,lower:Al.RaiseLower,moveleft:Al.MoveLeftRight,moveright:Al.MoveLeftRight,",":[Al.Spacer,go.thinmathspace],":":[Al.Spacer,go.mediummathspace],">":[Al.Spacer,go.mediummathspace],";":[Al.Spacer,go.thickmathspace],"!":[Al.Spacer,go.negativethinmathspace],enspace:[Al.Spacer,.5],quad:[Al.Spacer,1],qquad:[Al.Spacer,2],thinspace:[Al.Spacer,go.thinmathspace],negthinspace:[Al.Spacer,go.negativethinmathspace],"*":Al.DiscretionaryTimes,allowbreak:Al.AllowBreak,goodbreak:[Al.Linebreak,Ko.LineBreak.GOODBREAK],badbreak:[Al.Linebreak,Ko.LineBreak.BADBREAK],nobreak:[Al.Linebreak,Ko.LineBreak.NOBREAK],break:Al.Break,hskip:Al.Hskip,hspace:Al.Hskip,kern:[Al.Hskip,!0],mskip:Al.Hskip,mspace:Al.Hskip,mkern:[Al.Hskip,!0],rule:Al.rule,Rule:[Al.Rule],Space:[Al.Rule,"blank"],nonscript:Al.Nonscript,big:[Al.MakeBig,mr.ORD,.85],Big:[Al.MakeBig,mr.ORD,1.15],bigg:[Al.MakeBig,mr.ORD,1.45],Bigg:[Al.MakeBig,mr.ORD,1.75],bigl:[Al.MakeBig,mr.OPEN,.85],Bigl:[Al.MakeBig,mr.OPEN,1.15],biggl:[Al.MakeBig,mr.OPEN,1.45],Biggl:[Al.MakeBig,mr.OPEN,1.75],bigr:[Al.MakeBig,mr.CLOSE,.85],Bigr:[Al.MakeBig,mr.CLOSE,1.15],biggr:[Al.MakeBig,mr.CLOSE,1.45],Biggr:[Al.MakeBig,mr.CLOSE,1.75],bigm:[Al.MakeBig,mr.REL,.85],Bigm:[Al.MakeBig,mr.REL,1.15],biggm:[Al.MakeBig,mr.REL,1.45],Biggm:[Al.MakeBig,mr.REL,1.75],mathord:[Al.TeXAtom,mr.ORD],mathop:[Al.TeXAtom,mr.OP],mathopen:[Al.TeXAtom,mr.OPEN],mathclose:[Al.TeXAtom,mr.CLOSE],mathbin:[Al.TeXAtom,mr.BIN],mathrel:[Al.TeXAtom,mr.REL],mathpunct:[Al.TeXAtom,mr.PUNCT],mathinner:[Al.TeXAtom,mr.INNER],vtop:[Al.VBox,"top"],vcenter:[Al.VBox,"center"],vbox:[Al.VBox,"bottom"],hsize:Al.Hsize,parbox:Al.ParBox,breakAlign:Al.BreakAlign,buildrel:Al.BuildRel,hbox:[Al.HBox,0],text:Al.HBox,mbox:[Al.HBox,0],fbox:Al.FBox,boxed:[Al.Macro,"\\fbox{$\\displaystyle{#1}$}",1],framebox:Al.FrameBox,makebox:Al.MakeBox,strut:Al.Strut,mathstrut:[Al.Macro,"\\vphantom{(}"],phantom:Al.Phantom,vphantom:[Al.Phantom,1,0],hphantom:[Al.Phantom,0,1],smash:Al.Smash,acute:[Al.Accent,"00B4"],grave:[Al.Accent,"0060"],ddot:[Al.Accent,"00A8"],dddot:[Al.Accent,"20DB"],ddddot:[Al.Accent,"20DC"],tilde:[Al.Accent,"007E"],bar:[Al.Accent,"00AF"],breve:[Al.Accent,"02D8"],check:[Al.Accent,"02C7"],hat:[Al.Accent,"005E"],vec:[Al.Accent,"2192",!1],dot:[Al.Accent,"02D9"],widetilde:[Al.Accent,"007E",!0],widehat:[Al.Accent,"005E",!0],matrix:Al.Matrix,array:Al.Matrix,pmatrix:[Al.Matrix,"(",")"],cases:[Al.Matrix,"{","","left left",null,".2em",null,!0],eqalign:[Al.Matrix,null,null,"right left",Il,".5em","D"],displaylines:[Al.Matrix,null,null,"center",null,".5em","D"],cr:Al.Cr,"\\":Al.CrLaTeX,newline:[Al.CrLaTeX,!0],hline:Al.HLine,hdashline:[Al.HLine,"dashed"],eqalignno:[Al.Matrix,null,null,"right left",Il,".5em","D",null,"right"],leqalignno:[Al.Matrix,null,null,"right left",Il,".5em","D",null,"left"],hfill:Al.HFill,hfil:Al.HFill,hfilll:Al.HFill,bmod:[Al.Macro,`\\mmlToken{mo}[lspace="${Il}" rspace="${Il}"]{mod}`],pmod:[Al.Macro,"\\pod{\\mmlToken{mi}{mod}\\kern 6mu #1}",1],mod:[Al.Macro,"\\mathchoice{\\kern18mu}{\\kern12mu}{\\kern12mu}{\\kern12mu}\\mmlToken{mi}{mod}\\,\\,#1",1],pod:[Al.Macro,"\\mathchoice{\\kern18mu}{\\kern8mu}{\\kern8mu}{\\kern8mu}(#1)",1],iff:[Al.Macro,"\\;\\Longleftrightarrow\\;"],skew:[Al.Macro,"{{#2{#3\\mkern#1mu}\\mkern-#1mu}{}}",3],pmb:[Al.Macro,"\\rlap{#1}\\kern1px{#1}",1],TeX:[Al.Macro,"T\\kern-.14em\\lower.5ex{E}\\kern-.115em X"],LaTeX:[Al.Macro,"L\\kern-.325em\\raise.21em{\\scriptstyle{A}}\\kern-.17em\\TeX"],not:Al.Not,dots:Al.Dots,space:Al.Tilde,"\xa0":Al.Tilde," ":Al.Tilde,begin:Al.BeginEnd,end:Al.BeginEnd,label:Al.HandleLabel,ref:Al.HandleRef,nonumber:Al.HandleNoTag,newcolumntype:Al.NewColumnType,mathchoice:Al.MathChoice,mmlToken:Al.MmlToken}),new Wa("environment",Ml.environment,{displaymath:[Al.Equation,null,!1],math:[Al.Equation,null,!1,!1],array:[Al.AlignedArray],darray:[Al.AlignedArray,null,"D"],equation:[Al.Equation,null,!0],eqnarray:[Al.EqnArray,null,!0,!0,"rcl","bmt",ya.cols(0,go.thickmathspace),".5em"],indentalign:[Al.IndentAlign]}),new ja("not_remap",null,{"\u2190":"\u219a","\u2192":"\u219b","\u2194":"\u21ae","\u21d0":"\u21cd","\u21d2":"\u21cf","\u21d4":"\u21ce","\u2208":"\u2209","\u220b":"\u220c","\u2223":"\u2224","\u2225":"\u2226","\u223c":"\u2241","~":"\u2241","\u2243":"\u2244","\u2245":"\u2247","\u2248":"\u2249","\u224d":"\u226d","=":"\u2260","\u2261":"\u2262","<":"\u226e",">":"\u226f","\u2264":"\u2270","\u2265":"\u2271","\u2272":"\u2274","\u2273":"\u2275","\u2276":"\u2278","\u2277":"\u2279","\u227a":"\u2280","\u227b":"\u2281","\u2282":"\u2284","\u2283":"\u2285","\u2286":"\u2288","\u2287":"\u2289","\u22a2":"\u22ac","\u22a8":"\u22ad","\u22a9":"\u22ae","\u22ab":"\u22af","\u227c":"\u22e0","\u227d":"\u22e1","\u2291":"\u22e2","\u2292":"\u22e3","\u22b2":"\u22ea","\u22b3":"\u22eb","\u22b4":"\u22ec","\u22b5":"\u22ed","\u2203":"\u2204"});const Dl=Ko.Variant;function Pl(t,e){const s=t.stack.env.font,i=t.stack.env.italicFont,r=s?{mathvariant:s}:{},n=Va.getMap("remap").lookup(e),o=Ir(e),a=o[3],l=t.create("token",a,r,n?n.char:e),c=ya.isLatinOrGreekChar(e)?t.configuration.mathStyle(e,!0)||i:"",h=o[4]||(s&&c===Dl.NORMAL?"":c);h&&l.attributes.set("mathvariant",h),"mo"===a&&(Jo.setProperty(l,"fixStretchy",!0),t.configuration.addNode("fixStretchy",l)),t.Push(l)}new ja("remap",null,{"-":"\u2212","*":"\u2217","`":"\u2018"});class Bl extends _a{}const Fl=Ja.create("base",{[sa.CONFIG]:function(t,e){const s=e.parseOptions.options;s.digits&&(s.numberPattern=s.digits),new Ba("digit",Ml.digit,s.initialDigit),new Ba("letter",Ml.variable,s.initialLetter);t.handlers.get(ia.CHARACTER).add(["letter","digit"],null,4)},[sa.HANDLER]:{[ia.CHARACTER]:["command","special"],[ia.DELIMITER]:["delimiter"],[ia.MACRO]:["delimiter","macros","lcGreek","ucGreek","mathchar0mi","mathchar0mo","mathchar7"],[ia.ENVIRONMENT]:["environment"]},[sa.FALLBACK]:{[ia.CHARACTER]:Pl,[ia.MACRO]:function(t,e){throw new la("UndefinedControlSequence","Undefined control sequence %1","\\"+e)},[ia.ENVIRONMENT]:function(t,e){throw new la("UnknownEnv","Unknown environment '%1'",e)}},[sa.ITEMS]:{[Qa.prototype.kind]:Qa,[Za.prototype.kind]:Za,[tl.prototype.kind]:tl,[el.prototype.kind]:el,[sl.prototype.kind]:sl,[il.prototype.kind]:il,[rl.prototype.kind]:rl,[nl.prototype.kind]:nl,[ol.prototype.kind]:ol,[al.prototype.kind]:al,[ll.prototype.kind]:ll,[cl.prototype.kind]:cl,[hl.prototype.kind]:hl,[dl.prototype.kind]:dl,[ul.prototype.kind]:ul,[pl.prototype.kind]:pl,[ml.prototype.kind]:ml,[fl.prototype.kind]:fl,[gl.prototype.kind]:gl,[bl.prototype.kind]:bl,[El.prototype.kind]:El,[xl.prototype.kind]:xl,[yl.prototype.kind]:yl,[Nl.prototype.kind]:Nl,[Tl.prototype.kind]:Tl,[vl.prototype.kind]:vl},[sa.OPTIONS]:{maxMacros:1e3,digits:"",numberPattern:/^(?:[0-9]+(?:\{,\}[0-9]{3})*(?:\.[0-9]*)?|\.[0-9]+)/,initialDigit:/[0-9.,]/,identifierPattern:/^[a-zA-Z]+/,initialLetter:/[a-zA-Z]/,baseURL:ui.document&&0!==ui.document.getElementsByTagName("base").length?String(ui.document.location).replace(/#.*$/,""):""},[sa.TAGS]:{base:Bl},[sa.POSTPROCESSORS]:[[function({data:t}){for(const e of t.getList("nonscript"))if(e.attributes.get("scriptlevel")>0){const s=e.parent;if(s.childNodes.splice(s.childIndex(e),1),t.removeFromList(e.kind,[e]),e.isKind("mrow")){const s=e.childNodes[0];t.removeFromList("mstyle",[s]),t.removeFromList("mspace",s.childNodes[0].childNodes)}}else e.isKind("mrow")&&(e.parent.replaceChild(e.childNodes[0],e),t.removeFromList("mrow",[e]))},-4]]});class jl extends Qi{static configure(t){const e=new Ya(t,["tex"]);return e.init(),e}static tags(t,e){Ma.addTags(e.tags),Ma.setDefault(t.options.tags),t.tags=Ma.getDefault(),t.tags.configuration=t}constructor(t={}){const[e,s,i]=ji(t,jl.OPTIONS,Xo.OPTIONS);super(s),this.findTeX=this.options.FindTeX||new Xo(i);const r=this.options.packages,n=this.configuration=jl.configure(r),o=this._parseOptions=new wa(n,[this.options,Ma.OPTIONS]);Pi(o.options,e),n.config(this),jl.tags(o,n),this.postFilters.addList([[ea.cleanSubSup,-7],[ea.setInherited,-6],[ea.checkScriptlevel,-5],[ea.moveLimits,-4],[ea.cleanStretchy,-3],[ea.cleanAttributes,-2],[ea.combineRelations,-1]])}setMmlFactory(t){super.setMmlFactory(t),this._parseOptions.nodeFactory.setMmlFactory(t)}get parseOptions(){return this._parseOptions}reset(t=0){this.parseOptions.tags.reset(t)}compile(t,e){let s,i;this.parseOptions.clear(),this.parseOptions.mathItem=t,this.executeFilters(this.preFilters,t,e,this.parseOptions),this.latex=t.math,this.parseOptions.tags.startEquation(t);try{i=new da(this.latex,{display:t.display,isInner:!1},this.parseOptions),s=i.mml()}catch(t){if(!(t instanceof la))throw t;this.parseOptions.error=!0,s=this.options.formatError(this,t)}return s=this.parseOptions.nodeFactory.create("node","math",[s]),s.attributes.set(Ko.Attr.LATEX,this.latex),t.display&&Jo.setAttribute(s,"display","block"),this.parseOptions.tags.finishEquation(t),this.parseOptions.root=s,this.executeFilters(this.postFilters,t,e,this.parseOptions),i&&i.stack.env.hsize&&(Jo.setAttribute(s,"maxwidth",i.stack.env.hsize),Jo.setAttribute(s,"overflow","linebreak")),this.mathNode=this.parseOptions.root,this.mathNode}findMath(t){return this.findTeX.findMath(t)}formatError(t){const e=t.message.replace(/\n.*/,"");return this.parseOptions.nodeFactory.create("error",e,t.id,this.latex)}}jl.NAME="TeX",jl.OPTIONS=Object.assign(Object.assign({},Qi.OPTIONS),{FindTeX:null,packages:["base"],maxBuffer:5120,maxTemplateSubtitutions:1e4,mathStyle:"TeX",formatError:(t,e)=>t.formatError(e)});class Ul extends yl{constructor(t,...e){super(t),this.factory.configuration.tags.start("multline",!0,e[0])}get kind(){return"multline"}EndEntry(){this.table.length&&ya.fixInitialMO(this.factory.configuration,this.nodes);const t=this.getProperty("shove"),e=this.create("node","mtd",this.nodes,t?{columnalign:t}:{});this.setProperty("shove",null),this.row.push(e),this.Clear()}EndRow(){if(1!==this.row.length)throw new la("MultlineRowsOneCol","The rows within the %1 environment must have exactly one column","multline");const t=this.create("node","mtr",this.row);this.table.push(t),this.row=[]}EndTable(){if(super.EndTable(),this.table.length){const t=this.table.length-1;let e=-1;Jo.getAttribute(Jo.getChildren(this.table[0])[0],"columnalign")||Jo.setAttribute(Jo.getChildren(this.table[0])[0],"columnalign",Ko.Align.LEFT),Jo.getAttribute(Jo.getChildren(this.table[t])[0],"columnalign")||Jo.setAttribute(Jo.getChildren(this.table[t])[0],"columnalign",Ko.Align.RIGHT);const s=this.factory.configuration.tags.getTag();if(s){e=this.arraydef.side===Ko.Align.LEFT?0:this.table.length-1;const t=this.table[e],i=this.create("node","mlabeledtr",[s].concat(Jo.getChildren(t)));Jo.copyAttributes(t,i),this.table[e]=i}}this.factory.configuration.tags.end()}}class Hl extends Nl{get kind(){return"flalign"}constructor(t,e,s,i,r){super(t),this.name=e,this.numbered=s,this.padded=i,this.center=r,this.factory.configuration.tags.start(e,s,s)}EndEntry(){super.EndEntry();const t=this.getProperty("xalignat");if(t&&this.row.length>t)throw new la("XalignOverflow","Extra %1 in row of %2","&",this.name)}EndRow(){let t;const e=this.row,s=this.getProperty("xalignat");for(;e.lengththis.maxrow&&(this.maxrow=this.row.length),super.EndRow();const i=this.table[this.table.length-1];if(this.getProperty("zeroWidthLabel")&&i.isKind("mlabeledtr")){const t=Jo.getChildren(i)[0],e=this.factory.configuration.options.tagSide,s=Object.assign({width:0},"right"===e?{lspace:"-1width"}:{}),r=this.create("node","mpadded",Jo.getChildren(t),s);t.setChildren([r])}}EndTable(){if(super.EndTable(),this.center&&this.maxrow<=2){delete this.arraydef.width,delete this.global.indentalign}}}var ql;!function(t){t.NEW_DELIMITER="new-Delimiter",t.NEW_COMMAND="new-Command",t.NEW_ENVIRONMENT="new-Environment"}(ql||(ql={}));const Wl=-100,zl={GetCSname(t,e){if("\\"!==t.GetNext())throw new la("MissingCS","%1 must be followed by a control sequence",e);const s=na.trimSpaces(t.GetArgument(e)).substring(1);return this.checkProtectedMacros(t,s),s},GetCsNameArgument(t,e){let s=na.trimSpaces(t.GetArgument(e));if("\\"===s.charAt(0)&&(s=s.substring(1)),!s.match(/^(.|[a-z]+)$/i))throw new la("IllegalControlSequenceName","Illegal control sequence name for %1",e);return this.checkProtectedMacros(t,s),s},GetArgCount(t,e){let s=t.GetBrackets(e);if(s&&(s=na.trimSpaces(s),!s.match(/^[0-9]+$/)))throw new la("IllegalParamNumber","Illegal number of parameters specified in %1",e);return s},GetTemplate(t,e,s){let i=t.GetNext();const r=[];let n=0,o=t.i;for(;t.i0?[n.toString()].concat(r):n;t.i++}throw new la("MissingReplacementString","Missing replacement string for definition of %1",e)},GetParameter(t,e,s){if(null==s)return t.GetArgument(e);let i=t.i,r=0,n=!1;for(;t.it.string.substring(t.i,t.i+e.length)!==e||e.match(/\\[a-z]+$/i)&&t.string.charAt(t.i+e.length).match(/[a-z]/i)?0:(t.i+=e.length,1),checkGlobal:(t,e,s)=>t.stack.env.isGlobal?t.configuration.packageData.get("begingroup").stack.checkGlobal(e,s):s.map(e=>t.configuration.handlers.retrieve(e)),checkProtectedMacros(t,e){var s;if(null===(s=t.options.protectedMacros)||void 0===s?void 0:s.includes(e))throw new la("ProtectedMacro","The control sequence %1 can't be redefined",`\\${e}`)},addDelimiter(t,e,s,i){const r=e.substring(1);this.checkProtectedMacros(t,r);const[n,o]=zl.checkGlobal(t,[r,e],[ql.NEW_COMMAND,ql.NEW_DELIMITER]);r!==e&&n.remove(r),o.add(e,new Ia(e,s,i)),delete t.stack.env.isGlobal},addMacro(t,e,s,i,r=""){this.checkProtectedMacros(t,e);const n=zl.checkGlobal(t,[e],[ql.NEW_COMMAND])[0];this.undefineDelimiter(t,"\\"+e),n.add(e,new Oa(r||e,s,i)),delete t.stack.env.isGlobal},addEnvironment(t,e,s,i){zl.checkGlobal(t,[e],[ql.NEW_ENVIRONMENT])[0].add(e,new Oa(e,s,i)),delete t.stack.env.isGlobal},undefineMacro(t,e){const s=zl.checkGlobal(t,[e],[ql.NEW_COMMAND])[0];s.remove(e),t.configuration.handlers.get(ia.MACRO).applicable(e)&&(s.add(e,new Oa(e,()=>Xa.FALLBACK,[])),this.undefineDelimiter(t,"\\"+e)),delete t.stack.env.isGlobal},undefineDelimiter(t,e){const s=zl.checkGlobal(t,[e],[ql.NEW_DELIMITER])[0];s.remove(e),t.configuration.handlers.get(ia.DELIMITER).applicable(e)&&s.add(e,new Ia(e,null,{})),delete t.stack.env.isGlobal}};function Vl(t){if(!t||t.isInferred&&0===t.childNodes.length)return[null,null];if(t.isKind("msubsup")&&Xl(t))return[t,null];const e=Jo.getChildAt(t,0);return t.isInferred&&e&&Xl(e)?(t.childNodes.splice(0,1),[e,t]):[null,t]}function Xl(t){const e=t.childNodes[0];return e&&e.isKind("mi")&&""===e.getText()}const Gl={AmsEqnArray(t,e,s,i,r,n,o,a){const l=t.GetBrackets("\\begin{"+e.getName()+"}"),c=Al.EqnArray(t,e,s,i,r,n,o,a);return ya.setArrayAlign(c,l,t)},AlignAt(t,e,s,i){const r=e.getName();let n,o="",a="";const l=[];i||(n=t.GetBrackets("\\begin{"+r+"}"));const c=t.GetArgument("\\begin{"+r+"}");if(c.match(/[^0-9]/))throw new la("PositiveIntegerArg","Argument to %1 must be a positive integer","\\begin{"+r+"}");let h=parseInt(c,10);for(;h>0;)o+="rl",a+="bt",l.push("0em 0em"),h--;const d=l.join(" ");if(i)return Gl.EqnArray(t,e,s,i,o,a,d);const u=Gl.EqnArray(t,e,s,i,o,a,d);return ya.setArrayAlign(u,n,t)},Multline(t,e,s){ya.checkEqnEnv(t),t.Push(e);const i=t.options.ams.multlineIndent,r=t.itemFactory.create("multline",s,t.stack);return r.arraydef={displaystyle:!0,rowspacing:".5em",columnspacing:"100%",width:t.options.ams.multlineWidth,side:t.options.tagSide,minlabelspacing:t.options.tagIndent,"data-array-padding":`${i} ${i}`,"data-width-includes-label":!0},r},XalignAt(t,e,s,i){const r=t.GetArgument("\\begin{"+e.getName()+"}");if(r.match(/[^0-9]/))throw new la("PositiveIntegerArg","Argument to %1 must be a positive integer","\\begin{"+e.getName()+"}");const n=i?"crl":"rlc",o=i?"mbt":"btm",a=i?"fit auto auto":"auto auto fit",l=Gl.FlalignArray(t,e,s,i,!1,n,o,a,!0);return l.setProperty("xalignat",2*parseInt(r)),l},FlalignArray(t,e,s,i,r,n,o,a,l=!1){ya.checkEqnEnv(t),t.Push(e),n=n.split("").join(" ").replace(/r/g,"right").replace(/l/g,"left").replace(/c/g,"center"),o=kl(o);const c=t.itemFactory.create("flalign",e.getName(),s,i,r,t.stack);return c.arraydef={width:"100%",displaystyle:!0,columnalign:n,columnspacing:"0em",columnwidth:a,rowspacing:"3pt","data-break-align":o,side:t.options.tagSide,minlabelspacing:l?"0":t.options.tagIndent,"data-width-includes-label":!0},c.setProperty("zeroWidthLabel",l),c},HandleDeclareOp(t,e){const s=t.GetStar()?"*":"",i=zl.GetCsNameArgument(t,e),r=t.GetArgument(e);zl.addMacro(t,i,Gl.Macro,[`\\operatorname${s}{${r}}`]),t.Push(t.itemFactory.create("null"))},HandleOperatorName(t,e){const s=t.GetStar(),i=na.trimSpaces(t.GetArgument(e));let r=new da(i,Object.assign(Object.assign({},t.stack.env),{font:Ko.Variant.NORMAL,multiLetterIdentifiers:t.options.ams.operatornamePattern,operatorLetters:!0,noAutoOP:!0}),t.configuration).mml();if(r.isKind("mi")?r.removeProperty("autoOP"):r=t.create("node","TeXAtom",[r]),Jo.setProperties(r,{movesupsub:s,movablelimits:!0,texClass:mr.OP}),!s){const e=t.GetNext(),s=t.i;"\\"===e&&++t.i&&"limits"!==t.GetCS()&&(t.i=s)}t.Push(t.itemFactory.create("fn",r))},SideSet(t,e){const[s,i]=Vl(t.ParseArg(e)),[r,n]=Vl(t.ParseArg(e)),o=t.ParseArg(e);let a=o;s&&(i?s.replaceChild(t.create("node","mphantom",[t.create("node","mpadded",[ya.copyNode(o,t)],{width:0})]),Jo.getChildAt(s,0)):(a=t.create("node","mmultiscripts",[o]),r&&Jo.appendChildren(a,[Jo.getChildAt(r,1)||t.create("node","none"),Jo.getChildAt(r,2)||t.create("node","none")]),Jo.setProperty(a,"scriptalign","left"),Jo.appendChildren(a,[t.create("node","mprescripts"),Jo.getChildAt(s,1)||t.create("node","none"),Jo.getChildAt(s,2)||t.create("node","none")]))),r&&a===o&&(r.replaceChild(o,Jo.getChildAt(r,0)),a=r);const l=t.create("node","TeXAtom",[],{texClass:mr.OP,movesupsub:!0,movablelimits:!0});i&&(s&&l.appendChild(s),l.appendChild(i)),l.appendChild(a),n&&l.appendChild(n),t.Push(l)},operatorLetter:(t,e)=>!!t.stack.env.operatorLetters&&Ml.variable(t,e),MultiIntegral(t,e,s){let i=t.GetNext();if("\\"===i){const r=t.i;i=t.GetArgument(e),t.i=r,"\\limits"===i&&(s="\\!\\!\\mathop{\\,\\,"+s+"}")}t.string=s+" "+t.string.slice(t.i),t.i=0},xArrow(t,e,s,i,r,n=0){const o={width:"+"+na.em((i+r)/18),lspace:na.em(i/18)},a=t.GetBrackets(e),l=t.ParseArg(e),c=t.create("node","mspace",[],{depth:".2em"});let h=t.create("token","mo",{stretchy:!0,texClass:mr.ORD},String.fromCodePoint(s));n&&h.attributes.set("minsize",na.em(n)),h=t.create("node","mstyle",[h],{scriptlevel:0});const d=t.create("node","munderover",[h]);let u=t.create("node","mpadded",[l,c],o);if(Jo.setAttribute(u,"voffset","-.2em"),Jo.setAttribute(u,"height","-.2em"),Jo.setChild(d,d.over,u),a){const e=new da(a,t.stack.env,t.configuration).mml(),s=t.create("node","mspace",[],{height:".75em"});u=t.create("node","mpadded",[e,s],o),Jo.setAttribute(u,"voffset",".15em"),Jo.setAttribute(u,"depth","-.15em"),Jo.setChild(d,d.under,u)}Jo.setProperty(d,"subsupOK",!0),t.Push(t.create("node","TeXAtom",[t.create("node","TeXAtom",[],{texClass:mr.NONE}),d],{texClass:mr.REL}))},HandleShove(t,e,s){const i=t.stack.Top();if("multline"!==i.kind)throw new la("CommandOnlyAllowedInEnv","%1 only allowed in %2 environment",t.currentCS,"multline");if(i.Size())throw new la("CommandAtTheBeginingOfLine","%1 must come at the beginning of the line",t.currentCS);i.setProperty("shove",s)},CFrac(t,e){let s=na.trimSpaces(t.GetBrackets(e,""));const i=t.GetArgument(e),r=t.GetArgument(e),n={l:Ko.Align.LEFT,r:Ko.Align.RIGHT,"":""},o=new da("\\strut\\textstyle{"+i+"}",t.stack.env,t.configuration).mml(),a=new da("\\strut\\textstyle{"+r+"}",t.stack.env,t.configuration).mml(),l=t.create("node","mfrac",[o,a]);if(s=n[s],null==s)throw new la("IllegalAlign","Illegal alignment specified in %1",t.currentCS);s&&Jo.setProperties(l,{numalign:s,denomalign:s}),t.Push(l)},Genfrac(t,e,s,i,r,n){null==s&&(s=t.GetDelimiterArg(e)),null==i&&(i=t.GetDelimiterArg(e)),null==r&&(r=t.GetArgument(e)),null==n&&(n=na.trimSpaces(t.GetArgument(e)));const o=t.ParseArg(e),a=t.ParseArg(e);let l=t.create("node","mfrac",[o,a]);if(""!==r&&Jo.setAttribute(l,"linethickness",r),(s||i)&&(Jo.setProperty(l,"withDelims",!0),l=ya.fixedFence(t.configuration,s,l,i)),""!==n){const e=parseInt(n,10),s=["D","T","S","SS"][e];if(null==s)throw new la("BadMathStyleFor","Bad math style for %1",t.currentCS);l=t.create("node","mstyle",[l]),"D"===s?Jo.setProperties(l,{displaystyle:!0,scriptlevel:0}):Jo.setProperties(l,{displaystyle:!1,scriptlevel:e-1})}t.Push(l)},HandleTag(t,e){if(!t.tags.currentTag.taggable&&t.tags.env)throw new la("CommandNotAllowedInEnv","%1 not allowed in %2 environment",t.currentCS,t.tags.env);if(t.tags.currentTag.tag)throw new la("MultipleCommand","Multiple %1",t.currentCS);const s=t.GetStar(),i=na.trimSpaces(t.GetArgument(e));t.tags.tag(i,s),t.Push(t.itemFactory.create("null"))},HandleNoTag:Al.HandleNoTag,HandleRef:Al.HandleRef,Macro:Al.Macro,Accent:Al.Accent,Tilde:Al.Tilde,Array:Al.Array,Spacer:Al.Spacer,NamedOp:Al.NamedOp,EqnArray:Al.EqnArray,Equation:Al.Equation};new ja("AMSmath-mathchar0mo",Ml.mathchar0mo,{iiiint:["\u2a0c",{texClass:mr.OP}]}),new Ba("AMSmath-operatorLetter",Gl.operatorLetter,/[-*]/i),new qa("AMSmath-macros",{mathring:[Gl.Accent,"02DA"],nobreakspace:Gl.Tilde,negmedspace:[Gl.Spacer,go.negativemediummathspace],negthickspace:[Gl.Spacer,go.negativethickmathspace],idotsint:[Gl.MultiIntegral,"\\int\\cdots\\int"],dddot:[Gl.Accent,"20DB"],ddddot:[Gl.Accent,"20DC"],sideset:Gl.SideSet,boxed:[Gl.Macro,"\\fbox{$\\displaystyle{#1}$}",1],tag:Gl.HandleTag,notag:Gl.HandleNoTag,eqref:[Gl.HandleRef,!0],substack:[Gl.Macro,"\\begin{subarray}{c}#1\\end{subarray}",1],injlim:[Gl.NamedOp,"inj lim"],projlim:[Gl.NamedOp,"proj lim"],varliminf:[Gl.Macro,"\\mathop{\\underline{\\mmlToken{mi}{lim}}}"],varlimsup:[Gl.Macro,"\\mathop{\\overline{\\mmlToken{mi}{lim}}}"],varinjlim:[Gl.Macro,"\\mathop{\\underrightarrow{\\mmlToken{mi}{lim}}}"],varprojlim:[Gl.Macro,"\\mathop{\\underleftarrow{\\mmlToken{mi}{lim}}}"],DeclareMathOperator:Gl.HandleDeclareOp,operatorname:Gl.HandleOperatorName,genfrac:Gl.Genfrac,frac:[Gl.Genfrac,"","","",""],tfrac:[Gl.Genfrac,"","","","1"],dfrac:[Gl.Genfrac,"","","","0"],binom:[Gl.Genfrac,"(",")","0",""],tbinom:[Gl.Genfrac,"(",")","0","1"],dbinom:[Gl.Genfrac,"(",")","0","0"],cfrac:Gl.CFrac,shoveleft:[Gl.HandleShove,Ko.Align.LEFT],shoveright:[Gl.HandleShove,Ko.Align.RIGHT],xrightarrow:[Gl.xArrow,8594,5,10],xleftarrow:[Gl.xArrow,8592,10,5]}),new Wa("AMSmath-environment",Ml.environment,{"equation*":[Gl.Equation,null,!1],"eqnarray*":[Gl.EqnArray,null,!1,!0,"rcl","bmt",ya.cols(0,go.thickmathspace),".5em"],align:[Gl.EqnArray,null,!0,!0,"rl","bt",ya.cols(0,2)],"align*":[Gl.EqnArray,null,!1,!0,"rl","bt",ya.cols(0,2)],multline:[Gl.Multline,null,!0],"multline*":[Gl.Multline,null,!1],split:[Gl.EqnArray,null,!1,!1,"rl","bt",ya.cols(0)],gather:[Gl.EqnArray,null,!0,!0,"c","m"],"gather*":[Gl.EqnArray,null,!1,!0,"c","m"],alignat:[Gl.AlignAt,null,!0,!0],"alignat*":[Gl.AlignAt,null,!1,!0],alignedat:[Gl.AlignAt,null,!1,!1],aligned:[Gl.AmsEqnArray,null,null,null,"rl","bt",ya.cols(0,2),".5em","D"],gathered:[Gl.AmsEqnArray,null,null,null,"c","m",null,".5em","D"],xalignat:[Gl.XalignAt,null,!0,!0],"xalignat*":[Gl.XalignAt,null,!1,!0],xxalignat:[Gl.XalignAt,null,!1,!1],flalign:[Gl.FlalignArray,null,!0,!1,!0,"rlc","btm","auto auto fit"],"flalign*":[Gl.FlalignArray,null,!1,!1,!0,"rlc","btm","auto auto fit"],subarray:[Gl.Array,null,null,null,null,ya.cols(0),"0.1em","S",!0],smallmatrix:[Gl.Array,null,null,null,"c",ya.cols(1/3),".2em","S",!0],matrix:[Gl.Array,null,null,null,"c"],pmatrix:[Gl.Array,null,"(",")","c"],bmatrix:[Gl.Array,null,"[","]","c"],Bmatrix:[Gl.Array,null,"\\{","\\}","c"],vmatrix:[Gl.Array,null,"\\vert","\\vert","c"],Vmatrix:[Gl.Array,null,"\\Vert","\\Vert","c"],cases:[Gl.Array,null,"\\{",".","ll",null,".2em","T"]}),new Ua("AMSmath-delimiter",Ml.delimiter,{"\\lvert":["|",{texClass:mr.OPEN}],"\\rvert":["|",{texClass:mr.CLOSE}],"\\lVert":["\u2016",{texClass:mr.OPEN}],"\\rVert":["\u2016",{texClass:mr.CLOSE}]}),new ja("AMSsymbols-mathchar0mi",Ml.mathchar0mi,{digamma:"\u03dd",varkappa:"\u03f0",varGamma:["\u0393",{mathvariant:Ko.Variant.ITALIC}],varDelta:["\u0394",{mathvariant:Ko.Variant.ITALIC}],varTheta:["\u0398",{mathvariant:Ko.Variant.ITALIC}],varLambda:["\u039b",{mathvariant:Ko.Variant.ITALIC}],varXi:["\u039e",{mathvariant:Ko.Variant.ITALIC}],varPi:["\u03a0",{mathvariant:Ko.Variant.ITALIC}],varSigma:["\u03a3",{mathvariant:Ko.Variant.ITALIC}],varUpsilon:["\u03a5",{mathvariant:Ko.Variant.ITALIC}],varPhi:["\u03a6",{mathvariant:Ko.Variant.ITALIC}],varPsi:["\u03a8",{mathvariant:Ko.Variant.ITALIC}],varOmega:["\u03a9",{mathvariant:Ko.Variant.ITALIC}],beth:"\u2136",gimel:"\u2137",daleth:"\u2138",backprime:["\u2035",{variantForm:!0}],hslash:"\u210f",varnothing:["\u2205",{variantForm:!0}],blacktriangle:"\u25b4",triangledown:["\u25bd",{variantForm:!0}],blacktriangledown:"\u25be",square:"\u25fb",Box:"\u25fb",blacksquare:"\u25fc",lozenge:"\u25ca",Diamond:"\u25ca",blacklozenge:"\u29eb",circledS:["\u24c8",{mathvariant:Ko.Variant.NORMAL}],bigstar:"\u2605",sphericalangle:"\u2222",measuredangle:"\u2221",nexists:"\u2204",complement:"\u2201",mho:"\u2127",eth:["\xf0",{mathvariant:Ko.Variant.NORMAL}],Finv:"\u2132",diagup:"\u2571",Game:"\u2141",diagdown:"\u2572",Bbbk:["k",{mathvariant:Ko.Variant.DOUBLESTRUCK}],yen:"\xa5",circledR:"\xae",checkmark:"\u2713",maltese:"\u2720"}),new ja("AMSsymbols-mathchar0mo",Ml.mathchar0mo,{dotplus:"\u2214",ltimes:"\u22c9",smallsetminus:["\u2216",{variantForm:!0}],rtimes:"\u22ca",Cap:"\u22d2",doublecap:"\u22d2",leftthreetimes:"\u22cb",Cup:"\u22d3",doublecup:"\u22d3",rightthreetimes:"\u22cc",barwedge:"\u22bc",curlywedge:"\u22cf",veebar:"\u22bb",curlyvee:"\u22ce",doublebarwedge:"\u2a5e",boxminus:"\u229f",circleddash:"\u229d",boxtimes:"\u22a0",circledast:"\u229b",boxdot:"\u22a1",circledcirc:"\u229a",boxplus:"\u229e",centerdot:["\u22c5",{variantForm:!0}],divideontimes:"\u22c7",intercal:"\u22ba",leqq:"\u2266",geqq:"\u2267",leqslant:"\u2a7d",geqslant:"\u2a7e",eqslantless:"\u2a95",eqslantgtr:"\u2a96",lesssim:"\u2272",gtrsim:"\u2273",lessapprox:"\u2a85",gtrapprox:"\u2a86",approxeq:"\u224a",lessdot:"\u22d6",gtrdot:"\u22d7",lll:"\u22d8",llless:"\u22d8",ggg:"\u22d9",gggtr:"\u22d9",lessgtr:"\u2276",gtrless:"\u2277",lesseqgtr:"\u22da",gtreqless:"\u22db",lesseqqgtr:"\u2a8b",gtreqqless:"\u2a8c",doteqdot:"\u2251",Doteq:"\u2251",eqcirc:"\u2256",risingdotseq:"\u2253",circeq:"\u2257",fallingdotseq:"\u2252",triangleq:"\u225c",backsim:"\u223d",thicksim:["\u223c",{variantForm:!0}],backsimeq:"\u22cd",thickapprox:["\u2248",{variantForm:!0}],subseteqq:"\u2ac5",supseteqq:"\u2ac6",Subset:"\u22d0",Supset:"\u22d1",sqsubset:"\u228f",sqsupset:"\u2290",preccurlyeq:"\u227c",succcurlyeq:"\u227d",curlyeqprec:"\u22de",curlyeqsucc:"\u22df",precsim:"\u227e",succsim:"\u227f",precapprox:"\u2ab7",succapprox:"\u2ab8",vartriangleleft:"\u22b2",lhd:"\u22b2",vartriangleright:"\u22b3",rhd:"\u22b3",trianglelefteq:"\u22b4",unlhd:"\u22b4",trianglerighteq:"\u22b5",unrhd:"\u22b5",vDash:"\u22a8",Vdash:"\u22a9",Vvdash:"\u22aa",smallsmile:["\u2323",{variantForm:!0}],shortmid:["\u2223",{variantForm:!0}],smallfrown:["\u2322",{variantForm:!0}],shortparallel:["\u2225",{variantForm:!0}],bumpeq:"\u224f",between:"\u226c",Bumpeq:"\u224e",pitchfork:"\u22d4",varpropto:["\u221d",{variantForm:!0}],backepsilon:"\u220d",blacktriangleleft:"\u25c2",blacktriangleright:"\u25b8",therefore:"\u2234",because:"\u2235",eqsim:"\u2242",vartriangle:["\u25b3",{variantForm:!0}],Join:"\u22c8",nless:"\u226e",ngtr:"\u226f",nleq:"\u2270",ngeq:"\u2271",nleqslant:["\u2a87",{variantForm:!0}],ngeqslant:["\u2a88",{variantForm:!0}],nleqq:["\u2270",{variantForm:!0}],ngeqq:["\u2271",{variantForm:!0}],lneq:"\u2a87",gneq:"\u2a88",lneqq:"\u2268",gneqq:"\u2269",lvertneqq:["\u2268",{variantForm:!0}],gvertneqq:["\u2269",{variantForm:!0}],lnsim:"\u22e6",gnsim:"\u22e7",lnapprox:"\u2a89",gnapprox:"\u2a8a",nprec:"\u2280",nsucc:"\u2281",npreceq:["\u22e0",{variantForm:!0}],nsucceq:["\u22e1",{variantForm:!0}],precneqq:"\u2ab5",succneqq:"\u2ab6",precnsim:"\u22e8",succnsim:"\u22e9",precnapprox:"\u2ab9",succnapprox:"\u2aba",nsim:"\u2241",ncong:"\u2247",nshortmid:["\u2224",{variantForm:!0}],nshortparallel:["\u2226",{variantForm:!0}],nmid:"\u2224",nparallel:"\u2226",nvdash:"\u22ac",nvDash:"\u22ad",nVdash:"\u22ae",nVDash:"\u22af",ntriangleleft:"\u22ea",ntriangleright:"\u22eb",ntrianglelefteq:"\u22ec",ntrianglerighteq:"\u22ed",nsubseteq:"\u2288",nsupseteq:"\u2289",nsubseteqq:["\u2288",{variantForm:!0}],nsupseteqq:["\u2289",{variantForm:!0}],subsetneq:"\u228a",supsetneq:"\u228b",varsubsetneq:["\u228a",{variantForm:!0}],varsupsetneq:["\u228b",{variantForm:!0}],subsetneqq:"\u2acb",supsetneqq:"\u2acc",varsubsetneqq:["\u2acb",{variantForm:!0}],varsupsetneqq:["\u2acc",{variantForm:!0}],leftleftarrows:"\u21c7",rightrightarrows:"\u21c9",leftrightarrows:"\u21c6",rightleftarrows:"\u21c4",Lleftarrow:"\u21da",Rrightarrow:"\u21db",twoheadleftarrow:"\u219e",twoheadrightarrow:"\u21a0",leftarrowtail:"\u21a2",rightarrowtail:"\u21a3",looparrowleft:"\u21ab",looparrowright:"\u21ac",leftrightharpoons:"\u21cb",rightleftharpoons:["\u21cc",{variantForm:!0}],curvearrowleft:"\u21b6",curvearrowright:"\u21b7",circlearrowleft:"\u21ba",circlearrowright:"\u21bb",Lsh:"\u21b0",Rsh:"\u21b1",upuparrows:"\u21c8",downdownarrows:"\u21ca",upharpoonleft:"\u21bf",upharpoonright:"\u21be",downharpoonleft:"\u21c3",restriction:"\u21be",multimap:"\u22b8",downharpoonright:"\u21c2",leftrightsquigarrow:"\u21ad",rightsquigarrow:"\u21dd",leadsto:"\u21dd",dashrightarrow:"\u21e2",dashleftarrow:"\u21e0",nleftarrow:"\u219a",nrightarrow:"\u219b",nLeftarrow:"\u21cd",nRightarrow:"\u21cf",nleftrightarrow:"\u21ae",nLeftrightarrow:"\u21ce"}),new Ua("AMSsymbols-delimiter",Ml.delimiter,{"\\ulcorner":"\u231c","\\urcorner":"\u231d","\\llcorner":"\u231e","\\lrcorner":"\u231f"}),new qa("AMSsymbols-macros",{implies:[Gl.Macro,"\\;\\Longrightarrow\\;"],impliedby:[Gl.Macro,"\\;\\Longleftarrow\\;"]});class Jl extends ha{get kind(){return"beginEnv"}get isOpen(){return!0}checkItem(t){if(t.isKind("end")){if(t.getName()!==this.getName())throw new la("EnvBadEnd","\\begin{%1} ended with \\end{%2}",this.getName(),t.getName());return[[this.factory.create("mml",this.toMml())],!0]}if(t.isKind("stop"))throw new la("EnvMissingEnd","Missing \\end{%1}",this.getName());return super.checkItem(t)}}const Kl={NewCommand(t,e){const s=zl.GetCsNameArgument(t,e),i=zl.GetArgCount(t,e),r=t.GetBrackets(e),n=t.GetArgument(e);zl.addMacro(t,s,Kl.Macro,[n,i,r]),t.Push(t.itemFactory.create("null"))},NewEnvironment(t,e){const s=na.trimSpaces(t.GetArgument(e)),i=zl.GetArgCount(t,e),r=t.GetBrackets(e),n=t.GetArgument(e),o=t.GetArgument(e);zl.addEnvironment(t,s,Kl.BeginEnv,[!0,n,o,i,r]),t.Push(t.itemFactory.create("null"))},MacroDef(t,e){const s=zl.GetCSname(t,e),i=zl.GetTemplate(t,e,"\\"+s),r=t.GetArgument(e);i instanceof Array?zl.addMacro(t,s,Kl.MacroWithTemplate,[r].concat(i)):zl.addMacro(t,s,Kl.Macro,[r,i]),t.Push(t.itemFactory.create("null"))},Let(t,e){const s=zl.GetCSname(t,e);let i=t.GetNext();"="===i&&(t.i++,i=t.GetNext());const r=t.configuration.handlers;if(t.Push(t.itemFactory.create("null")),"\\"===i){if(s===(e=zl.GetCSname(t,e)))return;const i=r.get(ia.MACRO).applicable(e);if(i instanceof Ha){const r=i.lookup(e);return void zl.addMacro(t,s,r.func,r.args,r.token)}if(i instanceof ja&&!(i instanceof Ua)){const r=i.lookup(e),n=t=>i.parser(t,r);return void zl.addMacro(t,s,n,[s,r.char])}const n=r.get(ia.DELIMITER).lookup("\\"+e);return n?void zl.addDelimiter(t,"\\"+s,n.char,n.attributes):(zl.checkProtectedMacros(t,s),zl.undefineMacro(t,s),void zl.undefineDelimiter(t,"\\"+s))}t.i++;const n=r.get(ia.DELIMITER).lookup(i);n?zl.addDelimiter(t,"\\"+s,n.char,n.attributes):zl.addMacro(t,s,Kl.Macro,[i])},MacroWithTemplate(t,e,s,i,...r){const n=parseInt(i,10);if(r.length){const i=[];if(t.GetNext(),r[0]&&!zl.MatchParam(t,r[0]))throw new la("MismatchUseDef","Use of %1 doesn't match its definition",e);if(n){for(let s=0;sic(t,e,r))):ic(t,e,r)}}function ic(t,e,s){const i=$a.get(s);if(i){let r=ec[e]||{};i.options&&1===Object.keys(i.options).length&&i.options[s]&&(r={[s]:r}),t.configuration.add(s,t,r);const n=t.parseOptions.packageData.get("require").configured;i.preprocessors.length&&!n.has(s)&&(n.set(s,!0),Zn.retryAfter(Promise.resolve()))}}function rc(t,e){var s,i;const r=t.options.require,n=r.allow,o=("["===e.substring(0,1)?"":r.prefix)+e;if(!(Object.hasOwn(n,o)?n[o]:Object.hasOwn(n,e)?n[e]:r.defaultAllow))throw new la("BadRequire",'Extension "%1" is not allowed to be loaded',o);const a=mi.packages.get(o);if(a||Zn.retryAfter(Ni.load(o).catch(t=>{})),a.hasFailed)throw new la("RequireFail",'Extension "%1" failed to load',e);const l=null===(s=Ti[o])||void 0===s?void 0:s.rendererExtensions,c=null===(i=Wi.startup.document)||void 0===i?void 0:i.menu;l&&c&&c.addRequiredExtensions(l),sc(t.configuration.packageData.get("require").jax,o)}const nc={Require(t,e){const s=t.GetArgument(e);if(s.match(/[^_a-zA-Z0-9]/)||""===s)throw new la("BadPackageName","Argument for %1 is not a valid package name",e);rc(t,s),t.Push(t.itemFactory.create("null"))}},oc={require:{allow:Ri({base:!1,autoload:!1,configmacros:!1,tagformat:!1,setoptions:!1,texhtml:!1}),defaultAllow:!0,prefix:"tex"}};new qa("require",{require:nc.Require});const ac=Ja.create("require",{[sa.HANDLER]:{[ia.MACRO]:["require"]},[sa.CONFIG]:function(t,e){e.parseOptions.packageData.set("require",{jax:e,required:[...e.options.packages],configured:new Map});const s=e.parseOptions.options.require,i=s.prefix;if(i.match(/[^_a-zA-Z0-9]/))throw Error("Illegal characters used in \\require prefix");Ti.paths[i]||(Ti.paths[i]="[mathjax]/input/tex/extensions"),s.prefix="["+i+"]/"},[sa.OPTIONS]:oc});function lc(t,e,s,i){if(mi.packages.has(t.options.require.prefix+s)){const r=t.options.autoload[s],[n,o]=2===r.length&&Array.isArray(r[0])?r:[r,[]];for(const t of n)cc.remove(t);for(const t of o)hc.remove(t);t.string=(i?e+" ":"\\begin{"+e.slice(1)+"}")+t.string.slice(t.i),t.i=0}rc(t,s)}const cc=new qa("autoload-macros",{}),hc=new qa("autoload-environments",{}),dc=Ja.create("autoload",{[sa.HANDLER]:{[ia.MACRO]:["autoload-macros"],[ia.ENVIRONMENT]:["autoload-environments"]},[sa.OPTIONS]:{autoload:Ri({action:["toggle","mathtip","texttip"],amscd:[[],["CD"]],bbox:["bbox"],boldsymbol:["boldsymbol"],braket:["bra","ket","braket","set","Bra","Ket","Braket","Set","ketbra","Ketbra"],bussproofs:[[],["prooftree"]],cancel:["cancel","bcancel","xcancel","cancelto"],color:["color","definecolor","textcolor","colorbox","fcolorbox"],enclose:["enclose"],extpfeil:["xtwoheadrightarrow","xtwoheadleftarrow","xmapsto","xlongequal","xtofrom","Newextarrow"],html:["data","href","class","style","cssId"],mhchem:["ce","pu"],newcommand:["newcommand","renewcommand","newenvironment","renewenvironment","def","let"],unicode:["unicode","U","char"],verb:["verb"]})},[sa.CONFIG]:function(t,e){const s=e.parseOptions,i=s.handlers.get(ia.MACRO),r=s.handlers.get(ia.ENVIRONMENT),n=s.options.autoload;s.packageData.set("autoload",{Autoload:lc});for(const t of Object.keys(n)){const e=n[t],[s,o]=2===e.length&&Array.isArray(e[0])?e:[e,[]];for(const e of s)i.lookup(e)&&"color"!==e||cc.add(e,new Oa(e,lc,[t,!0]));for(const e of o)r.lookup(e)||hc.add(e,new Oa(e,lc,[t,!1]))}s.packageData.get("require")||ac.config(t,e)},[sa.INIT]:function(t){t.options.require||Di(t.options,ac.options)},[sa.PRIORITY]:10}),uc="configmacros-map",pc="configmacros-active-map",mc="configmacros-env-map";function fc(t,e,s){const i=s.parseOptions.handlers.retrieve(e),r=s.parseOptions.options[t];for(const t of Object.keys(r)){const e="string"==typeof r[t]?[r[t]]:r[t],s=Array.isArray(e[2])?new Oa(t,$l.MacroWithTemplate,e.slice(0,2).concat(e[2])):new Oa(t,$l.Macro,e);i.add(t,s)}}const gc=Ja.create("configmacros",{[sa.INIT]:function(t){new Ha(pc,{}),new qa(uc,{}),new Wa(mc,Ml.environment,{}),t.append(Ja.local({handler:{[ia.CHARACTER]:[pc],[ia.MACRO]:[uc],[ia.ENVIRONMENT]:[mc]},priority:3}))},[sa.CONFIG]:function(t,e){!function(t){fc("active",pc,t)}(e),function(t){fc("macros",uc,t)}(e),function(t){const e=t.parseOptions.handlers.retrieve(mc),s=t.parseOptions.options.environments;for(const t of Object.keys(s))e.add(t,new Oa(t,$l.BeginEnv,[!0].concat(s[t])))}(e)},[sa.ITEMS]:{[Jl.prototype.kind]:Jl},[sa.OPTIONS]:{active:Ri({}),macros:Ri({}),environments:Ri({})}});const bc=Ja.create("noundefined",{[sa.FALLBACK]:{[ia.MACRO]:function(t,e){const s=t.create("text","\\"+e),i=t.options.noundefined,r={};for(const t of["color","background","size"])i[t]&&(r["math"+t]=i[t]);t.Push(t.create("node","mtext",[],r,s))}},[sa.OPTIONS]:{noundefined:{color:"red",background:"",size:""}},[sa.PRIORITY]:3});class Ec extends da{get texParser(){return this.configuration.packageData.get("textmacros").texParser}get tags(){return this.texParser.tags}constructor(t,e,s,i){super(t,e,s),this.level=i}mml(){return this.copyLists(),this.configuration.popParser(),null!=this.level?this.create("node","mstyle",this.nodes,{displaystyle:!1,scriptlevel:this.level}):1===this.nodes.length?this.nodes[0]:this.create("node","mrow",this.nodes)}copyLists(){const t=this.texParser.configuration;for(const[e,s]of Object.entries(this.configuration.nodeLists))for(const i of s)t.addNode(e,i);this.configuration.nodeLists={}}Parse(){this.text="",this.nodes=[],this.envStack=[],super.Parse()}saveText(){if(this.text){const t=this.stack.env.mathvariant,e=ya.internalText(this,this.text,t?{mathvariant:t}:{});this.text="",this.Push(e)}}Push(t){if(this.text&&this.saveText(),t instanceof Za)return super.Push(t);t instanceof ul?this.stack.env.mathcolor=this.stack.env.color:t instanceof yr&&(this.addAttributes(t),this.nodes.push(t))}PushMath(t){const e=this.stack.env;for(const s of["mathsize","mathcolor"])e[s]&&!t.attributes.hasExplicit(s)&&(t.isToken||t.isKind("mstyle")||(t=this.create("node","mstyle",[t])),Jo.setAttribute(t,s,e[s]));t.isInferred&&(t=this.create("node","mrow",t.childNodes)),t.isKind("TeXAtom")||(t=this.create("node","TeXAtom",[t])),this.nodes.push(t)}addAttributes(t){const e=this.stack.env;if(t.isToken)for(const s of["mathsize","mathcolor","mathvariant"])e[s]&&!t.attributes.hasExplicit(s)&&Jo.setAttribute(t,s,e[s])}ParseTextArg(t,e){const s=this.GetArgument(t);return e=Object.assign(Object.assign({},this.stack.env),e),new Ec(s,e,this.configuration).mml()}ParseArg(t){return new Ec(this.GetArgument(t),this.stack.env,this.configuration).mml()}Error(t,e,...s){throw new la(t,e,...s)}}const xc={Comment(t,e){for(;t.i":[xc.Spacer,go.mediummathspace],";":[xc.Spacer,go.thickmathspace],"!":[xc.Spacer,go.negativethinmathspace],enspace:[xc.Spacer,.5],quad:[xc.Spacer,1],qquad:[xc.Spacer,2],thinspace:[xc.Spacer,go.thinmathspace],negthinspace:[xc.Spacer,go.negativethinmathspace],hskip:xc.Hskip,hspace:xc.Hskip,kern:xc.Hskip,mskip:xc.Hskip,mspace:xc.Hskip,mkern:xc.Hskip,rule:xc.rule,Rule:[xc.Rule],Space:[xc.Rule,"blank"],color:xc.CheckAutoload,textcolor:xc.CheckAutoload,colorbox:xc.CheckAutoload,fcolorbox:xc.CheckAutoload,href:xc.CheckAutoload,style:xc.CheckAutoload,class:xc.CheckAutoload,data:xc.CheckAutoload,cssId:xc.CheckAutoload,unicode:xc.CheckAutoload,U:xc.CheckAutoload,char:xc.CheckAutoload,ref:[xc.HandleRef,!1],eqref:[xc.HandleRef,!0],underline:[xc.UnderOver,"2015"],llap:xc.Lap,rlap:xc.Lap,phantom:xc.Phantom,vphantom:[xc.Phantom,1,0],hphantom:[xc.Phantom,0,1],smash:xc.Smash,mmlToken:xc.MmlToken});const Nc=Ja.create("text-base",{[sa.PARSER]:"text",[sa.PRIORITY]:1,[sa.HANDLER]:{[ia.CHARACTER]:["command","text-special"],[ia.MACRO]:["text-macros"]},[sa.FALLBACK]:{[ia.CHARACTER]:(t,e)=>{t.text+=e},[ia.MACRO]:(t,e)=>{const s=t.texParser,i=s.lookup(ia.MACRO,e);i&&i._func!==xc.Macro&&t.Error("MathMacro","%1 is only supported in math mode","\\"+e),s.parse(ia.MACRO,[t,e])}},[sa.ITEMS]:{[Qa.prototype.kind]:Qa,[Za.prototype.kind]:Za,[fl.prototype.kind]:fl,[ul.prototype.kind]:ul}});function vc(t,e,s,i){const r=t.configuration.packageData.get("textmacros");return t instanceof Ec||(r.texParser=t),r.parseOptions.clear(),[new Ec(e,i?{mathvariant:i}:{},r.parseOptions,s).mml()]}const Tc=Ja.create("textmacros",{[sa.PRIORITY]:1,[sa.CONFIG]:(t,e)=>{const s=new Ya(e.parseOptions.options.textmacros.packages,["tex","text"]);s.init();const i=new wa(s,[]);i.options=e.parseOptions.options,s.config(e),Ma.addTags(s.tags),i.tags=Ma.getDefault(),i.tags.configuration=i,i.packageData=e.parseOptions.packageData,i.packageData.set("textmacros",{textConf:s,parseOptions:i,jax:e,texParser:null}),i.options.internalMath=vc},[sa.PREPROCESSORS]:[t=>{const e=t.data.packageData.get("textmacros");e.parseOptions.nodeFactory.setMmlFactory(e.jax.mmlFactory)}],[sa.OPTIONS]:{textmacros:{packages:["text-base"]}}});MathJax.loader&&MathJax.loader.checkVersion("input/tex",ii,"input"),ci({_:{input:{tex_ts:te,tex:{ColumnParser:Wt,Configuration:Kt,FilterUtil:It,FindTeX:Rt,HandlerTypes:Ot,MapHandler:Jt,NodeFactory:Ht,NodeUtil:St,ParseMethods:Qt,ParseOptions:zt,ParseUtil:qt,Stack:Pt,StackItem:Ft,StackItemFactory:Ut,Tags:Vt,TexConstants:Mt,TexError:Bt,TexParser:jt,Token:Xt,TokenMap:Gt,UnitUtil:Dt,ams:{AmsConfiguration:ae,AmsItems:ee,AmsMethods:ie},autoload:{AutoloadConfiguration:ce},base:{BaseConfiguration:Zt,BaseItems:$t,BaseMethods:Yt},configmacros:{ConfigMacrosConfiguration:he},newcommand:{NewcommandConfiguration:oe,NewcommandItems:re,NewcommandMethods:ne,NewcommandUtil:se},noundefined:{NoUndefinedConfiguration:de},require:{RequireConfiguration:le},textmacros:{TextMacrosConfiguration:me,TextMacrosMethods:pe,TextParser:ue}}}}}),Ni.preLoaded("input/tex-base","[tex]/ams","[tex]/newcommand","[tex]/textmacros","[tex]/noundefined","[tex]/require","[tex]/autoload","[tex]/configmacros"),function(t=[],e=!0){if(MathJax.startup){e&&(MathJax.startup.registerConstructor("tex",MathJax._.input.tex_ts.TeX),MathJax.startup.useInput("tex")),MathJax.config.tex||(MathJax.config.tex={});let s=MathJax.config.tex.packages;MathJax.config.tex.packages=t,s&&(Array.isArray(s)&&(s={"[+]":s.filter(e=>!t.includes(e))}),Oi(MathJax.config.tex,{packages:s}))}}(["base","ams","newcommand","textmacros","noundefined","require","autoload","configmacros"]);const wc="http://www.w3.org/1998/Math/MathML";class Cc extends Yi{findMath(t){const e=new Set;this.findMathNodes(t,e),this.findMathPrefixed(t,e);const s=this.adaptor.root(this.adaptor.document);return"html"===this.adaptor.kind(s)&&0===e.size&&this.findMathNS(t,e),this.processMath(e)}findMathNodes(t,e){for(const s of this.adaptor.tags(t,"math"))e.add(s)}findMathPrefixed(t,e){const s=this.adaptor.root(this.adaptor.document);for(const i of this.adaptor.allAttributes(s))if("xmlns:"===i.name.substring(0,6)&&i.value===wc){const s=i.name.substring(6);for(const i of this.adaptor.tags(t,s+":math"))e.add(i)}}findMathNS(t,e){for(const s of this.adaptor.tags(t,"math",wc))e.add(s)}processMath(t){const e=this.adaptor,s=[];for(const i of t.values()){if("mjx-assistive-mml"===e.kind(e.parent(i)))continue;const t="block"===e.getAttribute(i,"display")||"display"===e.getAttribute(i,"mode"),r={node:i,n:0,delim:""},n={node:i,n:0,delim:""};s.push({math:e.outerHTML(i),start:r,end:n,display:t})}return s}}Cc.OPTIONS={};class kc{constructor(t={}){const e=this.constructor;this.options=Pi(Di({},e.OPTIONS),t)}setMmlFactory(t){this.factory=t}compile(t){const e=this.makeNode(t);return e.verifyTree(this.options.verify),e.setInheritedAttributes({},!1,0,!1),e.walkTree(this.markMrows),e}makeNode(t){const e=this.adaptor;let s=!1;const i=e.kind(t).replace(/^.*:/,"");let r=e.getAttribute(t,"data-mjx-texclass")||"";r&&(r=this.filterAttribute("data-mjx-texclass",r)||"");let n=r&&"mrow"===i?"TeXAtom":i;for(const o of this.filterClassList(e.allClasses(t)))o.match(/^MJX-TeXAtom-/)&&"mrow"===i?(r=o.substring(12),n="TeXAtom"):"MJX-fixedlimits"===o&&(s=!0);return this.factory.getNodeClass(n)?this.createMml(n,t,r,s):this.unknownNode(n,t)}createMml(t,e,s,i){const r=this.factory.create(t);return"TeXAtom"!==t||"OP"!==s||i||(r.setProperty("movesupsub",!0),r.attributes.setInherited("movablelimits",!0)),s&&(r.texClass=mr[s],r.setProperty("texClass",r.texClass)),this.addAttributes(r,e),this.checkClass(r,e),this.addChildren(r,e),r}unknownNode(t,e){return this.factory.getNodeClass("html")&&this.options.allowHtmlInTokenNodes?this.factory.create("html").setHTML(e,this.adaptor):(this.error('Unknown node type "'+t+'"'),null)}addAttributes(t,e){let s=!1;for(const i of this.adaptor.allAttributes(e)){const e=i.name,r=this.filterAttribute(e,i.value);if(null!==r&&"xmlns"!==e)if("data-mjx-"===e.substring(0,9))switch(e.substring(9)){case"alternate":t.setProperty("variantForm",!0);break;case"variant":t.attributes.set("mathvariant",r),t.setProperty("ignore-variant",!0),s=!0;break;case"smallmatrix":t.setProperty("smallmatrix",!0),t.setProperty("useHeight",!1);break;case"mathaccent":t.setProperty("mathaccent","true"===r);break;case"auto-op":t.setProperty("autoOP","true"===r);break;case"script-align":t.setProperty("scriptalign",r);break;case"vbox":t.setProperty("vbox",r);break;default:t.attributes.set(e,r)}else if("class"!==e){const i=r.toLowerCase();"true"===i||"false"===i?t.attributes.set(e,"true"===i):s&&"mathvariant"===e||t.attributes.set(e,r)}}}filterAttribute(t,e){return e}filterClassList(t){return t}addChildren(t,e){if(0===t.arity)return;const s=this.adaptor;for(const i of s.childNodes(e)){const e=s.kind(i);if("#comment"!==e)if("#text"===e)this.addText(t,i);else if(t.isKind("annotation-xml"))t.appendChild(this.factory.create("XML").setXML(i,s));else{const e=t.appendChild(this.makeNode(i));0===e.arity&&s.childNodes(i).length&&!e.isKind("html")&&(this.options.fixMisplacedChildren?this.addChildren(t,i):e.mError("There should not be children for "+e.kind+" nodes",this.options.verify,!0))}}t.isToken&&this.trimSpace(t)}addText(t,e){let s=this.adaptor.value(e);(t.isToken||t.getProperty("isChars"))&&t.arity?(t.isToken&&(s=_o(s),s=this.normalizeSpace(s)),t.appendChild(this.factory.create("text").setText(s))):s.match(/\S/)&&this.error('Unexpected text node "'+s+'"')}checkClass(t,e){const s=[];for(const i of this.filterClassList(this.adaptor.allClasses(e)))"MJX-"===i.substring(0,4)?"MJX-variant"===i?t.setProperty("variantForm",!0):"MJX-TeXAtom"!==i.substring(0,11)&&t.attributes.set("mathvariant",this.fixCalligraphic(i.substring(3))):s.push(i);s.length&&t.attributes.set("class",s.join(" "))}fixCalligraphic(t){return t.replace(/caligraphic/,"calligraphic")}markMrows(t){if(t.isKind("mrow")&&!t.isInferred&&t.childNodes.length>=2){const e=t.childNodes[0],s=t.childNodes[t.childNodes.length-1];e.isKind("mo")&&e.attributes.get("fence")&&e.attributes.get("stretchy")&&s.isKind("mo")&&s.attributes.get("fence")&&s.attributes.get("stretchy")&&(e.childNodes.length&&t.setProperty("open",e.getText()),s.childNodes.length&&t.setProperty("close",s.getText()))}}normalizeSpace(t){return t.replace(/[\t\n\r]/g," ").replace(/ +/g," ")}trimSpace(t){let e=t.childNodes[0];e&&(e.isKind("text")&&e.setText(e.getText().replace(/^ +/,"")),e=t.childNodes[t.childNodes.length-1],e.isKind("text")&&e.setText(e.getText().replace(/ +$/,"")))}error(t){throw new Error(t)}}kc.OPTIONS={MmlFactory:null,allowHtmlInTokenNodes:!1,fixMisplacedChildren:!0,verify:Object.assign({},yr.verifyDefaults),translateEntities:!0};class _c extends Qi{constructor(t={}){const[e,s,i]=ji(t,Cc.OPTIONS,kc.OPTIONS);super(e),this.findMathML=this.options.FindMathML||new Cc(s),this.mathml=this.options.MathMLCompile||new kc(i),this.mmlFilters=new gi(this.options.mmlFilters)}setAdaptor(t){super.setAdaptor(t),this.findMathML.adaptor=t,this.mathml.adaptor=t}setMmlFactory(t){super.setMmlFactory(t),this.mathml.setMmlFactory(t)}get processStrings(){return!1}compile(t,e){let s=t.start.node;if(!s||!t.end.node||this.options.forceReparse||"#text"===this.adaptor.kind(s)){let i=this.executeFilters(this.preFilters,t,e,(t.math||"").trim());"html"===this.options.parseAs&&(i=`${i}`);const r=this.checkForErrors(this.adaptor.parse(i,"text/"+this.options.parseAs)),n=this.adaptor.body(r);1!==this.adaptor.childNodes(n).length&&this.error("MathML must consist of a single element"),s=this.adaptor.remove(this.adaptor.firstChild(n)),"math"!==this.adaptor.kind(s).replace(/^[a-z]+:/,"")&&this.error("MathML must be formed by a element, not <"+this.adaptor.kind(s)+">")}s=this.executeFilters(this.mmlFilters,t,e,s);let i=this.mathml.compile(s);return i=this.executeFilters(this.postFilters,t,e,i),t.display="block"===i.attributes.get("display"),i}checkForErrors(t){const e=this.adaptor.tags(this.adaptor.body(t),"parsererror")[0];return e&&(""===this.adaptor.textContent(e)&&this.error("Error processing MathML"),this.options.parseError.call(this,e)),t}error(t){throw new Error(t)}findMath(t){return this.findMathML.findMath(t)}}_c.NAME="MathML",_c.OPTIONS=Di({parseAs:"html",forceReparse:!1,mmlFilters:[],FindMathML:null,MathMLCompile:null,parseError:function(t){this.error(this.adaptor.textContent(t).replace(/\n.*/g,""))}},Qi.OPTIONS),MathJax.loader&&MathJax.loader.checkVersion("input/mml",ii,"input"),ci({_:{input:{mathml_ts:be,mathml:{FindMathML:fe,MathMLCompile:ge}}}}),MathJax.loader&&MathJax.loader.pathFilters.add(t=>(t.name=t.name.replace(/\/util\/entities\/.*?\.js/,"/input/mml/entities.js"),!0)),MathJax.startup&&(MathJax.startup.registerConstructor("mml",_c),MathJax.startup.useInput("mml"));const Lc={None:"",Vertical:"v",Horizontal:"h"},Ac=Lc.Vertical,Rc=Lc.Horizontal;var Sc=function(t,e,s,i){return new(s||(s=Promise))(function(r,n){function o(t){try{l(i.next(t))}catch(t){n(t)}}function a(t){try{l(i.throw(t))}catch(t){n(t)}}function l(t){var e;t.done?r(t.value):(e=t.value,e instanceof s?e:new s(function(t){t(e)})).then(o,a)}l((i=i.apply(t,e||[])).next())})};const Mc={dir:Lc.None};function Ic(t,e,s){return s?Di(t,{[e]:s})[e]:t[e]}class Oc{get CLASS(){return this.constructor}static charOptions(t,e){const s=t[e];if(!Array.isArray(s))throw Error(`Character data hasn't been loaded for 0x${e.toString(16).toUpperCase()}`);return 3===s.length&&(s[3]={}),s[3]}static defineDynamicFiles(t,e=""){const s={};return(t||[]).forEach(([t,i,r])=>{s[t]={extension:e,file:t,variants:i,delimiters:r||[],promise:null,failed:!1,setup:e=>{s[t].failed=!0}}}),s}static dynamicSetup(t,e,s,i={},r=null){const n=t?this.dynamicExtensions.get(t):null;(t?n.files:this.dynamicFiles)[e].setup=e=>{Object.keys(s).forEach(t=>e.defineChars(t,s[t])),e.defineDelimiters(i),t&&this.adjustDelimiters(e.delimiters,Object.keys(i),n.sizeN,n.stretchN),r&&e.addDynamicFontCss(r)}}static adjustDelimiters(t,e,s,i){e.forEach(e=>{const r=t[parseInt(e)];"dir"in r&&(r.variants&&(r.variants=this.adjustArrayIndices(r.variants,s)),r.stretchv&&(r.stretchv=this.adjustArrayIndices(r.stretchv,i)))})}static adjustArrayIndices(t,e){return t.map(t=>t<0?e-1-t:t)}static addExtension(t,e=""){const s={name:t.name,prefix:e||`[${t.name}-extension]/${this.JAX.toLowerCase()}/dynamic`,files:this.defineDynamicFiles(t.ranges,t.name),sizeN:this.defaultSizeVariants.length,stretchN:this.defaultStretchVariants.length};this.dynamicExtensions.set(t.name,s);for(const[e,s]of[["options","OPTIONS"],["variants","defaultVariants"],["variantSmp","VariantSmp"],["cssFonts","defaultCssFonts"],["accentMap","defaultAccentMap"],["moMap","defaultMoMap"],["mnMap","defaultMnMap"],["parameters","defaultParams"],["chars","defaultChars"],["sizeVariants","defaultSizeVariants"],["stretchVariants","defaultStretchVariants"]])Ic(this,s,t[e]);t.delimiters&&(Object.assign(this.defaultDelimiters,t.delimiters),this.adjustDelimiters(this.defaultDelimiters,Object.keys(t.delimiters),s.sizeN,s.stretchN))}constructor(t=null){this.variant={},this.delimiters={},this.cssFontMap={},this.cssFontPrefix="",this.remapChars={},this.skewIcFactor=.75;const e=this.CLASS;this.options=Pi(Di({},e.OPTIONS),t),this.params=Object.assign({},e.defaultParams),this.sizeVariants=[...e.defaultSizeVariants],this.stretchVariants=[...e.defaultStretchVariants],this.defineCssFonts(e.defaultCssFonts),this.cssFamilyPrefix=e.defaultCssFamilyPrefix,this.createVariants(e.defaultVariants),this.defineDelimiters(e.defaultDelimiters),Object.keys(e.defaultChars).forEach(t=>this.defineChars(t,e.defaultChars[t])),this.defineRemap("accent",e.defaultAccentMap),this.defineRemap("mo",e.defaultMoMap),this.defineRemap("mn",e.defaultMnMap),this.defineDynamicCharacters(e.dynamicFiles),e.dynamicExtensions.forEach(t=>this.defineDynamicCharacters(t.files))}setOptions(t){Di(this.options,t)}addExtension(t,e=""){const s=this.constructor.JAX.toLowerCase(),i={name:t.name,prefix:e||`[${t.name}-extension]/${s}/dynamic`,files:this.CLASS.defineDynamicFiles(t.ranges,e),sizeN:this.sizeVariants.length,stretchN:this.stretchVariants.length};this.CLASS.dynamicExtensions.set(t.name,i),Di(this.options,t.options||{}),Di(this.params,t.parameters||{}),Ic(this,"sizeVariants",t.sizeVariants),Ic(this,"stretchVariants",t.stretchVariants),Ic(this.constructor,"VariantSmp",t.variantSmp),this.defineCssFonts(Ic({cssFonts:{}},"cssFonts",t.cssFonts)),this.createVariants(Ic({variants:[]},"variants",t.variants)),t.delimiters&&(this.defineDelimiters(Ic({delimiters:{}},"delimiters",t.delimiters)),this.CLASS.adjustDelimiters(this.delimiters,Object.keys(t.delimiters),i.sizeN,i.stretchN));for(const e of Object.keys(t.chars||{}))this.defineChars(e,t.chars[e]);return this.defineRemap("accent",t.accentMap),this.defineRemap("mo",t.moMap),this.defineRemap("mn",t.mnMap),t.ranges&&this.defineDynamicCharacters(i.files),[]}get styles(){return this._styles}set styles(t){this._styles=t}createVariant(t,e=null,s=null){const i={linked:[],chars:Object.create(e?this.variant[e].chars:{})};this.variant[s]&&(Object.assign(i.chars,this.variant[s].chars),this.variant[s].linked.push(i.chars),i.chars=Object.create(i.chars)),this.remapSmpChars(i.chars,t),this.variant[t]=i}remapSmpChars(t,e){const s=this.CLASS;let i=s.VariantSmp[e];if("string"==typeof i&&(i=s.VariantSmp[i]),!i)return;const r=s.SmpRemap,n=[null,null,s.SmpRemapGreekU,s.SmpRemapGreekL];for(const[e,o,a]of s.SmpRanges){const s=i[e];if(s){for(let e=o;e<=a;e++){if(930===e)continue;const i=s+e-o;t[e]=this.smpChar(r[i]||i)}if(n[e])for(const i of Object.keys(n[e]).map(t=>parseInt(t)))t[i]=this.smpChar(s+n[e][i])}}const o=i[5]||{};for(const e of Object.keys(o))t[e]=this.smpChar(i[5][e])}smpChar(t){return[,,,{smp:t}]}createVariants(t){for(const e of t)this.createVariant(e[0],e[1],e[2])}defineChars(t,e){const s=this.variant[t];Object.assign(s.chars,e);for(const t of s.linked)Object.assign(t,e)}defineCssFonts(t){Object.assign(this.cssFontMap,t);for(const e of Object.keys(t))"unknown"===this.cssFontMap[e][0]&&(this.cssFontMap[e][0]=this.options.unknownFamily)}defineDelimiters(t){Object.assign(this.delimiters,t)}defineRemap(t,e){e&&(Object.hasOwn(this.remapChars,t)||(this.remapChars[t]={}),Object.assign(this.remapChars[t],e))}defineDynamicCharacters(t){for(const e of Object.keys(t)){const s=t[e];for(const t of Object.keys(s.variants))this.defineChars(t,this.flattenRanges(s.variants[t],s));this.defineDelimiters(this.flattenRanges(s.delimiters,s))}}flattenRanges(t,e){const s={};for(const i of t)if(Array.isArray(i))for(let t=i[0];t<=i[1];t++)s[t]=e;else s[i]=e;return s}dynamicFileName(t){const e=t.extension?this.CLASS.dynamicExtensions.get(t.extension).prefix:this.options.dynamicPrefix;return t.file.match(/^(?:[/[]|[a-z]+:\/\/|[a-z]:)/i)?t.file:e+"/"+t.file.replace(/(\.js)?$/,".js")}loadDynamicFile(t){return Sc(this,void 0,void 0,function*(){return t.failed?Promise.reject(new Error(`dynamic file '${t.file}' failed to load`)):(t.promise||(t.promise=uo(this.dynamicFileName(t)).catch(e=>{t.failed=!0,console.warn(e)})),t.promise.then(()=>t.setup(this)))})}loadDynamicFiles(){const t=this.CLASS.dynamicFiles,e=Object.keys(t).map(e=>this.loadDynamicFile(t[e]));for(const t of this.CLASS.dynamicExtensions.values())e.push(...Object.keys(t.files).map(e=>this.loadDynamicFile(t.files[e])));return Promise.all(e)}loadDynamicFilesSync(){if(!Zn.asyncIsSynchronous)throw Error("MathJax(loadDynamicFilesSync): mathjax.asyncLoad must be specified and synchronous\n Try importing #js/../components/require.mjs and #js/util/asyncLoad/node.js");const t=this.CLASS.dynamicFiles;Object.keys(t).forEach(e=>this.loadDynamicFileSync(t[e]));for(const t of this.CLASS.dynamicExtensions.values())Object.keys(t.files).forEach(e=>this.loadDynamicFileSync(t.files[e]))}loadDynamicFileSync(t){if(!t.promise){t.promise=Promise.resolve();try{Zn.asyncLoad(this.dynamicFileName(t))}catch(e){t.failed=!0,console.warn(e)}t.setup(this)}}addDynamicFontCss(t,e){}getDelimiter(t){const e=this.delimiters[t];return e&&!("dir"in e)?(this.delimiters[t]=null,On(this.loadDynamicFile(e)),null):e}getSizeVariant(t,e){const s=this.getDelimiter(t);return s&&s.variants&&(e=s.variants[e]),this.sizeVariants[e]}getStretchVariant(t,e){const s=this.getDelimiter(t);return this.stretchVariants[s.stretchv?s.stretchv[e]:0]}getStretchVariants(t){return[0,1,2,3].map(e=>this.getStretchVariant(t,e))}getChar(t,e){const s=this.variant[t].chars[e];if(s&&!Array.isArray(s)){const i=this.variant[t];return delete i.chars[e],i.linked.forEach(t=>delete t[e]),On(this.loadDynamicFile(s)),null}return s}getVariant(t){return this.variant[t]}getCssFont(t){return this.cssFontMap[t]||["serif",!1,!1]}getFamily(t){return this.cssFamilyPrefix?this.cssFamilyPrefix+", "+t:t}getRemappedChar(t,e){return(this.remapChars[t]||{})[e]}}Oc.OPTIONS={unknownFamily:"serif",dynamicPrefix:"."},Oc.JAX="common",Oc.NAME="",Oc.defaultVariants=[["normal"],["bold","normal"],["italic","normal"],["bold-italic","italic","bold"],["double-struck","bold"],["fraktur","normal"],["bold-fraktur","bold","fraktur"],["script","italic"],["bold-script","bold-italic","script"],["sans-serif","normal"],["bold-sans-serif","bold","sans-serif"],["sans-serif-italic","italic","sans-serif"],["sans-serif-bold-italic","bold-italic","bold-sans-serif"],["monospace","normal"],["-smallop","normal"],["-largeop","normal"],["-tex-calligraphic","italic"],["-tex-bold-calligraphic","bold-italic"],["-tex-oldstyle","normal"],["-tex-bold-oldstyle","bold"],["-tex-mathit","italic"],["-tex-variant","normal"]],Oc.defaultCssFonts={normal:["unknown",!1,!1],bold:["unknown",!1,!0],italic:["unknown",!0,!1],"bold-italic":["unknown",!0,!0],"double-struck":["unknown",!1,!0],fraktur:["unknown",!1,!1],"bold-fraktur":["unknown",!1,!0],script:["cursive",!1,!1],"bold-script":["cursive",!1,!0],"sans-serif":["sans-serif",!1,!1],"bold-sans-serif":["sans-serif",!1,!0],"sans-serif-italic":["sans-serif",!0,!1],"sans-serif-bold-italic":["sans-serif",!0,!0],monospace:["monospace",!1,!1],"-smallop":["unknown",!1,!1],"-largeop":["unknown",!1,!1],"-tex-calligraphic":["cursive",!0,!1],"-tex-bold-calligraphic":["cursive",!0,!0],"-tex-oldstyle":["unknown",!1,!1],"-tex-bold-oldstyle":["unknown",!1,!0],"-tex-mathit":["unknown",!0,!1],"-tex-variant":["unknown",!1,!1]},Oc.defaultCssFamilyPrefix="",Oc.VariantSmp={bold:[119808,119834,120488,120514,120782,{988:120778,989:120779}],italic:[119860,119886,120546,120572],"bold-italic":[119912,119938,120604,120630],script:[119964,119990],"bold-script":[120016,120042],fraktur:[120068,120094],"double-struck":[120120,120146,,,120792],"bold-fraktur":[120172,120198],"sans-serif":[120224,120250,,,120802],"bold-sans-serif":[120276,120302,120662,120688,120812],"sans-serif-italic":[120328,120354],"sans-serif-bold-italic":[120380,120406,120720,120746],monospace:[120432,120458,,,120822]},Oc.SmpRanges=[[0,65,90],[1,97,122],[2,913,937],[3,945,969],[4,48,57]],Oc.SmpRemap={119893:8462,119965:8492,119968:8496,119969:8497,119971:8459,119972:8464,119975:8466,119976:8499,119981:8475,119994:8495,119996:8458,120004:8500,120070:8493,120075:8460,120076:8465,120085:8476,120093:8488,120122:8450,120127:8461,120133:8469,120135:8473,120136:8474,120137:8477,120145:8484},Oc.SmpRemapGreekU={8711:25,1012:17},Oc.SmpRemapGreekL={977:27,981:29,982:31,1008:28,1009:30,1013:26,8706:25},Oc.defaultAccentMap={94:"\u02c6",126:"\u02dc",768:"\u02cb",769:"\u02ca",770:"\u02c6",771:"\u02dc",772:"\u02c9",774:"\u02d8",775:"\u02d9",776:"\xa8",778:"\u02da",780:"\u02c7",8594:"\u20d7"},Oc.defaultMoMap={45:"\u2212"},Oc.defaultMnMap={45:"\u2212"},Oc.defaultParams={x_height:.442,quad:1,num1:.676,num2:.394,num3:.444,denom1:.686,denom2:.345,sup1:.413,sup2:.363,sup3:.289,sub1:.15,sub2:.247,sup_drop:.386,sub_drop:.05,delim1:2.39,delim2:1,axis_height:.25,rule_thickness:.06,big_op_spacing1:.111,big_op_spacing2:.167,big_op_spacing3:.2,big_op_spacing4:.6,big_op_spacing5:.1,surd_height:.06,scriptspace:.05,nulldelimiterspace:.12,delimiterfactor:901,delimitershortfall:.3,rule_factor:1.25,min_rule_thickness:1.25,separation_factor:1.75,extra_ic:.033,extender_factor:.333},Oc.defaultDelimiters={},Oc.defaultChars={},Oc.defaultSizeVariants=[],Oc.defaultStretchVariants=[],Oc.dynamicFiles={},Oc.dynamicExtensions=new Map;class Dc extends No{static from(t,e,s=null){const i=new this;return Object.assign(i,t),i.lineLeading=e,s&&(i.indentData=s),i}constructor(t,e=null){super(t),this.indentData=null,this.isFirst=!1,this.originalL=this.L,e&&(this.start=e)}append(t){this.isFirst&&(t.originalL+=t.L,t.L=0),t.indentData&&(this.indentData=t.indentData),this.lineLeading=t.lineLeading,super.append(t),this.isFirst=t.isFirst}copy(){const t=Dc.from(this,this.lineLeading);return t.indentData=this.indentData,t.lineLeading=this.lineLeading,t}getIndentData(t){let{indentalign:e,indentshift:s,indentalignfirst:i,indentshiftfirst:r,indentalignlast:n,indentshiftlast:o}=t.attributes.getAllAttributes();"indentalign"===i&&(i=t.attributes.getInherited("indentalign")),"indentshift"===r&&(r=t.attributes.getInherited("indentshift")),"indentalign"===n&&(n=e),"indentshift"===o&&(o=s),this.indentData=[[i,r],[e,s],[n,o]]}copyIndentData(t){return t.indentData.map(([t,e])=>[t,e])}}const Pc=1e6;class Bc extends Xn{breakToWidth(t,e){}}class Fc extends Bc{constructor(){super(...arguments),this.PENALTY={newline:t=>0,nobreak:t=>Pc,goodbreak:t=>t-200*this.state.depth,badbreak:t=>t+200*this.state.depth,auto:t=>t},this.FACTORS={depth:t=>t+800*this.state.depth,width:t=>t+Math.floor((this.state.width-this.state.w)/this.state.width*2500),tail:t=>t+Math.floor(this.state.width/Math.max(1e-4,this.state.mathLeft-this.state.w)*500),open:(t,e)=>{const s=e.node.prevClass;if(s===mr.BIN||s===mr.REL||s===mr.OP)return t+5e3;const i=this.getPrevious(e);if(i&&("postfix"!==i.attributes.get("form")||"nobreak"===i.attributes.get("linebreak")))return t+5e3;const r=e.node.Parent;if((null==r?void 0:r.isKind("mmultiscripts"))&&e.node===this.getFirstToken(r)){if(!!r.childNodes.filter(t=>t.isKind("mprescripts")).length)return Pc}return t-500},close:(t,e)=>{var s;const i=e.node.Parent;return!(null==i?void 0:i.isKind("msubsup"))||i.isKind("mmultiscripts")&&(null===(s=i.childNodes[1])||void 0===s?void 0:s.isKind("mprescripts"))||e.node!==this.getLastToken(i.childNodes[0])?t+500:Pc},space:(t,e)=>{const s=e;if(!s.canBreak)return Pc;const i=s.getBBox().w;return i<0?Pc:i<1?t:t-100*(i+4)},separator:t=>t+500,fuzz:t=>.99*t},this.TEXCLASS={[mr.BIN]:t=>t-250,[mr.REL]:t=>t-500}}breakToWidth(t,e){const s=this.state;this.state=this.createState(t),this.state.width=e;const i=t.breakCount;for(let s=0;s<=i;s++){(t.lineBBox[s]||t.getLineBBox(s)).w>e&&this.breakLineToWidth(t,s)}for(const[t,e]of this.state.breaks){if(null===e){const e=t.coreMO();e.setBreakStyle(e.node.attributes.get("linebreakstyle")||"before")}else t.setBreakAt(e);t.invalidateBBox()}this.state=s}createState(t){const e=t.getBBox().w;return{breaks:new Set,potential:[],width:0,w:0,prevWidth:0,prevBreak:null,depth:0,mathWidth:e,mathLeft:e}}breakLineToWidth(t,e){const s=this.state;s.potential=[],s.w=0,s.prevWidth=0,s.prevBreak=null,s.depth=0,this.visitNode(t,e)}addWidth(t,e=null){null===e&&(e=t.L+t.w+t.R),e&&(e*=t.rscale,this.state.w+=e,this.state.potential.length&&(this.state.potential[0][4]+=e),this.processBreak())}processBreak(){const t=this.state;for(;t.potential.length&&t.w>this.state.width;){const e=t.potential.pop(),[s,,i,r,n]=e;t.breaks.add(s),t.w=t.potential.reduce((t,e)=>t+e[4],r+n),t.prevBreak&&t.prevWidth+i<=t.width?(t.breaks.delete(t.prevBreak[0]),t.prevWidth+=i):t.prevWidth=i+r,t.potential.forEach(t=>t[2]-=i),t.prevBreak=e,t.mathLeft-=i}}pushBreak(t,e,s,i){var r;const n=this.state;if(!(e>=Pc||0===n.w&&0===n.prevWidth)){for(;n.potential.length&&n.potential[0][1]>this.FACTORS.fuzz(e);){const t=n.potential.shift();n.potential.length&&(n.potential[0][4]+=t[4])}n.potential.unshift([[t,i],e,n.w-((null===(r=n.prevBreak)||void 0===r?void 0:r[3])||0),s,0])}}getBorderLR(t){var e;const s=t.styleData;if(!s)return[0,0];const i=(null===(e=null==s?void 0:s.border)||void 0===e?void 0:e.width)||[0,0,0,0],r=(null==s?void 0:s.padding)||[0,0,0,0];return[i[3]+r[3],i[1]+r[1]]}getFirstToken(t){return t.isToken?t:this.getFirstToken(t.childNodes[0])}getLastToken(t){return t.isToken?t:this.getLastToken(t.childNodes[t.childNodes.length-1])}visitNode(t,e){t&&(this.state.depth++,t.node.isEmbellished&&!t.node.isKind("mo")?this.visitEmbellishedOperator(t,e):super.visitNode(t,e),this.state.depth--)}visitDefault(t,e){var s;const i=t.getLineBBox(e);if(t.node.isToken||t.node.linebreakContainer||!(null===(s=t.childNodes)||void 0===s?void 0:s[0]))this.addWidth(i);else{const[s,r]=this.getBorderLR(t);0===e&&this.addWidth(i,i.L+s),this.visitNode(t.childNodes[0],e),e===t.breakCount&&this.addWidth(i,i.R+r)}}visitEmbellishedOperator(t,e){const s=t.coreMO(),i=Dc.from(t.getOuterBBox(),t.linebreakOptions.lineleading);i.getIndentData(s.node);const r=s.getBreakStyle(s.node.attributes.get("linebreakstyle")),n=s.processIndent("",i.indentData[1][1],"",i.indentData[0][1],this.state.width)[1],o=this.moPenalty(s);if("before"===r)this.pushBreak(t,o,n-i.L,null),this.addWidth(i);else{this.addWidth(i);const e=("after"===r?0:s.multChar?s.multChar.getBBox().w:i.w)+n;this.pushBreak(t,o,e,null)}}visitMoNode(t,e){const s=t,i=Dc.from(s.getOuterBBox(),s.linebreakOptions.lineleading);i.getIndentData(s.node);const r=s.getBreakStyle(s.node.attributes.get("linebreakstyle")),n=s.processIndent("",i.indentData[1][1],"",i.indentData[0][1],this.state.width)[1],o=this.moPenalty(s);if("before"===r)this.pushBreak(t,o,n-i.L,null),this.addWidth(i);else{this.addWidth(i);const e=("after"===r?0:s.multChar?s.multChar.getBBox().w:i.w)+n;this.pushBreak(t,o,e,null)}}moPenalty(t){const{linebreak:e,fence:s,form:i}=t.node.attributes.getList("linebreak","fence","form"),r=this.FACTORS;let n=r.tail(r.width(0));const o=s&&"prefix"===i||t.node.texClass===mr.OPEN,a=s&&"postfix"===i||t.node.texClass===mr.CLOSE;return o&&(n=r.open(n,t),this.state.depth++),a&&(n=r.close(n,t),this.state.depth--),n=(this.TEXCLASS[t.node.texClass]||(t=>t))(n),(this.PENALTY[e]||(t=>t))(r.depth(n))}getPrevious(t){let e=t.node,s=e.parent,i=s.childIndex(e);for(;s&&(s.notParent||s.isKind("mrow"))&&0===i;)e=s,s=e.parent,i=s.childIndex(e);if(!s||!i)return null;const r=s.childNodes[i-1];return r.isEmbellished?r.coreMO():null}visitMspaceNode(t,e){const s=t.getLineBBox(e),i=t;if(i.canBreak){const e=this.mspacePenalty(i);s.getIndentData(t.node);const r=t.processIndent("",s.indentData[1][1],"",s.indentData[0][1],this.state.width)[1];this.pushBreak(t,e,r-s.w,null)}this.addWidth(s)}mspacePenalty(t){const e=t.node.attributes.get("linebreak"),s=this.FACTORS,i=s.space(s.tail(s.width(0)),t);return(this.PENALTY[e]||(t=>t))(s.depth(i))}visitMtextNode(t,e){if(!t.getText().match(/ /))return void this.visitDefault(t,e);const s=t;s.clearBreakPoints();const i=s.textWidth(" "),r=t.getBBox(),[n,o]=this.getBorderLR(t);this.addWidth(r,r.L+n);const a=s.childNodes;for(const e of a.keys()){const n=a[e];if(n.node.isKind("text")){const o=n.node.getText().split(/ /),a=o.pop();for(const n of o.keys())this.addWidth(r,s.textWidth(o[n])),this.pushBreak(t,this.mtextPenalty(),-i,[e,n+1]),this.addWidth(r,i);this.addWidth(r,s.textWidth(a))}else this.addWidth(n.getBBox())}this.addWidth(r,r.R+o)}mtextPenalty(){const t=this.FACTORS;return t.depth(t.tail(t.width(0)))}visitMrowNode(t,e){const s=t.lineBBox[e]||t.getLineBBox(e),[i,r]=s.start||[0,0],[n,o]=s.end||[t.childNodes.length-1,0],[a,l]=this.getBorderLR(t);this.addWidth(s,s.L+a);for(let e=i;e<=n;e++)this.visitNode(t.childNodes[e],e===i?r:e===n?o:0);this.addWidth(s,s.R+l)}visitInferredMrowNode(t,e){this.state.depth--,this.visitMrowNode(t,e),this.state.depth++}visitMfracNode(t,e){const s=t;!s.node.attributes.get("bevelled")&&s.getOuterBBox().w>this.state.width&&(this.breakToWidth(s.childNodes[0],this.state.width),this.breakToWidth(s.childNodes[1],this.state.width)),this.visitDefault(t,e)}visitMsqrtNode(t,e){if(t.getOuterBBox().w>this.state.width){const e=t,s=e.childNodes[e.base];this.breakToWidth(s,this.state.width-e.rootWidth()),e.getStretchedSurd()}this.visitDefault(t,e)}visitMrootNode(t,e){this.visitMsqrtNode(t,e)}visitMsubNode(t,e){this.visitDefault(t,e);const s=t,i=s.getOffset()[0],r=s.scriptChild.getOuterBBox(),[n,o]=this.getBorderLR(t);this.addWidth(s.getLineBBox(e),i+n+r.rscale*r.w+s.font.params.scriptspace+o)}visitMsupNode(t,e){this.visitDefault(t,e);const s=t,i=s.getOffset()[0],r=s.scriptChild.getOuterBBox(),[n,o]=this.getBorderLR(t);this.addWidth(s.getLineBBox(e),i+n+r.rscale*r.w+s.font.params.scriptspace+o)}visitMsubsupNode(t,e){this.visitDefault(t,e);const s=t,i=s.subChild.getOuterBBox(),r=s.supChild.getOuterBBox(),n=s.getAdjustedIc(),o=Math.max(i.rscale*i.w,n+r.rscale*r.w)+s.font.params.scriptspace,[a,l]=this.getBorderLR(t);this.addWidth(t.getLineBBox(e),a+o+l)}visitMmultiscriptsNode(t,e){const s=t,i=s.scriptData;if(i.numPrescripts){const r=Math.max(i.psup.rscale*i.psup.w,i.psub.rscale*i.psub.w);this.addWidth(t.getLineBBox(e),r+s.font.params.scriptspace)}if(this.visitDefault(t,e),i.numScripts){const r=Math.max(i.sup.rscale*i.sup.w,i.sub.rscale*i.sub.w);this.addWidth(t.getLineBBox(e),r+s.font.params.scriptspace)}}visitMfencedNode(t,e){const s=t,i=t.getLineBBox(e),[r,n]=this.getBorderLR(t);0===e&&this.addWidth(i,i.L+r),this.visitNode(s.mrow,e),e===t.breakCount&&this.addWidth(i,i.R+n)}visitMactionNode(t,e){const s=t,i=t.getLineBBox(e),[r,n]=this.getBorderLR(t);0===e&&this.addWidth(i,i.L+r),this.visitNode(s.selected,e),e===t.breakCount&&this.addWidth(i,i.R+n)}}!function(){for(const t of Object.keys(Dr.postfix)){const e=Dr.postfix[t][3];e&&e.fence&&(e.linebreakstyle="after")}Dr.infix["\u2061"]=[...Dr.infix["\u2061"]],Dr.infix["\u2061"][3]={linebreak:"nobreak"}}();const jc="@mathjax/%%FONT%%-font";class Uc extends Zi{get forceInlineBreaks(){return!1}constructor(t={},e=null,s=null){const[i,r]=t.fontData instanceof Oc?[t.fontData.constructor,t.fontData]:[t.fontData||s,null],[n,o]=ji(t,i.OPTIONS);super(n),this.factory=this.options.wrapperFactory||new e,this.factory.jax=this,this.styleJson=this.options.styleJson||new oo,this.font=r||new i(o),this.font.setOptions({mathmlSpacing:this.options.mathmlSpacing}),this.constructor.genericFont=i,this.unknownCache=new Map;const a=this.options.linebreaks.LinebreakVisitor||Fc;this.linebreaks=new a(this.factory)}setAdaptor(t){super.setAdaptor(t),"auto"===this.options.htmlHDW&&(this.options.htmlHDW=t.canMeasureNodes?"ignore":"force")}addExtension(t,e=""){return this.font.addExtension(t,e)}typeset(t,e){const s=this.constructor,i=s.genericFont;s.genericFont=this.font.constructor,this.setDocument(e);const r=this.createNode();try{this.toDOM(t,r,e)}finally{s.genericFont=i}return r}createNode(){const t=this.constructor.NAME;return this.html("mjx-container",{class:"MathJax",jax:t})}setScale(t,e){let s=this.getInitialScale()*this.options.scale;if("scale"===e.node.attributes.get("overflow")&&this.math.display){const t=e.getOuterBBox().w,i=Math.max(0,this.math.metrics.containerWidth-4)/this.pxPerEm;t>i&&t&&(s*=i/t)}1!==s&&this.adaptor.setStyle(t,"fontSize",Eo(s))}getInitialScale(){return this.math.metrics.scale}toDOM(t,e,s=null){var i;this.setDocument(s),this.math=t,this.container=e,this.pxPerEm=t.metrics.ex/this.font.params.x_height,this.executeFilters(this.preFilters,t,s,e),this.nodeMap=new Map,t.root.attributes.getAllInherited().overflow=this.options.displayOverflow;const r=t.root.attributes.get("overflow");this.adaptor.setAttribute(e,"overflow",r);"linebreak"===r&&this.getLinebreakWidth();const n=this.options.linebreaks.inline&&!t.display;let o=!!t.root.getProperty("inlineMarked");!o||n&&this.forceInlineBreaks===t.root.getProperty("inlineForced")||(this.unmarkInlineBreaks(t.root),t.root.removeProperty("inlineMarked"),t.root.removeProperty("inlineForced"),o=!1),n&&!o&&(this.markInlineBreaks(null===(i=t.root.childNodes)||void 0===i?void 0:i[0]),t.root.setProperty("inlineMarked",!0),t.root.setProperty("inlineForced",this.forceInlineBreaks)),t.root.setTeXclass(null);const a=this.factory.wrap(t.root);this.setScale(e,a),this.processMath(a,e),this.nodeMap=null,this.executeFilters(this.postFilters,t,s,e)}getBBox(t,e){this.setDocument(e),this.math=t,t.root.setTeXclass(null),this.nodeMap=new Map;const s=this.factory.wrap(t.root).getOuterBBox();return this.nodeMap=null,s}getLinebreakWidth(){const t=this.math.metrics.containerWidth/this.pxPerEm,e=this.math.root.attributes.get("maxwidth")||this.options.linebreaks.width;this.containerWidth=bo(e,t,1,this.pxPerEm)}markInlineBreaks(t){if(!t)return;const e=this.forceInlineBreaks;let s=!1,i=!1,r="";for(const n of t.childNodes)if(r)i=this.markInlineBreak(i,e,r,t,n),r="",s=!1;else if(n.isEmbellished){if(n===t.childNodes[0])continue;const o=n.coreMO(),a=o.texClass,l=o.attributes.get("linebreak"),c=o.attributes.get("linebreakstyle");(a===mr.BIN||a===mr.REL||a===mr.ORD&&o.hasSpacingAttributes()||"auto"!==l)&&"nobreak"!==l&&("before"===c?s&&"auto"===l||(i=this.markInlineBreak(i,e,l,t,n,o)):r=l),s="newline"===l&&"after"===c}else if(n.isKind("mspace")){const r=n.attributes.get("linebreak");"nobreak"!==r&&n.canBreak&&(i=this.markInlineBreak(i,e,r,t,n)),s="newline"===r}else s=!1,n.isKind("mstyle")&&!n.attributes.get("style")&&!n.attributes.hasExplicit("mathbackground")||n.isKind("semantics")?(this.markInlineBreaks(n.childNodes[0]),n.getProperty("process-breaks")&&(n.setProperty("inline-breaks",!0),n.childNodes[0].setProperty("inline-breaks",!0),t.parent.setProperty("process-breaks","true"))):n.isKind("mrow")&&n.attributes.get("data-semantic-added")&&(this.markInlineBreaks(n),n.getProperty("process-breaks")&&(n.setProperty("inline-breaks",!0),t.parent.setProperty("process-breaks","true")))}markInlineBreak(t,e,s,i,r,n=null){return r.setProperty("breakable",!0),e&&"newline"!==s?(r.setProperty("forcebreak",!0),null==n||n.setProperty("forcebreak",!0)):(r.removeProperty("forcebreak"),null==n||n.removeProperty("forcebreak"),"newline"===s&&r.setProperty("newline",!0)),t||(i.setProperty("process-breaks",!0),i.parent.setProperty("process-breaks",!0),t=!0),t}unmarkInlineBreaks(t){if(t&&(t.removeProperty("forcebreak"),t.removeProperty("breakable"),t.coreMO().removeProperty("forcebreak"),t.getProperty("process-breaks"))){t.removeProperty("process-breaks");for(const e of t.childNodes)this.unmarkInlineBreaks(e)}}getMetrics(t){this.setDocument(t);const e=this.adaptor,s=this.getMetricMaps(t);for(const i of t.math){const t=e.parent(i.start.node);if(i.state(){const s=this.wrap(t);return s.bbox.pwidth&&(e.notParent||e.isKind("math"))&&(this.bbox.pwidth=No.fullWidth),s})}wrap(t,e=null){const s=this.factory.wrap(t,e||this);return e&&e.childNodes.push(s),this.jax.nodeMap.set(t,s),s}getBBox(t=!0){if(this.bboxComputed)return this.bbox;const e=t?this.bbox:No.zero();return this.computeBBox(e),this.bboxComputed=t,e}getOuterBBox(t=!0){var e;const s=this.getBBox(t);if(!this.styleData)return s;const i=this.styleData.padding,r=(null===(e=this.styleData.border)||void 0===e?void 0:e.width)||[0,0,0,0],n=s.copy();for(const[,t,e]of No.boxSides)n[e]+=i[t]+r[t];return n}getUnbrokenHD(){const t=this.breakCount+1;let e=0,s=0;for(let i=0;ie&&(e=t),r>s&&(s=r)}return[e,s]}computeBBox(t,e=!1){t.empty();for(const e of this.childNodes)t.append(e.getOuterBBox());t.clean(),this.fixesPWidth&&this.setChildPWidths(e)&&this.computeBBox(t,!0)}getLineBBox(t){if(!this.lineBBox[t]){const e=this.breakCount;if(e){const s=this.embellishedBBox(t)||this.computeLineBBox(t);this.lineBBox[t]=s,0===t&&(!this.node.isKind("mo")&&this.node.isEmbellished?s.originalL=this.getBBox().L:s.L=this.getBBox().L),t===e&&(s.R=this.getBBox().R)}else{const e=this.getOuterBBox();this.lineBBox[t]=Dc.from(e,this.linebreakOptions.lineleading)}}return this.lineBBox[t]}embellishedBBox(t){if(!this.node.isEmbellished||this.node.isKind("mo"))return null;const e=this.coreMO();return e.moLineBBox(t,e.embellishedBreakStyle,this.getOuterBBox())}computeLineBBox(t){return this.getChildLineBBox(this.childNodes[0],t)}getBreakNode(t){var e,s;if(!t.start)return[this,null];const[i,r]=t.start;if(this.node.isEmbellished)return[this,this.coreMO()];const n=(null===(s=null===(e=this.childNodes[0])||void 0===e?void 0:e.node)||void 0===s?void 0:s.isInferred)||this.node.isKind("semantics")?this.childNodes[0].childNodes:this.childNodes;return this.node.isToken||!n[i]?[this,null]:n[i].getBreakNode(n[i].getLineBBox(r))}getChildLineBBox(t,e){const s=this.breakCount;let i=t.getLineBBox(e);return(this.styleData||this.bbox.L||this.bbox.R)&&(i=i.copy()),this.addMiddleBorders(i),0===e?(i.L+=this.bbox.L,this.addLeftBorders(i)):e===s&&(i.R+=this.bbox.R,this.addRightBorders(i)),i}addLeftBorders(t){var e;if(!this.styleData)return;const s=this.styleData.border,i=this.styleData.padding;t.w+=((null===(e=null==s?void 0:s.width)||void 0===e?void 0:e[3])||0)+((null==i?void 0:i[3])||0)}addMiddleBorders(t){var e,s;if(!this.styleData)return;const i=this.styleData.border,r=this.styleData.padding;t.h+=((null===(e=null==i?void 0:i.width)||void 0===e?void 0:e[0])||0)+((null==r?void 0:r[0])||0),t.d+=((null===(s=null==i?void 0:i.width)||void 0===s?void 0:s[2])||0)+((null==r?void 0:r[2])||0)}addRightBorders(t){var e;if(!this.styleData)return;const s=this.styleData.border,i=this.styleData.padding;t.w+=((null===(e=null==s?void 0:s.width)||void 0===e?void 0:e[1])||0)+((null==i?void 0:i[1])||0)}setChildPWidths(t,e=null,s=!0){if(t)return!1;s&&(this.bbox.pwidth="");let i=!1;for(const r of this.childNodes){const n=r.getBBox();n.pwidth&&r.setChildPWidths(t,null===e?n.w:e,s)&&(i=!0)}return i}breakToWidth(t){}invalidateBBox(t=!0){(this.bboxComputed||this._breakCount>=0)&&(this.bboxComputed=!1,this.lineBBox=[],this._breakCount=-1,this.parent&&t&&this.parent.invalidateBBox())}copySkewIC(t){var e,s,i;const r=this.childNodes[0];(null===(e=null==r?void 0:r.bbox)||void 0===e?void 0:e.sk)&&(t.sk=r.bbox.sk),(null===(s=null==r?void 0:r.bbox)||void 0===s?void 0:s.dx)&&(t.dx=r.bbox.dx);const n=this.childNodes[this.childNodes.length-1];(null===(i=null==n?void 0:n.bbox)||void 0===i?void 0:i.ic)&&(t.ic=n.bbox.ic,t.w+=t.ic)}getStyles(){const t=this.node.attributes.getExplicit("style");if(!t)return;const e=this.styles=new Wo(t);for(let t=0,s=Xc.removeStyles.length;t600?"bold":"normal"),s.family?e=this.explicitVariant(s.family,s.weight,s.style):(this.node.getProperty("variantForm")&&(e="-tex-variant"),e=(Xc.BOLDVARIANTS[s.weight]||{})[e]||e,e=(Xc.ITALICVARIANTS[s.style]||{})[e]||e)}this.variant=e}explicitVariant(t,e,s){let i=this.styles;return i||(i=this.styles=new Wo),i.set("fontFamily",t),e&&i.set("fontWeight",e),s&&i.set("fontStyle",s),"-explicitFont"}getScale(){let t=1;const e=this.parent,s=e?e.bbox.scale:1,i=this.node.attributes,r=Math.min(i.get("scriptlevel"),2);let n=i.get("fontsize"),o=this.node.isToken||this.node.isKind("mstyle")?i.get("mathsize"):i.getInherited("mathsize");if(0!==r&&(t=Math.pow(i.get("scriptsizemultiplier"),r)),this.removedStyles&&this.removedStyles.fontSize&&!n&&(n=this.removedStyles.fontSize),n&&!i.hasExplicit("mathsize")&&(o=n),"1"!==o&&(t*=this.length2em(o,1,1)),0!==r){const e=this.length2em(i.get("scriptminsize"),.4,1);t0;if(this.bbox.L=n.isSet("lspace")?Math.max(0,this.length2em(n.get("lspace"))):zc(o,r,t.lspace),this.bbox.R=n.isSet("rspace")?Math.max(0,this.length2em(n.get("rspace"))):zc(o,r,t.rspace),!i)return;const a=s.childNodes[i-1];if(!a.isEmbellished)return;const l=this.jax.nodeMap.get(a).getBBox();l.R&&(this.bbox.L=Math.max(0,this.bbox.L-l.R))}getTeXSpacing(t,e){if(!e){const t=this.node.texSpacing();t&&(this.bbox.L=this.length2em(t))}if(t||e){const t=this.node.coreMO().attributes;t.isSet("lspace")&&(this.bbox.L=Math.max(0,this.length2em(t.get("lspace")))),t.isSet("rspace")&&(this.bbox.R=Math.max(0,this.length2em(t.get("rspace"))))}}isTopEmbellished(){return this.node.isEmbellished&&!(this.node.parent&&this.node.parent.isEmbellished)}core(){return this.jax.nodeMap.get(this.node.core())}coreMO(){return this.jax.nodeMap.get(this.node.coreMO())}coreRScale(){let t=this.bbox.rscale,e=this.coreMO();for(;e!==this&&e;)t*=e.bbox.rscale,e=e.parent;return t}getRScale(){let t=1,e=this;for(;e;)t*=e.bbox.rscale,e=e.parent;return t}getText(){let t="";if(this.node.isToken)for(const e of this.node.childNodes)e instanceof Cr&&(t+=e.getText());return t}canStretch(t){if(this.stretch=Mc,this.node.isEmbellished){const e=this.core();e&&e.node!==this.node&&e.canStretch(t)&&(this.stretch=e.stretch)}return this.stretch.dir!==Lc.None}getAlignShift(){let{indentalign:t,indentshift:e,indentalignfirst:s,indentshiftfirst:i}=this.node.attributes.getAllAttributes();return"indentalign"!==s&&(t=s),"indentshift"!==i&&(e=i),this.processIndent(t,e)}processIndent(t,e,s="",i="",r=this.metrics.containerWidth){if(!this.jax.math.display)return["left",0];s&&"auto"!==s||(s=this.jax.math.root.getProperty("inlineMarked")?"left":this.jax.options.displayAlign),i&&"auto"!==i||(i=this.jax.math.root.getProperty("inlineMarked")?"0":this.jax.options.displayIndent),"auto"===t&&(t=s),"auto"===e&&(e=i,"right"!==t||e.match(/^\s*0[a-z]*\s*$/)||(e=("-"+e.trim()).replace(/^--/,"")));return[t,this.length2em(e,r)]}getAlignX(t,e,s){return"right"===s?t-(e.w+e.R)*e.rscale:"left"===s?e.L*e.rscale:(t-e.w*e.rscale)/2}getAlignY(t,e,s,i,r){return"top"===r?t-s:"bottom"===r?i-e:"center"===r?(t-s-(e-i))/2:0}getWrapWidth(t){return this.childNodes[t].getBBox().w}getChildAlign(t){return"left"}percent(t){return Eo(t)}em(t){return xo(t)}px(t,e=-po){return yo(t,e,this.metrics.em)}length2em(t,e=1,s=null){null===s&&(s=this.bbox.scale);const i=this.font.params.rule_thickness,r=Ui(t,{medium:1,thin:2/3,thick:5/3},0);return r?r*i:bo(t,e,s,this.jax.pxPerEm)}unicodeChars(t,e=this.variant){let s=Fr(t);const i=this.font.getVariant(e);if(i&&i.chars){const t=i.chars;s=s.map(e=>{var s,i;return(null===(i=null===(s=t[e])||void 0===s?void 0:s[3])||void 0===i?void 0:i.smp)||e})}return s}remapChars(t){return t}mmlText(t){return this.node.factory.create("text").setText(t)}mmlNode(t,e={},s=[]){return this.node.factory.create(t,e,s)}createMo(t){const e=this.node.factory,s=e.create("text").setText(t),i=e.create("mo",{stretchy:!0},[s]);i.inheritAttributesFrom(this.node),i.parent=this.node.parent;const r=this.wrap(i);return r.parent=this,r}getVariantChar(t,e){const s=this.font.getChar(t,e)||[0,0,0,{unknown:!0}];return 3===s.length&&(s[3]={}),s}html(t,e={},s=[]){return this.jax.html(t,e,s)}}Xc.kind="unknown",Xc.styles={},Xc.removeStyles=["fontSize","fontFamily","fontWeight","fontStyle","fontVariant","font"],Xc.skipAttributes={fontfamily:!0,fontsize:!0,fontweight:!0,fontstyle:!0,color:!0,background:!0,class:!0,href:!0,style:!0,xmlns:!0},Xc.BOLDVARIANTS={bold:{normal:"bold",italic:"bold-italic",fraktur:"bold-fraktur",script:"bold-script","sans-serif":"bold-sans-serif","sans-serif-italic":"sans-serif-bold-italic"},normal:{bold:"normal","bold-italic":"italic","bold-fraktur":"fraktur","bold-script":"script","bold-sans-serif":"sans-serif","sans-serif-bold-italic":"sans-serif-italic"}},Xc.ITALICVARIANTS={italic:{normal:"italic",bold:"bold-italic","sans-serif":"sans-serif-italic","bold-sans-serif":"sans-serif-bold-italic"},normal:{italic:"normal","bold-italic":"bold","sans-serif-italic":"sans-serif","sans-serif-bold-italic":"bold-sans-serif"}};const Gc={"70.7%":"s","70%":"s","50%":"ss","60%":"Tn","85%":"sm","120%":"lg","144%":"Lg","173%":"LG","207%":"hg","249%":"HG"};class Jc extends Xc{toCHTML(t){this.toEmbellishedCHTML(t)||this.addChildren(this.standardChtmlNodes(t))}toEmbellishedCHTML(t){if(t.length<=1||!this.node.isEmbellished)return!1;const e=this.adaptor;t.forEach(t=>e.append(t,this.html("mjx-linestrut")));const s=this.coreMO().embellishedBreakStyle,i=[];for(const[r,n]of[[t[0],"before"],[t[1],"after"]])s!==n?(this.toCHTML([r]),i.push(this.dom[0]),"after"===n&&e.removeAttribute(this.dom[0],"space")):i.push(this.createChtmlNodes([r])[0]);return this.dom=i,!0}addChildren(t){for(const e of this.childNodes)e.toCHTML(t)}standardChtmlNodes(t){this.markUsed();const e=this.createChtmlNodes(t);return this.handleStyles(),this.handleScale(),this.handleBorders(),this.handleColor(),this.handleSpace(),this.handleAttributes(),this.handlePWidth(),e}markUsed(){this.jax.wrapperUsage.add(this.kind)}createChtmlNodes(t){this.dom=t.map(t=>this.html("mjx-"+this.node.kind)),t=this.handleHref(t);for(const e of t.keys())this.adaptor.append(t[e],this.dom[e]);return this.dom}handleHref(t){const e=this.node.attributes.get("href");return e?t.map(t=>this.adaptor.append(t,this.html("a",{href:e}))):t}handleStyles(){if(!this.styles)return;const t=this.styles.cssText;if(t){const e=this.adaptor;this.dom.forEach(s=>e.setAttribute(s,"style",t));const s=this.styles.get("font-family");s&&this.dom.forEach(t=>e.setStyle(t,"font-family",this.font.cssFamilyPrefix+", "+s))}}handleScale(){this.dom.forEach(t=>this.setScale(t,this.bbox.rscale))}setScale(t,e){const s=Math.abs(e-1)<.001?1:e;if(t&&1!==s){const e=this.percent(s);Gc[e]?this.adaptor.setAttribute(t,"size",Gc[e]):this.adaptor.setStyle(t,"fontSize",e)}return t}handleSpace(){const t=this.adaptor,e=!!this.node.getProperty("breakable")&&!this.node.getProperty("newline"),s=this.dom.length-1;for(const i of[[this.getLineBBox(0).L,"space","marginLeft",0],[this.getLineBBox(s).R,"rspace","marginRight",s]]){const[s,r,n,o]=i,a=this.em(s);if(e&&"space"===r){const e=t.node("mjx-break",Vc[a]?{size:Vc[a]}:{style:`letter-spacing: ${this.em(s-1)}`},[t.text(" ")]);t.insert(e,this.dom[o])}else s&&(Vc[a]?t.setAttribute(this.dom[o],r,Vc[a]):t.setStyle(this.dom[o],n,a))}}handleBorders(){var t,e;const s=null===(t=this.styleData)||void 0===t?void 0:t.border,i=null===(e=this.styleData)||void 0===e?void 0:e.padding,r=this.dom.length-1;if(!s||!r)return;const n=this.adaptor;for(const t of this.dom.keys()){const e=this.dom[t];t&&(s.width[3]&&n.setStyle(e,"border-left"," none"),i[3]&&n.setStyle(e,"padding-left","0")),t!==r&&(s.width[1]&&n.setStyle(e,"border-right","none"),i[1]&&n.setStyle(e,"padding-right","0"))}}handleColor(){var t;const e=this.adaptor,s=this.node.attributes,i=s.getExplicit("mathcolor")||s.getExplicit("color"),r=s.getExplicit("mathbackground")||s.getExplicit("background")||(null===(t=this.styles)||void 0===t?void 0:t.get("background-color"));i&&this.dom.forEach(t=>e.setStyle(t,"color",i)),r&&this.dom.forEach(t=>e.setStyle(t,"backgroundColor",r))}handleAttributes(){const t=this.adaptor,e=this.node.attributes,s=e.getAllDefaults(),i=Jc.skipAttributes;for(const r of e.getExplicitNames())if(!1===i[r]||!(r in s)&&!i[r]&&!t.hasAttribute(this.dom[0],r)){const s=e.getExplicit(r);this.dom.forEach(e=>t.setAttribute(e,r,s))}if(e.get("class")){const s=e.get("class").trim().split(/ +/);for(const e of s)this.dom.forEach(s=>t.addClass(s,e))}this.node.getProperty("inline-breaks")&&this.dom.forEach(e=>t.setAttribute(e,"inline-breaks","true"))}handlePWidth(){if(this.bbox.pwidth){const t=this.adaptor;this.bbox.pwidth===No.fullWidth?this.dom.forEach(e=>t.setAttribute(e,"width","full")):this.dom.forEach(e=>t.setStyle(e,"width",this.bbox.pwidth))}}setIndent(t,e,s){const i=this.adaptor;if("center"===e||"left"===e){const e=this.getBBox().L;s+e&&i.setStyle(t,"margin-left",this.em(s+e))}if("center"===e||"right"===e){const e=this.getBBox().R;s+e&&i.setStyle(t,"margin-right",this.em(-s+e))}}drawBBox(){const{w:t,h:e,d:s,R:i}=this.getOuterBBox(),r=this.html("mjx-box",{style:{opacity:.25,"margin-left":this.em(-t-i)}},[this.html("mjx-box",{style:{height:this.em(e),width:this.em(t),"background-color":"red"}}),this.html("mjx-box",{style:{height:this.em(s),width:this.em(t),"margin-left":this.em(-t),"vertical-align":this.em(-s),"background-color":"green"}})]),n=this.dom[0]||this.parent.dom[0],o=this.adaptor.getAttribute(n,"size");o&&this.adaptor.setAttribute(r,"size",o);const a=this.adaptor.getStyle(n,"fontSize");a&&this.adaptor.setStyle(r,"fontSize",a),this.adaptor.append(this.adaptor.parent(n),r),this.adaptor.setStyle(n,"backgroundColor","#FFEE00")}html(t,e={},s=[]){return this.jax.html(t,e,s)}text(t){return this.jax.text(t)}char(t){return this.font.charSelector(t).substring(1)}}function Kc(t){return class extends t{getWrapWidth(t){return this.parent?this.getBBox().w:this.metrics.containerWidth/this.jax.pxPerEm}computeBBox(t,e=!1){super.computeBBox(t,e);const s=this.node.attributes;if(!this.parent&&this.jax.math.display&&"linebreak"===s.get("overflow")){const e=this.containerWidth;t.w>e&&this.childNodes[0].breakToWidth(e),t.updateFrom(this.childNodes[0].getBBox())}}}}Jc.kind="unknown",Jc.autoStyle=!0;const $c=function(){var t;const e=Kc(Jc);return(t=class extends e{handleDisplay(t){const e=this.adaptor,[s,i]=this.getAlignShift();if("center"!==s&&e.setAttribute(t,"justify",s),this.bbox.pwidth===No.fullWidth){if(e.setAttribute(t,"width","full"),this.jax.table){let{L:r,w:n,R:o}=this.jax.table.getOuterBBox();"right"===s?o=Math.max(o||-i,-i):"left"===s?r=Math.max(r||i,i):"center"===s&&(n+=2*Math.abs(i));const a=this.em(Math.max(0,r+n+o));e.setStyle(t,"min-width",a),e.setStyle(this.jax.table.dom[0],"min-width",a)}}else this.setIndent(this.dom[0],s,i)}handleInline(t){const e=this.adaptor,s=e.getStyle(this.dom[0],"margin-right");s&&(e.setStyle(this.dom[0],"margin-right",""),e.setStyle(t,"margin-right",s),e.setStyle(t,"width","0"))}toCHTML(t){super.toCHTML(t);const e=this.adaptor;"block"===this.node.attributes.get("display")?(e.setAttribute(this.dom[0],"display","true"),e.setAttribute(t[0],"display","true"),this.handleDisplay(t[0])):this.handleInline(t[0]),e.addClass(this.dom[0],`${this.font.cssFontPrefix}-N`)}setChildPWidths(t,e=null,s=!0){return!!this.parent&&super.setChildPWidths(t,e,s)}handleAttributes(){super.handleAttributes();const t=this.adaptor;this.node.getProperty("process-breaks")&&this.dom.forEach(e=>t.setAttribute(e,"breakable","true"))}}).kind=_r.prototype.kind,t.styles={"mjx-math":{"line-height":0,"text-align":"left","text-indent":0,"font-style":"normal","font-weight":"normal","font-size":"100%","font-size-adjust":"none","letter-spacing":"normal","word-wrap":"normal","word-spacing":"normal",direction:"ltr",padding:"1px 0"},'mjx-container[jax="CHTML"][display="true"] mjx-math':{padding:0},"mjx-math[breakable]":{display:"inline"},'mjx-container[jax="CHTML"] mjx-break':{"white-space":"normal","line-height":"0","clip-path":"rect(0 0 0 0)","font-family":"MJX-BRK !important"},'mjx-break[size="0"]':{"letter-spacing":"-0.999em"},'mjx-break[size="1"]':{"letter-spacing":"-0.889em"},'mjx-break[size="2"]':{"letter-spacing":"-0.833em"},'mjx-break[size="3"]':{"letter-spacing":"-0.778em"},'mjx-break[size="4"]':{"letter-spacing":"-0.722em"},'mjx-break[size="5"]':{"letter-spacing":"-0.667em"}},t}();function Yc(t){return class extends t{computeBBox(t,e=!1){super.computeBBox(t),this.copySkewIC(t)}}}const Qc=function(){var t;const e=Yc(Jc);return(t=class extends e{}).kind=Lr.prototype.kind,t}();function Zc(t){return class extends t{get breakCount(){return this.breakStyle?1:0}get embellishedBreakCount(){return this.embellishedBreakStyle?1:0}get embellishedBreakStyle(){return this.breakStyle||this.getBreakStyle()}protoBBox(t){const e=this.stretch.dir!==Lc.None;e&&null===this.size&&this.getStretchedVariant([0]),e&&this.size<0||(super.computeBBox(t),0!==t.w||!this.node.attributes.hasExplicit("fence")||""!==this.node.getText()||this.node.texClass!==mr.OPEN&&this.node.texClass!==mr.CLOSE||this.jax.options.mathmlSpacing||(t.R=this.font.params.nulldelimiterspace),this.copySkewIC(t))}getAccentOffset(){const t=No.empty();return this.protoBBox(t),-t.w/2}getCenterOffset(t=null){return t||(t=No.empty(),super.computeBBox(t)),(t.h+t.d)/2+this.font.params.axis_height-t.h}getStretchedVariant(t,e=!1){if(this.stretch.dir===Lc.None)return;let s=this.getWH(t);const i=this.getSize("minsize",0),r=this.getSize("maxsize",1/0),n=this.node.getProperty("mathaccent");s=Math.max(i,Math.min(r,s));const o=this.font.params.delimiterfactor/1e3,a=this.font.params.delimitershortfall,l=i||e?s:n?Math.min(s/o,s+a):Math.max(s*o,s-a),c=this.getText().codePointAt(0);let h=this.stretch;this.size&&(this.stretch=h=this.font.getDelimiter(c),this.size=null);const d=h.c||c;let u=0;if(h.sizes)for(const t of h.sizes){if(t>=l)return n&&u&&u--,void this.setDelimSize(d,u);u++}h.stretch?(this.size=-1,this.invalidateBBox(),this.getStretchBBox(t,this.checkExtendedHeight(s,h),h)):this.setDelimSize(d,u-1)}setDelimSize(t,e){const s=this.stretch;this.variant=this.font.getSizeVariant(t,e),this.size=e;const i=s.schar&&s.schar[Math.min(e,s.schar.length-1)]||t;this.stretch=Object.assign(Object.assign({},s),{c:i}),this.childNodes[0].invalidateBBox()}getSize(t,e){const s=this.node.attributes;return s.isSet(t)&&(e=this.length2em(s.get(t),1,1)),e}getWH(t){if(0===t.length)return 0;if(1===t.length)return t[0];const[e,s]=t,i=this.font.params.axis_height;return this.node.attributes.get("symmetric")?2*Math.max(e-i,s+i):e+s}getStretchBBox(t,e,s){Object.hasOwn(s,"min")&&s.min>e&&(e=s.min);let[i,r,n]=s.HDW;if(this.stretch.dir===Lc.Vertical)[i,r]=this.getBaseline(t,e,s);else if(n=e,this.stretch.hd&&!this.jax.options.mathmlSpacing){const t=this.font.params.extender_factor;i=i*(1-t)+this.stretch.hd[0]*t,r=r*(1-t)+this.stretch.hd[1]*t}this.bbox.h=i,this.bbox.d=r,this.bbox.w=n}getBaseline(t,e,s){const i=2===t.length&&t[0]+t[1]===e,r=this.node.attributes.get("symmetric"),[n,o]=i?t:[e,0];let[a,l]=[n+o,0];if(r){const t=this.font.params.axis_height;i&&(a=2*Math.max(n-t,o+t)),l=a/2-t}else if(i)l=o;else{const[t,e]=s.HDW||[.75,.25];l=e*(a/(t+e))}return[a-l,l]}checkExtendedHeight(t,e){if(e.fullExt){const[s,i]=e.fullExt;t=i+Math.ceil(Math.max(0,t-i)/s)*s}return t}setBreakStyle(t=""){var e;if(this.breakStyle=(null===(e=this.node.parent)||void 0===e?void 0:e.isEmbellished)&&!t?"":this.getBreakStyle(t),this.breakCount&&this.multChar){const t=this.parent.node.childIndex(this.node),e=this.parent.node.childNodes[t+1];e&&e.setTeXclass(this.multChar.node)}}getBreakStyle(t=""){const e=this.node.attributes;let s=t||("newline"===e.get("linebreak")||this.node.getProperty("forcebreak")?e.get("linebreakstyle"):"");return"infixlinebreakstyle"===s&&(s=e.get(s)),s}getMultChar(){const t=this.node.attributes.get("linebreakmultchar");t&&"\u2062"===this.getText()&&"\u2062"!==t&&(this.multChar=this.createMo(t))}constructor(t,e,s=null){super(t,e,s),this.size=null,this.isAccent=this.node.isAccent,this.getMultChar(),this.setBreakStyle()}computeBBox(t,e=!1){if(this.protoBBox(t),this.node.attributes.get("symmetric")&&this.stretch.dir!==Lc.Horizontal){const e=this.getCenterOffset(t);t.h+=e,t.d-=e}this.node.getProperty("mathaccent")&&(this.stretch.dir===Lc.None||this.size>=0)&&(t.w=0)}computeLineBBox(t){return this.moLineBBox(t,this.breakStyle)}moLineBBox(t,e,s=null){const i=this.node.attributes.get("lineleading"),r=this.length2em(i,this.linebreakOptions.lineleading);if(0===t&&"before"===e){const t=Dc.from(No.zero(),r);return t.originalL=this.bbox.L,this.bbox.L=0,t}let n=Dc.from(s||this.getOuterBBox(),r);return 1===t&&("after"===e?(n.w=n.h=n.d=0,n.isFirst=!0,this.bbox.R=0):"duplicate"===e?n.L=0:this.multChar&&(n=Dc.from(this.multChar.getOuterBBox(),r)),n.getIndentData(this.node)),n}canStretch(t){if(this.stretch.dir!==Lc.None)return this.stretch.dir===t;if(!this.node.attributes.get("stretchy"))return!1;const e=this.getText();if(1!==Array.from(e).length)return!1;const s=this.font.getDelimiter(e.codePointAt(0));return this.stretch=s&&s.dir===t?s:Mc,this.stretch.dir!==Lc.None}getVariant(){this.node.attributes.get("largeop")?this.variant=this.node.attributes.get("displaystyle")?"-largeop":"-smallop":this.node.attributes.hasExplicit("mathvariant")||!1!==this.node.getProperty("pseudoscript")?super.getVariant():this.variant="-tex-variant"}remapChars(t){const e=this.node.getProperty("primes");if(e)return Fr(e);if(1===t.length){const e=this.node.coreParent().parent,s=this.isAccent&&!e.isKind("mrow")?"accent":"mo",i=this.font.getRemappedChar(s,t[0]);i&&(t=this.unicodeChars(i,this.variant))}return t}}}class th{constructor(){this.used=new Set,this.needsUpdate=[]}add(t){const e=JSON.stringify(t);this.used.has(e)||this.needsUpdate.push(t),this.used.add(e)}has(t){return this.used.has(JSON.stringify(t))}clear(){this.used.clear(),this.needsUpdate=[]}update(){const t=this.needsUpdate;return this.needsUpdate=[],t}}class eh extends Oc{constructor(){super(...arguments),this.charUsage=new th,this.delimUsage=new th,this.fontUsage={},this.newFonts=0}static charOptions(t,e){return super.charOptions(t,e)}static addFontURLs(t,e,s){for(const i of Object.keys(e)){const r=Object.assign({},e[i]);r.src=r.src.replace(/%%URL%%/,s),t[i]=r}}static addDynamicFontCss(t,e,s){const i={};for(const s of e){const e=s.slice(4);i[`@font-face /* ${e} */`]={"font-family":s,src:`url("%%URL%%/${s.toLowerCase()}.woff2") format("woff2")`},t[`.${e}`]={"font-family":`${this.defaultCssFamilyPrefix}, ${s}`}}this.addFontURLs(t,i,s)}static addExtension(t,e=""){super.addExtension(t,e),t.fonts&&this.addDynamicFontCss(this.defaultStyles,t.fonts,t.fontURL)}addExtension(t,e=""){if(super.addExtension(t,e),!t.fonts||!this.options.adaptiveCSS)return[];const s={},i=new oo;return this.constructor.addDynamicFontCss(s,t.fonts,t.fontURL),i.addStyles(s),i.getStyleRules()}adaptiveCSS(t){this.options.adaptiveCSS=t}clearCache(){this.options.adaptiveCSS&&(this.charUsage.clear(),this.delimUsage.clear())}createVariant(t,e=null,s=null){super.createVariant(t,e,s),this.variant[t].letter=this.constructor.defaultVariantLetters[t]}defineChars(t,e){super.defineChars(t,e);const s=this.variant[t].letter,i=this.constructor;for(const t of Object.keys(e)){const r=parseInt(t);if(!Array.isArray(e[r]))continue;const n=i.charOptions(e,r);void 0===n.f&&(n.f=s);for(const[t,e]of i.combiningChars)if(r>=t&&r<=e){n.cmb=!0;break}}}addDynamicFontCss(t,e=this.options.fontURL){this.constructor.addDynamicFontCss(this.fontUsage,t,e)}updateDynamicStyles(){const t=this.fontUsage;return this.fontUsage={},this.options.adaptiveCSS||this.updateStyles(t),t}get styles(){const t=this.constructor,e=Object.assign(Object.assign({},t.defaultStyles),this.fontUsage);return this.fontUsage={},t.addFontURLs(e,t.defaultFonts,this.options.fontURL),this.options.adaptiveCSS?this.updateStyles(e):this.allStyles(e),e}updateStyles(t){for(const e of this.delimUsage.update())this.addDelimiterStyles(t,e,this.getDelimiter(e));for(const[e,s]of this.charUsage.update()){const i=this.variant[e];this.addCharStyles(t,i.letter,s,i.chars[s])}return t}allStyles(t){var e;for(const e of Object.keys(this.delimiters)){const s=parseInt(e);this.addDelimiterStyles(t,s,this.delimiters[s])}for(const s of Object.keys(this.variant)){const i=this.variant[s],r=i.letter;for(const s of Object.keys(i.chars)){const n=parseInt(s),o=i.chars[n];!(null===(e=null==o?void 0:o[3])||void 0===e?void 0:e.smp)&&Array.isArray(o)&&(o.length<4&&(o[3]={}),this.addCharStyles(t,r,n,o))}}}addDelimiterStyles(t,e,s){if(!s.stretch)return;const i=s.c&&s.c!==e?this.charSelector(s.c):this.charSelector(e);s.dir===Lc.Vertical?this.addDelimiterVStyles(t,e,i,s):this.addDelimiterHStyles(t,e,i,s)}addDelimiterVStyles(t,e,s,i){const r=i.HDW,[n,o,a,l]=i.stretch,[c,h,d,u]=this.getStretchVariants(e),p=this.addDelimiterVPart(t,s,"beg",n,c,r);this.addDelimiterVPart(t,s,"ext",o,h,r);const m=this.addDelimiterVPart(t,s,"end",a,d,r);if(l){const e=this.addDelimiterVPart(t,s,"mid",l,u,r),i=this.em(e/2-.03);t[`mjx-stretchy-v${s} > mjx-ext:first-of-type`]={height:"50%","border-width":`${this.em1(p-.03)} 0 ${i}`},t[`mjx-stretchy-v${s} > mjx-ext:last-of-type`]={height:"50%","border-width":`${i} 0 ${this.em1(m-.03)}`}}else(m||p)&&(t[`mjx-stretchy-v${s} > mjx-ext`]["border-width"]=`${this.em1(p-.03)} 0 ${this.em1(m-.03)}`)}addDelimiterVPart(t,e,s,i,r,n){if(!i)return 0;const[o,a,l]=this.getChar(r,i),c={width:this.em0(l)};if("ext"!==s){const t=l>n[2]?this.em((n[2]-l)/2):"auto",e="beg"===s?o:"end"===s?-a:(o-a)/2;c.margin=`${this.em(e)} ${t} ${this.em(-e)}`}else c["line-height"]=this.em0(o+a+.005),t[`mjx-stretchy-v${e} > mjx-${s} > mjx-spacer`]={"margin-top":this.em(-a)};return t[`mjx-stretchy-v${e} > mjx-${s}`]=c,o+a}addDelimiterHStyles(t,e,s,i){const r=[...i.HDW],[n,o,a,l]=i.stretch,[c,h,d,u]=this.getStretchVariants(e);if(i.hd&&!this.options.mathmlSpacing){const t=this.params.extender_factor;r[0]=r[0]*(1-t)+i.hd[0]*t,r[1]=r[1]*(1-t)+i.hd[1]*t}const p=this.addDelimiterHPart(t,s,"beg",n,c,r);this.addDelimiterHPart(t,s,"ext",o,h,r);const m=this.addDelimiterHPart(t,s,"end",a,d,r);if(l){const e=this.addDelimiterHPart(t,s,"mid",l,u,r),i=this.em0(e/2-.03);t[`mjx-stretchy-h${s} > mjx-ext:first-of-type`]={width:"50%","border-width":`0 ${i} 0 ${this.em0(p-.03)}`},t[`mjx-stretchy-h${s} > mjx-ext:last-of-type`]={width:"50%","border-width":`0 ${this.em0(m-.03)} 0 ${i}`}}else(p||m)&&(t[`mjx-stretchy-h${s} > mjx-ext`]["border-width"]=`0 ${this.em0(m-.06)} 0 ${this.em0(p-.06)}`);i.ext&&(t[`mjx-stretchy-h${s} > mjx-ext > mjx-spacer`]["letter-spacing"]=this.em(-i.ext))}addDelimiterHPart(t,e,s,i,r,n){if(!i)return 0;let[,,o,a]=this.getChar(r,i);const l={padding:this.padding(n,o-n[2])};if("ext"===s){const i=l.padding.split(/ /);i[1]=i[3]="0",l.padding=i.join(" "),!o&&a.dx&&(o=2*a.dx-.06),t[`mjx-stretchy-h${e} > mjx-${s} > mjx-spacer`]={"margin-left":this.em(-o/2)},a.cmb&&(t[`mjx-stretchy-h${e} > mjx-${s} > mjx-c`]={width:this.em(o),"text-align":"right"})}else"mid"===s?l.margin=`0 ${this.em(-o/2)}`:l["end"==s?"margin-left":"margin-right"]=this.em(-o),this.checkCombiningChar(a,l);return t[`mjx-stretchy-h${e} > mjx-${s}`]=l,o}addCharStyles(t,e,s,i){const r=i[3],n=void 0!==r.f?r.f:e,o=r.ff||(n?`${this.cssFontPrefix}-${n}`:""),a="mjx-c"+this.charSelector(s)+(o?"."+o:""),l=r.oc||r.ic||0;t[a]={padding:this.padding(i,l)},r.oc&&(t[a+"[noic]"]={"padding-right":this.em(i[2])}),this.checkCombiningChar(r,t[a])}checkCombiningChar(t,e){if(!t.cmb)return;const s=e.padding.split(/ /);e.width=s[1],s[1]="0",s[3]||s.pop(),e.padding=s.join(" "),"0"===e.width&&t.dx&&(e.width=this.em(2*t.dx),e["margin-left"]="-"+e.width)}em(t){return xo(t)}em0(t){return xo(Math.max(0,t))}em1(t){const e=xo(Math.max(0,t));return"0"===e?".1px":e}padding([t,e,s],i=0){return[t,s+i,e,0].map(this.em0).join(" ")}charSelector(t){return".mjx-c"+t.toString(16).toUpperCase()}}function sh(t,e){for(const s of Object.keys(e)){const i=parseInt(s),r=e[i];r.c&&(r.c=r.c.replace(/\\[0-9A-F]+/gi,t=>String.fromCodePoint(parseInt(t.substring(1),16)))),Object.assign(Oc.charOptions(t,i),r)}return t}eh.OPTIONS=Object.assign(Object.assign({},Oc.OPTIONS),{dynamicPrefix:"./chtml/dynamic",fontURL:"./chtml/woff2"}),eh.JAX="CHTML",eh.defaultVariantLetters={},eh.defaultStyles={},eh.defaultFonts={},eh.combiningChars=[[768,879],[8400,8447]];const ih=function(){var t;const e=Zc(Jc);return t=class extends e{toCHTML(t){const e=this.adaptor,s=this.node.attributes,i=s.get("symmetric")&&this.stretch.dir!==Lc.Horizontal,r=this.stretch.dir!==Lc.None;r&&null===this.size&&this.getStretchedVariant([]),t.length>1&&t.forEach(t=>e.append(t,this.html("mjx-linestrut")));const n=this.standardChtmlNodes(t);if(n.length>1&&"duplicate"!==this.breakStyle){const t="after"===this.breakStyle?1:0;e.remove(n[t]),n[t]=null}if(r&&this.size<0)this.stretchHTML(n);else{if(i||s.get("largeop")){const t=this.em(this.getCenterOffset());"0"!==t&&n.forEach(s=>s&&e.setStyle(s,"verticalAlign",t))}this.node.getProperty("mathaccent")&&n.forEach(t=>{e.setStyle(t,"width","0"),e.setStyle(t,"margin-left",this.em(this.getAccentOffset()))}),n[0]&&this.addChildren([n[0]]),n[1]&&(this.multChar||this).addChildren([n[1]])}}stretchHTML(t){const e=this.getText().codePointAt(0);this.font.delimUsage.add(e),this.childNodes[0].markUsed();const s=this.stretch,i=s.stretch,r=this.font.getStretchVariants(e),n=[],o=[];for(let t=0;tt?o?t[0]+t[1]:t[2]:0);l=Math.max(0,l-n);const[d,u]=t[3]?[(r-h)/2-a,(r-h)/2-c]:[r-a-c,0];this.createPart("mjx-beg",t[0],e[0],s[0],i),this.createPart("mjx-ext",t[1],e[1],s[1],i,d,l,o),t[3]&&(this.createPart("mjx-mid",t[3],e[3],s[3],i),this.createPart("mjx-ext",t[1],e[1],s[1],i,u,l,o)),this.createPart("mjx-end",t[2],e[2],s[2],i)}createPart(t,e,s,i,r,n=0,o=0,a=""){if(s){const l=e[3],c=l.f||("normal"===i?"":this.font.getVariant(i).letter),h=l.ff||(c?`${this.font.cssFontPrefix}-${c}`:""),d=l.c||String.fromCodePoint(s);let u=[];if("mjx-ext"===t&&(o||l.dx)){o||(o=Math.max(.06,2*l.dx-.06));const t=Math.min(Math.ceil(n/o)+1,500);if(l.cmb){u.push(this.html("mjx-spacer"));for(let e=0;e`mjx-stretchy-h > mjx-${t}`).join(", ")]:{display:"inline-block",width:0,"text-align":"right"},"mjx-stretchy-h > mjx-ext":{"clip-path":"padding-box polygon(0 -1em, 100% -1em, 100% calc(100% + 1em), 0 calc(100% + 1em))",width:"100%",border:"0px solid transparent","box-sizing":"border-box","text-align":"left"},"mjx-stretchy-v":{display:"inline-block","text-align":"center"},[["beg","ext","end","mid"].map(t=>`mjx-stretchy-v > mjx-${t}`).join(", ")]:{display:"block",height:0,margin:"0 auto"},"mjx-stretchy-v > mjx-ext > mjx-spacer":{display:"block"},"mjx-stretchy-v > mjx-ext":{"clip-path":"padding-box polygon(-1em 0, calc(100% + 1em) 0, calc(100% + 1em) 100%, -1em 100%)",height:"100%",border:"0.1px solid transparent","box-sizing":"border-box","white-space":"pre"},"mjx-mark":{display:"inline-block",height:0}},t}();function rh(t){return class extends t{remapChars(t){if(t.length){const e=this.font.getRemappedChar("mn",t[0]);if(e){const s=this.unicodeChars(e,this.variant);1===s.length?t[0]=s[0]:t=s.concat(t.slice(1))}}return t}}}const nh=function(){var t;const e=rh(Jc);return(t=class extends e{}).kind=Ar.prototype.kind,t}();function oh(t){return class extends t{createText(t){const e=this.wrap(this.mmlText(t));return e.parent=this,e}constructor(t,e,s=null){super(t,e,s);const i=this.node.attributes,r=i.getList("lquote","rquote");"monospace"!==this.variant&&(i.isSet("lquote")||'"'!==r.lquote||(r.lquote="\u201c"),i.isSet("rquote")||'"'!==r.rquote||(r.rquote="\u201d")),this.childNodes.unshift(this.createText(r.lquote)),this.childNodes.push(this.createText(r.rquote))}}}const ah=function(){var t;const e=oh(Jc);return(t=class extends e{}).kind=Gr.prototype.kind,t}();function lh(t){var e;return e=class extends t{constructor(){super(...arguments),this.breakPoints=[]}textWidth(t){let e=this.textNode;if(!e){const t=this.node.factory.create("text");t.parent=this.node,e=this.textNode=this.factory.wrap(t),e.parent=this}return e.node.setText(t),e.invalidateBBox(!1),e.getBBox().w}get breakCount(){return this.breakPoints.length}getVariant(){const t=this.jax.options,e=this.jax.math.outputData,s=(!!e.merrorFamily||!!t.merrorFont)&&this.node.Parent.isKind("merror");if(e.mtextFamily||t.mtextFont||s){const i=this.node.attributes.get("mathvariant"),r=this.constructor.INHERITFONTS[i]||this.jax.font.getCssFont(i),n=r[0]||(s?e.merrorFamily||t.merrorFont:e.mtextFamily||t.mtextFont);return void(this.variant=this.explicitVariant(n,r[2]?"bold":"",r[1]?"italic":""))}super.getVariant()}setBreakAt(t){this.breakPoints.push(t)}clearBreakPoints(){this.breakPoints=[]}computeLineBBox(t){const e=Dc.from(this.getOuterBBox(),this.linebreakOptions.lineleading);return this.breakCount?(e.w=this.getBreakWidth(t),0===t?(e.R=0,this.addLeftBorders(e)):(e.L=0,e.indentData=[["left","0"],["left","0"],["left","0"]],t===this.breakCount&&this.addRightBorders(e)),e):e}getBreakWidth(t){const e=this.childNodes;let[s,i]=this.breakPoints[t-1]||[0,0];const[r,n]=this.breakPoints[t]||[e.length,0];let o=e[s].node.getText().split(/ /);if(s===r)return this.textWidth(o.slice(i,n).join(" "));let a=this.textWidth(o.slice(i).join(" "));for(;++s1&&t.forEach(t=>this.adaptor.append(t,this.html("mjx-linestrut")));const e=this.standardChtmlNodes(t);let{w:s,h:i,d:r}=this.getBBox();s<0&&(this.adaptor.setStyle(e[0],"marginRight",this.em(s)),s=0),s&&!this.breakCount&&this.adaptor.setStyle(e[0],"width",this.em(s)),i=Math.max(0,i+r),i&&this.adaptor.setStyle(e[0],"height",this.em(Math.max(0,i))),r&&this.adaptor.setStyle(e[0],"verticalAlign",this.em(-r))}}).kind=Xr.prototype.kind,t}();function uh(t){return class extends t{get containerWidth(){const t=this.node.attributes,e=t.get("width").toString();return e.match(/^[-+]|%$/)||"linebreak"!==t.get("data-overflow")?this.parent.containerWidth:this.length2em(e)}getDimens(){const t=this.node.attributes.getList("width","height","depth","lspace","voffset"),e=this.childNodes[0].getOuterBBox();let{w:s,h:i,d:r}=e;const n=s,o=i,a=r;let l=0,c=0,h=0;""!==t.width&&(s=this.dimen(t.width,e,"w",0)),""!==t.height&&(i=this.dimen(t.height,e,"h",0)),""!==t.depth&&(r=this.dimen(t.depth,e,"d",0)),""!==t.voffset&&(c=this.dimen(t.voffset,e)),""!==t.lspace&&(l=this.dimen(t.lspace,e));const d=this.node.attributes.get("data-align");return d&&(h=this.getAlignX(s,e,d)),[o,a,n,i-o,r-a,s-n,l,c,h]}dimen(t,e,s="",i=null){const r=(t=String(t)).match(/width|height|depth/),n=r?e[r[0].charAt(0)]:s?e[s]:0;let o=this.length2em(t,n)||0;return t.match(/^[-+]/)&&s&&(o+=n),null!=i&&(o=Math.max(i,o)),o}setBBoxDimens(t){const[e,s,i,r,n,o]=this.getDimens();t.w=i+o,t.h=e+r,t.d=s+n}computeBBox(t,e=!1){this.setBBoxDimens(t);if(this.childNodes[0].getOuterBBox().w>t.w){const e=this.node.attributes.get("data-overflow");("linebreak"===e||"auto"===e&&"linebreak"===this.jax.math.root.attributes.get("overflow"))&&(this.childNodes[0].breakToWidth(t.w),this.setBBoxDimens(t))}this.setChildPWidths(e,t.w)}getWrapWidth(t){return this.getBBox().w}getChildAlign(t){return this.node.attributes.get("data-align")||"left"}}}const ph=function(){var t;const e=uh(Jc);return(t=class extends e{toCHTML(t){if(this.toEmbellishedCHTML(t))return;let e=this.standardChtmlNodes(t);const s=[],i={},[,,r,n,o,a,l,c,h]=this.getDimens();if((a||this.childNodes[0].getBBox().pwidth)&&(i.width=this.em(r+a)),(n||o)&&(i.margin=this.em(n)+" 0 "+this.em(o)),l+h||c){i.position="relative";const t=this.html("mjx-rbox",{style:{left:this.em(l+h),top:this.em(-c),"max-width":i.width}});l+h&&this.childNodes[0].getBBox().pwidth&&(this.adaptor.setAttribute(t,"width","full"),this.adaptor.setStyle(t,"left",this.em(l))),s.push(t)}e=[this.adaptor.append(e[0],this.html("mjx-block",{style:i},s))],this.childNodes[0].childNodes.length?this.childNodes[0].toCHTML([s[0]||e[0]]):(n||o)&&this.adaptor.append(s[0]||e[0],this.html("mjx-box"))}}).kind=en.prototype.kind,t.styles={"mjx-mpadded":{display:"inline-block"},"mjx-rbox":{display:"inline-block",position:"relative"}},t}(),mh=4,fh=1,gh=2,bh=.067,Eh=.2,xh=bh+"em solid",yh={top:0,right:1,bottom:2,left:3},Nh=Object.keys(yh),vh=t=>new Array(4).fill(t.thickness+t.padding),Th=t=>new Array(4).fill(t.padding),wh=t=>new Array(4).fill(t.thickness),Ch=t=>Math.max(t.padding,t.thickness*(t.arrowhead.x+t.arrowhead.dx+1)),kh=(t,e)=>{if(t.childNodes[0]){const{h:s,d:i}=t.childNodes[0].getBBox();e[0]=e[2]=Math.max(0,t.thickness*t.arrowhead.y-(s+i)/2)}return e},_h=(t,e)=>{if(t.childNodes[0]){const{w:s}=t.childNodes[0].getBBox();e[1]=e[3]=Math.max(0,t.thickness*t.arrowhead.y-s/2)}return e},Lh={up:[-Math.PI/2,!1,!0,"verticalstrike"],down:[Math.PI/2,!1,!0,"verticakstrike"],right:[0,!1,!1,"horizontalstrike"],left:[Math.PI,!1,!1,"horizontalstrike"],updown:[Math.PI/2,!0,!0,"verticalstrike uparrow downarrow"],leftright:[0,!0,!1,"horizontalstrike leftarrow rightarrow"]},Ah={updiagonal:[-1,0,!1,"updiagonalstrike northeastarrow"],northeast:[-1,0,!1,"updiagonalstrike updiagonalarrow"],southeast:[1,0,!1,"downdiagonalstrike"],northwest:[1,Math.PI,!1,"downdiagonalstrike"],southwest:[-1,Math.PI,!1,"updiagonalstrike"],northeastsouthwest:[-1,0,!0,"updiagonalstrike northeastarrow updiagonalarrow southwestarrow"],northwestsoutheast:[1,0,!0,"downdiagonalstrike northwestarrow southeastarrow"]},Rh={up:t=>_h(t,[Ch(t),0,t.padding,0]),down:t=>_h(t,[t.padding,0,Ch(t),0]),right:t=>kh(t,[0,Ch(t),0,t.padding]),left:t=>kh(t,[0,t.padding,0,Ch(t)]),updown:t=>_h(t,[Ch(t),0,Ch(t),0]),leftright:t=>kh(t,[0,Ch(t),0,Ch(t)])},Sh=function(t){return e=>{const s=yh[e];return[e,{renderer:t,bbox:t=>{const e=[0,0,0,0];return e[s]=t.thickness+t.padding,e},border:t=>{const e=[0,0,0,0];return e[s]=t.thickness,e}}]}},Mh=function(t){return(e,s,i)=>{const r=yh[s],n=yh[i];return[e,{renderer:t,bbox:t=>{const e=t.thickness+t.padding,s=[0,0,0,0];return s[r]=s[n]=e,s},border:t=>{const e=[0,0,0,0];return e[r]=e[n]=t.thickness,e},remove:s+" "+i}]}},Ih=function(t){return e=>{const s="mjx-"+e.charAt(0)+"strike";return[e+"diagonalstrike",{renderer:t(s),bbox:vh}]}},Oh=function(t){return e=>{const[s,i,r,n]=Ah[e];return[e+"arrow",{renderer:(e,n)=>{const[o,a]=e.arrowAW(),l=e.arrow(a,s*(o-i),r);t(e,l)},bbox:t=>{const{a:e,x:s,y:i}=t.arrowData(),[r,n,o]=[t.arrowhead.x,t.arrowhead.y,t.arrowhead.dx],[a,l]=t.getArgMod(r+o,n),c=i+(a>e?t.thickness*l*Math.sin(a-e):0),h=s+(a>Math.PI/2-e?t.thickness*l*Math.sin(a+e-Math.PI/2):0);return[c,h,c,h]},remove:n}]}},Dh=function(t){return e=>{const[s,i,r,n]=Lh[e];return[e+"arrow",{renderer:(e,n)=>{const{w:o,h:a,d:l}=e.getBBox(),[c,h]=r?[a+l,"X"]:[o,"Y"],d=e.getOffset(h),u=e.arrow(c,s,i,h,d);t(e,u)},bbox:Rh[e],remove:n}]}};function Ph(t){return class extends t{getParameters(){const t=this.node.attributes,e=t.get("data-padding");void 0!==e&&(this.padding=this.length2em(e,Eh));const s=t.get("data-thickness");void 0!==s&&(this.thickness=this.length2em(s,bh));const i=t.get("data-arrowhead");if(void 0!==i){const[t,e,s]=Hr(i);this.arrowhead={x:t?parseFloat(t):mh,y:e?parseFloat(e):gh,dx:s?parseFloat(s):fh}}}getNotations(){const t=this.constructor.notations;for(const e of Hr(this.node.attributes.get("notation"))){const s=t.get(e);s&&(this.notations[e]=s,s.renderChild&&(this.renderChild=s.renderer))}}removeRedundantNotations(){for(const t of Object.keys(this.notations))if(this.notations[t]){const e=this.notations[t].remove||"";for(const t of e.split(/ /))delete this.notations[t]}}initializeNotations(){for(const t of Object.keys(this.notations)){const e=this.notations[t].init;e&&e(this)}}getBBoxExtenders(){const t=[0,0,0,0];for(const e of Object.keys(this.notations))this.maximizeEntries(t,this.notations[e].bbox(this));return t}getPadding(){const t=[0,0,0,0];for(const e of Object.keys(this.notations)){const s=this.notations[e].border;s&&this.maximizeEntries(t,s(this))}return[0,1,2,3].map(e=>this.TRBL[e]-t[e])}maximizeEntries(t,e){for(let s=0;s.001?n:0}getArgMod(t,e){return[Math.atan2(e,t),Math.sqrt(t*t+e*e)]}arrow(t,e,s,i="",r=0){return null}arrowData(){const[t,e]=[this.padding,this.thickness],s=e*(this.arrowhead.x+Math.max(1,this.arrowhead.dx)),{h:i,d:r,w:n}=this.childNodes[0].getBBox(),o=i+r,a=Math.sqrt(o*o+n*n),l=Math.max(t,s*n/a),c=Math.max(t,s*o/a),[h,d]=this.getArgMod(n+2*l,o+2*c);return{a:h,W:d,x:l,y:c}}arrowAW(){const{h:t,d:e,w:s}=this.childNodes[0].getBBox(),[i,r,n,o]=this.TRBL;return this.getArgMod(o+s+r,i+t+e+n)}createMsqrt(t){const e=this.node.factory.create("msqrt");e.inheritAttributesFrom(this.node),e.childNodes[0]=t.node;const s=this.wrap(e);return s.parent=this,s}sqrtTRBL(){const t=this.msqrt.getBBox(),e=this.msqrt.childNodes[0].getBBox();return[t.h-e.h,0,t.d-e.d,t.w-e.w]}constructor(t,e,s=null){super(t,e,s),this.notations={},this.renderChild=null,this.msqrt=null,this.padding=Eh,this.thickness=bh,this.arrowhead={x:mh,y:gh,dx:fh},this.TRBL=[0,0,0,0],this.getParameters(),this.getNotations(),this.removeRedundantNotations(),this.initializeNotations(),this.TRBL=this.getBBoxExtenders()}computeBBox(t,e=!1){const[s,i,r,n]=this.TRBL,o=this.childNodes[0].getBBox();t.combine(o,n,0),t.h+=s,t.d+=r,t.w+=i,this.setChildPWidths(e)}}}const Bh=function(t,e=""){return(s,i)=>{const r=s.adjustBorder(s.html("mjx-"+t));if(e){const t=s.getOffset(e);if(s.thickness!==bh||t){const i=`translate${e}(${s.Em(s.thickness/2-t)})`;s.adaptor.setStyle(r,"transform",i)}}s.adaptor.append(s.dom[0],r)}},Fh=function(t){return Sh((e,s)=>{e.adaptor.setStyle(s,"border-"+t,e.Em(e.thickness)+" solid")})(t)},jh=function(t,e,s){return Mh((t,i)=>{const r=t.Em(t.thickness)+" solid";t.adaptor.setStyle(i,"border-"+e,r),t.adaptor.setStyle(i,"border-"+s,r)})(t,e,s)},Uh=function(t,e){return Ih(t=>(s,i)=>{const{w:r,h:n,d:o}=s.getBBox(),[a,l]=s.getArgMod(r,n+o),c=e*s.thickness/2,h=s.adjustBorder(s.html(t,{style:{width:s.Em(l),transform:"rotate("+s.fixed(-e*a)+"rad) translateY("+c+"em)"}}));s.adaptor.append(s.dom[0],h)})(t)},Hh=function(t){return Oh((t,e)=>{t.adaptor.append(t.dom[0],e)})(t)},qh=function(t){return Dh((t,e)=>{t.adaptor.append(t.dom[0],e)})(t)};function Wh(t,e){return Math.atan2(t,e).toFixed(3).replace(/\.?0+$/,"")}const zh=Wh(fh,gh),Vh=function(){var t;const e=Ph(Jc);return(t=class extends e{adjustArrow(t,e){const s=this.thickness,i=this.arrowhead;if(i.x===mh&&i.y===gh&&i.dx===fh&&s===bh)return;const[r,n]=[s*i.x,s*i.y].map(t=>this.em(t)),o=Wh(i.dx,i.y),[a,l,c,h,d]=this.adaptor.childNodes(t);this.adjustHead(l,[n,"0","1px",r],o),this.adjustHead(c,["1px","0",n,r],"-"+o),this.adjustHead(h,[n,r,"1px","0"],"-"+o),this.adjustHead(d,["1px",r,n,"0"],o),this.adjustLine(a,s,i.x,e)}adjustHead(t,e,s){t&&(this.adaptor.setStyle(t,"border-width",e.join(" ")),this.adaptor.setStyle(t,"transform","skewX("+s+"rad)"))}adjustLine(t,e,s,i){this.adaptor.setStyle(t,"borderTop",this.em(e)+" solid"),this.adaptor.setStyle(t,"top",this.em(-e/2)),this.adaptor.setStyle(t,"right",this.em(e*(s-1))),i&&this.adaptor.setStyle(t,"left",this.em(e*(s-1)))}moveArrow(t,e,s){if(!s)return;const i=this.adaptor.getStyle(t,"transform");this.adaptor.setStyle(t,"transform",`translate${e}(${this.em(-s)})${i?" "+i:""}`)}adjustBorder(t){return this.thickness!==bh&&this.adaptor.setStyle(t,"borderWidth",this.em(this.thickness)),t}adjustThickness(t){return this.thickness!==bh&&this.adaptor.setStyle(t,"strokeWidth",this.fixed(this.thickness)),t}fixed(t,e=3){return Math.abs(t)<6e-4?"0":t.toFixed(e).replace(/\.?0+$/,"")}Em(t){return super.em(t)}toCHTML(t){const e=this.adaptor,s=this.standardChtmlNodes(t),i=e.append(s[0],this.html("mjx-box"));this.renderChild?this.renderChild(this,i):this.childNodes[0].toCHTML([i]);for(const t of Object.keys(this.notations)){const e=this.notations[t];e.renderChild||e.renderer(this,i)}const r=this.getPadding();for(const t of Nh){const s=yh[t];r[s]>0&&e.setStyle(i,"padding-"+t,this.em(r[s]))}}arrow(t,e,s,i="",r=0){const n=this.getBBox().w,o={width:this.em(t)};n!==t&&(o.left=this.em((n-t)/2)),e&&(o.transform="rotate("+this.fixed(e)+"rad)");const a=this.html("mjx-arrow",{style:o},[this.html("mjx-aline"),this.html("mjx-rthead"),this.html("mjx-rbhead")]);return s&&(this.adaptor.append(a,this.html("mjx-lthead")),this.adaptor.append(a,this.html("mjx-lbhead")),this.adaptor.setAttribute(a,"double","true")),this.adjustArrow(a,s),this.moveArrow(a,i,r),a}}).kind=nn.prototype.kind,t.styles={"mjx-menclose":{position:"relative"},"mjx-menclose > mjx-dstrike":{display:"inline-block",left:0,top:0,position:"absolute","border-top":xh,"transform-origin":"top left"},"mjx-menclose > mjx-ustrike":{display:"inline-block",left:0,bottom:0,position:"absolute","border-top":xh,"transform-origin":"bottom left"},"mjx-menclose > mjx-hstrike":{"border-top":xh,position:"absolute",left:0,right:0,bottom:"50%",transform:"translateY("+xo(bh/2)+")"},"mjx-menclose > mjx-vstrike":{"border-left":xh,position:"absolute",top:0,bottom:0,right:"50%",transform:"translateX("+xo(bh/2)+")"},"mjx-menclose > mjx-rbox":{position:"absolute",top:0,bottom:0,right:0,left:0,border:xh,"border-radius":xo(bh+Eh)},"mjx-menclose > mjx-cbox":{position:"absolute",top:0,bottom:0,right:0,left:0,border:xh,"border-radius":"50%"},"mjx-menclose > mjx-arrow":{position:"absolute",left:0,bottom:"50%",height:0,width:0},"mjx-menclose > mjx-arrow > mjx-aline":{display:"block",position:"absolute","box-sizing":"border-box","transform-origin":"bottom",left:0,top:xo(-bh/2),right:xo(bh*(mh-1)),height:0,"border-top":xo(bh)+" solid","border-left":0,"border-right":0},"mjx-menclose > mjx-arrow[double] > mjx-aline":{display:"block",position:"absolute","box-sizing":"border-box","transform-origin":"bottom",left:xo(bh*(mh-1)),height:0,"border-left":xo(bh*mh)+" solid","border-right":0},"mjx-menclose > mjx-arrow > mjx-rthead":{display:"block",position:"absolute","box-sizing":"border-box","transform-origin":"bottom",transform:"skewX("+zh+"rad)",right:0,bottom:"-1px","border-left":xo(bh*mh)+" solid","border-right":0,"border-bottom":"1px solid transparent","border-top":xo(bh*gh)+" solid transparent"},"mjx-menclose > mjx-arrow > mjx-rbhead":{display:"block",position:"absolute","box-sizing":"border-box",transform:"skewX(-"+zh+"rad)","transform-origin":"top",right:0,top:"-1px","border-left":xo(bh*mh)+" solid","border-right":0,"border-top":"1px solid transparent","border-bottom":xo(bh*gh)+" solid transparent"},"mjx-menclose > mjx-arrow > mjx-lthead":{display:"block",position:"absolute","box-sizing":"border-box",transform:"skewX(-"+zh+"rad)","transform-origin":"bottom",left:0,bottom:"-1px","border-left":0,"border-right":xo(bh*mh)+" solid","border-bottom":"1px solid transparent","border-top":xo(bh*gh)+" solid transparent"},"mjx-menclose > mjx-arrow > mjx-lbhead":{display:"block",position:"absolute","box-sizing":"border-box",transform:"skewX("+zh+"rad)","transform-origin":"top",left:0,top:"-1px","border-left":0,"border-right":xo(bh*mh)+" solid","border-top":"1px solid transparent","border-bottom":xo(bh*gh)+" solid transparent"},"mjx-menclose > mjx-dbox-top":{position:"absolute",top:0,bottom:"50%",left:0,width:xo(1.5*Eh),"border-width":xo(bh),"border-style":"solid solid none none","border-radius":"0 100% 0 0","box-sizing":"border-box"},"mjx-menclose > mjx-dbox-bot":{position:"absolute",top:"50%",bottom:0,left:0,width:xo(1.5*Eh),"border-width":xo(bh),"border-style":"none solid solid none","border-radius":"0 0 100% 0","box-sizing":"border-box"}},t.notations=new Map([Fh("top"),Fh("right"),Fh("bottom"),Fh("left"),jh("actuarial","top","right"),jh("madruwb","bottom","right"),Uh("up",1),Uh("down",-1),["horizontalstrike",{renderer:Bh("hstrike","Y"),bbox:t=>[0,t.padding,0,t.padding]}],["verticalstrike",{renderer:Bh("vstrike","X"),bbox:t=>[t.padding,0,t.padding,0]}],["box",{renderer:(t,e)=>{t.adaptor.setStyle(e,"border",t.Em(t.thickness)+" solid")},bbox:vh,border:wh,remove:"left right top bottom"}],["roundedbox",{renderer:Bh("rbox"),bbox:vh}],["circle",{renderer:Bh("cbox"),bbox:vh}],["phasorangle",{renderer:(t,e)=>{const{h:s,d:i}=t.getBBox(),[r,n]=t.getArgMod(1.75*t.padding,s+i),o=t.thickness*Math.sin(r)*.9;t.adaptor.setStyle(e,"border-bottom",t.Em(t.thickness)+" solid");const a=t.adjustBorder(t.html("mjx-ustrike",{style:{width:t.Em(n),transform:`translateX(${t.Em(o)}) rotate(${t.fixed(-r)}rad)`}}));t.adaptor.append(t.dom[0],a)},bbox:t=>{const e=t.padding/2,s=t.thickness;return[2*e,e,e+s,3*e+s]},border:t=>[0,0,t.thickness,0],remove:"bottom"}],qh("up"),qh("down"),qh("left"),qh("right"),qh("updown"),qh("leftright"),Hh("updiagonal"),Hh("northeast"),Hh("southeast"),Hh("northwest"),Hh("southwest"),Hh("northeastsouthwest"),Hh("northwestsoutheast"),["longdiv",{renderer:(t,e)=>{const s=t.adaptor;s.setStyle(e,"border-top",t.Em(t.thickness)+" solid");const i=s.append(t.dom[0],t.html("mjx-dbox-top")),r=s.append(t.dom[0],t.html("mjx-dbox-bot")),n=t.thickness,o=t.padding;n!==bh&&(s.setStyle(i,"border-width",t.Em(n)),s.setStyle(r,"border-width",t.Em(n))),o!==Eh&&(s.setStyle(i,"width",t.Em(1.5*o)),s.setStyle(r,"width",t.Em(1.5*o)))},bbox:t=>{const e=t.padding,s=t.thickness;return[e+s,e,e,2*e+s/2]}}],["radical",{renderer:(t,e)=>{t.msqrt.toCHTML([e]);const s=t.sqrtTRBL();t.adaptor.setStyle(t.msqrt.dom[0],"margin",s.map(e=>t.Em(-e)).join(" "))},init:t=>{t.msqrt=t.createMsqrt(t.childNodes[0])},bbox:t=>t.sqrtTRBL(),renderChild:!0}]]),t}();function Xh(t){return class extends t{stretchChildren(){const t=[];for(const e of this.childNodes)e.canStretch(Lc.Vertical)&&t.push(e);const e=t.length,s=this.childNodes.length;if(e&&s>1){let i=0,r=0;const n=e>1&&e===s;for(const t of this.childNodes){const e=t.stretch.dir===Lc.None;if(n||e){const e=t.getBBox().rscale;let[s,n]=t.getUnbrokenHD();s*=e,n*=e,s>i&&(i=s),n>r&&(r=n)}}for(const e of t){const t=e.coreRScale();e.coreMO().getStretchedVariant([i/t,r/t])}}}get fixesPWidth(){return!1}get breakCount(){return this._breakCount<0&&(this._breakCount=this.childNodes.length?this.childNodes.reduce((t,e)=>t+e.breakCount,0):0),this._breakCount}breakTop(t,e){const s=this;return this.isStack?this.parent.breakTop(s,s):s}constructor(t,e,s=null){super(t,e,s),this.dh=0;const i=this;this.isStack=!this.parent||this.parent.node.isInferred||this.parent.breakTop(i,i)!==i,this.stretchChildren();for(const t of this.childNodes)if(t.bbox.pwidth){this.bbox.pwidth=No.fullWidth;break}}computeBBox(t,e=!1){const s=this.breakCount;this.lineBBox=s?[new Dc({h:.75,d:.25,w:0},[0,0])]:[],t.empty();for(const e of this.childNodes.keys()){const i=this.childNodes[e];t.append(i.getOuterBBox()),s&&this.computeChildLineBBox(i,e)}t.clean(),s&&!this.coreMO().node.isEmbellished&&this.computeLinebreakBBox(t),this.fixesPWidth&&this.setChildPWidths(e)&&this.computeBBox(t,!0),this.vboxAdjust(t)}computeLinebreakBBox(t){var e;t.empty();const s=this.isStack,i=this.lineBBox,r=i.length-1;if(s)for(const t of i.keys()){const e=i[t];this.addMiddleBorders(e),0===t&&this.addLeftBorders(e),t===r&&this.addRightBorders(e)}let n=0;for(const s of i.keys()){const r=i[s];t.combine(r,0,n),n-=Math.max(.25,r.d)+r.lineLeading+Math.max(.75,(null===(e=i[s+1])||void 0===e?void 0:e.h)||0)}s?(i[0].L=this.bbox.L,i[r].R=this.bbox.R):(t.w=Math.max(...this.lineBBox.map(t=>t.w)),this.shiftLines(t),this.jax.math.display||this.linebreakOptions.inline||(t.pwidth=No.fullWidth,this.node.isInferred&&(this.parent.bbox.pwidth=No.fullWidth))),t.clean()}vboxAdjust(t){if(!this.parent)return;const e=this.breakCount,s=this.parent.node.attributes.get("data-vertical-align");if(e&&"bottom"===s)this.dh=e?t.d-this.lineBBox[e-1].d:0;else{if(!("center"===s||e&&"middle"===s))return void(this.dh=0);{const{h:e,d:s}=t,i=this.font.params.axis_height;this.dh=(e+s)/2+i-e}}t.h+=this.dh,t.d-=this.dh}computeChildLineBBox(t,e){const s=this.lineBBox[this.lineBBox.length-1];s.end=[e,0],s.append(t.getLineBBox(0));const i=t.breakCount+1;if(1!==i)for(let s=1;st.w&&(t.w=p)}}setChildPWidths(t,e=null,s=!0){return this.breakCount?!t&&(null!==e&&this.bbox.w!==e&&(this.bbox.w=e,this.shiftLines(this.bbox)),!0):super.setChildPWidths(t,e,s)}breakToWidth(t){this.linebreaks.breakToWidth(this,t)}}}function Gh(t){return class extends t{getScale(){this.bbox.scale=this.parent.bbox.scale,this.bbox.rscale=1}}}const Jh=function(){var t;const e=Xh(Jc);return t=class extends e{constructor(){super(...arguments),this.linebreakCount=0}toCHTML(t){const e=this.linebreakCount=this.isStack?0:this.breakCount;e||!this.node.isInferred?t=this.standardChtmlNodes(t):this.dom=t,this.addChildren(t),e?this.placeLines(t,e):(this.handleVerticalAlign(t[0]),this.handleNegativeWidth(t[0]))}placeLines(t,e){var s,i;this.getBBox();const r=this.lineBBox,n=this.adaptor,[o,a]=(null===(s=r[1].indentData)||void 0===s?void 0:s[0])||["left","0"];for(const s of t.keys()){const l=r[s],[c,h]=0===s?[o,a]:(null===(i=l.indentData)||void 0===i?void 0:i[s===e?2:1])||["left","0"],[d,u]=this.processIndent(c,h,o,a);n.setAttribute(t[s],"align",d),u&&n.setStyle(t[s],"margin-left",this.em(u)),s mjx-linebox":{display:"inline"},"mjx-linestack[breakable] > mjx-linebox::before":{"white-space":"pre",content:'"\\A"'},"mjx-linestack[breakable] > mjx-linebox::after":{"white-space":"normal",content:'" "',"letter-spacing":"-.999em","font-family":"MJX-BRK"},"mjx-linestack[breakable] > mjx-linebox:first-of-type::before":{display:"none"},"mjx-linestack[breakable] > mjx-linebox:last-of-type::after":{display:"none"},"mjx-linebox":{display:"block"},'mjx-linebox[align="left"]':{"text-align":"left"},'mjx-linebox[align="center"]':{"text-align":"center"},'mjx-linebox[align="right"]':{"text-align":"right"},"mjx-linestrut":{display:"inline-block",height:"1em","vertical-align":"-.25em"}},t}(),Kh=function(){var t;const e=Gh(Jh);return(t=class extends e{}).kind=Kr.prototype.kind,t}();function $h(t){return class extends t{createMrow(){const t=this.node.factory.create("inferredMrow");t.inheritAttributesFrom(this.node),this.mrow=this.wrap(t),this.mrow.parent=this}addMrowChildren(){const t=this.node,e=this.mrow;this.addMo(t.open),this.childNodes.length&&e.childNodes.push(this.childNodes[0]);let s=0;for(const i of this.childNodes.slice(1))this.addMo(t.separators[s++]),e.childNodes.push(i);this.addMo(t.close),e.stretchChildren()}addMo(t){if(!t)return;const e=this.wrap(t);this.mrow.childNodes.push(e),e.parent=this.mrow}constructor(t,e,s=null){super(t,e,s),this.mrow=null,this.createMrow(),this.addMrowChildren()}computeBBox(t,e=!1){t.updateFrom(this.mrow.getOuterBBox()),this.setChildPWidths(e)}get breakCount(){return this.mrow.breakCount}computeLineBBox(t){return this.mrow.getLineBBox(t)}}}const Yh=function(){var t;const e=$h(Jc);return(t=class extends e{toCHTML(t){const e=this.standardChtmlNodes(t);this.mrow.toCHTML(e)}}).kind=rn.prototype.kind,t}();function Qh(t){return class extends t{getFractionBBox(t,e,s){const i=this.childNodes[0].getOuterBBox(),r=this.childNodes[1].getOuterBBox(),n=this.font.params.axis_height,{T:o,u:a,v:l}=this.getTUV(e,s);t.combine(i,0,n+o+Math.max(i.d*i.rscale,a)),t.combine(r,0,n-o-Math.max(r.h*r.rscale,l)),t.w+=2*this.pad+.2}getTUV(t,e){const s=this.font.params,i=s.axis_height,r=(t?3.5:1.5)*e;return{T:(t?3.5:1.5)*e,u:(t?s.num1:s.num2)-i-r,v:(t?s.denom1:s.denom2)+i-r}}getAtopBBox(t,e){const{u:s,v:i,nbox:r,dbox:n}=this.getUVQ(e);t.combine(r,0,s),t.combine(n,0,-i),t.w+=2*this.pad}getUVQ(t){const e=this.childNodes[0].getOuterBBox(),s=this.childNodes[1].getOuterBBox(),i=this.font.params;let[r,n]=t?[i.num1,i.denom1]:[i.num3,i.denom2];const o=(t?7:3)*i.rule_thickness;let a=r-e.d*e.scale-(s.h*s.scale-n);return a mjx-line, mjx-dtable > mjx-row":{"font-size":"2000%"},"mjx-dbox":{display:"block","font-size":"5%"},"mjx-num":{display:"block","text-align":"center"},"mjx-den":{display:"block","text-align":"center"},"mjx-mfrac[bevelled] > mjx-num":{display:"inline-block"},"mjx-mfrac[bevelled] > mjx-den":{display:"inline-block"},'mjx-den[align="right"], mjx-num[align="right"]':{"text-align":"right"},'mjx-den[align="left"], mjx-num[align="left"]':{"text-align":"left"},"mjx-nstrut":{display:"inline-block",height:".054em",width:0,"vertical-align":"-.054em"},'mjx-nstrut[type="d"]':{height:".217em","vertical-align":"-.217em"},"mjx-dstrut":{display:"inline-block",height:".505em",width:0},'mjx-dstrut[type="d"]':{height:".726em"},"mjx-line":{display:"block","box-sizing":"border-box","min-height":"1px",height:".06em","border-top":".075em solid",margin:".06em -.1em",overflow:"hidden"},'mjx-line[type="d"]':{margin:".18em -.1em"}},t}();function td(t){return class extends t{get base(){return 0}get root(){return null}combineRootBBox(t,e,s){}getPQ(t){const e=this.font.params.rule_thickness,s=this.font.params.surd_height,i=this.node.attributes.get("displaystyle")?this.font.params.x_height:e;return[i,t.h+t.d>this.surdH?(t.h+t.d-(this.surdH-e-s-i/2))/2:s+i/4]}getRootDimens(t,e){return[0,0,0,0]}rootWidth(){return 1.25}getStretchedSurd(){const t=this.font.params.rule_thickness,e=this.font.params.surd_height,s=this.node.attributes.get("displaystyle")?this.font.params.x_height:t,{h:i,d:r}=this.childNodes[this.base].getOuterBBox();this.surdH=i+r+t+e+s/4,this.surd.getStretchedVariant([this.surdH-r,r],!0)}constructor(t,e,s=null){super(t,e,s),this.surd=this.createMo("\u221a"),this.surd.canStretch(Lc.Vertical),this.getStretchedSurd()}computeBBox(t,e=!1){t.empty();const s=this.surd.getBBox(),i=new No(this.childNodes[this.base].getOuterBBox()),r=this.getPQ(s)[1],n=this.font.params.rule_thickness,o=this.font.params.surd_height,a=i.h+r+n,[l]=this.getRootDimens(s,a);t.h=a+o,this.combineRootBBox(t,s,a),t.combine(s,l,a-s.h),t.combine(i,l+s.w,0),t.clean(),this.setChildPWidths(e)}invalidateBBox(){super.invalidateBBox(),this.surd.childNodes[0].invalidateBBox()}}}const ed=function(){var t;const e=td(Jc);return t=class extends e{toCHTML(t){const e=this.surd,s=this.childNodes[this.base],i=e.getBBox(),r=s.getOuterBBox(),[,n]=this.getPQ(i),o=this.font.params.surd_height,a=r.h+n+o,l=this.adaptor,c=this.standardChtmlNodes(t);let h,d,u,p;null!=this.root&&(u=l.append(c[0],this.html("mjx-root")),p=this.childNodes[this.root]);const m=l.append(c[0],this.html("mjx-sqrt",{},[h=this.html("mjx-surd"),d=this.html("mjx-box",{style:{paddingTop:this.em(n)}})]));.06!==o&&l.setStyle(d,"border-top-width",this.em(o*this.font.params.rule_factor)),this.addRoot(u,p,i,a),e.toCHTML([h]),s.toCHTML([d]),e.size<0&&l.addClass(m,"mjx-tall")}addRoot(t,e,s,i){}},t.kind=Yr.prototype.kind,t.styles={"mjx-root":{display:"inline-block","white-space":"nowrap"},"mjx-surd":{display:"inline-block","vertical-align":"top"},"mjx-sqrt":{display:"inline-block","padding-top":".075em"},"mjx-sqrt > mjx-box":{"border-top":".075em solid","padding-left":".03em","margin-left":"-.03em"},"mjx-sqrt.mjx-tall > mjx-box":{"padding-left":".3em","margin-left":"-.3em"}},t}();function sd(t){return class extends t{get root(){return 1}combineRootBBox(t,e,s){const i=this.childNodes[this.root].getOuterBBox(),r=this.getRootDimens(e,s)[1];t.combine(i,0,r)}getRootDimens(t,e){const s=this.surd,i=this.childNodes[this.root].getOuterBBox(),r=(s.size<0?.5:.6)*t.w,{w:n,rscale:o}=i,a=Math.max(n,r/o),l=Math.max(0,a-n);return[a*o-r,this.rootHeight(i,t,s.size,e),l]}rootHeight(t,e,s,i){const r=e.h+e.d;return(s<0?1.9:.55*r)-(r-i)+Math.max(0,t.d*t.rscale)}rootWidth(){const t=this.childNodes[this.root].getOuterBBox();return.4+t.w*t.rscale}}}const id=function(){var t;const e=sd(ed);return t=class extends e{addRoot(t,e,s,i){e.toCHTML([t]);const r=this.adaptor,[n,o,a]=this.getRootDimens(s,i);r.setStyle(t,"verticalAlign",this.em(o)),r.setStyle(t,"width",this.em(n)),a&&r.setStyle(r.firstChild(t),"paddingLeft",this.em(a))}},t.kind=Qr.prototype.kind,t}();function rd(t){var e;return(e=class extends t{get scriptChild(){return this.childNodes[this.node.sub]}getOffset(){return[this.baseIsChar?0:this.getAdjustedIc(),-this.getV()]}}).useIC=!1,e}function nd(t){return class extends t{get scriptChild(){return this.childNodes[this.node.sup]}getOffset(){return[this.getAdjustedIc()-(this.baseRemoveIc?0:this.baseIc),this.getU()]}}}function od(t){var e;return e=class extends t{constructor(){super(...arguments),this.UVQ=null}get subChild(){return this.childNodes[this.node.sub]}get supChild(){return this.childNodes[this.node.sup]}get scriptChild(){return this.supChild}getUVQ(t=this.subChild.getOuterBBox(),e=this.supChild.getOuterBBox()){const s=this.baseCore,i=s.getLineBBox(s.breakCount);if(this.UVQ)return this.UVQ;const r=this.font.params,n=3*r.rule_thickness,o=this.length2em(this.node.attributes.get("subscriptshift"),r.sub2),a=this.baseCharZero(i.d*this.baseScale+r.sub_drop*t.rscale),l=e.d*e.rscale,c=t.h*t.rscale;let[h,d]=[this.getU(),Math.max(a,o)],u=h-l-(c-d);if(u0&&(h+=t,d-=t)}return h=Math.max(this.length2em(this.node.attributes.get("superscriptshift"),h),h),d=Math.max(this.length2em(this.node.attributes.get("subscriptshift"),d),d),u=h-l-(c-d),this.UVQ=[h,-d,u],this.UVQ}appendScripts(t){const[e,s]=[this.subChild.getOuterBBox(),this.supChild.getOuterBBox()],i=this.getBaseWidth(),r=this.getAdjustedIc(),[n,o]=this.getUVQ(),a=t.d-this.baseChild.getLineBBox(this.baseChild.breakCount).d;return t.combine(e,i+(this.baseIsChar?0:r),o-a),t.combine(s,i+r,n-a),t.w+=this.font.params.scriptspace,t}},e.useIC=!1,e}function ad(t){var e;return e=class extends t{get baseChild(){return this.childNodes[this.node.base]}get scriptChild(){return this.childNodes[1]}getBaseCore(){let t=this.getSemanticBase()||this.childNodes[0],e=null==t?void 0:t.node;for(;t&&(1===t.childNodes.length&&(e.isKind("mrow")||e.isKind("TeXAtom")||e.isKind("mstyle")||e.isKind("mpadded")&&!e.getProperty("vbox")||e.isKind("mphantom")||e.isKind("semantics"))||e.isKind("munderover")&&t.isMathAccent);)this.setBaseAccentsFor(t),t=t.childNodes[0],e=null==t?void 0:t.node;return t||(this.baseHasAccentOver=this.baseHasAccentUnder=!1),t||this.childNodes[0]}setBaseAccentsFor(t){t.node.isKind("munderover")&&(null===this.baseHasAccentOver&&(this.baseHasAccentOver=!!t.node.attributes.get("accent")),null===this.baseHasAccentUnder&&(this.baseHasAccentUnder=!!t.node.attributes.get("accentunder")))}getSemanticBase(){const t=this.node.attributes.getExplicit("data-semantic-fencepointer");return this.getBaseFence(this.baseChild,t)}getBaseFence(t,e){if(!t||!t.node.attributes||!e)return null;if(t.node.attributes.getExplicit("data-semantic-id")===e)return t;for(const s of t.childNodes){const t=this.getBaseFence(s,e);if(t)return t}return null}getBaseScale(){let t=this.baseCore,e=1;for(;t&&t!==this;){e*=t.getOuterBBox().rscale,t=t.parent}return e}getBaseIc(){return this.baseCore.getOuterBBox().ic*this.baseScale}getAdjustedIc(){return this.baseIc?1.05*this.baseIc+.05:0}isCharBase(){const t=this.baseCore;return(t.node.isKind("mo")&&null===t.size||t.node.isKind("mi")||t.node.isKind("mn"))&&1===t.bbox.rscale&&1===Array.from(t.getText()).length}checkLineAccents(){if(this.node.isKind("munderover"))if(this.node.isKind("mover"))this.isLineAbove=this.isLineAccent(this.scriptChild);else if(this.node.isKind("munder"))this.isLineBelow=this.isLineAccent(this.scriptChild);else{const t=this;this.isLineAbove=this.isLineAccent(t.overChild),this.isLineBelow=this.isLineAccent(t.underChild)}}isLineAccent(t){const e=t.coreMO().node;return e.isToken&&"\u2015"===e.getText()}getBaseWidth(){const t=this.baseChild.getLineBBox(this.baseChild.breakCount);return t.w*t.rscale-(this.baseRemoveIc?this.baseIc:0)+this.font.params.extra_ic}getOffset(){return[0,0]}baseCharZero(t){const e=!!this.baseCore.node.attributes.get("largeop"),s=!(!this.baseCore.node.isKind("mo")||!this.baseCore.size),i=this.baseScale;return!this.baseIsChar||e||s||1!==i?t:0}getV(){const t=this.baseCore,e=t.getLineBBox(t.breakCount),s=this.scriptChild.getOuterBBox(),i=this.font.params,r=this.length2em(this.node.attributes.get("subscriptshift"),i.sub1);return Math.max(this.baseCharZero(e.d*this.baseScale+i.sub_drop*s.rscale),r,s.h*s.rscale-.8*i.x_height)}getU(){const t=this.baseCore,e=t.getLineBBox(t.breakCount),s=this.scriptChild.getOuterBBox(),i=this.font.params,r=this.node.attributes.getList("displaystyle","superscriptshift"),n=this.node.getProperty("texprimestyle")?i.sup3:r.displaystyle?i.sup1:i.sup2,o=this.length2em(r.superscriptshift,n);return Math.max(this.baseCharZero(e.h*this.baseScale-i.sup_drop*s.rscale),o,s.d*s.rscale+1/4*i.x_height)}hasMovableLimits(){const t=this.node.attributes.get("displaystyle"),e=this.baseChild.coreMO().node;return!t&&!!e.attributes.get("movablelimits")}getOverKU(t,e){const s=this.node.attributes.get("accent"),i=this.font.params,r=e.d*e.rscale,n=i.rule_thickness*i.separation_factor,o=this.baseHasAccentOver?n:0,a=this.isLineAbove?3*i.rule_thickness:n,l=(s?a:Math.max(i.big_op_spacing1,i.big_op_spacing3-Math.max(0,r)))-o;return[l,t.h*t.rscale+l+r]}getUnderKV(t,e){const s=this.node.attributes.get("accentunder"),i=this.font.params,r=e.h*e.rscale,n=i.rule_thickness*i.separation_factor,o=this.baseHasAccentUnder?n:0,a=this.isLineBelow?3*i.rule_thickness:n,l=(s?a:Math.max(i.big_op_spacing2,i.big_op_spacing4-r))-o;return[l,-(t.d*t.rscale+l+r)]}getDeltaW(t,e=[0,0,0]){const s=this.node.attributes.get("align"),i=t.map(t=>t.w*t.rscale);i[0]-=this.baseRemoveIc&&!this.baseCore.node.attributes.get("largeop")?this.baseIc:0;const r=Math.max(...i),n=[];let o=0;for(const t of i.keys())n[t]=("center"===s?(r-i[t])/2:"right"===s?r-i[t]:0)+e[t],n[t]n[e]+=t[e]?t[e].dx*t[0].rscale:0),n}getDelta(t,e=!1){const s=this.node.attributes.get("accent");let{sk:i,ic:r}=this.baseCore.getOuterBBox();return s&&(i-=t.getOuterBBox().sk),((s&&!e?i:0)+this.font.skewIcFactor*r)*this.baseScale}stretchChildren(){const t=[];for(const e of this.childNodes)e.canStretch(Lc.Horizontal)&&t.push(e);const e=t.length,s=this.childNodes.length;if(e&&s>1){let i=0;const r=e>1&&e===s;for(const t of this.childNodes){const e=t.stretch.dir===Lc.None;if(r||e){const{w:s,rscale:r}=t.getOuterBBox(e);s*r>i&&(i=s*r)}}for(const e of t){const t=e.coreMO();null===t.size&&t.getStretchedVariant([i/e.coreRScale()])}}}constructor(t,e,s=null){super(t,e,s),this.baseScale=1,this.baseIc=0,this.baseRemoveIc=!1,this.baseIsChar=!1,this.baseHasAccentOver=null,this.baseHasAccentUnder=null,this.isLineAbove=!1,this.isLineBelow=!1,this.isMathAccent=!1;const i=this.baseCore=this.getBaseCore();i&&(this.setBaseAccentsFor(i),this.baseScale=this.getBaseScale(),this.baseIc=this.getBaseIc(),this.baseIsChar=this.isCharBase(),this.isMathAccent=this.baseIsChar&&this.scriptChild&&void 0!==this.scriptChild.coreMO().node.getProperty("mathaccent"),this.checkLineAccents(),this.baseRemoveIc=!this.isLineAbove&&!this.isLineBelow&&(!this.constructor.useIC||this.isMathAccent))}computeBBox(t,e=!1){t.empty(),t.append(this.baseChild.getOuterBBox()),this.appendScripts(t),t.clean(),this.setChildPWidths(e)}appendScripts(t){const e=this.getBaseWidth(),[s,i]=this.getOffset();return t.combine(this.scriptChild.getOuterBBox(),e+s,i),t.w+=this.font.params.scriptspace,t}get breakCount(){return this._breakCount<0&&(this._breakCount=this.node.isEmbellished?this.coreMO().embellishedBreakCount:this.node.linebreakContainer?0:this.childNodes[0].breakCount),this._breakCount}breakTop(t,e){return this.node.linebreakContainer||!this.parent||this.node.childIndex(e.node)?t:this.parent.breakTop(t,this)}computeLineBBox(t){const e=this.breakCount;if(!e)return Dc.from(this.getOuterBBox(),this.linebreakOptions.lineleading);const s=this.baseChild.getLineBBox(t).copy();return t=0||this.adaptor.setStyle(t,"marginBottom",this.em(e.d*e.rscale))}adjustUnderDepth(t,e){if(e.d>=0)return;const s=this.adaptor,i=this.em(e.d),r=this.html("mjx-box",{style:{"margin-bottom":i,"vertical-align":i}});for(const e of s.childNodes(s.firstChild(t)))s.append(r,e);s.append(s.firstChild(t),r)}adjustBaseHeight(t,e){if(this.node.attributes.get("accent")){const s=this.font.params.x_height*this.baseScale;e.h mjx-spacer":{display:"block"}},t}();function ud(t){return class extends t{get scriptChild(){return this.childNodes[this.node.under]}constructor(...t){super(...t),this.stretchChildren()}computeBBox(t,e=!1){if(this.hasMovableLimits())return void super.computeBBox(t,e);t.empty();const s=this.baseChild.getOuterBBox(),i=this.scriptChild.getOuterBBox(),r=this.getUnderKV(s,i)[1],n=this.isLineBelow?0:this.getDelta(this.scriptChild,!0),[o,a]=this.getDeltaW([s,i],[0,-n]);t.combine(s,o,0),t.combine(i,a,r),t.d+=this.font.params.big_op_spacing5,t.clean(),this.setChildPWidths(e)}}}function pd(t){return class extends t{get scriptChild(){return this.childNodes[this.node.over]}constructor(...t){super(...t),this.stretchChildren()}computeBBox(t){if(this.hasMovableLimits())return void super.computeBBox(t);t.empty();const e=this.baseChild.getOuterBBox(),s=this.scriptChild.getOuterBBox();this.node.attributes.get("accent")&&(e.h=Math.max(e.h,this.font.params.x_height*this.baseScale));const i=this.getOverKU(e,s)[1],r=this.isLineAbove?0:this.getDelta(this.scriptChild),[n,o]=this.getDeltaW([e,s],[0,r]);t.combine(e,n,0),t.combine(s,o,i),t.h+=this.font.params.big_op_spacing5,t.clean()}}}function md(t){return class extends t{get underChild(){return this.childNodes[this.node.under]}get overChild(){return this.childNodes[this.node.over]}get subChild(){return this.underChild}get supChild(){return this.overChild}constructor(...t){super(...t),this.stretchChildren()}computeBBox(t){if(this.hasMovableLimits())return void super.computeBBox(t);t.empty();const e=this.overChild.getOuterBBox(),s=this.baseChild.getOuterBBox(),i=this.underChild.getOuterBBox();this.node.attributes.get("accent")&&(s.h=Math.max(s.h,this.font.params.x_height*this.baseScale));const r=this.getOverKU(s,e)[1],n=this.getUnderKV(s,i)[1],o=this.getDelta(this.overChild),a=this.getDelta(this.underChild,!0),[l,c,h]=this.getDeltaW([s,i,e],[0,this.isLineBelow?0:-a,this.isLineAbove?0:o]);t.combine(s,l,0),t.combine(e,h,r),t.combine(i,c,n);const d=this.font.params.big_op_spacing5;t.h+=d,t.d+=d,t.clean()}}}const fd=function(){var t;const e=ud(cd);return(t=class extends e{toCHTML(t){if(this.toEmbellishedCHTML(t))return;if(this.hasMovableLimits())return super.toCHTML(t),void this.adaptor.setAttribute(this.dom[0],"limits","false");this.dom=this.standardChtmlNodes(t);const e=this.adaptor.append(this.adaptor.append(this.dom[0],this.html("mjx-row")),this.html("mjx-base")),s=this.adaptor.append(this.adaptor.append(this.dom[0],this.html("mjx-row")),this.html("mjx-under"));this.baseChild.toCHTML([e]),this.scriptChild.toCHTML([s]);const i=this.baseChild.getOuterBBox(),r=this.scriptChild.getOuterBBox(),n=this.getUnderKV(i,r)[0],o=this.isLineBelow?0:this.getDelta(this.scriptChild,!0);this.adaptor.setStyle(s,"paddingTop",this.em(n)),this.setDeltaW([e,s],this.getDeltaW([i,r],[0,-o])),this.adjustUnderDepth(s,r)}}).kind=dn.prototype.kind,t.styles={"mjx-over":{"text-align":"left"},'mjx-munder:not([limits="false"])':{display:"inline-table"},"mjx-munder > mjx-row":{"text-align":"left"},"mjx-under":{"padding-bottom":".1em"}},t}(),gd=function(){var t;const e=pd(hd);return(t=class extends e{toCHTML(t){if(this.toEmbellishedCHTML(t))return;if(this.hasMovableLimits())return super.toCHTML(t),void this.adaptor.setAttribute(this.dom[0],"limits","false");this.dom=this.standardChtmlNodes(t);const e=this.adaptor.append(this.dom[0],this.html("mjx-over")),s=this.adaptor.append(this.dom[0],this.html("mjx-base"));this.scriptChild.toCHTML([e]),this.baseChild.toCHTML([s]);const i=this.scriptChild.getOuterBBox(),r=this.baseChild.getOuterBBox();this.adjustBaseHeight(s,r);const n=this.getOverKU(r,i)[0],o=this.isLineAbove?0:this.getDelta(this.scriptChild);this.adaptor.setStyle(e,"paddingBottom",this.em(n)),this.setDeltaW([s,e],this.getDeltaW([r,i],[0,o])),this.adjustOverDepth(e,i)}}).kind=un.prototype.kind,t.styles={'mjx-mover:not([limits="false"])':{"padding-top":".1em"},[["base","over"].map(t=>`mjx-mover:not([limits="false"]) > mjx-${t}`).join(", ")]:{display:"block","text-align":"left"}},t}(),bd=function(){var t;const e=md(dd);return(t=class extends e{toCHTML(t){if(this.toEmbellishedCHTML(t))return;if(this.hasMovableLimits())return super.toCHTML(t),void this.adaptor.setAttribute(this.dom[0],"limits","false");this.dom=this.standardChtmlNodes(t);const e=this.adaptor.append(this.dom[0],this.html("mjx-over")),s=this.adaptor.append(this.adaptor.append(this.dom[0],this.html("mjx-box")),this.html("mjx-munder")),i=this.adaptor.append(this.adaptor.append(s,this.html("mjx-row")),this.html("mjx-base")),r=this.adaptor.append(this.adaptor.append(s,this.html("mjx-row")),this.html("mjx-under"));this.overChild.toCHTML([e]),this.baseChild.toCHTML([i]),this.underChild.toCHTML([r]);const n=this.overChild.getOuterBBox(),o=this.baseChild.getOuterBBox(),a=this.underChild.getOuterBBox();this.adjustBaseHeight(i,o);const l=this.getOverKU(o,n)[0],c=this.getUnderKV(o,a)[0],h=this.getDelta(this.overChild),d=this.getDelta(this.underChild,!0);this.adaptor.setStyle(e,"paddingBottom",this.em(l)),this.adaptor.setStyle(r,"paddingTop",this.em(c)),this.setDeltaW([i,r,e],this.getDeltaW([o,a,n],[0,this.isLineBelow?0:-d,this.isLineAbove?0:h])),this.adjustOverDepth(e,n),this.adjustUnderDepth(r,a)}}).kind=hn.prototype.kind,t.styles={'mjx-munderover:not([limits="false"])':{"padding-top":".1em"},[["over","box"].map(t=>`mjx-munderover:not([limits="false"]) > mjx-${t}`).join(", ")]:{display:"block"}},t}(),Ed={base:"subList",subList:"supList",supList:"subList",psubList:"psupList",psupList:"psubList"},xd=["sup","sup","psup","psub"];function yd(t){return class extends t{combinePrePost(t,e){const s=new No(t);return s.combine(e,0,0),s}getScriptData(){const t=this.scriptData={base:null,sub:No.empty(),sup:No.empty(),psub:No.empty(),psup:No.empty(),numPrescripts:0,numScripts:0},e=this.getScriptBBoxLists();this.combineBBoxLists(t.sub,t.sup,e.subList,e.supList),this.combineBBoxLists(t.psub,t.psup,e.psubList,e.psupList),t.base=e.base[0],t.numPrescripts=e.psubList.length,t.numScripts=e.subList.length}getScriptBBoxLists(){const t={base:[],subList:[],supList:[],psubList:[],psupList:[]};let e="base";for(const s of this.childNodes)s.node.isKind("mprescripts")?e="psubList":(t[e].push(s.getOuterBBox()),e=Ed[e]);return this.firstPrescript=t.subList.length+t.supList.length+2,this.padLists(t.subList,t.supList),this.padLists(t.psubList,t.psupList),t}padLists(t,e){t.length>e.length&&e.push(No.empty())}combineBBoxLists(t,e,s,i){for(let r=0;rt.h&&(t.h=o),a>t.d&&(t.d=a),c>e.h&&(e.h=c),h>e.d&&(e.d=h)}}getScaledWHD(t){const{w:e,h:s,d:i,rscale:r}=t;return[e*r,s*r,i*r]}getCombinedUV(){const t=this.scriptData,e=this.combinePrePost(t.sub,t.psub),s=this.combinePrePost(t.sup,t.psup);return this.getUVQ(e,s)}addPrescripts(t,e,s){const i=this.scriptData;if(i.numPrescripts){const r=this.font.params.scriptspace;t.combine(i.psup,r,e),t.combine(i.psub,r,s)}return t}addPostscripts(t,e,s){const i=this.scriptData;if(i.numScripts){const r=t.w;t.combine(i.sup,r,e),t.combine(i.sub,r,s),t.w+=this.font.params.scriptspace}return t}constructor(...t){super(...t),this.scriptData=null,this.firstPrescript=0,this.getScriptData()}appendScripts(t){t.empty();const[e,s]=this.getCombinedUV();return this.addPrescripts(t,e,s),t.append(this.scriptData.base),this.addPostscripts(t,e,s),t.clean(),t}computeLineBBox(t){const e=this.baseChild.breakCount,s=this.baseChild.getLineBBox(t).copy();let i=s;const[r,n]=this.getCombinedUV();return 0===t?(i=Dc.from(this.addPrescripts(No.zero(),r,n),this.linebreakOptions.lineleading),i.append(s),this.addLeftBorders(i),i.L=this.bbox.L):t===e&&(i=this.addPostscripts(i,r,n),this.addRightBorders(i),i.R=this.bbox.R),this.addMiddleBorders(i),i}getUVQ(t,e){if(!this.UVQ){let[s,i,r]=[0,0,0];0===t.w?s=this.getU():0===e.w?s=-this.getV():[s,i,r]=super.getUVQ(t,e),this.UVQ=[s,i,r]}return this.UVQ}}}const Nd=function(){var t;const e=yd(dd);return(t=class extends e{toCHTML(t){if(this.toEmbellishedCHTML(t))return;const e=this.standardChtmlNodes(t),s=this.scriptData,i=this.node.getProperty("scriptalign")||"right left",[r,n]=Hr(i+" "+i),[o,a]=this.getCombinedUV();if(s.numPrescripts){const t=this.addScripts(this.dom[0],o,-a,!0,s.psub,s.psup,this.firstPrescript,s.numPrescripts);"right"!==r&&this.adaptor.setAttribute(t,"script-align",r)}if(this.childNodes[0].toCHTML(e),s.numScripts){const t=this.addScripts(this.dom[this.dom.length-1],o,-a,!1,s.sub,s.sup,1,s.numScripts);"left"!==n&&this.adaptor.setAttribute(t,"script-align",n)}}addScripts(t,e,s,i,r,n,o,a){const l=this.adaptor,c=e-n.d+(s-r.h),h=e<0&&0===s?r.h+e:e,d=c>0?{style:{height:this.em(c)}}:{},u=h?{style:{"vertical-align":this.em(h)}}:{},p=this.html("mjx-row"),m=this.html("mjx-row",d),f=this.html("mjx-row"),g="mjx-"+(i?"pre":"")+"scripts",b=o+2*a;for(;o mjx-row > mjx-cell":{"text-align":"right"},'[script-align="left"] > mjx-row > mjx-cell':{"text-align":"left"},'[script-align="center"] > mjx-row > mjx-cell':{"text-align":"center"},'[script-align="right"] > mjx-row > mjx-cell':{"text-align":"right"},"mjx-none":{display:"inline-block",height:"1px"}},t}(),vd=.333;function Td(t){return class extends t{get tableRows(){return this.childNodes}findContainer(){let t=this,e=t.parent;for(;e&&(e.node.notParent||e.node.isKind("mrow"));)t=e,e=e.parent;this.container=e,this.containerI=t.node.childPosition()}getPercentageWidth(){if(this.hasLabels)this.bbox.pwidth=No.fullWidth;else{const t=this.node.attributes.get("width");Ur(t)&&(this.bbox.pwidth=t)}}stretchRows(){const t=this.node.attributes.get("equalrows"),e=t?this.getEqualRowHeight():0,{H:s,D:i}=t?this.getTableData():{H:[0],D:[0]},r=this.tableRows;for(let n=0;ne&&(e=s)}}}}if(null!==e){const i=this.getTableData().W;for(const r of s){let s=r.getBBox().w;r.coreMO().getStretchedVariant([Math.max(e,s)/r.coreRScale()]),s=r.getBBox().w,s>i[t]&&(i[t]=s)}}}breakColumn(t,e,s){if("linebreak"!==this.jax.math.root.attributes.get("overflow")||!this.jax.math.display)return;const{H:i,D:r}=this.getTableData();let n=0,o=0;for(const s of this.tableRows){const a=s.getChild(t);if(a){const l=s.getBBox().rscale,c=a.getBBox();if(a&&c.w*l>e){a.childNodes[0].breakToWidth(e);const o=s.node.attributes.get("rowalign");this.updateHDW(a,t,n,o,i,r)}c.w*l>o&&(o=c.w*l)}const l=s.getBBox();l.h=i[n],l.d=r[n],n++}("fit"===s||"auto"===s||Ur(s)||o>this.cWidths[t])&&(this.cWidths[t]=o)}getTableData(){if(this.data)return this.data;const t=new Array(this.numRows).fill(0),e=new Array(this.numRows).fill(0),s=new Array(this.numCols).fill(0),i=new Array(this.numRows),r=new Array(this.numRows),n=[0],o=this.tableRows;for(let a=0;ao[e]&&(o[e]=c)}recordPWidthCell(t,e){t.childNodes[0]&&t.childNodes[0].getBBox().pwidth&&this.pwidthCells.push([t,e])}setColumnPWidths(){const t=this.cWidths;for(const[e,s]of this.pwidthCells)e.setChildPWidths(!1,t[s])&&(e.invalidateBBox(),e.getBBox())}getBBoxHD(t){const[e,s]=this.getAlignmentRow();if(null===s){const s=this.font.params.axis_height,i=t/2;return{top:[0,t],center:[i,i],bottom:[t,0],baseline:[i,i],axis:[i+s,i-s]}[e]||[i,i]}{const i=this.getVerticalPosition(s,e);return[i,t-i]}}getBBoxLR(){var t;if(this.hasLabels){const t=this.node.attributes,e=t.get("side");let[s,i]=this.getPadAlignShift(e);const r=this.hasLabels&&!!t.get("data-width-includes-label");return r&&this.frame&&this.fSpace[0]&&(s-=this.fSpace[0]),"center"!==i||r?"left"===e?[s,0]:[0,s]:[s,s]}return[(null===(t=this.bbox)||void 0===t?void 0:t.L)||0,0]}getPadAlignShift(t){const{L:e}=this.getTableData();let s=e+this.length2em(this.node.attributes.get("minlabelspacing"));const[i,r]=null==this.styles?["",""]:[this.styles.get("padding-left"),this.styles.get("padding-right")];(i||r)&&(s=Math.max(s,this.length2em(i||"0"),this.length2em(r||"0")));let[n,o]=this.getAlignShift();return n===t&&(o="left"===t?Math.max(s,o)-s:Math.min(-s,o)+s),[s,n,o]}getWidth(){return this.pWidth||this.getBBox().w}adjustWideTable(){const t=this.node.attributes;if("auto"!==t.get("width"))return;const[e,s]=this.getPadAlignShift(t.get("side")),i=Math.max(this.containerWidth/10,this.containerWidth-e-("center"===s?e:0));this.naturalWidth()>i&&this.adjustColumnWidths(i)}naturalWidth(){return zo(this.getComputedWidths().concat(this.cLines,this.cSpace))+2*this.fLine+this.fSpace[0]+this.fSpace[2]}getEqualRowHeight(){const{H:t,D:e}=this.getTableData(),s=Array.from(t.keys()).map(s=>t[s]+e[s]);return Math.max(...s)}getComputedWidths(){const t=this.getTableData().W;let e=Array.from(t.keys()).map(e=>"number"==typeof this.cWidths[e]?this.cWidths[e]:t[e]);return this.node.attributes.get("equalcolumns")&&(e=Array(e.length).fill(Vo(e))),e}getColumnWidths(){const t=this.node.attributes.get("width");if(this.node.attributes.get("equalcolumns"))return this.getEqualColumns(t);const e=this.getColumnAttributes("columnwidth",0);return"auto"===t?this.getColumnWidthsAuto(e):Ur(t)?this.getColumnWidthsPercent(e):this.getColumnWidthsFixed(e,this.length2em(t))}getEqualColumns(t){const e=Math.max(1,this.numCols);let s;if("auto"===t){const{W:t}=this.getTableData();s=Vo(t)}else if(Ur(t))s=this.percent(1/e);else{const i=zo([].concat(this.cLines,this.cSpace))+this.fSpace[0]+this.fSpace[2];s=Math.max(0,this.length2em(t)-i)/e}return Array(this.numCols).fill(s)}getColumnWidthsAuto(t){return t.map(t=>"auto"===t||"fit"===t?null:Ur(t)?t:this.length2em(t))}getColumnWidthsPercent(t){const e=t.includes("fit"),{W:s}=e?this.getTableData():{W:null};return Array.from(t.keys()).map(i=>{const r=t[i];return"fit"===r?null:"auto"===r?e?s[i]:null:Ur(r)?r:this.length2em(r)})}getColumnWidthsFixed(t,e){const s=Array.from(t.keys()),i=s.filter(e=>"fit"===t[e]),r=s.filter(e=>"auto"===t[e]),n=i.length||r.length,{W:o}=n?this.getTableData():{W:null},a=e-zo([].concat(this.cLines,this.cSpace))-this.fSpace[0]-this.fSpace[2];let l=a;s.forEach(e=>{const s=t[e];l-="fit"===s||"auto"===s?o[e]:this.length2em(s,a)});const c=n&&l>0?l/n:0;return s.map(e=>{const s=t[e];return"fit"===s?o[e]+c:"auto"===s?o[e]+(0===i.length?c:0):this.length2em(s,a)})}adjustColumnWidths(t){const{W:e}=this.getTableData(),s=this.getColumnAttributes("columnwidth",0),i=Array.from(s.keys()),r=[...i.filter(t=>"fit"===s[t]).sort((t,s)=>e[s]-e[t]),...i.filter(t=>"auto"===s[t]).sort((t,s)=>e[s]-e[t]),...i.filter(t=>Ur(s[t])).sort((t,s)=>e[s]-e[t]),...i.filter(t=>"fit"!==s[t]&&"auto"!==s[t]&&!Ur(s[t])).sort((t,s)=>e[s]-e[t])];if(!r.length)return;this.cWidths=i.map(t=>"number"==typeof this.cWidths[t]?this.cWidths[t]:e[t]);const n=t-zo([].concat(this.cLines,this.cSpace))-this.fSpace[0]-this.fSpace[2];let o=zo(this.cWidths)-n,a=0,l=0;for(;lthis.cWidths[t]*=o)}getVerticalPosition(t,e){const s=this.node.attributes.get("equalrows"),{H:i,D:r}=this.getTableData(),n=s?this.getEqualRowHeight():0,o=this.getRowHalfSpacing();let a=this.fLine;for(let e=0;et/2);return t.unshift(this.fSpace[1]),t.push(this.fSpace[1]),t}getColumnHalfSpacing(){const t=this.cSpace.map(t=>t/2);return t.unshift(this.fSpace[0]),t.push(this.fSpace[2]),t}getAlignmentRow(){const[t,e]=Hr(this.node.attributes.get("align"));if(null==e)return[t,null];let s=parseInt(e);return s<0&&(s+=this.numRows+1),[t,s<1||s>this.numRows?null:s-1]}getColumnAttributes(t,e=1){const s=this.numCols-e,i=this.getAttributeArray(t);if(0===i.length)return null;for(;i.lengths&&i.splice(s),i}getRowAttributes(t,e=1){const s=this.numRows-e,i=this.getAttributeArray(t);if(0===i.length)return null;for(;i.lengths&&i.splice(s),i}getAttributeArray(t){const e=this.node.attributes.get(t);return e?Hr(e):[this.node.attributes.getDefault(t)]}addEm(t,e=1){return t?t.map(t=>this.em(t/e)):null}convertLengths(t){return t?t.map(t=>this.length2em(t)):null}constructor(t,e,s=null){super(t,e,s),this.numCols=0,this.numRows=0,this.data=null,this.pwidthCells=[],this.pWidth=0,this.adjustHD={top:(t,e,s,i,r)=>{t>s[r]&&(i[r]-=t-s[r],s[r]=t),t+e>s[r]+i[r]&&(i[r]=t+e-s[r])},bottom:(t,e,s,i,r)=>{e>i[r]&&(s[r]-=e-i[r],i[r]=e),t+e>s[r]+i[r]&&(s[r]=t+e-i[r])},center:(t,e,s,i,r)=>{t+e>s[r]+i[r]&&(s[r]=i[r]=(t+e)/2)},other:(t,e,s,i,r)=>{t>s[r]&&(s[r]=t),e>i[r]&&(i[r]=e)}},this.numCols=Vo(this.tableRows.map(t=>t.numCells)),this.numRows=this.childNodes.length,this.hasLabels=this.childNodes.reduce((t,e)=>t||e.node.isKind("mlabeledtr"),!1),this.findContainer(),this.isTop=!this.container||this.container.node.isKind("math")&&!this.container.parent,this.isTop&&(this.jax.table=this),this.getPercentageWidth();const i=this.node.attributes,r=i.get("frame");this.frame="none"!==r,this.fframe=this.frame||void 0!==i.get("data-frame-styles"),this.fLine=this.frame?.07:0,this.fSpace=this.getFrameSpacing(),this.cSpace=this.convertLengths(this.getColumnAttributes("columnspacing")),this.rSpace=this.convertLengths(this.getRowAttributes("rowspacing")),this.cLines=this.getColumnAttributes("columnlines").map(t=>"none"===t?0:.07),this.rLines=this.getRowAttributes("rowlines").map(t=>"none"===t?0:.07),this.cWidths=this.getColumnWidths(),this.adjustWideTable(),this.stretchColumns(),this.stretchRows()}getStyles(){super.getStyles();const t=this.node.attributes.get("data-frame-styles");if(!t)return;this.styles||(this.styles=new Wo(""));const e=t.split(/ /);for(const t of Ro.keys()){const s=e[t];"none"!==s&&this.styles.set(`border-${Ro[t]}`,`.07em ${s}`)}}computeBBox(t,e=!1){const{H:s,D:i}=this.getTableData();let r,n;if(this.node.attributes.get("equalrows")){const t=this.getEqualRowHeight();r=zo([].concat(this.rLines,this.rSpace))+t*this.numRows}else r=zo(s.concat(i,this.rLines,this.rSpace));r+=2*(this.fLine+this.fSpace[1]),n=this.naturalWidth();const o=this.node.attributes.get("width");"auto"!==o&&(n=Math.max(this.length2em(o,0)+2*this.fLine,n));const[a,l]=this.getBBoxHD(r);t.h=a,t.d=l,t.w=n;const[c,h]=this.getBBoxLR();t.L=c,t.R=h,Ur(o)||this.setColumnPWidths()}setChildPWidths(t,e,s){const i=this.node.attributes.get("width");if(!Ur(i))return!1;this.hasLabels||(this.bbox.pwidth="",this.container.bbox.pwidth="");const{w:r,L:n,R:o}=this.bbox,a=this.node.attributes.get("data-width-includes-label"),l=Math.max(r,this.length2em(i,Math.max(e,n+r+o)))-(a?n+o:0),c=this.node.attributes.get("equalcolumns")?Array(this.numCols).fill(this.percent(1/Math.max(1,this.numCols))):this.getColumnAttributes("columnwidth",0);return this.cWidths=this.getColumnWidthsFixed(c,l),this.pWidth=this.naturalWidth(),this.isTop&&(this.bbox.w=this.pWidth),this.setColumnPWidths(),this.pWidth!==r&&this.parent.invalidateBBox(),this.pWidth!==r}getAlignShift(){return this.isTop?super.getAlignShift():[this.container.getChildAlign(this.containerI),0]}}}const wd=function(){var t;const e=Td(Jc);return t=class extends e{constructor(t,e,s=null){super(t,e,s),this.itable=this.html("mjx-itable"),this.labels=this.html("mjx-itable")}getAlignShift(){const t=super.getAlignShift();return this.isTop||(t[1]=0),t}toCHTML(t){const e=this.standardChtmlNodes(t);this.adaptor.append(e[0],this.html("mjx-table",{},[this.itable]));for(const t of this.childNodes)t.toCHTML([this.itable]);this.padRows(),this.handleColumnSpacing(),this.handleColumnLines(),this.handleColumnWidths(),this.handleRowSpacing(),this.handleRowLines(),this.handleRowHeights(),this.handleFrame(),this.handleWidth(),this.handleLabels(),this.handleAlign(),this.handleJustify(),this.shiftColor()}shiftColor(){const t=this.adaptor,e=t.getStyle(this.dom[0],"backgroundColor");e&&(t.setStyle(this.dom[0],"backgroundColor",""),t.setStyle(this.itable,"backgroundColor",e))}padRows(){const t=this.adaptor;for(const e of t.childNodes(this.itable))for(;t.childNodes(e).length1&&"0.4em"!==r||"0"!==r&&1===s)&&this.adaptor.setStyle(o,"paddingLeft",r),(s1&&"0.215em"!==r||s&&1===i)&&this.adaptor.setStyle(e.dom[0],"paddingTop",r),(i mjx-itable":{"vertical-align":"middle","text-align":"left","box-sizing":"border-box"},"mjx-labels > mjx-itable":{position:"absolute",top:0},'mjx-mtable[justify="left"]':{"text-align":"left"},'mjx-mtable[justify="right"]':{"text-align":"right"},'mjx-mtable[justify="left"][side="left"]':{"padding-right":"0 ! important"},'mjx-mtable[justify="left"][side="right"]':{"padding-left":"0 ! important"},'mjx-mtable[justify="right"][side="left"]':{"padding-right":"0 ! important"},'mjx-mtable[justify="right"][side="right"]':{"padding-left":"0 ! important"},"mjx-mtable[align]":{"vertical-align":"baseline"},'mjx-mtable[align="top"] > mjx-table':{"vertical-align":"top"},'mjx-mtable[align="bottom"] > mjx-table':{"vertical-align":"bottom"},'mjx-mtable[side="right"] mjx-labels':{"min-width":"100%"}},t}();function Cd(t){return class extends t{get numCells(){return this.childNodes.length}get labeled(){return!1}get tableCells(){return this.childNodes}getChild(t){return this.childNodes[t]}getChildBBoxes(){return this.childNodes.map(t=>t.getBBox())}stretchChildren(t=null){const e=[],s=this.labeled?this.childNodes.slice(1):this.childNodes;for(const t of s){const s=t.childNodes[0];s.canStretch(Lc.Vertical)&&e.push(s)}const i=e.length,r=this.childNodes.length;if(i&&r>1&&!t){let e=0,n=0;const o=i>1&&i===r;for(const t of s){const s=t.childNodes[0],i=s.stretch.dir===Lc.None;if(o||i){const{h:t,d:r}=s.getBBox(i);t>e&&(e=t),r>n&&(n=r)}}t=[e,n]}if(t)for(const s of e){const e=s.coreRScale();s.coreMO().getStretchedVariant(t.map(t=>t*e))}}get fixesPWidth(){return!1}}}function kd(t){return class extends t{get numCells(){return Math.max(0,this.childNodes.length-1)}get labeled(){return!0}get tableCells(){return this.childNodes.slice(1)}getChild(t){return this.childNodes[t+1]}getChildBBoxes(){return this.childNodes.slice(1).map(t=>t.getBBox())}}}const _d=function(){var t;const e=Cd(Jc);return(t=class extends e{toCHTML(t){super.toCHTML(t);const e=this.node.attributes.get("rowalign");"baseline"!==e&&this.adaptor.setAttribute(this.dom[0],"rowalign",e);const{h:s,d:i}=this.getBBox();this.adaptor.setStyle(this.dom[0],"height",this.em(s+i))}}).kind=bn.prototype.kind,t.styles={"mjx-mtr":{display:"table-row"},'mjx-mtr[rowalign="top"] > mjx-mtd':{"vertical-align":"top"},'mjx-mtr[rowalign="center"] > mjx-mtd':{"vertical-align":"middle"},'mjx-mtr[rowalign="bottom"] > mjx-mtd':{"vertical-align":"bottom"},'mjx-mtr[rowalign="baseline"] > mjx-mtd':{"vertical-align":"baseline"},'mjx-mtr[rowalign="axis"] > mjx-mtd':{"vertical-align":".25em"}},t}(),Ld=function(){var t;const e=kd(_d);return(t=class extends e{toCHTML(t){super.toCHTML(t);const e=this.adaptor.firstChild(this.dom[0]);if(e){this.adaptor.remove(e);const t=this.node.attributes.get("rowalign"),s="baseline"!==t&&"axis"!==t?{rowalign:t}:{},i=this.html("mjx-mtr",s,[e]);this.adaptor.append(this.parent.labels,i)}}markUsed(){super.markUsed(),this.jax.wrapperUsage.add(_d.kind)}}).kind=En.prototype.kind,t.styles={"mjx-mlabeledtr":{display:"table-row"},'mjx-mlabeledtr[rowalign="top"] > mjx-mtd':{"vertical-align":"top"},'mjx-mlabeledtr[rowalign="center"] > mjx-mtd':{"vertical-align":"middle"},'mjx-mlabeledtr[rowalign="bottom"] > mjx-mtd':{"vertical-align":"bottom"},'mjx-mlabeledtr[rowalign="baseline"] > mjx-mtd':{"vertical-align":"baseline"},'mjx-mlabeledtr[rowalign="axis"] > mjx-mtd':{"vertical-align":".25em"}},t}();function Ad(t){return class extends t{get fixesPWidth(){return!1}invalidateBBox(){this.bboxComputed=!1,this.lineBBox=[]}getWrapWidth(t){const e=this.parent.parent,s=this.parent,i=this.node.childPosition()-(s.labeled?1:0);return"number"==typeof e.cWidths[i]?e.cWidths[i]:e.getTableData().W[i]}getChildAlign(t){return this.node.attributes.get("columnalign")}}}const Rd=function(){var t;const e=Ad(Jc);return(t=class extends e{toCHTML(t){super.toCHTML(t);const e=this.node.attributes.get("rowalign"),s=this.node.attributes.get("columnalign");e!==this.parent.node.attributes.get("rowalign")&&this.adaptor.setAttribute(this.dom[0],"rowalign",e),"center"===s||"mlabeledtr"===this.parent.kind&&this===this.parent.childNodes[0]&&s===this.parent.parent.node.attributes.get("side")||this.adaptor.setStyle(this.dom[0],"textAlign",s),this.parent.parent.node.getProperty("useHeight")&&this.adaptor.append(this.dom[0],this.html("mjx-tstrut"))}}).kind=xn.prototype.kind,t.styles={"mjx-mtd":{display:"table-cell","text-align":"center",padding:".215em .4em"},"mjx-mtd:first-child":{"padding-left":0},"mjx-mtd:last-child":{"padding-right":0},"mjx-mtable > * > mjx-itable > *:first-child > mjx-mtd":{"padding-top":0},"mjx-mtable > * > mjx-itable > *:last-child > mjx-mtd":{"padding-bottom":0},"mjx-tstrut":{display:"inline-block",height:"1em","vertical-align":"-.25em"},'mjx-labels[align="left"] > mjx-mtr > mjx-mtd':{"text-align":"left"},'mjx-labels[align="right"] > mjx-mtr > mjx-mtd':{"text-align":"right"},"mjx-mtd[extra]":{padding:0},'mjx-mtd[rowalign="top"]':{"vertical-align":"top"},'mjx-mtd[rowalign="center"]':{"vertical-align":"middle"},'mjx-mtd[rowalign="bottom"]':{"vertical-align":"bottom"},'mjx-mtd[rowalign="baseline"]':{"vertical-align":"baseline"},'mjx-mtd[rowalign="axis"]':{"vertical-align":".25em"}},t}(),Sd={dx:".2em",dy:".1em",postDelay:600,clearDelay:100,hoverTimer:new Map,clearTimer:new Map,stopTimers:(t,e)=>{e.clearTimer.has(t)&&(clearTimeout(e.clearTimer.get(t)),e.clearTimer.delete(t)),e.hoverTimer.has(t)&&(clearTimeout(e.hoverTimer.get(t)),e.hoverTimer.delete(t))}};function Md(t){return class extends t{get selected(){const t=this.node.attributes.get("selection"),e=Math.max(1,Math.min(this.childNodes.length,t))-1;return this.childNodes[e]||this.wrap(this.node.selected)}getParameters(){const t=this.node.attributes.get("data-offsets"),[e,s]=Hr(t||"");this.tipDx=this.length2em(e||Sd.dx),this.tipDy=this.length2em(s||Sd.dy)}constructor(t,e,s=null){super(t,e,s);const i=this.constructor.actions,r=this.node.attributes.get("actiontype"),[n,o]=i.get(r)||[(t,e)=>{},{}];this.action=n,this.data=o,this.getParameters()}computeBBox(t,e=!1){t.updateFrom(this.selected.getOuterBBox()),this.selected.setChildPWidths(e)}get breakCount(){return this.node.isEmbellished?this.selected.coreMO().embellishedBreakCount:this.selected.breakCount}computeLineBBox(t){return this.getChildLineBBox(this.selected,t)}}}const Id=function(){var t;const e=Md(Jc);return(t=class extends e{setEventHandler(t,e,s=null){(s?[s]:this.dom).forEach(s=>s.addEventListener(t,e))}Em(t){return this.em(t)}toCHTML(t){if(this.toEmbellishedCHTML(t))return;const e=this.standardChtmlNodes(t);this.selected.toCHTML(e),this.action(this,this.data)}}).kind=on.prototype.kind,t.styles={"mjx-maction":{position:"relative"},"mjx-maction > mjx-tool":{display:"none",position:"absolute",bottom:0,right:0,width:0,height:0,"z-index":500},"mjx-tool > mjx-tip":{display:"inline-block","line-height":0,padding:".2em",border:"1px solid #888","background-color":"#F8F8F8",color:"black","box-shadow":"2px 2px 5px #AAAAAA"},"mjx-maction[toggle]":{cursor:"pointer"},"mjx-status":{display:"block",position:"fixed",left:"1em",bottom:"1em","min-width":"25%",padding:".2em .4em",border:"1px solid #888","font-size":"90%","background-color":"#F8F8F8",color:"black"},"mjx-container [data-mjx-collapsed]":{color:"#55F"},"@media (prefers-color-scheme: dark) /* chtml maction */":{"mjx-tool > mjx-tip":{border:"1px solid #888","background-color":"#303030",color:"#E0E0E0","box-shadow":"2px 2px 5px #000"},"mjx-status":{"background-color":"#303030",color:"#E0E0E0"},"mjx-container [data-mjx-collapsed]":{color:"#88F"}}},t.actions=new Map([["toggle",[(t,e)=>{t.dom.forEach(e=>{t.adaptor.setAttribute(e,"toggle",t.node.attributes.get("selection"))});const s=t.factory.jax.math,i=t.factory.jax.document,r=t.node;t.setEventHandler("click",t=>{s.end.node||(s.start.node=s.end.node=s.typesetRoot,s.start.n=s.end.n=0),r.nextToggleSelection(),s.rerender(i,r.attributes.get("data-maction-id")?or.ENRICHED:or.RERENDER),t.stopPropagation()})},{}]],["tooltip",[(t,e)=>{const s=t.childNodes[1];if(s)if(s.node.isKind("mtext")){const e=s.node.getText();t.dom.forEach(s=>t.adaptor.setAttribute(s,"title",e))}else{const i=t.adaptor;for(const r of t.dom){const n=i.append(r,t.html("mjx-tool",{style:{bottom:t.Em(-t.tipDy),right:t.Em(-t.tipDx)}},[t.html("mjx-tip")]));s.toCHTML([i.firstChild(n)]),t.setEventHandler("mouseover",t=>{e.stopTimers(r,e);const s=setTimeout(()=>i.setStyle(n,"display","block"),e.postDelay);e.hoverTimer.set(r,s),t.stopPropagation()},r),t.setEventHandler("mouseout",t=>{e.stopTimers(r,e);const s=setTimeout(()=>i.setStyle(n,"display",""),e.clearDelay);e.clearTimer.set(r,s),t.stopPropagation()},r)}}},Sd]],["statusline",[(t,e)=>{const s=t.childNodes[1];if(s&&s.node.isKind("mtext")){const i=t.adaptor,r=s.node.getText();t.dom.forEach(t=>i.setAttribute(t,"statusline",r)),t.setEventHandler("mouseover",s=>{if(null===e.status){const s=i.body(i.document);e.status=i.append(s,t.html("mjx-status",{},[t.text(r)]))}s.stopPropagation()}),t.setEventHandler("mouseout",t=>{e.status&&(i.remove(e.status),e.status=null),t.stopPropagation()})}},{status:null}]]]),t}();function Od(t){return class extends t{constructor(t,e,s=null){super(t,e,s),this.getParameters()}getParameters(){const{width:t,height:e,valign:s,src:i,index:r}=this.node.attributes.getList("width","height","valign","src","index");if(i)this.width="auto"===t?1:this.length2em(t),this.height="auto"===e?1:this.length2em(e),this.valign=this.length2em(s||"0");else{const t=String.fromCodePoint(parseInt(r)),e=this.node.factory;this.charWrapper=this.wrap(e.create("text").setText(t)),this.charWrapper.parent=this}}computeBBox(t,e=!1){this.charWrapper?t.updateFrom(this.charWrapper.getBBox()):(t.w=this.width,t.h=this.height+this.valign,t.d=-this.valign)}}}const Dd=function(){var t;const e=Od(Jc);return(t=class extends e{toCHTML(t){const e=this.standardChtmlNodes(t);if(this.charWrapper)return void this.charWrapper.toCHTML(e);const{src:s,alt:i}=this.node.attributes.getList("src","alt"),r={width:this.em(this.width),height:this.em(this.height)};this.valign&&(r.verticalAlign=this.em(this.valign));const n=this.html("img",{src:s,style:r,alt:i,title:i});this.adaptor.append(e[0],n)}}).kind=vn.prototype.kind,t.styles={"mjx-mglyph > img":{display:"inline-block",border:0,padding:0}},t}();function Pd(t){return class extends t{computeBBox(t,e=!1){if(this.childNodes.length){const{w:e,h:s,d:i}=this.childNodes[0].getBBox();t.w=e,t.h=s,t.d=i}}get breakCount(){return this.node.isEmbellished?this.coreMO().embellishedBreakCount:this.childNodes[0].breakCount}}}function Bd(t){class e extends t{constructor(t,e,s=null){super(t,e,s),this.rscale=this.getRScale()}computeBBox(t,e=!1){const s=this.node.getXML(),i=this.getHDW(s,"use","force"),{h:r,d:n,w:o}=i?this.splitHDW(i):this.measureXmlNode(s);t.w=o,t.h=r,t.d=n}getHTML(){let t=this.adaptor.clone(this.node.getXML());const e=this.getFontStyles();return(this.getHDW(t,"force")||1!==this.jax.options.scale)&&(t=this.addHDW(t,e)),this.html("mjx-html",{variant:this.parent.variant,style:e},[t])}getHDW(t,e,s=e){const i=this.jax.options.htmlHDW,r=this.adaptor.getAttribute(t,"data-mjx-hdw");return!r||i!==e&&i!==s?null:r}splitHDW(t){const e=1/this.metrics.scale,[s,i,r]=Hr(t).map(t=>this.length2em(t||"0")*e);return{h:s,d:i,w:r}}getFontStyles(){var t;const e=this.adaptor,s=this.metrics;return{"font-family":(null===(t=this.parent.styles)||void 0===t?void 0:t.get("font-family"))||s.family||e.fontFamily(e.parent(this.jax.math.start.node))||"initial","font-size":this.jax.fixed(s.em*this.rscale)+"px"}}measureXmlNode(t){const e=this.adaptor,s=this.html("mjx-xml-block",{style:{display:"inline-block"}},[e.clone(t)]),i=this.html("mjx-baseline",{style:{display:"inline-block",width:0,height:0}}),r=this.getFontStyles(),n=this.html("mjx-measure-xml",{style:r},[i,s]),o=this.jax.container;e.append(e.parent(this.jax.math.start.node),o),e.append(o,n);const a=this.metrics,l=a.em*a.scale*this.rscale,{left:c,right:h,bottom:d,top:u}=e.nodeBBox(s),p=(h-c)/l,m=(e.nodeBBox(i).top-u)/l,f=(d-u)/l-m;return e.remove(o),e.remove(n),{w:p,h:m,d:f}}getStyles(){}getScale(){}getVariant(){}}return e.autoStyle=!1,e.styles={"mjx-measure-xml":{position:"absolute",left:0,top:0,display:"inline-block","line-height":"normal","white-space":"normal"},"mjx-html":{display:"inline-block","line-height":"normal","text-align":"initial","white-space":"initial"},"mjx-html-holder":{display:"block",position:"absolute",top:0,left:0,bottom:0,right:0}},e}const Fd=function(){var t;const e=Pd(Jc);return(t=class extends e{toCHTML(t){if(this.toEmbellishedCHTML(t))return;const e=this.standardChtmlNodes(t);this.childNodes.length&&this.childNodes[0].toCHTML(e)}}).kind=Tn.prototype.kind,t}(),jd=function(){var t;return(t=class extends Jc{toCHTML(t){super.toCHTML(t)}computeBBox(){return this.bbox}}).kind=Cn.prototype.kind,t}(),Ud=function(){var t;return(t=class extends Jc{}).kind=wn.prototype.kind,t.styles={"mjx-annotation-xml":{"font-family":"initial","line-height":"normal"}},t}(),Hd=function(){var t;const e=Bd(Jc);return(t=class extends e{toCHTML(t){this.markUsed(),this.dom=[this.adaptor.append(t[0],this.getHTML())]}addHDW(t,e){const s=this.jax.options.scale,{h:i,d:r,w:n}=this.bbox,o=s*this.metrics.scale;return e.width=this.em(n*o),e.height=this.em((i+r)*o),e["vertical-align"]=this.em(-r*o),e.position="relative",this.html("mjx-html-holder",{style:{transform:`scale(${this.jax.fixed(s)})`,"transform-origin":"top left"}},[t])}}).kind=kr.prototype.kind,t}();function qd(t){return class extends t{computeBBox(t,e=!1){super.computeBBox(t,e),this.childNodes[0]&&this.childNodes[0].bbox.ic&&(t.ic=this.childNodes[0].bbox.ic)}}}const Wd=function(){var t;const e=qd(Jc);return(t=class extends e{toCHTML(t){super.toCHTML(t),this.dom.forEach(t=>this.adaptor.setAttribute(t,"texclass",fr[this.node.texClass]))}}).kind=kn.prototype.kind,t}();function zd(t){return class extends t{remappedText(t,e){const s=this.parent.stretch.c;return s?[s]:this.parent.remapChars(this.unicodeChars(t,e))}computeBBox(t,e=!1){const s=this.parent.variant,i=this.node.getText();if("-explicitFont"===s){const e=this.jax.getFontData(this.parent.styles),{w:r,h:n,d:o}=this.jax.measureText(i,s,e);t.h=n,t.d=o,t.w=r}else{const e=this.remappedText(i,s);let r="";t.empty();for(let i=0;i1&&(t.sk=0),t.clean()}}addUtextBBox(t,e,s){if(e){const{h:i,d:r,w:n}=this.jax.measureText(e,s);this.updateBBox(t,i,r,n)}return""}updateBBox(t,e,s,i){t.w+=i,e>t.h&&(t.h=e),s>t.d&&(t.d=s)}getStyles(){}getVariant(){}getScale(){}getSpace(){}}}const Vd=function(){var t;const e=zd(Jc);return t=class extends e{toCHTML(t){this.markUsed();const e=t[0],s=this.adaptor,i=this.parent.variant,r=this.node.getText();if(0===r.length)return;const n=this.getBBox();if("-explicitFont"===i)s.append(e,this.jax.unknownText(r,i,n.w));else{let t="";const o=this.remappedText(r,i),a=o.length>1?this.em(this.parent.getBBox().h):"",l=o.length;for(let r=0;r mjx-math.NCM-N[breakable] > *':{"font-family":"MJX-NCM-ZERO, MJX-NCM-N"},".NCM-N":{"font-family":"MJX-NCM-ZERO, MJX-NCM-N"},".NCM-B":{"font-family":"MJX-NCM-ZERO, MJX-NCM-B"},".NCM-I":{"font-family":"MJX-NCM-ZERO, MJX-NCM-I"},".NCM-BI":{"font-family":"MJX-NCM-ZERO, MJX-NCM-BI"},".NCM-DS":{"font-family":"MJX-NCM-ZERO, MJX-NCM-DS"},".NCM-F":{"font-family":"MJX-NCM-ZERO, MJX-NCM-F"},".NCM-FB":{"font-family":"MJX-NCM-ZERO, MJX-NCM-FB"},".NCM-SS":{"font-family":"MJX-NCM-ZERO, MJX-NCM-SS"},".NCM-SSB":{"font-family":"MJX-NCM-ZERO, MJX-NCM-SSB"},".NCM-SSI":{"font-family":"MJX-NCM-ZERO, MJX-NCM-SSI"},".NCM-SSBI":{"font-family":"MJX-NCM-ZERO, MJX-NCM-SSBI"},".NCM-M":{"font-family":"MJX-NCM-ZERO, MJX-NCM-M"},".NCM-SO":{"font-family":"MJX-NCM-ZERO, MJX-NCM-SO"},".NCM-LO":{"font-family":"MJX-NCM-ZERO, MJX-NCM-LO"},".NCM-S3":{"font-family":"MJX-NCM-ZERO, MJX-NCM-S3"},".NCM-S4":{"font-family":"MJX-NCM-ZERO, MJX-NCM-S4"},".NCM-S5":{"font-family":"MJX-NCM-ZERO, MJX-NCM-S5"},".NCM-S6":{"font-family":"MJX-NCM-ZERO, MJX-NCM-S6"},".NCM-S7":{"font-family":"MJX-NCM-ZERO, MJX-NCM-S7"},".NCM-MI":{"font-family":"MJX-NCM-ZERO, MJX-NCM-MI"},".NCM-C":{"font-family":"MJX-NCM-ZERO, MJX-NCM-C"},".NCM-CB":{"font-family":"MJX-NCM-ZERO, MJX-NCM-CB"},".NCM-OS":{"font-family":"MJX-NCM-ZERO, MJX-NCM-OS"},".NCM-OB":{"font-family":"MJX-NCM-ZERO, MJX-NCM-OB"},".NCM-V":{"font-family":"MJX-NCM-ZERO, MJX-NCM-V"},".NCM-LT":{"font-family":"MJX-NCM-ZERO, MJX-NCM-LT"},".NCM-RB":{"font-family":"MJX-NCM-ZERO, MJX-NCM-RB"},".NCM-EM":{"font-family":"MJX-NCM-ZERO, MJX-NCM-EM"},".NCM-B-a":{"font-family":"MJX-NCM-ZERO, MJX-NCM-B-a"},".NCM-U":{"font-family":"MJX-NCM-ZERO, MJX-NCM-U"},".NCM-U-a":{"font-family":"MJX-NCM-ZERO, MJX-NCM-U-a"},".NCM-S":{"font-family":"MJX-NCM-ZERO, MJX-NCM-S"},".NCM-SB":{"font-family":"MJX-NCM-ZERO, MJX-NCM-SB"}}),Yd.defaultFonts=Object.assign(Object.assign({},eh.defaultFonts),{"@font-face /* MJX-NCM-ZERO */":{"font-family":"MJX-NCM-ZERO",src:'url("%%URL%%/mjx-ncm-zero.woff2") format("woff2")'},"@font-face /* MJX-BRK */":{"font-family":"MJX-BRK",src:'url("%%URL%%/mjx-ncm-brk.woff2") format("woff2")'},"@font-face /* MJX-NCM-N */":{"font-family":"MJX-NCM-N",src:'url("%%URL%%/mjx-ncm-n.woff2") format("woff2")'},"@font-face /* MJX-NCM-B */":{"font-family":"MJX-NCM-B",src:'url("%%URL%%/mjx-ncm-b.woff2") format("woff2")'},"@font-face /* MJX-NCM-I */":{"font-family":"MJX-NCM-I",src:'url("%%URL%%/mjx-ncm-i.woff2") format("woff2")'},"@font-face /* MJX-NCM-BI */":{"font-family":"MJX-NCM-BI",src:'url("%%URL%%/mjx-ncm-bi.woff2") format("woff2")'},"@font-face /* MJX-NCM-DS */":{"font-family":"MJX-NCM-DS",src:'url("%%URL%%/mjx-ncm-ds.woff2") format("woff2")'},"@font-face /* MJX-NCM-F */":{"font-family":"MJX-NCM-F",src:'url("%%URL%%/mjx-ncm-f.woff2") format("woff2")'},"@font-face /* MJX-NCM-FB */":{"font-family":"MJX-NCM-FB",src:'url("%%URL%%/mjx-ncm-fb.woff2") format("woff2")'},"@font-face /* MJX-NCM-SS */":{"font-family":"MJX-NCM-SS",src:'url("%%URL%%/mjx-ncm-ss.woff2") format("woff2")'},"@font-face /* MJX-NCM-SSB */":{"font-family":"MJX-NCM-SSB",src:'url("%%URL%%/mjx-ncm-ssb.woff2") format("woff2")'},"@font-face /* MJX-NCM-SSI */":{"font-family":"MJX-NCM-SSI",src:'url("%%URL%%/mjx-ncm-ssi.woff2") format("woff2")'},"@font-face /* MJX-NCM-SSBI */":{"font-family":"MJX-NCM-SSBI",src:'url("%%URL%%/mjx-ncm-ssbi.woff2") format("woff2")'},"@font-face /* MJX-NCM-M */":{"font-family":"MJX-NCM-M",src:'url("%%URL%%/mjx-ncm-m.woff2") format("woff2")'},"@font-face /* MJX-NCM-SO */":{"font-family":"MJX-NCM-SO",src:'url("%%URL%%/mjx-ncm-so.woff2") format("woff2")'},"@font-face /* MJX-NCM-LO */":{"font-family":"MJX-NCM-LO",src:'url("%%URL%%/mjx-ncm-lo.woff2") format("woff2")'},"@font-face /* MJX-NCM-S3 */":{"font-family":"MJX-NCM-S3",src:'url("%%URL%%/mjx-ncm-s3.woff2") format("woff2")'},"@font-face /* MJX-NCM-S4 */":{"font-family":"MJX-NCM-S4",src:'url("%%URL%%/mjx-ncm-s4.woff2") format("woff2")'},"@font-face /* MJX-NCM-S5 */":{"font-family":"MJX-NCM-S5",src:'url("%%URL%%/mjx-ncm-s5.woff2") format("woff2")'},"@font-face /* MJX-NCM-S6 */":{"font-family":"MJX-NCM-S6",src:'url("%%URL%%/mjx-ncm-s6.woff2") format("woff2")'},"@font-face /* MJX-NCM-S7 */":{"font-family":"MJX-NCM-S7",src:'url("%%URL%%/mjx-ncm-s7.woff2") format("woff2")'},"@font-face /* MJX-NCM-MI */":{"font-family":"MJX-NCM-MI",src:'url("%%URL%%/mjx-ncm-mi.woff2") format("woff2")'},"@font-face /* MJX-NCM-C */":{"font-family":"MJX-NCM-C",src:'url("%%URL%%/mjx-ncm-c.woff2") format("woff2")'},"@font-face /* MJX-NCM-CB */":{"font-family":"MJX-NCM-CB",src:'url("%%URL%%/mjx-ncm-cb.woff2") format("woff2")'},"@font-face /* MJX-NCM-OS */":{"font-family":"MJX-NCM-OS",src:'url("%%URL%%/mjx-ncm-os.woff2") format("woff2")'},"@font-face /* MJX-NCM-OB */":{"font-family":"MJX-NCM-OB",src:'url("%%URL%%/mjx-ncm-ob.woff2") format("woff2")'},"@font-face /* MJX-NCM-V */":{"font-family":"MJX-NCM-V",src:'url("%%URL%%/mjx-ncm-v.woff2") format("woff2")'},"@font-face /* MJX-NCM-LT */":{"font-family":"MJX-NCM-LT",src:'url("%%URL%%/mjx-ncm-lt.woff2") format("woff2")'},"@font-face /* MJX-NCM-RB */":{"font-family":"MJX-NCM-RB",src:'url("%%URL%%/mjx-ncm-rb.woff2") format("woff2")'},"@font-face /* MJX-NCM-EM */":{"font-family":"MJX-NCM-EM",src:'url("%%URL%%/mjx-ncm-em.woff2") format("woff2")'},"@font-face /* MJX-NCM-B-a */":{"font-family":"MJX-NCM-B-a",src:'url("%%URL%%/mjx-ncm-b-a.woff2") format("woff2")'},"@font-face /* MJX-NCM-U */":{"font-family":"MJX-NCM-U",src:'url("%%URL%%/mjx-ncm-u.woff2") format("woff2")'},"@font-face /* MJX-NCM-U-a */":{"font-family":"MJX-NCM-U-a",src:'url("%%URL%%/mjx-ncm-u-a.woff2") format("woff2")'},"@font-face /* MJX-NCM-S */":{"font-family":"MJX-NCM-S",src:'url("%%URL%%/mjx-ncm-s.woff2") format("woff2")'},"@font-face /* MJX-NCM-SB */":{"font-family":"MJX-NCM-SB",src:'url("%%URL%%/mjx-ncm-sb.woff2") format("woff2")'}}),Yd.dynamicFiles=eh.defineDynamicFiles([["latin",{normal:[[192,214],[216,239],[241,246],[248,304],[306,566],[568,591],[7680,7835],7838,[7840,7929],11377]}],["latin-b",{bold:[[192,214],[216,239],[241,246],[248,304],[306,566],[568,591],[7680,7699],[7704,7707],[7710,7719],[7722,7755],[7764,7779],[7784,7799],[7804,7833],7835,7838,[7840,7929],11377]}],["latin-i",{italic:[[192,214],[216,239],[241,246],[248,304],[306,566],[568,591],[7680,7699],[7704,7707],[7710,7719],[7722,7755],[7764,7779],[7784,7799],[7804,7833],7835,7838,[7840,7929]]}],["latin-bi",{"bold-italic":[[192,214],[216,239],[241,246],[248,304],[306,566],[568,591],[7680,7699],[7704,7707],[7710,7719],[7722,7755],[7764,7779],[7784,7799],[7804,7833],7835,7838,[7840,7929]]}],["double-struck",{normal:[8450,8461,8469,8473,8474,8477,8484,[8508,8512],[8517,8521],120120,120121,[120123,120126],[120128,120132],120134,[120138,120144],[120146,120171],[120792,120801]],"double-struck":[305,567]}],["fraktur",{normal:[8460,8465,8476,8488,8493,120068,120069,[120071,120074],[120077,120084],[120086,120092],[120094,120119],[120172,120223]],fraktur:[305,567],"bold-fraktur":[305,567]}],["script",{normal:[8458,8459,8464,8466,8467,8472,8475,8492,[8495,8497],8499,8500,119964,119966,119967,119970,119973,119974,[119977,119980],[119982,119993],119995,[119997,120003],[120005,120067]],script:[],"bold-script":[]}],["sans-serif",{normal:[[8513,8516],[120224,120431],[120662,120777],[120802,120821]],"sans-serif":[[32,47],[58,64],[91,96],[123,126],160,163,165,167,168,172,[175,177],[180,183],215,240,247,305,567,710,711,[713,715],[728,730],732,[768,776],778,780,[913,929],[931,937],[945,969],977,978,981,982,1008,1009,[1012,1014],[8208,8212],8214,8216,8217,8220,8221,8224,8225,8230,8260,8364,8486,8487,[8592,8595],8722,8734],"bold-sans-serif":[32,33,[35,47],58,59,61,63,64,[91,96],[123,126],160,163,165,167,168,172,[175,177],[180,183],215,240,247,305,567,710,711,[713,715],[728,730],732,[768,776],778,780,978,1014,[8208,8212],8214,8216,8217,8220,8221,8224,8225,8230,8260,8364,8486,8487,[8592,8595],8722,8734],"sans-serif-italic":[[32,64],[91,96],[123,126],160,163,165,167,168,172,[175,177],[180,183],215,240,247,305,567,710,711,[713,715],[728,730],732,[768,776],778,780,[913,929],[931,937],[945,969],977,978,981,982,1008,1009,[1012,1014],[8208,8212],8214,8216,8217,8220,8221,8224,8225,8230,8260,8364,8486,8487,[8592,8595],8722,8734],"sans-serif-bold-italic":[32,33,[35,59],61,63,64,[91,96],[123,126],160,163,165,167,168,172,[175,177],[180,183],215,240,247,305,567,710,711,[713,715],[728,730],732,[768,776],778,780,978,1014,[8208,8212],8214,8216,8217,8220,8221,8224,8225,8230,8260,8364,8486,8487,[8592,8595],8722,8734]}],["sans-serif-r",{"sans-serif":[[192,214],[216,239],[241,246],[248,304],[306,566],[568,591],[7680,7699],[7704,7707],[7710,7719],[7722,7755],[7764,7779],[7784,7799],[7804,7833],7835,7838,[7840,7929],11377]}],["sans-serif-b",{"bold-sans-serif":[[192,214],[216,239],[241,246],[248,304],[306,566],[568,591],[7680,7699],[7704,7707],[7710,7719],[7722,7755],[7764,7779],[7784,7799],[7804,7833],7835,7838,[7840,7929],11377]}],["sans-serif-i",{"sans-serif-italic":[[192,214],[216,239],[241,246],[248,304],[306,566],[568,591],[7680,7699],[7704,7707],[7710,7719],[7722,7755],[7764,7779],[7784,7799],[7804,7833],7835,7838,[7840,7929],11377]}],["sans-serif-bi",{"sans-serif-bold-italic":[[192,214],[216,239],[241,246],[248,304],[306,566],[568,591],[7680,7699],[7704,7707],[7710,7719],[7722,7755],[7764,7779],[7784,7799],[7804,7833],7835,7838,[7840,7929],11377]}],["sans-serif-ex",{"sans-serif":[161,162,164,166,[169,171],173,174,184,[186,191],[688,709],712,716,[718,727],731,[733,766],777,779,[781,823],[825,846],[848,879],3647,7620,7621,7624,7625,8218,8219,8222,8223,8226,8233,8240,8241,[8249,8251],8253,8255,8256,8261,8262,8274,8276,8319,8320,8353,8358,8361,8363,8369,8370,8451,8470,8471,8478,8480,8482,8494,[8592,8595],8730,8738,8960,9001,9002,9250,9251,9474,9553,9702,9773,9792,9834,9901,9902,9906,10013,10214,10215,11800,59395,[59908,59910],59913,59915,59917,59920,59927,59930,59932,59934,59935,59942,59946,59948,59951,59957,59959,59962,59966,59970,59973,60163,60164,60168,60175,60177,60178,60182,60185,60190,60191,60200,60201,60203,60209,60213,60214,60218,60219,60224,60232,60233,60237,60257,60259,60261,60270,60271,[60424,60430],60432,60433,61699,61700,61705,[61719,61726],[61729,61731],[61734,61741],61743,[61747,61752],61757,[61761,61766],[61771,61788],[61791,61797],61800,[61804,61810],61813,[61817,61819],[61822,61824],61826,61828,61829,[61832,61839],61842,61850,61854,61855,61857,61859,61860,[61863,61877],62082,62083,62110,62113,62116,[62119,62121],62124,62126,62127,[62560,62568],[62570,62578],63166,[63187,63190],63198,[64256,64260],65126],"bold-sans-serif":[161,162,164,166,[169,171],173,174,184,[186,191],[688,709],712,716,[718,727],731,[733,766],777,779,[781,823],[825,846],[848,879],3647,7620,7621,7624,7625,8218,8219,8222,8223,8226,8233,8240,8241,[8249,8251],8253,8255,8256,8261,8262,8274,8276,8319,8320,8353,8358,8361,8363,8369,8370,8451,8470,8471,8478,8480,8482,8494,[8592,8595],8730,8738,8960,9001,9002,9250,9251,9474,9553,9702,9773,9792,9834,9901,9902,9906,10013,10214,10215,11800,59395,[59908,59910],59913,59915,59917,59920,59927,59930,59932,59934,59935,59942,59946,59948,59951,59957,59962,59966,59970,59973,60163,60164,60168,[60175,60178],60182,60185,60190,60191,60200,60201,60203,60209,60213,60214,60218,60219,60224,60232,60233,60237,60257,60259,60261,60270,60271,[60424,60430],60432,60433,61699,61700,61705,[61719,61726],[61729,61731],[61734,61741],61743,[61747,61752],61757,[61761,61766],[61771,61788],[61791,61797],61800,[61804,61810],61813,[61817,61819],[61822,61824],61826,61828,61829,[61832,61839],61842,61850,61854,61855,61857,61859,61860,[61863,61877],62082,62083,62110,62113,62116,[62119,62121],62124,62126,62127,[62560,62568],[62570,62578],63166,[63187,63190],63198,[64256,64260],65126],"sans-serif-italic":[161,162,164,166,[169,171],173,174,184,[186,191],[688,709],712,716,[718,727],731,[733,766],777,779,[781,823],[825,846],[848,879],3647,7620,7621,7624,7625,8218,8219,8222,8223,8226,8233,8240,8241,[8249,8251],8253,8255,8256,8261,8262,8274,8276,8319,8320,8353,8358,8361,8363,8369,8370,8451,8470,8471,8478,8480,8482,8494,[8592,8595],8730,8738,8960,9001,9002,9250,9251,9474,9553,9702,9773,9792,9834,9901,9902,9906,10013,10214,10215,11800,59395,[59908,59910],59913,59915,59917,59920,59927,59930,59932,59934,59935,59942,59946,59948,59951,59957,59962,59966,59970,59973,60163,60164,60168,[60175,60178],60182,60185,60190,60191,60200,60201,60203,60209,60213,60214,60218,60219,60224,60232,60233,60237,60257,60259,60261,60270,60271,[60424,60430],60432,60433,61699,61700,61705,[61719,61726],[61729,61731],[61734,61741],61743,[61747,61752],61757,[61761,61766],[61771,61788],[61791,61797],61800,[61804,61810],61813,[61817,61819],[61822,61824],61826,61828,61829,[61832,61839],61842,61850,61854,61855,61857,61859,61860,[61863,61877],62082,62083,62110,62113,62116,[62119,62121],62124,62126,62127,[62560,62568],[62570,62578],63166,[63187,63190],63198,[64256,64260],65126],"sans-serif-bold-italic":[161,162,164,166,[169,171],173,174,184,[186,191],[688,709],712,716,[718,727],731,[733,766],777,779,[781,823],[825,879],3647,7620,7621,7624,7625,8218,8219,8222,8223,8226,8233,8240,8241,[8249,8251],8253,8255,8256,8261,8262,8274,8276,8319,8320,8353,8358,8361,8363,8369,8370,8451,8470,8471,8478,8480,8482,8494,[8592,8595],8730,8738,8960,9001,9002,9250,9251,9474,9553,9702,9773,9792,9834,9901,9902,9906,10013,10214,10215,11800,59395,[59908,59910],59913,59915,59917,59920,59927,59930,59932,59934,59935,59942,59946,59948,59951,59957,59962,59966,59970,59973,60163,60164,60168,[60175,60178],60182,60185,60190,60191,60200,60201,60203,60209,60213,60214,60218,60219,60224,60232,60233,60237,60257,60259,60261,60270,60271,[60424,60430],60432,60433,61699,61700,61705,[61719,61726],[61729,61731],[61734,61741],61743,[61747,61752],61757,[61761,61766],[61771,61788],[61791,61797],61800,[61804,61810],61813,[61817,61819],[61822,61824],61826,61828,61829,[61832,61839],61842,61850,61854,61855,61857,61859,61860,[61863,61877],62082,62083,62110,62113,62116,[62119,62121],62124,62126,62127,[62560,62568],[62570,62578],63166,[63187,63190],63198,[64256,64260],65126]}],["monospace",{normal:[[120432,120483],[120822,120831]],monospace:[[32,47],[58,64],[91,96],[123,126],160,163,165,167,168,172,[175,177],[180,183],215,240,247,305,567,710,711,[728,730],732,[768,776],778,780,[913,929],[931,937],[945,969],977,978,981,982,1008,1009,[1012,1014],[8208,8212],8214,8216,8217,8220,8221,8224,8225,8230,8260,8364,8486,8487,[8592,8595],8722,8734]}],["monospace-l",{monospace:[[192,214],[216,239],[241,246],[248,304],[306,566],[568,591],[7680,7699],[7704,7707],[7710,7719],[7722,7755],[7764,7779],[7784,7799],[7804,7833],7835,7838,[7840,7929],11377]}],["monospace-ex",{monospace:[161,162,164,166,[169,171],173,174,184,[186,191],[592,709],712,716,[718,727],731,[733,766],777,779,[781,823],[825,887],[890,895],[900,906],908,[910,912],[938,944],[970,976],979,980,[983,995],1010,1011,[1015,1143],[1146,1158],[1160,1230],[1232,1273],[1276,1279],1298,1299,[1306,1309],3647,7424,7431,7434,7435,7437,7448,7449,7452,[7491,7499],7501,[7503,7507],[7510,7512],7514,7515,7517,7518,7520,7521,7544,[7568,7571],7575,7620,7621,7624,7625,[7936,7957],[7960,7965],[7968,8005],[8008,8013],[8016,8023],8025,8027,8029,[8031,8061],[8064,8116],[8118,8132],[8134,8147],[8150,8155],[8157,8175],[8178,8180],[8182,8190],8218,8219,8222,8223,8226,8233,8240,8241,[8249,8251],8253,8255,8256,8261,8262,8274,8276,8319,8320,8353,8358,8361,8363,8369,8370,8451,8470,8471,8478,8480,8482,8494,[8592,8595],8730,8738,8960,9001,9002,9250,9251,9472,9474,9484,9488,9492,9496,9500,9508,9516,9524,9532,[9552,9579],9702,9773,9792,9834,9901,9902,9906,10013,10214,10215,11800,[59908,59910],59913,59915,59917,59920,59927,59930,59932,59934,59935,59942,59946,59948,59951,59957,59962,59966,59970,59973,60163,60164,60168,[60175,60178],60182,60185,60190,60191,60201,60203,60209,60213,60214,60218,60219,60224,60232,60233,60237,60259,60261,60270,60271,[60424,60430],60432,60433,61699,61700,61705,[61719,61726],[61729,61731],[61734,61741],61743,[61747,61752],61757,[61761,61766],[61771,61788],[61791,61797],61800,[61804,61810],61813,[61817,61819],[61822,61824],61826,61828,61829,[61832,61839],61842,61850,61854,61855,61857,61859,61860,[61863,61877],62082,62083,62110,62113,62116,[62119,62121],62124,62126,62127,[62560,62568],[62570,62578],63166,[63187,63190],63198,[64256,64262],65126]}],["calligraphic",{"-tex-calligraphic":[[65,90]],"-tex-bold-calligraphic":[[65,90]]}],["math",{normal:[8714,8717,8731,8732,8762,8763,8782,8783,[8785,8787],[8790,8796],8798,8844,[8886,8889],[8891,8895],8903,[8912,8929],[8932,8937],[8946,8959],[10176,10199],[10202,10204],[10207,10213],[10625,10646],[10649,10740],10742,[10746,10751],10762,10763,[10781,10798],[10800,10814],[10816,10876],[10879,10884],[10893,10900],[10903,10926],[10939,10948],[10951,10954],[10957,10973],[10988,10993],[10998,11003],[11005,11007]]}],["symbols",{normal:[127,161,162,164,166,[169,171],173,174,178,179,[185,191],3647,8215,8218,8219,8222,8223,[8226,8229],8233,8240,8241,[8248,8259],[8261,8278],[8280,8286],8319,8320,8353,8358,[8361,8363],8369,8370,8448,8449,[8451,8454],8456,8457,8468,8470,8471,[8478,8483],8485,8489,8494,[8505,8507],[8522,8527],[8960,8966],[8977,8984],8986,8987,[8996,9e3],[9003,9114],9142,[9146,9165],9167,[9169,9179],[9186,9203],[9208,9215],9250,9251,11159,11193,11209,[11216,11241],[11248,11263],11800,12306,12310,12311,12336,[64256,64262],65126,65279]},[8215]],["symbols-b-i",{bold:[161,162,164,166,[169,171],173,174,[186,191],3647,8218,8219,8222,8223,8226,8233,8240,8241,[8249,8251],8253,8255,8256,8261,8262,8274,8276,8319,8320,8353,8358,[8361,8363],8369,8370,8451,8470,8471,8478,8480,8482,8494,8960,9250,9251,11800,[64256,64262],65126],italic:[[161,167],[169,174],177,[181,183],[186,191],215,240,247,3647,8218,8219,[8222,8226],8233,8240,8241,[8249,8251],8253,8255,8256,8261,8262,8274,8276,8320,8353,8358,8361,8363,8369,8370,8451,8470,8471,8478,8480,8482,8494,8960,9250,9251,11800,[64256,64262],65126],"bold-italic":[[161,167],[169,174],177,[181,183],[186,191],215,240,247,3647,8218,8219,[8222,8226],8233,8240,8241,[8249,8251],8253,8255,8256,8261,8262,8274,8276,8320,8353,8358,[8361,8363],8369,8370,8451,8470,8471,8478,8480,8482,8494,8960,9250,9251,11800,[64256,64262],65126]}],["greek",{normal:[[880,887],[890,895],[900,906],908,[910,912],[938,944],[970,976],979,980,[983,1007],1010,1011,[1015,1023],[7936,7957],[7960,7965],[7968,8005],[8008,8013],[8016,8023],8025,8027,8029,[8031,8061],[8064,8116],[8118,8132],[8134,8147],[8150,8155],[8157,8175],[8178,8180],[8182,8190],[11392,11507],[11513,11519]],bold:[[880,887],[890,895],[900,906],908,[910,912],[938,944],[970,976],979,980,[983,987],[990,1007],1010,1011,[1015,1023],[7936,7957],[7960,7965],[7968,8005],[8008,8013],[8016,8023],8025,8027,8029,[8031,8061],[8064,8116],[8118,8132],[8134,8147],[8150,8155],[8157,8175],[8178,8180],[8182,8190],[11392,11507],[11513,11519]],italic:[[880,887],[890,895],[900,906],908,[910,912],[938,944],[970,976],979,980,[983,1007],1010,1011,[1015,1023],[7936,7957],[7960,7965],[7968,8005],[8008,8013],[8016,8023],8025,8027,8029,[8031,8061],[8064,8116],[8118,8132],[8134,8147],[8150,8155],[8157,8175],[8178,8180],[8182,8190],[11392,11507],[11513,11519]],"bold-italic":[[880,887],[890,895],[900,906],908,[910,912],[938,944],[970,976],979,980,[983,1007],1010,1011,[1015,1023],[7936,7957],[7960,7965],[7968,8005],[8008,8013],[8016,8023],8025,8027,8029,[8031,8061],[8064,8116],[8118,8132],[8134,8147],[8150,8155],[8157,8175],[8178,8180],[8182,8190],[11392,11507],[11513,11519]]}],["greek-ss",{"sans-serif":[[880,887],[890,895],[900,906],908,[910,912],[938,944],[970,976],979,980,[983,1007],1010,1011,[1015,1023],[7936,7957],[7960,7965],[7968,8005],[8008,8013],[8016,8023],8025,8027,8029,[8031,8061],[8064,8116],[8118,8132],[8134,8147],[8150,8155],[8157,8175],[8178,8180],[8182,8190]],"bold-sans-serif":[[880,887],[890,895],[900,906],908,[910,912],[938,944],[970,976],979,980,[983,1007],1010,1011,[1015,1023],[7936,7957],[7960,7965],[7968,8005],[8008,8013],[8016,8023],8025,8027,8029,[8031,8061],[8064,8116],[8118,8121],[8123,8132],[8134,8147],[8150,8155],[8157,8175],[8178,8180],[8182,8190]],"sans-serif-italic":[[880,887],[890,895],[900,906],908,[910,912],[938,944],[970,976],979,980,[983,1007],1010,1011,[1015,1023],[7936,7957],[7960,7965],[7968,8005],[8008,8013],[8016,8023],8025,8027,8029,[8031,8061],[8064,8116],[8118,8132],[8134,8147],[8150,8155],[8157,8175],[8178,8180],[8182,8190]],"sans-serif-bold-italic":[[880,887],[890,895],[900,906],908,[910,912],[938,944],[970,976],979,980,[983,1007],1010,1011,[1015,1023],[7936,7957],[7960,7965],[7968,8005],[8008,8013],[8016,8023],8025,8027,8029,[8031,8061],[8064,8116],[8118,8121],[8123,8132],[8134,8147],[8150,8155],[8157,8175],[8178,8180],[8182,8190]]}],["cyrillic",{normal:[[1024,1143],[1146,1158],[1160,1230],[1232,1273],[1276,1279],1298,1299,[1306,1309]],bold:[[1024,1143],[1146,1158],[1160,1230],[1232,1273],[1276,1279],1298,1299,[1306,1309]],italic:[[1024,1143],[1146,1158],[1160,1225],[1227,1230],[1232,1273],[1276,1279],1298,1299,[1306,1309]],"bold-italic":[[1024,1143],[1146,1158],[1160,1225],[1227,1230],[1232,1273],[1276,1279],1298,1299,[1306,1309]]}],["cyrillic-ss",{"sans-serif":[[1024,1143],[1146,1158],[1160,1230],[1232,1273],[1276,1279],1298,1299,[1306,1309]],"bold-sans-serif":[[1024,1143],[1146,1158],[1160,1230],[1232,1273],[1276,1279],1298,1299,[1306,1309]],"sans-serif-italic":[[1024,1143],[1146,1158],[1160,1230],[1232,1273],[1276,1279],1298,1299,[1306,1309]],"sans-serif-bold-italic":[[1024,1143],[1146,1158],[1160,1230],[1232,1273],[1276,1279],1298,1299,[1306,1309]]}],["phonetics",{normal:[[592,687],7424,7431,7434,7435,7437,7448,7449,7452,[7491,7499],7501,[7503,7507],[7510,7512],7514,7515,7517,7518,7520,7521,7544,[7568,7571],7575],bold:[[592,687],7424,7431,7434,7435,7437,7448,7449,7452,[7491,7499],7501,[7503,7507],[7510,7512],7514,7515,7517,7518,7520,7521,7544,[7568,7571],7575],italic:[[592,685],687],"bold-italic":[[592,687]]}],["phonetics-ss",{"sans-serif":[[592,687],7424,7431,7434,7435,7437,7448,7449,7452,[7491,7499],7501,[7503,7507],[7510,7512],7514,7515,7517,7518,7520,7521,7544,[7568,7571],7575],"bold-sans-serif":[[592,687],7424,7431,7434,7435,7437,7448,7449,7452,[7491,7499],7501,[7503,7507],[7510,7512],7514,7515,7517,7518,7520,7521,7544,[7568,7571],7575],"sans-serif-italic":[[592,687],7424,7431,7434,7435,7437,7448,7449,7452,[7491,7499],7501,[7503,7507],[7510,7512],7514,7515,7517,7518,7520,7521,7544,[7568,7571],7575],"sans-serif-bold-italic":[[592,687],7424,7431,7434,7435,7437,7448,7449,7452,[7491,7499],7501,[7503,7507],[7510,7512],7514,7515,7517,7518,7520,7521,7544,[7568,7571],7575]}],["hebrew",{normal:[[1425,1479],[1488,1514],[1519,1525],1527,[64285,64335]],bold:[[1425,1479],[1488,1515],[1519,1525],1527,[64285,64335]],italic:[[1425,1479],[1488,1514],[1519,1525],1527,[64285,64335]],"bold-italic":[[1425,1479],[1488,1515],[1519,1525],1527,[64285,64335]]}],["devanagari",{normal:[[2304,2431]],bold:[],italic:[],"bold-italic":[]}],["cherokee",{normal:[[5024,5109],[5112,5117]],bold:[[5024,5109],[5112,5117]],italic:[[5024,5115]],"bold-italic":[[5024,5115]]}],["arabic",{normal:[[126464,126498],126500,126503,[126505,126514],[126516,126519],126521,126523,126530,126535,126537,126539,[126541,126543],126545,126546,126548,126551,126553,126555,126557,126559,126561,126562,126564,[126567,126570],[126572,126578],[126580,126583],[126585,126588],[126590,126601],[126603,126619],[126625,126627],[126629,126633],[126635,126651],126704,126705],bold:[],italic:[],"bold-italic":[]}],["braille-d",{normal:[[10240,10495]]}],["braille",{"sans-serif":[[10240,10495]]}],["arrows",{normal:[8604,8605,8607,8609,8613,8615,8616,8621,[8623,8629],8632,8633,[8662,8665],[8668,8671],[8678,8692],[8695,8703],9166,10145,[10224,10228],10239,[10496,10505],[10508,10569],10572,10573,10575,10577,10580,10581,10584,10585,10588,10589,[10592,10601],[10608,10619],[11008,11026],[11056,11087],[11098,11123],[11126,11157],[11160,11192],[11244,11247]],"-largeop":[8593,8595,[8597,8603],[8606,8611],8613,8615,[8617,8622],[8624,8627],8630,8631,[8636,8655],8657,8659,[8661,8667],[8678,8681],8691,8693,8694,[11012,11015],11020,11021,11057],"-lf-tp":[[8678,8681],10503,11013,11014],"-rt-bt":[[8678,8681],10502,11015,11020],"-ex-md":[8678,8679,11013,11014]},[8607,8609,8613,8615,8621,8622,[8624,8627],[8662,8665],8668,8669,[8678,8681],8691,10145,10237,10238,10502,10503,10572,10573,10575,10577,10588,10589,10592,10593,[11012,11015],11020,11021,11057]],["marrows",{normal:[[129024,129035],[129040,129095],[129104,129113],[129120,129159],[129168,129197],129200,129201]}],["accents",{normal:[184,[688,709],712,716,[718,727],731,[733,766],777,779,[781,823],[825,879],7620,7621,7624,7625,[8403,8405],8408,[8413,8415],[8420,8427],8432],"-smallop":[785,[812,816],818,819,831,845],"-largeop":[785,[812,816]],"-size3":[785,[812,816]],"-size4":[785,[812,816]],"-size5":[785,[812,816]],"-size6":[785,[812,816]],"-size7":[785,[812,816]],"-ex-md":[818,819,831,845]},[785,[812,816],818,819,831,845,8425]],["accents-b-i",{bold:[184,[688,709],712,716,[718,727],731,[733,766],777,779,[781,823],[825,846],[848,879],7620,7621,7624,7625],italic:[184,[688,700],[702,709],712,716,[718,727],731,[733,766],777,779,[781,823],[825,846],[848,879]],"bold-italic":[184,[688,709],712,716,[718,727],731,[733,766],777,779,[781,823],[825,846],[848,879]]}],["shapes",{normal:[8962,[8998,9e3],9003,[9211,9214],[9472,9631],[9634,9641],[9644,9649],9672,9673,[9676,9678],[9680,9701],[9703,9710],[9712,9719],9728,9733,9734,9737,9761,9773,[9785,9790],9792,9794,[9824,9831],[9833,9835],[9837,9839],9854,[9856,9865],9893,[9898,9902],9906,10003,10013,10016,10026,10038,10045,10098,10099,10139,10145,[11026,11055],[11088,11097],[11194,11208],[11210,11215],11242,11243],bold:[9474,9553,9773,9792,9834,9901,9902,9906,10013],italic:[9773,9834,9901,9902,10013],"bold-italic":[9773,9834,9901,9902,10013]}],["mshapes",{normal:[[128896,128984],[128992,129003]]}],["variants",{"-tex-variant":[34,39,42,96,126,170,176,178,179,185,186,8212,8289,8304,8305,[8308,8334]]}],["PUA",{normal:[[57344,57395],[57409,57458],[59264,59274],59395,[59908,59910],59913,59915,59917,59920,59927,59930,59932,59934,59935,59942,59946,59948,59951,59957,59962,59966,59970,59973,60163,60164,60168,[60175,60178],60182,60185,60190,60191,60200,60201,60203,60209,60213,60214,60218,60219,60224,60232,60233,60237,60257,60259,60261,60270,60271,[60424,60430],60432,60433,61699,61700,61705,[61719,61726],[61729,61731],[61734,61741],61743,[61747,61752],61757,[61761,61766],[61771,61788],[61791,61797],61800,[61804,61810],61813,[61817,61819],[61822,61824],61826,61828,61829,[61832,61839],61842,61850,61854,61855,61857,61859,61860,[61863,61877],62082,62083,62110,62113,62116,[62119,62121],62124,62126,62127,[62560,62568],[62570,62578],63166,[63187,63190],63198],bold:[59395,[59908,59910],59913,59915,59917,59920,59927,59930,59932,59934,59935,59942,59946,59948,59951,59957,59962,59966,59970,59973,60163,60164,60168,[60175,60178],60182,60185,60190,60191,60200,60201,60203,60209,60213,60214,60218,60219,60224,60232,60233,60237,60257,60259,60261,60270,60271,[60424,60430],60432,60433,61699,61700,61705,[61719,61726],[61729,61731],[61734,61741],61743,[61747,61752],61757,[61761,61766],[61771,61788],[61791,61797],61800,[61804,61810],61813,[61817,61819],[61822,61824],61826,61828,61829,[61832,61839],61842,61850,61854,61855,61857,61859,61860,[61863,61877],62082,62083,62110,62113,62116,[62119,62121],62124,62126,62127,[62560,62568],[62570,62578],63166,[63187,63190],63198],italic:[59395,[59908,59910],59913,59915,59917,59920,59927,59930,59932,59934,59935,59942,59946,59948,59951,59957,59962,59966,59970,59973,60163,60164,60168,[60175,60178],60182,60185,60190,60191,60200,60201,60203,60209,60213,60214,60218,60219,60224,60232,60233,60237,60257,60259,60261,60270,60271,[60424,60430],60432,60433,61699,61700,61705,[61719,61726],[61729,61731],[61734,61741],61743,[61747,61752],61757,61867,61868,[61873,61877],62082,62083,62110,62113,62116,62119,62120,[62560,62568],[62570,62578],63166,63172,[63174,63176],[63187,63190],63198],"bold-italic":[59395,[59908,59910],59913,59915,59917,59920,59927,59930,59932,59934,59935,59942,59946,59948,59951,59957,59962,59966,59970,59973,60163,60164,60168,[60175,60178],60182,60185,60190,60191,60200,60201,60203,60209,60213,60214,60218,60219,60224,60232,60233,60237,60257,60259,60261,60270,60271,[60424,60430],60432,60433,61699,61700,61705,[61719,61726],[61729,61731],[61734,61741],61743,[61747,61752],61757,61867,61868,[61873,61877],62082,62083,62110,62113,62116,62119,62120,[62560,62568],[62570,62578],63166,63172,[63174,63176],[63187,63190],63198]}]]);const Qd={fontName:"mathjax-newcm",DefaultFont:Yd},Zd=Qd.fontName,tu=Qd.DefaultFont;class eu extends Uc{constructor(t={}){super(t,Jd,tu),this.chtmlStyles=null,this.font.adaptiveCSS(this.options.adaptiveCSS),this.wrapperUsage=new th}addExtension(t,e=""){const s=super.addExtension(t,e);return s.length&&this.options.adaptiveCSS&&this.chtmlStyles&&this.adaptor.insertRules(this.chtmlStyles,s),[]}escaped(t,e){return this.setDocument(e),this.html("span",{},[this.text(t.math)])}styleSheet(t){if(this.chtmlStyles){const t=new oo;return this.options.adaptiveCSS&&(this.addWrapperStyles(t),this.updateFontStyles(t)),t.addStyles(this.font.updateDynamicStyles()),this.adaptor.insertRules(this.chtmlStyles,t.getStyleRules()),this.chtmlStyles}const e=this.chtmlStyles=super.styleSheet(t);return this.adaptor.setAttribute(e,"id",eu.STYLESHEETID),this.wrapperUsage.update(),e}updateFontStyles(t){t.addStyles(this.font.updateStyles({}))}addWrapperStyles(t){if(this.options.adaptiveCSS)for(const e of this.wrapperUsage.update()){const s=this.factory.getNodeClass(e);s&&this.addClassStyles(s,t)}else super.addWrapperStyles(t)}addClassStyles(t,e){const s=t;s.autoStyle&&"unknown"!==s.kind&&e.addStyles({["mjx-"+s.kind]:{display:"inline-block","text-align":"left"}}),this.wrapperUsage.add(s.kind),super.addClassStyles(t,e)}insertStyles(t){this.chtmlStyles&&this.adaptor.insertRules(this.chtmlStyles,new oo(t).getStyleRules())}processMath(t,e){t.toCHTML([e])}clearCache(){this.styleJson.clear(),this.font.clearCache(),this.wrapperUsage.clear(),this.chtmlStyles=null}reset(){this.clearCache()}unknownText(t,e,s=null){const i={},r=100/this.math.metrics.scale;if(100!==r&&(i["font-size"]=this.fixed(r,1)+"%",i.padding=xo(75/r)+" 0 "+xo(20/r)+" 0"),"-explicitFont"!==e){const s=Fr(t);(1!==s.length||s[0]<119808||s[0]>120831)&&this.cssFontStyles(this.font.getCssFont(e),i)}return null!==s&&(i.width=this.fixed(s*this.math.metrics.scale)+"em"),this.html("mjx-utext",{variant:e,style:i},[this.text(t)])}measureTextNode(t){const e=this.adaptor,s=e.clone(t);e.setStyle(s,"font-family",e.getStyle(s,"font-family").replace(/MJXZERO, /g,""));const i=this.math.metrics.em,r={position:"absolute",top:0,left:0,"white-space":"nowrap","font-size":this.fixed(i,3)+"px"},n=this.html("mjx-measure-text",{style:r},[s]);e.append(e.parent(this.math.start.node),this.container),e.append(this.container,n);const o=e.nodeSize(s,i)[0];return e.remove(this.container),e.remove(n),{w:o,h:.75,d:.2}}}function su(t,e){const s={};for(const i of Object.keys(t)){const r=t[i];for(const t of Object.keys(r)){s[t]||(s[t]={});const n=r[t];if(i)for(const t of Object.keys(n)){const s=n[parseInt(t)];s[3]||(s[3]={}),e?s[3].ff=e+"-"+i:s[3].f=i}Object.assign(s[t],n)}}return s}function iu(t,e,s,i=""){const r="https://cdn.jsdelivr.net"===(MathJax.config.loader?.paths?.fonts||"").substring(0,24)?"@%%VERSION%%":"",n=s.fontPath||`[fonts]/%%FONT%%-font${i}${r}`,o=t.match(/^[a-z]+:/)?(t.match(/[^/:\\]*$/)||[e])[0]:t;return li(MathJax.config.loader,"paths",{[o+i]:o===t?n.replace(/%%FONT%%/g,t).replace(/%%VERSION%%/g,Zn.version):t}),`[${o}${i}]`}eu.NAME="CHTML",eu.OPTIONS=Object.assign(Object.assign({},Uc.OPTIONS),{adaptiveCSS:!0,matchFontHeight:!0}),eu.commonStyles=Object.assign(Object.assign({},Uc.commonStyles),{'mjx-container[jax="CHTML"]':{"white-space":"nowrap"},[["mjx-mo > mjx-c","mjx-mi > mjx-c","mjx-mn > mjx-c","mjx-ms > mjx-c","mjx-mtext > mjx-c"].join(", ")]:{"clip-path":"padding-box polygon("+["-1em -2px","calc(100% + 1em) -2px","calc(100% + 1em) calc(100% + 2px)","-1em calc(100% + 2px)"].join(", ")+")"},"mjx-stretchy-h":{"clip-path":"padding-box polygon(0 -2px, 100% -2px, 100% calc(100% + 2px), 0 calc(100% + 2px))"},"mjx-stretchy-v":{"clip-path":"padding-box polygon(-2px 0, calc(100% + 2px) 0, calc(100% + 2px) 100%, -2px 100%)"},'mjx-container [space="1"]':{"margin-left":".111em"},'mjx-container [space="2"]':{"margin-left":".167em"},'mjx-container [space="3"]':{"margin-left":".222em"},'mjx-container [space="4"]':{"margin-left":".278em"},'mjx-container [space="5"]':{"margin-left":".333em"},'mjx-container [rspace="1"]':{"margin-right":".111em"},'mjx-container [rspace="2"]':{"margin-right":".167em"},'mjx-container [rspace="3"]':{"margin-right":".222em"},'mjx-container [rspace="4"]':{"margin-right":".278em"},'mjx-container [rspace="5"]':{"margin-right":".333em"},'mjx-container [size="s"]':{"font-size":"70.7%"},'mjx-container [size="ss"]':{"font-size":"50%"},'mjx-container [size="Tn"]':{"font-size":"60%"},'mjx-container [size="sm"]':{"font-size":"85%"},'mjx-container [size="lg"]':{"font-size":"120%"},'mjx-container [size="Lg"]':{"font-size":"144%"},'mjx-container [size="LG"]':{"font-size":"173%"},'mjx-container [size="hg"]':{"font-size":"207%"},'mjx-container [size="HG"]':{"font-size":"249%"},'mjx-container [width="full"]':{width:"100%"},"mjx-box":{display:"inline-block"},"mjx-block":{display:"block"},"mjx-itable":{display:"inline-table"},"mjx-row":{display:"table-row"},[["cell","base","under","over","den"].map(t=>`mjx-row > mjx-${t}`).join(", ")]:{display:"table-cell"},"mjx-container [inline-breaks]":{display:"inline"},"mjx-container .mjx-selected":{outline:"2px solid black"},"@media (prefers-color-scheme: dark)":{"mjx-container .mjx-selected":{outline:"2px solid #C8C8C8"}},"mjx-mtext":{display:"inline-block"},"mjx-mstyle":{display:"inline-block"},"mjx-merror":{display:"inline-block",color:"red","background-color":"yellow"},"mjx-mphantom":{visibility:"hidden"}}),eu.STYLESHEETID="MJX-CHTML-styles",MathJax.loader&&MathJax.loader.checkVersion("output/chtml",ii,"output"),ci({_:{output:{chtml_ts:Is,chtml:{DefaultFont:Ms,DynamicFonts:Os,FontData:Me,Notation:Xe,Usage:Se,Wrapper:Ce,WrapperFactory:Ss,Wrappers_ts:Rs,Wrappers:{HtmlNode:As,TeXAtom:ks,TextNode:Ls,maction:xs,math:_e,menclose:Ge,mfenced:Ye,mfrac:Ze,mglyph:Ns,mi:Ae,mmultiscripts:ds,mn:De,mo:Ie,mpadded:We,mroot:is,mrow:Ke,ms:Be,mspace:He,msqrt:es,msubsup:as,mtable:ps,mtd:bs,mtext:je,mtr:fs,munderover:cs,scriptbase:os,semantics:ws}},common_ts:ve,common:{Direction:Ee,FontData:xe,LineBBox:ye,LinebreakVisitor:Ne,Notation:ze,Wrapper:we,WrapperFactory:Te,Wrappers:{TeXAtom:Cs,TextNode:_s,XmlNode:Ts,maction:Es,math:ke,menclose:Ve,mfenced:$e,mfrac:Qe,mglyph:ys,mi:Le,mmultiscripts:hs,mn:Oe,mo:Re,mpadded:qe,mroot:ss,mrow:Je,ms:Pe,mspace:Ue,msqrt:ts,msubsup:rs,mtable:us,mtd:gs,mtext:Fe,mtr:ms,munderover:ls,scriptbase:ns,semantics:vs}}}}});const ru={config(t,e,s,i){if(MathJax.loader){li(MathJax.config,t,MathJax.config.output||{});let e=MathJax.config[t],r=e.font||e.fontData||s;"string"!=typeof r&&(e.fontData=r,e.font=r=r.NAME),"["!==r.charAt(0)&&(r=iu(r,t,e));const n=r.substring(1,r.length-1),o=function(t,e){const s=[];for(const i of e.fontExtensions||[]){const r=`${iu(i,t,e,"-extension")}/${t}`;s.push(r)}return s}(t,e);if(o.length&&MathJax.loader.addPackageData(`${r}/${t}`,{extraLoads:o}),n===s&&i){const e=MathJax.config.loader[`${r}/${t}`]?.extraLoads;e&&MathJax.loader.addPackageData(`output/${t}`,{extraLoads:e}),ci({_:{output:{fonts:{[n]:{[t+"_ts"]:{[i.NAME+"Font"]:i}}}}}}),li(MathJax,"config",{output:{font:r},[t]:{fontData:i,dynamicPrefix:`${r}/${t}/dynamic`}}),"chtml"===t&&li(MathJax.config,t,{fontURL:mi.resolvePath(`${r}/${t}/woff2`,!1)})}else MathJax.loader.addPackageData(`output/${t}`,{extraLoads:[`${r}/${t}`]})}MathJax.startup&&(MathJax.startup.registerConstructor(t,e),MathJax.startup.useOutput(t))},loadFont:(t,e,s,i)=>MathJax.loader?(i&&MathJax.loader.preLoaded(`[${s}]/${e}`),mi.loadPromise(`output/${e}`).then(t)):t};var nu;ru.config("chtml",eu,Zd,tu),function(t){t[t.RETURN=13]="RETURN",t[t.ESCAPE=27]="ESCAPE",t[t.SPACE=32]="SPACE",t[t.LEFT=37]="LEFT",t[t.UP=38]="UP",t[t.RIGHT=39]="RIGHT",t[t.DOWN=40]="DOWN"}(nu||(nu={}));const ou="click",au="dblclick",lu="mousedown",cu="mouseup",hu="mouseover",du="mouseout",uu="selectstart";class pu{constructor(){this.bubble=!1}bubbleKey(){this.bubble=!0}keydown(t){switch(t.keyCode){case nu.ESCAPE:this.escape(t);break;case nu.RIGHT:this.right(t);break;case nu.LEFT:this.left(t);break;case nu.UP:this.up(t);break;case nu.DOWN:this.down(t);break;case nu.RETURN:case nu.SPACE:this.space(t);break;default:return}this.bubble?this.bubble=!1:this.stop(t)}escape(t){}space(t){}left(t){}right(t){}up(t){}down(t){}stop(t){t&&(t.stopPropagation(),t.preventDefault(),t.cancelBubble=!0)}mousedown(t){return this.stop(t)}mouseup(t){return this.stop(t)}mouseover(t){return this.stop(t)}mouseout(t){return this.stop(t)}click(t){return this.stop(t)}addEvents(t){t.addEventListener(lu,this.mousedown.bind(this)),t.addEventListener(cu,this.mouseup.bind(this)),t.addEventListener(hu,this.mouseover.bind(this)),t.addEventListener(du,this.mouseout.bind(this)),t.addEventListener(ou,this.click.bind(this)),t.addEventListener("keydown",this.keydown.bind(this)),t.addEventListener("dragstart",this.stop.bind(this)),t.addEventListener(uu,this.stop.bind(this)),t.addEventListener("contextmenu",this.stop.bind(this)),t.addEventListener(au,this.stop.bind(this))}}class mu extends pu{addAttributes(t){for(const e in t)this.html.setAttribute(e,t[e])}get html(){return this._html||this.generateHtml(),this._html}set html(t){this._html=t,this.addEvents(t)}generateHtml(){const t=document.createElement("div");t.classList.add(this.className),t.setAttribute("role",this.role),this.html=t}focus(){const t=this.html;t.setAttribute("tabindex","0"),setTimeout(()=>t.focus(),50)}unfocus(){const t=this.html;t.hasAttribute("tabindex")&&t.setAttribute("tabindex","-1");try{t.blur()}catch(t){}t.blur()}}class fu extends mu{constructor(){super(...arguments),this.posted=!1}isPosted(){return this.posted}post(t,e){this.posted||(void 0!==t&&void 0!==e&&this.html.setAttribute("style","left: "+t+"px; top: "+e+"px;"),this.display(),this.posted=!0)}unpost(){if(!this.posted)return;const t=this.html;t.parentNode&&t.parentNode.removeChild(t),this.posted=!1}}function gu(t){return"CtxtMenu_"+t}function bu(t){return gu(t)}function Eu(t){return gu(t)}const xu={ATTACHED:bu("Attached"),CONTEXTMENU:bu("ContextMenu"),MENU:bu("Menu"),MENUARROW:bu("MenuArrow"),MENUACTIVE:bu("MenuActive"),MENUCHECK:bu("MenuCheck"),MENUCLOSE:bu("MenuClose"),MENUCOMBOBOX:bu("MenuComboBox"),MENUDISABLED:bu("MenuDisabled"),MENUFRAME:bu("MenuFrame"),MENUITEM:bu("MenuItem"),MENULABEL:bu("MenuLabel"),MENURADIOCHECK:bu("MenuRadioCheck"),MENUINPUTBOX:bu("MenuInputBox"),MENURULE:bu("MenuRule"),MENUSLIDER:bu("MenuSlider"),MOUSEPOST:bu("MousePost"),RTL:bu("RTL"),INFO:bu("Info"),INFOCLOSE:bu("InfoClose"),INFOCONTENT:bu("InfoContent"),INFOSIGNATURE:bu("InfoSignature"),INFOTITLE:bu("InfoTitle"),SLIDERVALUE:bu("SliderValue"),SLIDERBAR:bu("SliderBar"),SELECTION:bu("Selection"),SELECTIONBOX:bu("SelectionBox"),SELECTIONMENU:bu("SelectionMenu"),SELECTIONDIVIDER:bu("SelectionDivider"),SELECTIONITEM:bu("SelectionItem")},yu={COUNTER:Eu("Counter"),KEYDOWNFUNC:Eu("keydownFunc"),CONTEXTMENUFUNC:Eu("contextmenuFunc"),OLDTAB:Eu("Oldtabindex"),TOUCHFUNC:Eu("TouchFunc")};class Nu extends mu{constructor(t,e){super(),this._menu=t,this._type=e,this.className=xu.MENUITEM,this.role="menuitem",this.hidden=!1}get menu(){return this._menu}set menu(t){this._menu=t}get type(){return this._type}hide(){this.hidden=!0,this.menu.generateMenu()}show(){this.hidden=!1,this.menu.generateMenu()}isHidden(){return this.hidden}}function vu(t){const e=t.menu;e.baseMenu?e.baseMenu.unpost():e.unpost()}function Tu(t){const e=t.menu;return(e.baseMenu?e.baseMenu:e).store.active}function wu(t,e){console.error("ContextMenu Error: "+e)}function Cu(){return ku++}let ku=0;class _u extends Nu{constructor(t,e,s,i){super(t,e),this._content=s,this.disabled=!1,this.callbacks=[],this._id=i||s}get content(){return this._content}set content(t){this._content=t,this.generateHtml(),this.menu&&this.menu.generateHtml()}get id(){return this._id}press(){this.disabled||(this.executeAction(),this.executeCallbacks_())}executeAction(){}registerCallback(t){-1===this.callbacks.indexOf(t)&&this.callbacks.push(t)}unregisterCallback(t){const e=this.callbacks.indexOf(t);-1!==e&&this.callbacks.splice(e,1)}mousedown(t){this.press(),this.stop(t)}mouseover(t){this.focus(),this.stop(t)}mouseout(t){this.deactivate(),this.stop(t)}generateHtml(){super.generateHtml();const t=this.html;t.setAttribute("aria-disabled","false"),t.textContent=this.content}activate(){this.disabled||this.html.classList.add(xu.MENUACTIVE)}deactivate(){this.html.classList.remove(xu.MENUACTIVE)}focus(){this.menu.focused=this,super.focus(),this.activate()}unfocus(){this.deactivate(),super.unfocus()}escape(t){vu(this)}up(t){this.menu.up(t)}down(t){this.menu.down(t)}left(t){this.menu.left(t)}right(t){this.menu.right(t)}space(t){this.press()}disable(){this.disabled=!0;const t=this.html;t.classList.add(xu.MENUDISABLED),t.setAttribute("aria-disabled","true")}enable(){this.disabled=!1;const t=this.html;t.classList.remove(xu.MENUDISABLED),t.removeAttribute("aria-disabled")}executeCallbacks_(){for(const t of this.callbacks)try{t(this)}catch(t){wu(0,"Callback for menu entry "+this.id+" failed.")}}}class Lu extends _u{static fromJson(t,{content:e,menu:s,id:i},r){const n=new this(r,e,i),o=t.get("subMenu")(t,s,n);return n.submenu=o,n}constructor(t,e,s){super(t,"submenu",e,s),this._submenu=null}set submenu(t){this._submenu=t}get submenu(){return this._submenu}mouseover(t){this.focus(),this.stop(t)}mouseout(t){this.stop(t)}unfocus(){if(this.submenu.isPosted()){if(this.menu.focused!==this)return super.unfocus(),void this.menu.unpostSubmenus();this.html.setAttribute("tabindex","-1"),this.html.blur()}else super.unfocus()}focus(){super.focus(),this.submenu.isPosted()||this.disabled||this.submenu.post()}executeAction(){this.submenu.isPosted()?this.submenu.unpost():this.submenu.post()}generateHtml(){super.generateHtml();const t=this.html;this.span=document.createElement("span"),this.span.textContent="\u25ba",this.span.classList.add(xu.MENUARROW),this.span.setAttribute("aria-hidden","true"),t.appendChild(this.span),t.setAttribute("aria-haspopup","true")}left(t){this.submenu.isPosted()?this.submenu.unpost():super.left(t)}right(t){this.submenu.isPosted()?this.submenu.down(t):this.submenu.post()}toJson(){return{type:""}}}class Au extends fu{constructor(){super(...arguments),this.className=xu.CONTEXTMENU,this.role="menu",this._items=[],this._baseMenu=null}set baseMenu(t){this._baseMenu=t}get baseMenu(){return this._baseMenu}get items(){return this._items}set items(t){this._items=t}get pool(){return this.variablePool}get focused(){return this._focused}set focused(t){if(this._focused===t)return;this._focused||this.unfocus();const e=this._focused;this._focused=t,e&&e.unfocus()}up(t){const e=this.items.filter(t=>t instanceof _u&&!t.isHidden());if(0===e.length)return;if(!this.focused)return void e[e.length-1].focus();let s=e.indexOf(this.focused);-1!==s&&(s=s?--s:e.length-1,e[s].focus())}down(t){const e=this.items.filter(t=>t instanceof _u&&!t.isHidden());if(0===e.length)return;if(!this.focused)return void e[0].focus();let s=e.indexOf(this.focused);-1!==s&&(s++,s=s===e.length?0:s,e[s].focus())}generateHtml(){super.generateHtml(),this.generateMenu()}generateMenu(){const t=this.html;t.classList.add(xu.MENU);for(const e of this.items){if(!e.isHidden()){t.appendChild(e.html);continue}const s=e.html;s.parentNode&&s.parentNode.removeChild(s)}}post(t,e){this.variablePool.update(),super.post(t,e)}unpostSubmenus(){const t=this.items.filter(t=>t instanceof Lu);for(const e of t)e.submenu.unpost(),e!==this.focused&&e.unfocus()}unpost(){super.unpost(),this.unpostSubmenus(),this.focused=null}find(t){for(const e of this.items)if("rule"!==e.type){if(e.id===t)return e;if("submenu"===e.type){const s=e.submenu.find(t);if(s)return s}}return null}}class Ru{constructor(t){this.menu=t,this.store=[],this._active=null,this.counter=0,this.attachedClass=xu.ATTACHED+"_"+Cu(),this.taborder=!0,this.attrMap={}}set active(t){do{if(-1!==this.store.indexOf(t)){this._active=t;break}t=t.parentNode}while(t)}get active(){return this._active}next(){const t=this.store.length;if(0===t)return this.active=null,null;let e=this.store.indexOf(this.active);return e=-1===e?0:et.setAttribute("tabindex","0"))}removeTaborder_(){this.store.forEach(t=>t.setAttribute("tabindex","-1"))}addTabindex(t){t.hasAttribute("tabindex")&&t.setAttribute(yu.OLDTAB,t.getAttribute("tabindex")),t.setAttribute("tabindex","0")}removeTabindex(t){t.hasAttribute(yu.OLDTAB)?(t.setAttribute("tabindex",t.getAttribute(yu.OLDTAB)),t.removeAttribute(yu.OLDTAB)):t.removeAttribute("tabindex")}addEvents(t){t.hasAttribute(yu.COUNTER)||(this.addEvent(t,"contextmenu",this.menu.post.bind(this.menu)),this.addEvent(t,"keydown",this.keydown.bind(this)),t.setAttribute(yu.COUNTER,this.counter.toString()),this.counter++)}addEvent(t,e,s){const i=yu[e.toUpperCase()+"FUNC"];this.attrMap[i+this.counter]=s,t.addEventListener(e,s)}removeEvents(t){if(!t.hasAttribute(yu.COUNTER))return;const e=t.getAttribute(yu.COUNTER);this.removeEvent(t,"contextmenu",e),this.removeEvent(t,"keydown",e),t.removeAttribute(yu.COUNTER)}removeEvent(t,e,s){const i=yu[e.toUpperCase()+"FUNC"],r=this.attrMap[i+s];t.removeEventListener(e,r)}keydown(t){t.keyCode===nu.SPACE&&(this.menu.post(t),t.preventDefault(),t.stopImmediatePropagation())}}class Su{constructor(){this.pool={}}insert(t){this.pool[t.name]=t}lookup(t){return this.pool[t]}remove(t){delete this.pool[t]}update(){for(const t in this.pool)this.pool[t].update()}}class Mu extends Au{static fromJson(t,{pool:e,items:s,id:i=""}){const r=new this(t);r.id=i;const n=t.get("variable");e.forEach(e=>n(t,e,r.pool));const o=t.get("items")(t,s,r);return r.items=o,r}constructor(t){super(),this.factory=t,this.id="",this.moving=!1,this._store=new Ru(this),this.widgets=[],this.variablePool=new Su}generateHtml(){this.isPosted()&&this.unpost(),super.generateHtml(),this._frame=document.createElement("div"),this._frame.classList.add(xu.MENUFRAME);const t="left: 0px; top: 0px; z-index: 200; width: 100%; height: 100%; border: 0px; padding: 0px; margin: 0px;";this._frame.setAttribute("style","position: absolute; "+t);const e=document.createElement("div");e.setAttribute("style","position: fixed; "+t),this._frame.appendChild(e),e.addEventListener("mousedown",function(t){this.unpost(),this.unpostWidgets(),this.stop(t)}.bind(this))}display(){document.body.appendChild(this.frame),this.frame.appendChild(this.html),this.focus()}escape(t){this.unpost(),this.unpostWidgets()}unpost(){if(super.unpost(),this.widgets.length>0)return;this.frame.parentNode.removeChild(this.frame);const t=this.store;this.moving||t.insertTaborder(),t.active.focus()}left(t){this.move_(this.store.previous())}right(t){this.move_(this.store.next())}get frame(){return this._frame}get store(){return this._store}post(t,e){if(void 0!==e)return this.moving||this.store.removeTaborder(),void super.post(t,e);const s=t;let i,r,n;if(s instanceof Event?(i=s.target,this.stop(s)):i=s,s instanceof MouseEvent&&(r=s.pageX,n=s.pageY,r||n||!s.clientX||(r=s.clientX+document.body.scrollLeft+document.documentElement.scrollLeft,n=s.clientY+document.body.scrollTop+document.documentElement.scrollTop)),!r&&!n&&i){const t=window.pageXOffset||document.documentElement.scrollLeft,e=window.pageYOffset||document.documentElement.scrollTop,s=i.getBoundingClientRect();r=(s.right+s.left)/2+t,n=(s.bottom+s.top)/2+e}this.store.active=i,this.anchor=this.store.active;const o=this.html;r+o.offsetWidth>document.body.offsetWidth-5&&(r=document.body.offsetWidth-o.offsetWidth-5),this.post(r,n)}registerWidget(t){this.widgets.push(t)}unregisterWidget(t){const e=this.widgets.indexOf(t);e>-1&&this.widgets.splice(e,1),0===this.widgets.length&&this.unpost()}unpostWidgets(){this.widgets.forEach(t=>t.unpost())}toJson(){return{type:""}}move_(t){this.anchor&&t!==this.anchor&&(this.moving=!0,this.unpost(),this.post(t),this.moving=!1)}}class Iu extends Au{static fromJson(t,{items:e},s){const i=new this(s),r=t.get("items")(t,e,i);return i.items=r,i}constructor(t){super(),this._anchor=t,this.variablePool=this.anchor.menu.pool,this.setBaseMenu()}get anchor(){return this._anchor}post(){if(!this.anchor.menu.isPosted())return;let t=this.anchor.html;const e=this.html,s=this.baseMenu.frame,i=t.offsetWidth;let r=i-2,n=0;for(;t&&t!==s;)r+=t.offsetLeft,n+=t.offsetTop,t=t.parentNode;r+e.offsetWidth>document.body.offsetWidth-5&&(r=Math.max(5,r-i-e.offsetWidth+6)),super.post(r,n)}display(){this.baseMenu.frame.appendChild(this.html)}setBaseMenu(){let t=this;do{t=t.anchor.menu}while(t instanceof Iu);this.baseMenu=t}left(t){this.focused=null,this.anchor.focus()}toJson(){return{type:""}}}class Ou extends _u{generateHtml(){super.generateHtml();const t=this.html;this.span||this.generateSpan(),t.appendChild(this.span),this.update()}register(){this.variable.register(this)}unregister(){this.variable.unregister(this)}update(){this.updateAria(),this.span&&this.updateSpan()}}class Du extends Ou{static fromJson(t,{content:e,variable:s,id:i},r){return new this(r,e,s,i)}constructor(t,e,s,i){super(t,"radio",e,i),this.role="menuitemradio",this.variable=t.pool.lookup(s),this.register()}executeAction(){this.variable.setValue(this.id),vu(this)}generateSpan(){this.span=document.createElement("span"),this.span.textContent="\u2713",this.span.classList.add(xu.MENURADIOCHECK),this.span.setAttribute("aria-hidden","true")}updateAria(){this.html.setAttribute("aria-checked",this.variable.getValue()===this.id?"true":"false")}updateSpan(){this.span.style.display=this.variable.getValue()===this.id?"":"none"}toJson(){return{type:""}}}class Pu extends Nu{static fromJson(t,e,s){return new this(s)}constructor(t){super(t,"rule"),this.className=xu.MENUITEM,this.role="separator"}generateHtml(){super.generateHtml();const t=this.html;t.classList.add(xu.MENURULE),t.setAttribute("aria-orientation","vertical")}addEvents(t){}toJson(){return{type:"rule"}}}class Bu extends _u{static fromJson(t,{content:e,action:s,id:i},r){return new this(r,e,s,i)}constructor(t,e,s,i){super(t,"command",e,i),this.command=s}mousedown(t){this.stop(t)}mouseup(t){this.press(),this.stop(t)}executeAction(){try{this.command(Tu(this))}catch(t){wu(0,"Illegal command callback.")}vu(this)}toJson(){return{type:""}}}class Fu{static fromJson(t,{name:e,getter:s,setter:i},r){const n=new this(e,s,i);r.insert(n)}constructor(t,e,s){this._name=t,this.getter=e,this.setter=s,this.items=[]}get name(){return this._name}getValue(t){try{return this.getter(t)}catch(t){return wu(0,"Command of variable "+this.name+" failed."),null}}setValue(t,e){try{this.setter(t,e)}catch(t){wu(0,"Command of variable "+this.name+" failed.")}this.update()}register(t){-1===this.items.indexOf(t)&&this.items.push(t)}unregister(t){const e=this.items.indexOf(t);-1!==e&&this.items.splice(e,1)}update(){this.items.forEach(t=>t.update())}registerCallback(t){this.items.forEach(e=>e.registerCallback(t))}unregisterCallback(t){this.items.forEach(e=>e.unregisterCallback(t))}toJson(){return{type:"variable",name:this.name,getter:this.getter.toString(),setter:this.setter.toString()}}}class ju extends Ou{static fromJson(t,{content:e,variable:s,id:i},r){return new this(r,e,s,i)}constructor(t,e,s,i){super(t,"checkbox",e,i),this.role="menuitemcheckbox",this.variable=t.pool.lookup(s),this.register()}executeAction(){this.variable.setValue(!this.variable.getValue()),vu(this)}generateSpan(){this.span=document.createElement("span"),this.span.textContent="\u2713",this.span.classList.add(xu.MENUCHECK),this.span.setAttribute("aria-hidden","true")}updateAria(){this.html.setAttribute("aria-checked",this.variable.getValue()?"true":"false")}updateSpan(){this.span.style.display=this.variable.getValue()?"":"none"}toJson(){return{type:""}}}class Uu extends Ou{static fromJson(t,{content:e,variable:s,id:i},r){return new this(r,e,s,i)}constructor(t,e,s,i){super(t,"combobox",e,i),this.role="combobox",this.inputEvent=!1,this.variable=t.pool.lookup(s),this.register()}executeAction(){this.variable.setValue(this.input.value,Tu(this))}space(t){super.space(t),vu(this)}focus(){super.focus(),this.input.focus()}unfocus(){super.unfocus(),this.updateSpan()}generateHtml(){super.generateHtml();this.html.classList.add(xu.MENUCOMBOBOX)}generateSpan(){this.span=document.createElement("span"),this.span.classList.add(xu.MENUINPUTBOX),this.input=document.createElement("input"),this.input.addEventListener("keydown",this.inputKey.bind(this)),this.input.setAttribute("size","10em"),this.input.setAttribute("type","text"),this.input.setAttribute("tabindex","-1"),this.span.appendChild(this.input)}inputKey(t){this.bubbleKey(),this.inputEvent=!0}keydown(t){if(this.inputEvent&&t.keyCode!==nu.ESCAPE&&t.keyCode!==nu.RETURN)return this.inputEvent=!1,void t.stopPropagation();super.keydown(t),t.stopPropagation()}updateAria(){}updateSpan(){let t;try{t=this.variable.getValue(Tu(this))}catch(e){t=""}this.input.value=t}toJson(){return{type:""}}}class Hu extends _u{static fromJson(t,{content:e,id:s},i){return new this(i,e,s)}constructor(t,e,s){super(t,"label",e,s)}generateHtml(){super.generateHtml();this.html.classList.add(xu.MENULABEL)}toJson(){return{type:""}}}class qu extends Ou{static fromJson(t,{content:e,variable:s,id:i},r){return new this(r,e,s,i)}constructor(t,e,s,i){super(t,"slider",e,i),this.role="slider",this.labelId="ctx_slideLabel"+Cu(),this.valueId="ctx_slideValue"+Cu(),this.inputEvent=!1,this.variable=t.pool.lookup(s),this.register()}executeAction(){this.variable.setValue(this.input.value,Tu(this)),this.update()}space(t){super.space(t),vu(this)}focus(){super.focus(),this.input.focus()}unfocus(){super.unfocus(),this.updateSpan()}generateHtml(){super.generateHtml();this.html.classList.add(xu.MENUSLIDER),this.valueSpan=document.createElement("span"),this.valueSpan.setAttribute("id",this.valueId),this.valueSpan.classList.add(xu.SLIDERVALUE),this.html.appendChild(this.valueSpan)}generateSpan(){this.span=document.createElement("span"),this.labelSpan=document.createElement("span"),this.labelSpan.setAttribute("id",this.labelId),this.labelSpan.appendChild(this.html.childNodes[0]),this.html.appendChild(this.labelSpan),this.input=document.createElement("input"),this.input.setAttribute("type","range"),this.input.setAttribute("min","0"),this.input.setAttribute("max","100"),this.input.setAttribute("aria-valuemin","0"),this.input.setAttribute("aria-valuemax","100"),this.input.setAttribute("aria-labelledby",this.labelId),this.input.addEventListener("keydown",this.inputKey.bind(this)),this.input.addEventListener("input",this.executeAction.bind(this)),this.input.classList.add(xu.SLIDERBAR),this.span.appendChild(this.input)}inputKey(t){this.inputEvent=!0}mousedown(t){t.stopPropagation()}mouseup(t){vu(this),t.stopPropagation()}keydown(t){const e=t.keyCode;return e===nu.UP||e===nu.DOWN?(t.preventDefault(),void super.keydown(t)):this.inputEvent&&e!==nu.ESCAPE&&e!==nu.RETURN?(this.inputEvent=!1,void t.stopPropagation()):(super.keydown(t),void t.stopPropagation())}updateAria(){const t=this.variable.getValue();t&&this.input&&(this.input.setAttribute("aria-valuenow",t),this.input.setAttribute("aria-valuetext",t+"%"))}updateSpan(){let t;try{t=this.variable.getValue(Tu(this)),this.valueSpan.innerHTML=t+"%"}catch(e){t=""}this.input.value=t}toJson(){return{type:""}}}class Wu extends fu{constructor(t){super(),this.element=t,this.className=xu.MENUCLOSE,this.role="button"}generateHtml(){const t=document.createElement("span");t.classList.add(this.className),t.setAttribute("role",this.role),t.setAttribute("tabindex","0");const e=document.createElement("span");e.textContent="\xd7",t.appendChild(e),this.html=t}display(){}unpost(){super.unpost(),this.element.unpost()}keydown(t){this.bubbleKey(),super.keydown(t)}space(t){this.unpost(),this.stop(t)}mousedown(t){this.unpost(),this.stop(t)}}class zu extends fu{constructor(t,e,s){super(),this.title=t,this.signature=s,this.className=xu.INFO,this.role="dialog",this.contentDiv=this.generateContent(),this.close=this.generateClose(),this.content=e||function(){return""}}attachMenu(t){this.menu=t}generateHtml(){super.generateHtml();const t=this.html;t.appendChild(this.generateTitle()),t.appendChild(this.contentDiv),t.appendChild(this.generateSignature()),t.appendChild(this.close.html),t.setAttribute("tabindex","0")}post(){super.post();const t=document.documentElement,e=this.html,s=window.innerHeight||t.clientHeight||t.scrollHeight||0,i=Math.floor(-e.offsetWidth/2),r=Math.floor((s-e.offsetHeight)/3);e.setAttribute("style","margin-left: "+i+"px; top: "+r+"px;"),window.event instanceof MouseEvent&&e.classList.add(xu.MOUSEPOST),e.focus()}display(){this.menu.registerWidget(this),this.contentDiv.innerHTML=this.content();const t=this.menu.html;t.parentNode&&t.parentNode.removeChild(t),this.menu.frame.appendChild(this.html)}click(t){}keydown(t){this.bubbleKey(),super.keydown(t)}escape(t){this.unpost()}unpost(){super.unpost(),this.html.classList.remove(xu.MOUSEPOST),this.menu.unregisterWidget(this)}generateClose(){const t=new Wu(this),e=t.html;return e.classList.add(xu.INFOCLOSE),e.setAttribute("aria-label","Close Dialog Box"),t}generateTitle(){const t=document.createElement("span");return t.innerHTML=this.title,t.classList.add(xu.INFOTITLE),t}generateContent(){const t=document.createElement("div");return t.classList.add(xu.INFOCONTENT),t.setAttribute("tabindex","0"),t}generateSignature(){const t=document.createElement("span");return t.innerHTML=this.signature,t.classList.add(xu.INFOSIGNATURE),t}toJson(){return{type:""}}}class Vu extends Au{static fromJson(t,{title:e,values:s,variable:i},r){const n=new this(r),o=t.get("label")(t,{content:e||"",id:e||"id"},n),a=t.get("rule")(t,{},n),l=s.map(e=>t.get("radio")(t,{content:e,variable:i,id:e},n)),c=[o,a].concat(l);return n.items=c,n}constructor(t){super(),this.anchor=t,this.className=xu.SELECTIONMENU,this.variablePool=this.anchor.menu.pool,this.baseMenu=this.anchor.menu}generateHtml(){super.generateHtml(),this.items.forEach(t=>t.html.classList.add(xu.SELECTIONITEM))}display(){}right(t){this.anchor.right(t)}left(t){this.anchor.left(t)}}class Xu extends zu{static fromJson(t,{title:e,signature:s,selections:i,order:r,grid:n},o){const a=new this(e,s,r,n);a.attachMenu(o);const l=i.map(e=>t.get("selectionMenu")(t,e,a));return a.selections=l,a}constructor(t,e,s="none",i="vertical"){super(t,null,e),this.style=s,this.grid=i,this._selections=[],this.prefix="ctxt-selection",this._balanced=!0}attachMenu(t){this.menu=t}get selections(){return this._selections}set selections(t){this._selections=[],t.forEach(t=>this.addSelection(t))}addSelection(t){t.anchor=this,this._selections.push(t)}rowDiv(t){const e=document.createElement("div");this.contentDiv.appendChild(e);const s=t.map(t=>(e.appendChild(t.html),t.html.id||(t.html.id=this.prefix+Cu()),t.html.getBoundingClientRect())),i=s.map(t=>t.width),r=i.reduce((t,e)=>t+e,0),n=s.reduce((t,e)=>Math.max(t,e.height),0);return e.classList.add(xu.SELECTIONDIVIDER),e.setAttribute("style","height: "+n+"px;"),[e,r,n,i]}display(){if(super.display(),this.order(),!this.selections.length)return;const t=[];let e=0,s=[];const i=this.getChunkSize(this.selections.length);for(let r=0;rt.html.style.height=l+"px"),s=this.combineColumn(s,c)}this._balanced&&(this.balanceColumn(t,s),e=s.reduce((t,e)=>t+e,20)),t.forEach(t=>t.style.width=e+"px")}getChunkSize(t){switch(this.grid){case"square":return Math.floor(Math.sqrt(t));case"horizontal":return Math.floor(t/Xu.chunkSize);default:return Xu.chunkSize}}balanceColumn(t,e){t.forEach(t=>{const s=Array.from(t.children);for(let t,i=0;t=s[i];i++)t.style.width=e[i]+"px"})}combineColumn(t,e){let s=[],i=0;for(;t[i]||e[i];){if(!t[i]){s=s.concat(e.slice(i));break}if(!e[i]){s=s.concat(t.slice(i));break}s.push(Math.max(t[i],e[i])),i++}return s}left(t){this.move(t,t=>(0===t?this.selections.length:t)-1)}right(t){this.move(t,t=>t===this.selections.length-1?0:t+1)}generateHtml(){super.generateHtml(),this.html.classList.add(xu.SELECTION)}generateContent(){const t=super.generateContent();return t.classList.add(xu.SELECTIONBOX),t.removeAttribute("tabindex"),t}findSelection(t){const e=t.target;let s=null;if(e.id&&(s=this.selections.find(t=>t.html.id===e.id)),!s){const t=e.parentElement.id;s=this.selections.find(e=>e.html.id===t)}return s}move(t,e){const s=this.findSelection(t);s.focused&&s.focused.unfocus();const i=e(this.selections.indexOf(s));this.selections[i].focus()}order(){this.selections.sort(Xu.orderMethod.get(this.style))}toJson(){return{type:""}}}Xu.chunkSize=4,Xu.orderMethod=new Map([["alphabetical",(t,e)=>t.items[0].content.localeCompare(e.items[0].content)],["none",(t,e)=>1],["decreasing",(t,e)=>{const s=t.items.length,i=e.items.length;return s{const s=t.items.length,i=e.items.length;return sthis.factory.add(t,e))}get factory(){return this._factory}items(t,e,s){const i=[];for(const t of e){const e=this.parse(t,s);e&&(s.items.push(e),t.disabled&&e.disable(),t.hidden&&i.push(e))}return i.forEach(t=>t.hide()),s.items}parse(t,...e){var{type:s}=t,i=Ju(t,["type"]);const r=this.factory.get(s);return r?r(this.factory,i,...e):null}}function $u(t){return"."+(xu[t]||t)}function Yu(t,e=";"){return"{\n "+t.join(e+"\n ")+";\n}"}const Qu={};Qu[$u("MENU")]=Yu(["position: absolute","background-color: white","color: black","width: auto","padding: 5px 0px","border: 1px solid #CCCCCC","margin: 0","cursor: default","font: menu","text-align: left","text-indent: 0","text-transform: none","line-height: normal","letter-spacing: normal","word-spacing: normal","word-wrap: normal","white-space: nowrap","float: none","z-index: 1001","border-radius: 5px","box-shadow: 0px 10px 20px #808080"]),Qu[$u("MENUITEM")]=Yu(["padding: 1px 2em","background: transparent"]),Qu[$u("MENUARROW")]=Yu(["position: absolute","right: 0.5em","padding-top: 0.25em","color: #666666","font-family: null","font-size: 0.75em"]),Qu[$u("MENUACTIVE")+" "+$u("MENUARROW")]=Yu(["color: white"]),Qu[$u("MENUARROW")+$u("RTL")]=Yu(["left: 0.5em","right: auto"]),Qu[$u("MENUCHECK")]=Yu(["position: absolute","left: 0.7em","font-family: null"]),Qu[$u("MENUCHECK")+$u("RTL")]=Yu(["right: 0.7em","left: auto"]),Qu[$u("MENURADIOCHECK")]=Yu(["position: absolute","left: 0.7em"]),Qu[$u("MENURADIOCHECK")+$u("RTL")]=Yu(["right: 0.7em","left: auto"]),Qu[$u("MENUINPUTBOX")]=Yu(["padding-left: 1em","right: 0.5em","color: #666666","font-family: null"]),Qu[$u("MENUINPUTBOX")+$u("RTL")]=Yu(["left: 0.1em"]),Qu[$u("MENUCOMBOBOX")]=Yu(["left: 0.1em","padding-bottom: 0.5em"]),Qu[$u("MENUSLIDER")]=Yu(["left: 0.1em"]),Qu[$u("SLIDERVALUE")]=Yu(["position: absolute","right: 0.1em","padding-top: 0.25em","color: #333333","font-size: 0.75em"]),Qu[$u("MENUACTIVE")+" "+$u("SLIDERVALUE")]=Yu(["color: #DDDDDD"]),Qu[$u("SLIDERBAR")]=Yu(["outline: none","background: #D3D3D3"]),Qu[$u("MENULABEL")]=Yu(["padding: 1px 2em 3px 1.33em","font-style: italic"]),Qu[$u("MENURULE")]=Yu(["border-top: 1px solid #DDDDDD","margin: 4px 3px"]),Qu[$u("MENUDISABLED")]=Yu(["color: #999"]),Qu[$u("MENUACTIVE")]=Yu(["background-color: #606872","color: white"]),Qu[$u("MENUDISABLED")+":focus"]=Yu(["background-color: #E8E8E8"]),Qu[$u("MENULABEL")+":focus"]=Yu(["background-color: #E8E8E8"]),Qu[$u("CONTEXTMENU")+":focus"]=Yu(["outline: none"]),Qu[$u("CONTEXTMENU")+" "+$u("MENUITEM")+":focus"]=Yu(["outline: none"]),Qu[$u("SELECTIONMENU")]=Yu(["position: relative","float: left","border-bottom: none","box-shadow: none ! important","border-radius: 0px !important"]),Qu[$u("SELECTIONITEM")]=Yu(["padding-right: 1em"]),Qu[$u("SELECTION")]=Yu(["right: 40%","width: 50%"]),Qu[$u("SELECTIONBOX")]=Yu(["padding: 0em","max-height: 20em","max-width: none","background-color: #FFFFFF"]),Qu[$u("SELECTIONDIVIDER")]=Yu(["clear: both","border-top: 2px solid #000000"]),Qu[$u("MENU")+" "+$u("MENUCLOSE")]=Yu(["top: -10px","left: -10px"]),Qu["@media (prefers-color-scheme: dark) /* menu */"]=Yu([$u("MENU")+" "+Yu(["color: #E0E0E0","background-color: #242436","box-shadow: 0px 10px 20px #000","border: 1px solid #808080"]),$u("SLIDERVALUE")+" "+Yu(["color: #D0D0D0"]),$u("MENUDISABLED")+":focus "+Yu(["background-color: #383838"]),$u("MENULABEL")+":focus "+Yu(["background-color: #585858"]),$u("MENURULE")+" "+Yu(["border-top: 1px solid #808080"]),$u("SELECTIONDIVIDER")+" "+Yu(["border-top: 2px solid #808080"])],"");const Zu={};Zu[$u("MENUCLOSE")]=Yu(["position: absolute","cursor: pointer","display: inline-block","border: 2px solid #AAA","border-radius: 18px",'font-family: "Courier New", Courier',"font-size: 24px","color: #F0F0F0"]),Zu[$u("MENUCLOSE")+" span"]=Yu(["display: block","background-color: #AAA","border: 1.5px solid","border-radius: 18px","line-height: 0","padding: 8px 0 6px"]),Zu[$u("MENUCLOSE")+":hover"]=Yu(["color: white !important","border: 2px solid #CCC !important"]),Zu[$u("MENUCLOSE")+":hover span"]=Yu(["background-color: #CCC !important"]),Zu[$u("MENUCLOSE")+":hover:focus"]=Yu(["outline: none"]);function tp(t,e=document,s="MJX-Menu-styles"){if(e.head.querySelector("#"+s))return;const i=e.createElement("style");i.id=s;const r=[];for(const e in t)r.push(`${e} ${t[e]}`);i.textContent=r.join("\n"),e.head.appendChild(i)}class ep extends Mu{constructor(){super(...arguments),this.mathItem=null,this.nofocus=!1,this.errorMsg=""}post(t,e){var s,i;if(this.mathItem){const r=null===(i=null===(s=this.mathItem)||void 0===s?void 0:s.explorers)||void 0===i?void 0:i.speech;(null==r?void 0:r.active)&&(r.restarted=r.semanticFocus()),void 0!==e&&(this.getOriginalMenu(),this.getSemanticsMenu(),this.getSpeechMenu(),this.getBrailleMenu(),this.getSvgMenu(),this.getErrorMessage(),this.dynamicSubmenus()),super.post(t,e)}}unpost(){this.posted&&super.unpost(),this.mathItem&&(this.mathItem.outputData.nofocus=this.nofocus),this.mathItem=null,this.nofocus=!1}findID(...t){let e=this,s=null;for(const i of t){if(!e)return null;for(s of e.items){if(s.id===i){e=s instanceof Lu?s.submenu:null;break}e=s=null}}return s}setJax(t){this.jax=t}getOriginalMenu(){const t=this.mathItem.inputJax.name,e=this.findID("Show","Original");e.content="MathML"===t?"Original MathML":t+" Commands";this.findID("Copy","Original").content=e.content}getSemanticsMenu(){const t=this.findID("Settings","MathmlIncludes","semantics");"MathML"===this.mathItem.inputJax.name?t.disable():t.enable()}getSpeechMenu(){const t=this.mathItem.outputData.speech;this.findID("Show","Speech")[t?"enable":"disable"](),this.findID("Copy","Speech")[t?"enable":"disable"]()}getBrailleMenu(){const t=this.mathItem.outputData.braille;this.findID("Show","Braille")[t?"enable":"disable"](),this.findID("Copy","Braille")[t?"enable":"disable"]()}getSvgMenu(){const t=this.jax.SVG;this.findID("Show","SVG")[t?"enable":"disable"](),this.findID("Copy","SVG")[t?"enable":"disable"]()}getErrorMessage(){const t=this.mathItem.root.childNodes[0].childNodes;let e=!0;if(this.errorMsg="",1===t.length&&t[0].isKind("merror")){const s=t[0].attributes;this.errorMsg=s.get("data-mjx-error")||s.get("data-mjx-message")||"",e=!this.errorMsg}this.findID("Show","Error")[e?"disable":"enable"](),this.findID("Copy","Error")[e?"disable":"enable"]()}dynamicSubmenus(){for(const[t,[e,s]]of ep.DynamicSubmenus){const i=this.find(t);i&&e(this,i,t=>{var e;i.submenu=t,!(null===(e=null==t?void 0:t.items)||void 0===e?void 0:e.length)||s&&!this.settings[s]?i.disable():i.enable()})}}}ep.DynamicSubmenus=new Map;class sp extends Xu{constructor(t,e,s,i,r,n){super(t,e,i,r),this.attachMenu(n);const o=n.factory;this.selections=s.map(t=>o.get("selectionMenu")(o,t,this))}post(){const t=Array.from(Object.values(this.menu.jax)).filter(t=>!!t)[0],e=new ho({title:this.title,message:"",adaptor:t.adaptor,styles:{"mjx-dialog > div":{padding:0}}});e.attach(),this.contentDiv=e.content,this.display()}display(){const t=this;if(t.order(),!this.selections.length)return;const e=[];let s=0,i=[];const r=t.getChunkSize(this.selections.length);for(let n=0;nt.html.style.height=c+"px"),i=t.combineColumn(i,h)}t._balanced&&(t.balanceColumn(e,i),s=i.reduce((t,e)=>t+e-2,20)),e.forEach(t=>t.style.width=s+"px")}}var ip,rp,np;!function(t){t.DOMAIN="domain",t.STYLE="style",t.LOCALE="locale",t.TOPIC="topic",t.MODALITY="modality"}(ip||(ip={}));class op{static createProp(...t){const e=ap.DEFAULT_ORDER,s={};for(let i=0,r=t.length,n=e.length;it.push(this.getProperty(e).slice())),t}toString(){const t=[];return this.order.forEach(e=>t.push(e+": "+this.getProperty(e).toString())),t.join("\n")}}class ap extends op{static createCstr(...t){const e=ap.DEFAULT_ORDER,s={};for(let i=0,r=t.length,n=e.length;i{const s=e.indexOf(t);return-1!==s&&e.splice(s,1)})}constructor(t,e){const s={};for(const[e,i]of Object.entries(t))s[e]=[i];super(s,e),this.components=t}getComponents(){return this.components}getValue(t){return this.components[t]}getValues(){return this.order.map(t=>this.getValue(t))}allProperties(){const t=super.allProperties();for(let e,s,i=0;e=t[i],s=this.order[i];i++){const t=this.getValue(s);-1===e.indexOf(t)&&e.unshift(t)}return t}toString(){return this.getValues().join(".")}equal(t){const e=t.getAxes();if(this.order.length!==e.length)return!1;for(let s,i=0;s=e[i];i++){const e=this.getValue(s);if(!e||t.getValue(s)!==e)return!1}return!0}}ap.DEFAULT_ORDER=[ip.LOCALE,ip.MODALITY,ip.DOMAIN,ip.STYLE,ip.TOPIC],ap.BASE_LOCALE="base",ap.DEFAULT_VALUE="default",ap.DEFAULT_VALUES={[ip.LOCALE]:"en",[ip.DOMAIN]:ap.DEFAULT_VALUE,[ip.STYLE]:ap.DEFAULT_VALUE,[ip.TOPIC]:ap.DEFAULT_VALUE,[ip.MODALITY]:"speech"};class lp{constructor(t){this.order=t}parse(t){const e=t.split("."),s={};if(e.length>this.order.length)throw new Error("Invalid dynamic constraint: "+s);let i=0;for(let t,r=0;t=this.order[r],e.length;r++,i++){const i=e.shift();s[t]=i}return new ap(s,this.order.slice(0,i))}}class cp{constructor(t,e=new op(t.getProperties(),t.getOrder())){this.reference=t,this.fallback=e,this.order=this.reference.getOrder()}getReference(){return this.reference}setReference(t,e){this.reference=t,this.fallback=e||new op(t.getProperties(),t.getOrder()),this.order=this.reference.getOrder()}match(t){const e=t.getAxes();return e.length===this.reference.getAxes().length&&e.every(e=>{const s=t.getValue(e);return s===this.reference.getValue(e)||-1!==this.fallback.getProperty(e).indexOf(s)})}compare(t,e){let s=!1;for(let i,r=0;i=this.order[r];r++){const r=t.getValue(i),n=e.getValue(i);if(!s){const t=this.reference.getValue(i);if(t===r&&t!==n)return-1;if(t===n&&t!==r)return 1;if(t===r&&t===n)continue;t!==r&&t!==n&&(s=!0)}const o=this.fallback.getProperty(i),a=o.indexOf(r),l=o.indexOf(n);if(a{}){this.stream_&&this.fileHandle.then(()=>{this.isActive_&&this.stream_&&(this.stream_.end("","",t),this.stream_=null)}),this.isActive_=!1}constructor(){this.isActive_=!1,this.fileHandle=Promise.resolve(),this.stream_=null}startDebugFile_(t){this.fileHandle=up.f.fs.promises.open(t,"w"),this.fileHandle=this.fileHandle.then(e=>{this.stream_=e.createWriteStream(t),this.outputFunction=function(...t){this.stream_.write(t.join(" ")),this.stream_.write("\n")}.bind(this),this.stream_.on("error",function(t){console.info("Invalid log file. Debug information sent to console."),this.outputFunction=console.info}.bind(this)),this.stream_.on("finish",function(){console.info("Finalizing debug file.")})})}output_(t){this.stream_?this.fileHandle.then(()=>this.outputFunction.apply(this.outputFunction,["Speech Rule Engine Debugger:"].concat(t))):console.info(...["Speech Rule Engine Debugger:"].concat(t))}}var fp=__webpack_require__(439);class gp{constructor(t={}){this.delay=!1,this.domain="clearspeak",this.style=ap.DEFAULT_VALUES[ip.STYLE],this.locale=ap.DEFAULT_VALUES[ip.LOCALE],this.subiso="",this.modality=ap.DEFAULT_VALUES[ip.MODALITY],this.speech=hp.NONE,this.markup=dp.NONE,this.mark=!0,this.automark=!1,this.character=!0,this.cleanpause=!0,this.cayleyshort=!0,this.linebreaks=!1,this.rate="100",this.walker="Table",this.structure=!1,this.aria=!1,this.tree=!1,this.strict=!1,this.pprint=!1,this.rules="",this.prune="",this.set(t)}set(t){this.ensureDomain(t);for(const[e,s]of Object.entries(t))(gp.BINARY_FEATURES.includes(e)||gp.STRING_FEATURES.includes(e))&&(this[e]=s)}json(){const t={};return[].concat(gp.STRING_FEATURES,gp.BINARY_FEATURES).forEach(e=>t[e]=this[e]),t}ensureDomain(t){if(t.modality&&"speech"!==t.modality||!t.modality&&"speech"!==this.modality)return;if(!t.domain&&!t.locale)return;if("default"===t.domain)return void(t.domain="mathspeak");const e=t.locale||this.locale,s=t.domain||this.domain;-1===bp.indexOf(e)||"mathspeak"===s?"en"!==e?"mathspeak"!==s&&"clearspeak"!==s&&(t.domain="mathspeak"):-1===Ep.indexOf(s)&&(t.domain="mathspeak"):t.domain="mathspeak"}}gp.BINARY_FEATURES=["automark","mark","character","cleanpause","strict","structure","aria","pprint","cayleyshort","linebreaks","tree"],gp.STRING_FEATURES=["markup","style","domain","speech","walker","locale","delay","modality","rate","rules","subiso","prune"];const bp=["ca","da","es"],Ep=["chromevox","clearspeak","mathspeak","emacspeak","html"];class xp extends Error{constructor(t=""){super(),this.message=t,this.name="SRE Error"}}class yp{set defaultLocale(t){this._defaultLocale=fp.u.ensureLocale(t,this._defaultLocale)}get defaultLocale(){return this._defaultLocale}static getInstance(){return yp.instance=yp.instance||new yp,yp.instance}static defaultEvaluator(t,e){return t}static evaluateNode(t){return yp.nodeEvaluator(t)}getRate(){const t=parseInt(this.options.rate,10);return isNaN(t)?100:t}setDynamicCstr(t){if(this.defaultLocale&&(ap.DEFAULT_VALUES[ip.LOCALE]=this.defaultLocale),t){const e=Object.keys(t);for(let s=0;s[ \f\n\r\t\v\u200b]+<").trim()}(t),i=!!s.match(/&(?!lt|gt|amp|quot|apos)\w+;/g);if(!s)throw new xp("Empty input!");try{const t=e.parseFromString(s,i?"text/html":"text/xml");return yp.getInstance().mode===rp.HTTP?(vp.currentDocument=t,i?t.body.childNodes[0]:t.documentElement):t.documentElement}catch(t){throw new xp("Illegal input: "+t.message)}}function Rp(t,e){t.parentNode&&(t.parentNode.insertBefore(e,t),t.parentNode.removeChild(t))}function Sp(t){return up.f.document.createElement(t)}function Mp(t){let e="",s=/(>)(<)(\/*)/g,i=0,r=(t=t.replace(s,"$1\r\n$2$3")).split("\r\n");for(s=/(\.)*(<)(\/*)/g,r=r.map(t=>t.replace(s,"$1\r\n$2$3").split("\r\n")).reduce((t,e)=>t.concat(e),[]);r.length;){let t=r.shift();if(!t)continue;let s=0;if(t.match(/^<\w[^>/]*>[^>]+$/)){const e=Ip(t,r[0]);e[0]?e[1]?(t+=r.shift().slice(0,-e[1].length),e[1].trim()&&r.unshift(e[1])):t+=r.shift():s=1}else if(t.match(/^<\/\w/))0!==i&&(i-=1);else if(t.match(/^<\w[^>]*[^/]>.*$/))s=1;else if(t.match(/^<\w[^>]*\/>.+$/)){const e=t.indexOf(">")+1,s=t.slice(e);s.trim()&&r.unshift(),t=t.slice(0,e)+s}else s=0;e+=new Array(i+1).join(" ")+t+"\r\n",i+=s}return e}function Ip(t,e){if(!e)return[!1,""];const s=t.match(/^<([^> ]+).*>/),i=e.match(/^<\/([^>]+)>(.*)/);return s&&i&&s[1]===i[1]?[!0,i[2]]:[!1,""]}function Op(t){return t.tagName.toUpperCase()}function Dp(t){return(new up.f.xmldom.XMLSerializer).serializeToString(t)}!function(t){t[t.ELEMENT_NODE=1]="ELEMENT_NODE",t[t.ATTRIBUTE_NODE=2]="ATTRIBUTE_NODE",t[t.TEXT_NODE=3]="TEXT_NODE",t[t.CDATA_SECTION_NODE=4]="CDATA_SECTION_NODE",t[t.ENTITY_REFERENCE_NODE=5]="ENTITY_REFERENCE_NODE",t[t.ENTITY_NODE=6]="ENTITY_NODE",t[t.PROCESSING_INSTRUCTION_NODE=7]="PROCESSING_INSTRUCTION_NODE",t[t.COMMENT_NODE=8]="COMMENT_NODE",t[t.DOCUMENT_NODE=9]="DOCUMENT_NODE",t[t.DOCUMENT_TYPE_NODE=10]="DOCUMENT_TYPE_NODE",t[t.DOCUMENT_FRAGMENT_NODE=11]="DOCUMENT_FRAGMENT_NODE",t[t.NOTATION_NODE=12]="NOTATION_NODE"}(_p||(_p={}));class Pp{constructor(t,e,s){this.domain=t,this.name=e,this.func=s,this.active=!1}annotate(t){t.childNodes.forEach(this.annotate.bind(this)),t.contentNodes.forEach(this.annotate.bind(this)),t.addAnnotation(this.domain,this.func(t))}}class Bp{constructor(t,e,s,i={}){this.domain=t,this.name=e,this.func=s,this.def=i,this.active=!1}visit(t,e){let s=this.func(t,e);t.addAnnotation(this.domain,s[0]);for(let e,i=0;e=t.childNodes[i];i++)s=this.visit(e,s[1]);for(let e,i=0;e=t.contentNodes[i];i++)s=this.visit(e,s[1]);return s}}const Fp=new Map,jp=new Map;function Up(t){const e=t.domain+":"+t.name;t instanceof Pp?Fp.set(e,t):jp.set(e,t)}function Hp(t,e){const s=t+":"+e,i=Fp.get(s)||jp.get(s);i&&(i.active=!0)}var qp,Wp,zp;function Vp(t){const e=t.toString(16).toUpperCase();return e.length>3?e:("000"+e).slice(-4)}function Xp([t,e],s){const i=parseInt(t,16),r=parseInt(e,16),n=[];for(let t=i;t<=r;t++){let e=Vp(t);!1!==s[e]&&(e=s[e]||e,n.push(e))}return n}function Gp(t,e={}){return Xp(t,e).map(t=>String.fromCodePoint(parseInt(t,16)))}!function(t){t.BOLD="bold",t.BOLDFRAKTUR="bold-fraktur",t.BOLDITALIC="bold-italic",t.BOLDSCRIPT="bold-script",t.DOUBLESTRUCK="double-struck",t.DOUBLESTRUCKITALIC="double-struck-italic",t.FULLWIDTH="fullwidth",t.FRAKTUR="fraktur",t.ITALIC="italic",t.MONOSPACE="monospace",t.NORMAL="normal",t.SCRIPT="script",t.SANSSERIF="sans-serif",t.SANSSERIFITALIC="sans-serif-italic",t.SANSSERIFBOLD="sans-serif-bold",t.SANSSERIFBOLDITALIC="sans-serif-bold-italic"}(qp||(qp={})),function(t){t.SUPER="super",t.SUB="sub",t.CIRCLED="circled",t.PARENTHESIZED="parenthesized",t.PERIOD="period",t.NEGATIVECIRCLED="negative-circled",t.DOUBLECIRCLED="double-circled",t.CIRCLEDSANSSERIF="circled-sans-serif",t.NEGATIVECIRCLEDSANSSERIF="negative-circled-sans-serif",t.COMMA="comma",t.SQUARED="squared",t.NEGATIVESQUARED="negative-squared"}(Wp||(Wp={})),function(t){t.LATINCAP="latinCap",t.LATINSMALL="latinSmall",t.GREEKCAP="greekCap",t.GREEKSMALL="greekSmall",t.DIGIT="digit"}(zp||(zp={}));const Jp=[{interval:["1D400","1D419"],base:zp.LATINCAP,subst:{},capital:!0,category:"Lu",font:qp.BOLD},{interval:["1D41A","1D433"],base:zp.LATINSMALL,subst:{},capital:!1,category:"Ll",font:qp.BOLD},{interval:["1D56C","1D585"],base:zp.LATINCAP,subst:{},capital:!0,category:"Lu",font:qp.BOLDFRAKTUR},{interval:["1D586","1D59F"],base:zp.LATINSMALL,subst:{},capital:!1,category:"Ll",font:qp.BOLDFRAKTUR},{interval:["1D468","1D481"],base:zp.LATINCAP,subst:{},capital:!0,category:"Lu",font:qp.BOLDITALIC},{interval:["1D482","1D49B"],base:zp.LATINSMALL,subst:{},capital:!1,category:"Ll",font:qp.BOLDITALIC},{interval:["1D4D0","1D4E9"],base:zp.LATINCAP,subst:{},capital:!0,category:"Lu",font:qp.BOLDSCRIPT},{interval:["1D4EA","1D503"],base:zp.LATINSMALL,subst:{},capital:!1,category:"Ll",font:qp.BOLDSCRIPT},{interval:["1D538","1D551"],base:zp.LATINCAP,subst:{"1D53A":"2102","1D53F":"210D","1D545":"2115","1D547":"2119","1D548":"211A","1D549":"211D","1D551":"2124"},capital:!0,category:"Lu",font:qp.DOUBLESTRUCK},{interval:["1D552","1D56B"],base:zp.LATINSMALL,subst:{},capital:!1,category:"Ll",font:qp.DOUBLESTRUCK},{interval:["1D504","1D51D"],base:zp.LATINCAP,subst:{"1D506":"212D","1D50B":"210C","1D50C":"2111","1D515":"211C","1D51D":"2128"},capital:!0,category:"Lu",font:qp.FRAKTUR},{interval:["1D51E","1D537"],base:zp.LATINSMALL,subst:{},capital:!1,category:"Ll",font:qp.FRAKTUR},{interval:["FF21","FF3A"],base:zp.LATINCAP,subst:{},capital:!0,category:"Lu",font:qp.FULLWIDTH},{interval:["FF41","FF5A"],base:zp.LATINSMALL,subst:{},capital:!1,category:"Ll",font:qp.FULLWIDTH},{interval:["1D434","1D44D"],base:zp.LATINCAP,subst:{},capital:!0,category:"Lu",font:qp.ITALIC},{interval:["1D44E","1D467"],base:zp.LATINSMALL,subst:{"1D455":"210E"},capital:!1,category:"Ll",font:qp.ITALIC},{interval:["1D670","1D689"],base:zp.LATINCAP,subst:{},capital:!0,category:"Lu",font:qp.MONOSPACE},{interval:["1D68A","1D6A3"],base:zp.LATINSMALL,subst:{},capital:!1,category:"Ll",font:qp.MONOSPACE},{interval:["0041","005A"],base:zp.LATINCAP,subst:{},capital:!0,category:"Lu",font:qp.NORMAL},{interval:["0061","007A"],base:zp.LATINSMALL,subst:{},capital:!1,category:"Ll",font:qp.NORMAL},{interval:["1D49C","1D4B5"],base:zp.LATINCAP,subst:{"1D49D":"212C","1D4A0":"2130","1D4A1":"2131","1D4A3":"210B","1D4A4":"2110","1D4A7":"2112","1D4A8":"2133","1D4AD":"211B"},capital:!0,category:"Lu",font:qp.SCRIPT},{interval:["1D4B6","1D4CF"],base:zp.LATINSMALL,subst:{"1D4BA":"212F","1D4BC":"210A","1D4C4":"2134"},capital:!1,category:"Ll",font:qp.SCRIPT},{interval:["1D5A0","1D5B9"],base:zp.LATINCAP,subst:{},capital:!0,category:"Lu",font:qp.SANSSERIF},{interval:["1D5BA","1D5D3"],base:zp.LATINSMALL,subst:{},capital:!1,category:"Ll",font:qp.SANSSERIF},{interval:["1D608","1D621"],base:zp.LATINCAP,subst:{},capital:!0,category:"Lu",font:qp.SANSSERIFITALIC},{interval:["1D622","1D63B"],base:zp.LATINSMALL,subst:{},capital:!1,category:"Ll",font:qp.SANSSERIFITALIC},{interval:["1D5D4","1D5ED"],base:zp.LATINCAP,subst:{},capital:!0,category:"Lu",font:qp.SANSSERIFBOLD},{interval:["1D5EE","1D607"],base:zp.LATINSMALL,subst:{},capital:!1,category:"Ll",font:qp.SANSSERIFBOLD},{interval:["1D63C","1D655"],base:zp.LATINCAP,subst:{},capital:!0,category:"Lu",font:qp.SANSSERIFBOLDITALIC},{interval:["1D656","1D66F"],base:zp.LATINSMALL,subst:{},capital:!1,category:"Ll",font:qp.SANSSERIFBOLDITALIC},{interval:["0391","03A9"],base:zp.GREEKCAP,subst:{"03A2":"03F4"},capital:!0,category:"Lu",font:qp.NORMAL},{interval:["03B0","03D0"],base:zp.GREEKSMALL,subst:{"03B0":"2207","03CA":"2202","03CB":"03F5","03CC":"03D1","03CD":"03F0","03CE":"03D5","03CF":"03F1","03D0":"03D6"},capital:!1,category:"Ll",font:qp.NORMAL},{interval:["1D6A8","1D6C0"],base:zp.GREEKCAP,subst:{},capital:!0,category:"Lu",font:qp.BOLD},{interval:["1D6C1","1D6E1"],base:zp.GREEKSMALL,subst:{},capital:!1,category:"Ll",font:qp.BOLD},{interval:["1D6E2","1D6FA"],base:zp.GREEKCAP,subst:{},capital:!0,category:"Lu",font:qp.ITALIC},{interval:["1D6FB","1D71B"],base:zp.GREEKSMALL,subst:{},capital:!1,category:"Ll",font:qp.ITALIC},{interval:["1D71C","1D734"],base:zp.GREEKCAP,subst:{},capital:!0,category:"Lu",font:qp.BOLDITALIC},{interval:["1D735","1D755"],base:zp.GREEKSMALL,subst:{},capital:!1,category:"Ll",font:qp.BOLDITALIC},{interval:["1D756","1D76E"],base:zp.GREEKCAP,subst:{},capital:!0,category:"Lu",font:qp.SANSSERIFBOLD},{interval:["1D76F","1D78F"],base:zp.GREEKSMALL,subst:{},capital:!1,category:"Ll",font:qp.SANSSERIFBOLD},{interval:["1D790","1D7A8"],base:zp.GREEKCAP,subst:{},capital:!0,category:"Lu",font:qp.SANSSERIFBOLDITALIC},{interval:["1D7A9","1D7C9"],base:zp.GREEKSMALL,subst:{},capital:!1,category:"Ll",font:qp.SANSSERIFBOLDITALIC},{interval:["0030","0039"],base:zp.DIGIT,subst:{},offset:0,category:"Nd",font:qp.NORMAL},{interval:["2070","2079"],base:zp.DIGIT,subst:{2071:"00B9",2072:"00B2",2073:"00B3"},offset:0,category:"No",font:Wp.SUPER},{interval:["2080","2089"],base:zp.DIGIT,subst:{},offset:0,category:"No",font:Wp.SUB},{interval:["245F","2473"],base:zp.DIGIT,subst:{"245F":"24EA"},offset:0,category:"No",font:Wp.CIRCLED},{interval:["3251","325F"],base:zp.DIGIT,subst:{},offset:21,category:"No",font:Wp.CIRCLED},{interval:["32B1","32BF"],base:zp.DIGIT,subst:{},offset:36,category:"No",font:Wp.CIRCLED},{interval:["2474","2487"],base:zp.DIGIT,subst:{},offset:1,category:"No",font:Wp.PARENTHESIZED},{interval:["2487","249B"],base:zp.DIGIT,subst:{2487:"1F100"},offset:0,category:"No",font:Wp.PERIOD},{interval:["2775","277F"],base:zp.DIGIT,subst:{2775:"24FF"},offset:0,category:"No",font:Wp.NEGATIVECIRCLED},{interval:["24EB","24F4"],base:zp.DIGIT,subst:{},offset:11,category:"No",font:Wp.NEGATIVECIRCLED},{interval:["24F5","24FE"],base:zp.DIGIT,subst:{},offset:1,category:"No",font:Wp.DOUBLECIRCLED},{interval:["277F","2789"],base:zp.DIGIT,subst:{"277F":"1F10B"},offset:0,category:"No",font:Wp.CIRCLEDSANSSERIF},{interval:["2789","2793"],base:zp.DIGIT,subst:{2789:"1F10C"},offset:0,category:"No",font:Wp.NEGATIVECIRCLEDSANSSERIF},{interval:["FF10","FF19"],base:zp.DIGIT,subst:{},offset:0,category:"Nd",font:qp.FULLWIDTH},{interval:["1D7CE","1D7D7"],base:zp.DIGIT,subst:{},offset:0,category:"Nd",font:qp.BOLD},{interval:["1D7D8","1D7E1"],base:zp.DIGIT,subst:{},offset:0,category:"Nd",font:qp.DOUBLESTRUCK},{interval:["1D7E2","1D7EB"],base:zp.DIGIT,subst:{},offset:0,category:"Nd",font:qp.SANSSERIF},{interval:["1D7EC","1D7F5"],base:zp.DIGIT,subst:{},offset:0,category:"Nd",font:qp.SANSSERIFBOLD},{interval:["1D7F6","1D7FF"],base:zp.DIGIT,subst:{},offset:0,category:"Nd",font:qp.MONOSPACE},{interval:["1F101","1F10A"],base:zp.DIGIT,subst:{},offset:0,category:"No",font:Wp.COMMA},{interval:["24B6","24CF"],base:zp.LATINCAP,subst:{},capital:!0,category:"So",font:Wp.CIRCLED},{interval:["24D0","24E9"],base:zp.LATINSMALL,subst:{},capital:!1,category:"So",font:Wp.CIRCLED},{interval:["1F110","1F129"],base:zp.LATINCAP,subst:{},capital:!0,category:"So",font:Wp.PARENTHESIZED},{interval:["249C","24B5"],base:zp.LATINSMALL,subst:{},capital:!1,category:"So",font:Wp.PARENTHESIZED},{interval:["1F130","1F149"],base:zp.LATINCAP,subst:{},capital:!0,category:"So",font:Wp.SQUARED},{interval:["1F170","1F189"],base:zp.LATINCAP,subst:{},capital:!0,category:"So",font:Wp.NEGATIVESQUARED},{interval:["1F150","1F169"],base:zp.LATINCAP,subst:{},capital:!0,category:"So",font:Wp.NEGATIVECIRCLED}],Kp=new Map;function $p(t,e){return t+e.split("-").map(t=>t[0].toUpperCase()+t.slice(1)).join("")}for(const t of Jp){const e=$p(t.base,t.font),s=Gp(t.interval,t.subst);let i=Kp.get(e);i?i.unicode=i.unicode.concat(s):(i=t,i.unicode=s,Kp.set(e,i))}var Yp;!function(t){t.PUNCTUATION="punctuation",t.FENCE="fence",t.NUMBER="number",t.IDENTIFIER="identifier",t.TEXT="text",t.OPERATOR="operator",t.RELATION="relation",t.LARGEOP="largeop",t.FUNCTION="function",t.ACCENT="accent",t.FENCED="fenced",t.FRACTION="fraction",t.PUNCTUATED="punctuated",t.RELSEQ="relseq",t.MULTIREL="multirel",t.INFIXOP="infixop",t.PREFIXOP="prefixop",t.POSTFIXOP="postfixop",t.APPL="appl",t.INTEGRAL="integral",t.BIGOP="bigop",t.SQRT="sqrt",t.ROOT="root",t.LIMUPPER="limupper",t.LIMLOWER="limlower",t.LIMBOTH="limboth",t.SUBSCRIPT="subscript",t.SUPERSCRIPT="superscript",t.UNDERSCORE="underscore",t.OVERSCORE="overscore",t.TENSOR="tensor",t.TABLE="table",t.MULTILINE="multiline",t.MATRIX="matrix",t.VECTOR="vector",t.CASES="cases",t.ROW="row",t.LINE="line",t.CELL="cell",t.ENCLOSE="enclose",t.INFERENCE="inference",t.RULELABEL="rulelabel",t.CONCLUSION="conclusion",t.PREMISES="premises",t.UNKNOWN="unknown",t.EMPTY="empty"}(Yp||(Yp={}));const Qp=Object.assign({},Yp);var Zp;!function(t){t.COMMA="comma",t.SEMICOLON="semicolon",t.ELLIPSIS="ellipsis",t.FULLSTOP="fullstop",t.QUESTION="question",t.EXCLAMATION="exclamation",t.QUOTES="quotes",t.DASH="dash",t.TILDE="tilde",t.PRIME="prime",t.DEGREE="degree",t.VBAR="vbar",t.COLON="colon",t.OPENFENCE="openfence",t.CLOSEFENCE="closefence",t.APPLICATION="application",t.DUMMY="dummy",t.UNIT="unit",t.LABEL="label",t.OPEN="open",t.CLOSE="close",t.TOP="top",t.BOTTOM="bottom",t.NEUTRAL="neutral",t.METRIC="metric",t.LATINLETTER="latinletter",t.GREEKLETTER="greekletter",t.OTHERLETTER="otherletter",t.NUMBERSET="numbersetletter",t.INTEGER="integer",t.FLOAT="float",t.OTHERNUMBER="othernumber",t.INFTY="infty",t.MIXED="mixed",t.MULTIACCENT="multiaccent",t.OVERACCENT="overaccent",t.UNDERACCENT="underaccent",t.UNDEROVER="underover",t.SUBSUP="subsup",t.LEFTSUB="leftsub",t.LEFTSUPER="leftsuper",t.RIGHTSUB="rightsub",t.RIGHTSUPER="rightsuper",t.LEFTRIGHT="leftright",t.ABOVEBELOW="abovebelow",t.INTERVAL="interval",t.SETEMPTY="set empty",t.SETEXT="set extended",t.SETSINGLE="set singleton",t.SETCOLLECT="set collection",t.STRING="string",t.SPACE="space",t.ANNOTATION="annotation",t.TEXT="text",t.SEQUENCE="sequence",t.ENDPUNCT="endpunct",t.STARTPUNCT="startpunct",t.NEGATIVE="negative",t.POSITIVE="positive",t.NEGATION="negation",t.MULTIOP="multiop",t.PREFIXOP="prefix operator",t.POSTFIXOP="postfix operator",t.LIMFUNC="limit function",t.INFIXFUNC="infix function",t.PREFIXFUNC="prefix function",t.POSTFIXFUNC="postfix function",t.SIMPLEFUNC="simple function",t.COMPFUNC="composed function",t.SUM="sum",t.INTEGRAL="integral",t.GEOMETRY="geometry",t.BOX="box",t.BLOCK="block",t.ADDITION="addition",t.MULTIPLICATION="multiplication",t.SUBTRACTION="subtraction",t.IMPLICIT="implicit",t.DIVISION="division",t.VULGAR="vulgar",t.EQUALITY="equality",t.INEQUALITY="inequality",t.ARROW="arrow",t.ELEMENT="element",t.NONELEMENT="nonelement",t.REELEMENT="reelement",t.RENONELEMENT="renonelement",t.SET="set",t.DETERMINANT="determinant",t.ROWVECTOR="rowvector",t.BINOMIAL="binomial",t.SQUAREMATRIX="squarematrix",t.CYCLE="cycle",t.MULTILINE="multiline",t.MATRIX="matrix",t.VECTOR="vector",t.CASES="cases",t.TABLE="table",t.CAYLEY="cayley",t.PROOF="proof",t.LEFT="left",t.RIGHT="right",t.UP="up",t.DOWN="down",t.FINAL="final",t.SINGLE="single",t.HYP="hyp",t.AXIOM="axiom",t.LOGIC="logic",t.UNKNOWN="unknown",t.MGLYPH="mglyph"}(Zp||(Zp={}));const tm=Object.assign({},Zp);var em;!function(t){t.CALIGRAPHIC="caligraphic",t.CALIGRAPHICBOLD="caligraphic-bold",t.OLDSTYLE="oldstyle",t.OLDSTYLEBOLD="oldstyle-bold",t.UNKNOWN="unknown"}(em||(em={}));const sm=Object.assign(Object.assign(Object.assign({},qp),em),Wp);var im;!function(t){t.ALLLETTERS="allLetters",t.D="d",t.BAR="bar",t.TILDE="tilde",t.CURLY="curly",t.PAREN="paren",t.BRACKET="bracket",t.FLOOR="floor",t.CEIL="ceil"}(im||(im={}));const rm=Object.assign(Object.assign({},zp),im);var nm=function(t,e){var s={};for(var i in t)Object.prototype.hasOwnProperty.call(t,i)&&e.indexOf(i)<0&&(s[i]=t[i]);if(null!=t&&"function"==typeof Object.getOwnPropertySymbols){var r=0;for(i=Object.getOwnPropertySymbols(t);rparseInt(t,16))):e.push(parseInt(s,16));return e}(e);for(const e of r)i[e]||(t.set(String.fromCodePoint(e),String.fromCodePoint(e+s)),i[e]=!0,i[e+s]=!0)}const um=["0028","0029","207D","207E","208D","208E","2768","2769","276A","276B","27EE","27EF","FE59","FE5A","FF08","FF09"],pm=["005B","005D","2045","2046","298B","298C","298D","298E","298F","2990","FF3B","FF3D"],mm=["007B","007D","2774","2775","FE5B","FE5C","FF5B","FF5D"],fm=["2308","2309","2E22","2E23","300C","300E","FF62"],gm=["230A","230B","2E24","2E25","300D","300F","FF63"];function bm(t,e){for(const s of t){const t=String.fromCodePoint(parseInt(s,16));cm.Secondary.set(t,e),cm.FencesSecondary.set(t,e)}}const Em=["cos","cot","csc","sec","sin","tan","arccos","arccot","arccsc","arcsec","arcsin","arctan"].concat(["cosh","coth","csch","sech","sinh","tanh","arcosh","arcoth","arcsch","arsech","arsinh","artanh"],["deg","det","dim","hom","ker","Tr"],["log","ln","lg","exp","gcd","lcm","arg","im","re","Pr"]);function xm(t,e,s,i,r,n=[],o={},a={}){const l=Kp.get($p(t,i));l&&(l.unicode.forEach(t=>{cm.Meaning.set(t,{type:e,role:s,font:r}),n.forEach(e=>cm.Secondary.set(t,e))}),function(t,e){for(const[s,i]of Object.entries(e)){const e=t[s];void 0!==e&&cm.Meaning.set(e,i)}}(l.unicode,o),function(t,e){for(const[s,i]of Object.entries(e)){const e=t[s];void 0!==e&&cm.Secondary.set(e,i)}}(l.unicode,a))}[{set:["23","26","40","5c","a1","a7","b6","bf","2017",["2022","2025"],"2027","203b","203c",["2041","2043"],["2047","2049"],["204b","204d"],"2050","2055","2056",["2058","205e"],"2234","2235","fe45","fe46","fe5f","fe60","fe68","fe6b","ff03","ff06","ff0f","ff20","ff3c"],type:Qp.PUNCTUATION,role:tm.UNKNOWN},{set:["22","ab","bb","2dd",["2018","201f"],"2039","203a",["301d","301f"],"fe10","ff02","ff07"],type:Qp.PUNCTUATION,role:tm.QUOTES},{set:["3b","204f","2a1f","2a3e","fe14","fe54","ff1b"],type:Qp.PUNCTUATION,role:tm.SEMICOLON},{set:["3f","203d","fe16","fe56","ff1f"],type:Qp.PUNCTUATION,role:tm.QUESTION},{set:["21","fe15","fe57","ff01"],type:Qp.PUNCTUATION,role:tm.EXCLAMATION},{set:["5e","60","a8","aa","b4","ba","2c7",["2d8","2da"],"2040","207a","207d","207e","ff3e","ff40"],type:Qp.PUNCTUATION,role:tm.OVERACCENT},{set:["b8","2db","2038","203f","2054","208a","208d","208e"],type:Qp.PUNCTUATION,role:tm.UNDERACCENT},{set:["3a","2982","fe13","fe30","fe55","ff1a"],type:Qp.PUNCTUATION,role:tm.COLON},{set:["2c","2063","fe50","ff0c"],type:Qp.PUNCTUATION,role:tm.COMMA},{set:["2026",["22ee","22f1"],"fe19"],type:Qp.PUNCTUATION,role:tm.ELLIPSIS},{set:["2e","fe52","ff0e"],type:Qp.PUNCTUATION,role:tm.FULLSTOP},{set:["2d","207b","208b","2212","2796","fe63","ff0d"],type:Qp.OPERATOR,role:tm.DASH,secondary:rm.BAR},{set:["5f","af",["2010","2015"],"203e","208b",["fe49","fe4f"],"fe58","ff3f","ffe3"],type:Qp.PUNCTUATION,role:tm.DASH,secondary:rm.BAR},{set:["7e","2dc","2f7","303","330","334","2053","223c","223d","301c","ff5e"],type:Qp.OPERATOR,role:tm.TILDE,secondary:rm.TILDE},{set:["27","2b9","2ba",["2032","2037"],"2057"],type:Qp.PUNCTUATION,role:tm.PRIME},{set:["b0"],type:Qp.PUNCTUATION,role:tm.DEGREE},{set:["2b","b1","2064","2213","2214","2228","222a",["228c","228e"],"2294","2295","229d","229e","22bb","22bd","22c4","22ce","22d3","2304","271b","271c","2795","27cf","29fa","29fb","29fe",["2a22","2a28"],"2a2d","2a2e","2a39","2a42","2a45","2a46","2a48","2a4a","2a4c","2a4f","2a50","2a52","2a54","2a56","2a57","2a59","2a5b","2a5d",["2a61","2a63"],"2adc","2add","fe62","ff0b"],type:Qp.OPERATOR,role:tm.ADDITION},{set:["2a","b7","d7","2020","2021","204e","2051","2062",["2217","2219"],"2227","2229","2240","2293","2297",["2299","229b"],"22a0","22a1","22b9","22bc",["22c5","22cc"],"22cf","22d2","22d4","2303","2305","2306","25cb","2715","2716","27ce","27d1",["29d1","29d7"],"29e2","2a1d",["2a2f","2a37"],["2a3b","2a3d"],"2a40","2a43","2a44","2a47","2a49","2a4b","2a4d","2a4e","2a51","2a53","2a55","2a58","2a5a","2a5c",["2a5e","2a60"],"2ada","2adb","fe61","ff0a"],type:Qp.OPERATOR,role:tm.MULTIPLICATION},{set:["2d","af","2010","2011","2052","207b","208b","2212","2216","2238","2242","2296","229f","2796","29ff",["2a29","2a2c"],"2a3a","2a41","fe63","ff0d"],type:Qp.OPERATOR,role:tm.SUBTRACTION},{set:["2f","f7","2044","2215","2298","2797","27cc","29bc",["29f5","29f9"],"2a38"],type:Qp.OPERATOR,role:tm.DIVISION},{set:["25","2030","2031","ff05","fe6a"],type:Qp.OPERATOR,role:tm.POSTFIXOP},{set:["ac","2200","2201","2203","2204","2206",["221a","221c"],"2310","ffe2"],type:Qp.OPERATOR,role:tm.PREFIXOP},{set:["2320","2321","23aa","23ae","23af","23b2","23b3","23b6","23b7"],type:Qp.OPERATOR,role:tm.PREFIXOP},{set:["1d7ca","1d7cb"],type:Qp.OPERATOR,role:tm.PREFIXOP,font:sm.BOLD},{set:["3d","7e","207c","208c","221d","2237",["223a","223f"],"2243","2245","2248",["224a","224e"],["2251","225f"],"2261","2263","229c","22cd","22d5","29e4","29e6","2a66","2a67",["2a6a","2a6c"],["2a6c","2a78"],"fe66","ff1d"],type:Qp.RELATION,role:tm.EQUALITY},{set:["3c","3e","2241","2242","2244","2246","2247","2249","224f","2250","2260","2262",["2264","2281"],"22b0","22b1",["22d6","22e1"],["22e6","22e9"],["2976","2978"],"29c0","29c1","29e1","29e3","29e5",["2a79","2abc"],["2af7","2afa"],"fe64","fe65","ff1c","ff1e"],type:Qp.RELATION,role:tm.INEQUALITY},{set:[["2282","228b"],["228f","2292"],["22b2","22b8"],"22d0","22d1",["22e2","22e5"],["22ea","22ed"],"27c3","27c4",["27c7","27c9"],["27d5","27d7"],"27dc",["2979","297b"],"29df",["2abd","2ad8"]],type:Qp.RELATION,role:tm.SET},{set:["2236",["27e0","27e5"],"292b","292c",["29b5","29bb"],"29be","29bf",["29c2","29d0"]],type:Qp.RELATION,role:tm.UNKNOWN},{set:["2205",["29b0","29b4"]],type:Qp.IDENTIFIER,role:tm.SETEMPTY},{set:["1ab2","221e",["29dc","29de"]],type:Qp.IDENTIFIER,role:tm.INFTY},{set:["22a2","22a3",["22a6","22af"],"27da","27db","27dd","27de","2ade",["2ae2","2ae6"],"2aec","2aed"],type:Qp.RELATION,role:tm.LOGIC},{set:["22a4","22a5","22ba","27d8","27d9","27df","2adf","2ae0",["2ae7","2aeb"],"2af1"],type:Qp.IDENTIFIER,role:tm.LOGIC},{set:[["2190","21ff"],"2301","2324","238b","2794",["2798","27af"],["27b1","27be"],["27f0","27ff"],["2900","292a"],["292d","2975"],["297c","297f"],["2b00","2b11"],["2b30","2b4c"],["ffe9","ffec"]],type:Qp.RELATION,role:tm.ARROW},{set:["2208","220a",["22f2","22f9"],"22ff","27d2","2ad9"],type:Qp.OPERATOR,role:tm.ELEMENT},{set:["2209"],type:Qp.OPERATOR,role:tm.NONELEMENT},{set:["220b","220d",["22fa","22fe"]],type:Qp.OPERATOR,role:tm.REELEMENT},{set:["220c"],type:Qp.OPERATOR,role:tm.RENONELEMENT},{set:[["220f","2211"],["22c0","22c3"],["2a00","2a0b"],"2a3f","2afc","2aff"],type:Qp.LARGEOP,role:tm.SUM},{set:["2140"],type:Qp.LARGEOP,role:tm.SUM,font:sm.DOUBLESTRUCK},{set:[["222b","2233"],["2a0c","2a17"],["2a17","2a1c"]],type:Qp.LARGEOP,role:tm.INTEGRAL},{set:[["2500","257F"]],type:Qp.RELATION,role:tm.BOX},{set:[["2580","259F"]],type:Qp.IDENTIFIER,role:tm.BLOCK},{set:[["25A0","25FF"],["2B12","2B2F"],["2B50","2B59"]],type:Qp.RELATION,role:tm.GEOMETRY},{set:["220e","2300","2302","2311","29bd","29e0",["29e8","29f3"],"2a1e","2afe","ffed","ffee"],type:Qp.OPERATOR,role:tm.GEOMETRY},{set:[["221f","2222"],"22be","22bf",["2312","2314"],"237c","27c0",["299b","29af"]],type:Qp.OPERATOR,role:tm.GEOMETRY},{set:["24",["a2","a5"],"b5","2123",["2125","2127"],"212a","212b","fe69","ff04","ffe0","ffe1","ffe5","ffe6"],type:Qp.IDENTIFIER,role:tm.UNKNOWN},{set:["a9","ae","210f","2114","2116","2117",["211e","2122"],"212e","2132",["2139","213b"],["2141","2144"],"214d","214e",["1f12a","1f12c"],"1f18a"],type:Qp.IDENTIFIER,role:tm.OTHERLETTER},{set:["2224","2226","2239","2307","27b0","27bf","27c1","27c2","27ca","27cb","27cd","27d0","27d3","27d4","2981","2999","299a","29e7","29f4","2a20","2a21","2a64","2a65","2a68","2a69","2ae1",["2aee","2af0"],"2af2","2af3","2af5","2af6","2afb","2afd"],type:Qp.OPERATOR,role:tm.UNKNOWN},{set:["2605","2606","26aa","26ab",["2720","274d"]],type:Qp.OPERATOR,role:tm.UNKNOWN},{set:[["2145","2149"]],type:Qp.IDENTIFIER,role:tm.LATINLETTER,font:sm.DOUBLESTRUCKITALIC,secondary:rm.ALLLETTERS},{set:[["213c","213f"]],type:Qp.IDENTIFIER,role:tm.GREEKLETTER,font:sm.DOUBLESTRUCK,secondary:rm.ALLLETTERS},{set:["3d0","3d7","3f6",["1d26","1d2a"],"1d5e","1d60",["1d66","1d6a"]],type:Qp.IDENTIFIER,role:tm.GREEKLETTER,font:sm.NORMAL,secondary:rm.ALLLETTERS},{set:[["2135","2138"]],type:Qp.IDENTIFIER,role:tm.OTHERLETTER,font:sm.NORMAL,secondary:rm.ALLLETTERS},{set:["131","237"],type:Qp.IDENTIFIER,role:tm.LATINLETTER,font:sm.NORMAL},{set:["1d6a4","1d6a5"],type:Qp.IDENTIFIER,role:tm.LATINLETTER,font:sm.ITALIC},{set:["2113","2118"],type:Qp.IDENTIFIER,role:tm.LATINLETTER,font:sm.SCRIPT},{set:[["c0","d6"],["d8","f6"],["f8","1bf"],["1c4","2af"],["1d00","1d25"],["1d6b","1d9a"],["1e00","1ef9"],["363","36f"],["1dd3","1de6"],["1d62","1d65"],"1dca","2071","207f",["2090","209c"],"2c7c"],type:Qp.IDENTIFIER,role:tm.LATINLETTER,font:sm.NORMAL},{set:[["00bc","00be"],["2150","215f"],"2189"],type:Qp.NUMBER,role:tm.FLOAT},{set:["23E8",["3248","324f"]],type:Qp.NUMBER,role:tm.INTEGER},{set:[["214A","214C"],"2705","2713","2714","2717","2718"],type:Qp.IDENTIFIER,role:tm.UNKNOWN},{set:["20","a0","ad",["2000","200f"],["2028","202f"],["205f","2060"],"206a","206b","206e","206f","feff",["fff9","fffb"]],type:Qp.TEXT,role:tm.SPACE},{set:["7c","a6","2223","23b8","23b9","23d0","2758",["fe31","fe34"],"ff5c","ffe4","ffe8"],type:Qp.FENCE,role:tm.NEUTRAL},{set:["2016","2225","2980","2af4"],type:Qp.FENCE,role:tm.METRIC}].forEach(t=>{var{set:e}=t,s=nm(t,["set"]);return hm(function(t){let e=[];for(const s of t)Array.isArray(s)?e=e.concat(Gp(s)):e.push(String.fromCodePoint(parseInt(s,16)));return e}(e),s)}),dm(cm.FencesVert,["23b4",["23dc","23e1"],["fe35","fe44"],"fe47"]),dm(cm.FencesHoriz,["28","2045","207D","208D",["2308","230f"],["231c","231f"],"2329","23b0",["2768","2775"],"27c5",["27e6","27ef"],["2983","2998"],["29d8","29db"],"29fc",["2e22","2e29"],["3008","3011"],["3014","301b"],"fd3e","fe17",["fe59","fe5e"],"ff08","ff5f","ff62"]),dm(cm.FencesHoriz,["5b","7b","ff3b","ff5b"],2),dm(cm.FencesHoriz,[["239b","23a6"]],3),dm(cm.FencesHoriz,[["23a7","23a9"]],4),hm([...cm.FencesHoriz.keys()],{type:Qp.FENCE,role:tm.OPEN}),hm([...cm.FencesHoriz.values()],{type:Qp.FENCE,role:tm.CLOSE}),hm([...cm.FencesVert.keys()],{type:Qp.FENCE,role:tm.TOP}),hm([...cm.FencesVert.values()],{type:Qp.FENCE,role:tm.BOTTOM}),bm(um,rm.PAREN),bm(mm,rm.CURLY),bm(pm,rm.BRACKET),bm(fm,rm.CEIL),bm(gm,rm.FLOOR),function(){for(const[t,e]of Object.entries(sm)){const s=!!Wp[t]?sm.UNKNOWN:e===sm.FULLWIDTH?sm.NORMAL:e;xm(zp.LATINCAP,Qp.IDENTIFIER,tm.LATINLETTER,e,s,[rm.ALLLETTERS]),xm(zp.LATINSMALL,Qp.IDENTIFIER,tm.LATINLETTER,e,s,[rm.ALLLETTERS],{},{3:rm.D}),xm(zp.GREEKCAP,Qp.IDENTIFIER,tm.GREEKLETTER,e,s,[rm.ALLLETTERS]),xm(zp.GREEKSMALL,Qp.IDENTIFIER,tm.GREEKLETTER,e,s,[rm.ALLLETTERS],{0:{type:Qp.OPERATOR,role:tm.PREFIXOP,font:s},26:{type:Qp.OPERATOR,role:tm.PREFIXOP,font:s}}),xm(zp.DIGIT,Qp.NUMBER,tm.INTEGER,e,s)}}(),hm(["inf","lim","liminf","limsup","max","min","sup","injlim","projlim"],{type:Qp.FUNCTION,role:tm.LIMFUNC}),hm(Em,{type:Qp.FUNCTION,role:tm.PREFIXFUNC}),hm(["mod","rem"],{type:Qp.OPERATOR,role:tm.PREFIXFUNC});const ym=[];function Nm(t,e){for(let s,i=0;s=ym[i];i++){const i=s.compare(t,e);if(0!==i)return i}return 0}function vm(t){if(t.length<=1)return t;const e=t.slice();!function(t){t.sort(Nm)}(e);const s=[];let i;do{i=e.pop(),s.push(i)}while(i&&e.length&&0===Nm(e[e.length-1],i));return s}function Tm(t,e){return t.match(/^.+:.+$/)||!e?t:t+":"+e}new class{constructor(t,e=null){this.comparator=t,this.type=e,function(t){ym.push(t)}(this)}compare(t,e){return this.type&&this.type===t.type&&this.type===e.type?this.comparator(t,e):0}}(function(t,e){return t.role===tm.SIMPLEFUNC?1:e.role===tm.SIMPLEFUNC?-1:0},Qp.IDENTIFIER);class wm extends Map{set(t,e){return super.set(Tm(t,e.font),e),this}setNode(t){this.set(t.textContent,t.meaning())}get(t,e=null){return super.get(Tm(t,e))}getNode(t){return this.get(t.textContent,t.font)}}class Cm extends Map{add(t,e){const s=this.get(t);s?s.push(e):super.set(t,[e])}get(t,e=null){return super.get(Tm(t,e))}getNode(t){return this.get(t.textContent,t.font)}minimize(){for(const[t,e]of this)1===e.length&&this.delete(t)}isMultiValued(){for(const t of this.values())if(t.length>1)return!0;return!1}}class km extends Cm{add(t,e){super.add(Tm(t,e.font),e)}addNode(t){this.add(t.textContent,t)}toString(){const t=[];for(const[e,s]of this){const i=Array(e.length+3).join(" "),r=s.map(t=>t.toString()).join("\n"+i);t.push(e+": "+r)}return t.join("\n")}collateMeaning(){const t=new _m;for(const[e,s]of this)t.set(e,s.map(t=>t.meaning()));return t}}class _m extends Cm{add(t,e){const s=this.get(t,e.font);s&&s.find(function(t){return i=e,(s=t).type===i.type&&s.role===i.role&&s.font===i.font;var s,i})||super.add(Tm(t,e.font),e)}addNode(t){this.add(t.textContent,t.meaning())}toString(){const t=[];for(const[e,s]of this){const i=Array(e.length+3).join(" "),r=s.map(t=>`{type: ${t.type}, role: ${t.role}, font: ${t.font}}`).join("\n"+i);t.push(e+": "+r)}return t.join("\n")}reduce(){for(const[t,e]of this)1!==e.length&&this.set(t,vm(e))}default(){const t=new wm;for(const[e,s]of this)1===s.length&&t.set(e,s[0]);return t}newDefault(){const t=this.default();this.reduce();const e=this.default();return t.size!==e.size?e:null}}var Lm;!function(t){t.ANNOTATION="ANNOTATION",t.ANNOTATIONXML="ANNOTATION-XML",t.MACTION="MACTION",t.MALIGNGROUP="MALIGNGROUP",t.MALIGNMARK="MALIGNMARK",t.MATH="MATH",t.MENCLOSE="MENCLOSE",t.MERROR="MERROR",t.MFENCED="MFENCED",t.MFRAC="MFRAC",t.MGLYPH="MGLYPH",t.MI="MI",t.MLABELEDTR="MLABELEDTR",t.MMULTISCRIPTS="MMULTISCRIPTS",t.MN="MN",t.MO="MO",t.MOVER="MOVER",t.MPADDED="MPADDED",t.MPHANTOM="MPHANTOM",t.MPRESCRIPTS="MPRESCRIPTS",t.MROOT="MROOT",t.MROW="MROW",t.MS="MS",t.MSPACE="MSPACE",t.MSQRT="MSQRT",t.MSTYLE="MSTYLE",t.MSUB="MSUB",t.MSUBSUP="MSUBSUP",t.MSUP="MSUP",t.MTABLE="MTABLE",t.MTD="MTD",t.MTEXT="MTEXT",t.MTR="MTR",t.MUNDER="MUNDER",t.MUNDEROVER="MUNDEROVER",t.NONE="NONE",t.SEMANTICS="SEMANTICS"}(Lm||(Lm={}));const Am=Object.values(Lm),Rm=[Lm.MO,Lm.MI,Lm.MN,Lm.MTEXT,Lm.MS,Lm.MSPACE],Sm=[Lm.MERROR,Lm.MPHANTOM,Lm.MALIGNGROUP,Lm.MALIGNMARK,Lm.MPRESCRIPTS,Lm.ANNOTATION,Lm.ANNOTATIONXML],Mm=[Lm.MATH,Lm.MROW,Lm.MPADDED,Lm.MACTION,Lm.NONE,Lm.MSTYLE,Lm.SEMANTICS],Im=[Lm.MROOT,Lm.MSQRT],Om=["aria-label","exact-speech","alt"];function Dm(t){return!!t&&Op(t)===Lm.MATH}function Pm(t){return!!t&&(Sm.includes(Op(t))||!Am.includes(Op(t)))}function Bm(t){return!!t&&Mm.includes(Op(t))}function Fm(t){return!!t&&Op(t)===Lm.MGLYPH&&!function(t){return!!t&&Rm.includes(Op(t))}(t.parentNode)}function jm(t){const e=[];for(let s,i=0;s=t[i];i++){if(s.nodeType!==_p.ELEMENT_NODE)continue;const t=Op(s);Sm.includes(t)||(Mm.includes(t)&&0===s.childNodes.length||e.push(s))}return e}function Um(t,e){var s;if(null===(s=e.attributes)||void 0===s?void 0:s.length){const s=e.attributes;for(let e=s.length-1;e>=0;e--){const i=s[e].name;i.match(/^ext/)&&(t.attributes[i]=s[e].value,t.nobreaking=!0),Om.includes(i)&&(t.attributes["ext-speech"]=s[e].value,t.nobreaking=!0),"href"===i&&(t.attributes.href=s[e].value,t.nobreaking=!0),"data-latex"!==i.toLowerCase()&&"latex"!==i.toLowerCase()||(t.attributes.latex=s[e].value),i.match(/texclass$/)&&(t.attributes.texclass=s[e].value),"color"!==i&&"mathcolor"!==i||(t.attributes.color=s[e].value)}}}function Hm(t){return t&&t.embellished&&t.childNodes.length>0?Hm(t.childNodes[0]):t}function qm(t,e,s){s&&t.reverse();const i=[];for(let r,n=0;r=t[n];n++){if(e(r))return s?{head:t.slice(n+1).reverse(),div:r,tail:i.reverse()}:{head:i,div:r,tail:t.slice(n+1)};i.push(r)}return s?{head:[],div:null,tail:i.reverse()}:{head:i,div:null,tail:[]}}function Wm(t,e){let s=t;const i=[],r=[];let n=null;do{n=qm(s,e),r.push(n.head),i.push(n.div),s=n.tail}while(n.div);return i.pop(),{rel:i,comp:r}}var zm;!function(t){t.EMBELLISHED="embellished",t.FENCEPOINTER="fencepointer",t.FONT="font",t.ID="id",t.ANNOTATION="annotation",t.ROLE="role",t.TYPE="type",t.CHILDREN="children",t.CONTENT="content",t.TEXT="$t"}(zm||(zm={}));class Vm{static fromXml(t){const e=parseInt(t.getAttribute("id"),10),s=new Vm(e);return s.type=t.tagName,Vm.setAttribute(s,t,"role"),Vm.setAttribute(s,t,"font"),Vm.setAttribute(s,t,"embellished"),Vm.setAttribute(s,t,"fencepointer","fencePointer"),t.getAttribute("annotation")&&s.parseAnnotation(t.getAttribute("annotation")),Um(s,t),Vm.processChildren(s,t),s}static setAttribute(t,e,s,i){i=i||s;const r=e.getAttribute(s);r&&(t[i]=r)}static processChildren(t,e){for(const s of Lp(e.childNodes)){if(s.nodeType===_p.TEXT_NODE){t.textContent=s.textContent;continue}const e=Lp(s.childNodes).map(Vm.fromXml);e.forEach(e=>e.parent=t),"CONTENT"===Op(s)?t.contentNodes=e:t.childNodes=e}}constructor(t){this.id=t,this.mathml=[],this.parent=null,this.type=Qp.UNKNOWN,this.role=tm.UNKNOWN,this.font=sm.UNKNOWN,this.embellished=null,this.fencePointer="",this.childNodes=[],this.textContent="",this.mathmlTree=null,this.contentNodes=[],this.annotation={},this.attributes={},this.nobreaking=!1,this.noupdate=!1}querySelectorAll(t){let e=[];for(let s,i=0;s=this.childNodes[i];i++)e=e.concat(s.querySelectorAll(t));for(let s,i=0;s=this.contentNodes[i];i++)e=e.concat(s.querySelectorAll(t));return t(this)&&e.unshift(this),e}xml(t,e){const s=function(s,i){const r=i.map(function(s){return s.xml(t,e)}),n=t.createElementNS("",s);for(let t,e=0;t=r[e];e++)n.appendChild(t);return n},i=t.createElementNS("",this.type);return e||this.xmlAttributes(i),i.textContent=this.textContent,this.contentNodes.length>0&&i.appendChild(s(zm.CONTENT,this.contentNodes)),this.childNodes.length>0&&i.appendChild(s(zm.CHILDREN,this.childNodes)),i}toString(t=!1){const e=Ap("");return Dp(this.xml(e.ownerDocument,t))}allAttributes(){const t=[];return t.push([zm.ROLE,this.role]),this.font!==sm.UNKNOWN&&t.push([zm.FONT,this.font]),Object.keys(this.annotation).length&&t.push([zm.ANNOTATION,this.annotationXml()]),this.embellished&&t.push([zm.EMBELLISHED,this.embellished]),this.fencePointer&&t.push([zm.FENCEPOINTER,this.fencePointer]),t.push([zm.ID,this.id.toString()]),t}annotationXml(){const t=[];for(const[e,s]of Object.entries(this.annotation))s.forEach(s=>t.push(e+":"+s));return t.join(";")}attributesXml(){const t=[];for(const[e,s]of Object.entries(this.attributes))t.push(e+":"+Vm.escapeValue(s));return t.join(";")}toJson(){const t={};t[zm.TYPE]=this.type;const e=this.allAttributes();for(let s,i=0;s=e[i];i++)t[s[0]]=s[1].toString();return this.textContent&&(t[zm.TEXT]=this.textContent),this.childNodes.length&&(t[zm.CHILDREN]=this.childNodes.map(function(t){return t.toJson()})),this.contentNodes.length&&(t[zm.CONTENT]=this.contentNodes.map(function(t){return t.toJson()})),t}updateContent(t,e){const s=e?t.replace(/^[ \f\n\r\t\v\u200b]*/,"").replace(/[ \f\n\r\t\v\u200b]*$/,""):t.trim();if(t=t&&!s?t:s,this.textContent===t)return;const i=cm.Meaning.get(t.replace(/\s/g," "));this.textContent=t,this.role=i.role,this.type=i.type,this.font=i.font}addMathmlNodes(t){for(let e,s=0;e=t[s];s++)-1===this.mathml.indexOf(e)&&this.mathml.push(e)}appendChild(t){this.childNodes.push(t),this.addMathmlNodes(t.mathml),t.parent=this}replaceChild(t,e){const s=this.childNodes.indexOf(t);if(-1===s)return;t.parent=null,e.parent=this,this.childNodes[s]=e;const i=t.mathml.filter(function(t){return-1===e.mathml.indexOf(t)}),r=e.mathml.filter(function(e){return-1===t.mathml.indexOf(e)});this.removeMathmlNodes(i),this.addMathmlNodes(r)}appendContentNode(t){t&&(this.contentNodes.push(t),this.addMathmlNodes(t.mathml),t.parent=this)}removeContentNode(t){if(t){const e=this.contentNodes.indexOf(t);-1!==e&&this.contentNodes.slice(e,1)}}equals(t){if(!t)return!1;if(this.type!==t.type||this.role!==t.role||this.textContent!==t.textContent||this.childNodes.length!==t.childNodes.length||this.contentNodes.length!==t.contentNodes.length)return!1;for(let e,s,i=0;e=this.childNodes[i],s=t.childNodes[i];i++)if(!e.equals(s))return!1;for(let e,s,i=0;e=this.contentNodes[i],s=t.contentNodes[i];i++)if(!e.equals(s))return!1;return!0}displayTree(){console.info(this.displayTree_(0))}addAnnotation(t,e){e&&this.addAnnotation_(t,e)}getAnnotation(t){const e=this.annotation[t];return e||[]}hasAnnotation(t,e){const s=this.annotation[t];return!!s&&-1!==s.indexOf(e)}parseAnnotation(t){const e=t.split(";");for(let t=0,s=e.length;t0&&$m(e[e.length-1],tm.OPENFENCE)}function ff(t){return t.childNodes.every(function(t){return t.childNodes.length<=1})}function gf(t){return Jm(t,Qp.LINE)&&t.contentNodes.length&&$m(t.contentNodes[0],tm.LABEL)}function bf(t){return Jm(t,Qp.LARGEOP)||Jm(t,Qp.LIMBOTH)||Jm(t,Qp.LIMLOWER)||Jm(t,Qp.LIMUPPER)||Jm(t,Qp.FUNCTION)&&$m(t,tm.LIMFUNC)||(Jm(t,Qp.OVERSCORE)||Jm(t,Qp.UNDERSCORE))&&bf(t.childNodes[0])}function Ef(t,e,s){return 1===e.length&&(t[s].type===Qp.PUNCTUATION||t[s].embellished===Qp.PUNCTUATION)&&t[s]===e[0]}function xf(t){return Jm(t,Qp.IDENTIFIER)&&$m(t,tm.SIMPLEFUNC)}const yf=[Qp.PUNCTUATION,Qp.PUNCTUATED,Qp.RELSEQ,Qp.MULTIREL,Qp.TABLE,Qp.MULTILINE,Qp.CASES,Qp.INFERENCE],Nf=[Qp.LIMUPPER,Qp.LIMLOWER,Qp.LIMBOTH,Qp.SUBSCRIPT,Qp.SUPERSCRIPT,Qp.UNDERSCORE,Qp.OVERSCORE,Qp.TENSOR];function vf(t){const e=t.type;return-1===yf.indexOf(e)&&(e!==Qp.INFIXOP||t.role===tm.IMPLICIT)&&(e===Qp.FENCED?t.role!==tm.LEFTRIGHT||vf(t.childNodes[0]):-1===Nf.indexOf(e)||vf(t.childNodes[0]))}function Tf(t){return function(t){return t.type===Qp.NUMBER&&(t.role===tm.INTEGER||t.role===tm.FLOAT)}(t)||t.role===tm.VULGAR||t.role===tm.MIXED}function wf(t){const e=t.childNodes;return t.role===tm.UNIT&&(!e.length||e[0].role===tm.UNIT)}function Cf(t){const e=t.childNodes;return t.type===Qp.INFIXOP&&(t.role===tm.MULTIPLICATION||t.role===tm.IMPLICIT)&&e.length&&(wf(e[0])||Tf(e[0]))&&t.childNodes.slice(1).every(wf)}function kf(t){return t.type===Qp.INFIXOP&&(t.role===tm.IMPLICIT||t.role===tm.UNIT&&!!t.contentNodes.length&&t.contentNodes[0].textContent===om.invisibleTimes)}function _f(t){return t.type===Qp.INFIXOP&&t.role===tm.IMPLICIT}function Lf(t){return t.role===tm.NEUTRAL||t.role===tm.METRIC}function Af(t,e){return Lf(t)&&Lf(e)&&Hm(t).textContent===Hm(e).textContent}function Rf(t){return!!Lf(t)&&(!t.embellished||t.type!==Qp.SUPERSCRIPT&&t.type!==Qp.SUBSCRIPT&&(t.type!==Qp.TENSOR||t.childNodes[3].type===Qp.EMPTY&&t.childNodes[4].type===Qp.EMPTY))}function Sf(t){return!!Lf(t)&&(!t.embellished||(t.type!==Qp.TENSOR||t.childNodes[1].type===Qp.EMPTY&&t.childNodes[2].type===Qp.EMPTY))}function Mf(t){return[tm.ELEMENT,tm.NONELEMENT,tm.REELEMENT,tm.RENONELEMENT].includes(t.role)}const If={factory:null,options:new gp,updateFactory:function(t){If.factory=t},heuristics:new Map,flags:{combine_juxtaposition:!0,convert_juxtaposition:!0,multioperator:!0},blacklist:{},add:function(t){const e=t.name;If.heuristics.set(e,t),If.flags[e]||(If.flags[e]=!1)},run:function(t,e,s){const i=If.heuristics.get(t);return i&&!If.blacklist[t]&&(If.flags[t]||i.applicable(e))?i.apply(e):s?s(e):e}};class Of{static getInstance(){return Of.instance=Of.instance||new Of,Of.instance}static tableToMultiline(t){if(!ff(t))return If.run("rewrite_subcases",t,Of.classifyTable);t.type=Qp.MULTILINE;for(let e,s=0;e=t.childNodes[s];s++)Of.rowToLine_(e,tm.MULTILINE);return 1===t.childNodes.length&&!gf(t.childNodes[0])&&pf(t.childNodes[0].childNodes[0])&&Of.tableToMatrixOrVector_(Of.rewriteFencedLine_(t)),Of.classifyMultiline(t)}static number(t){t.type!==Qp.UNKNOWN&&t.type!==Qp.IDENTIFIER||(t.type=Qp.NUMBER),Of.meaningFromContent(t,Of.numberRole_),Of.exprFont_(t)}static classifyMultiline(t){return Of.binomialForm_(t),Of.classifyMultiline_(t),t}static classifyMultiline_(t){let e=0;const s=t.childNodes.length;let i;for(;e=s)return;const r=i.childNodes[0].role;r!==tm.UNKNOWN&&t.childNodes.every(function(t){const e=t.childNodes[0];return!e||e.role===r&&(Jm(e,Qp.RELATION)||Jm(e,Qp.RELSEQ))})&&(t.role=r)}static classifyTable(t){const e=Of.computeColumns_(t);return Of.classifyByColumns_(t,e,tm.EQUALITY)||Of.classifyByColumns_(t,e,tm.INEQUALITY,[tm.EQUALITY])||Of.classifyByColumns_(t,e,tm.ARROW)||Of.detectCaleyTable(t),t}static detectCaleyTable(t){if(!t.mathmlTree)return!1;const e=t.mathmlTree,s=e.getAttribute("columnlines"),i=e.getAttribute("rowlines");return!(!s||!i)&&(!(!Of.cayleySpacing(s)||!Of.cayleySpacing(i))&&(t.role=tm.CAYLEY,!0))}static cayleySpacing(t){const e=t.split(" ");return("solid"===e[0]||"dashed"===e[0])&&e.slice(1).every(t=>"none"===t)}static proof(t,e,s){const i=Of.separateSemantics(e);return Of.getInstance().proof(t,i,s)}static findSemantics(t,e,s){const i=null==s?null:s,r=Of.getSemantics(t);return!!r&&(!!r[e]&&(null==i||r[e]===i))}static getSemantics(t){const e=t.getAttribute("semantics");return e?Of.separateSemantics(e):null}static removePrefix(t){const[,...e]=t.split("_");return e.join("_")}static separateSemantics(t){const e={};return t.split(";").forEach(function(t){const[s,i]=t.split(":");e[Of.removePrefix(s)]=i}),e}static matchSpaces_(t,e){for(let s,i=0;s=e[i];i++){const e=t[i].mathmlTree,r=t[i+1].mathmlTree;if(!e||!r)continue;const n=e.nextSibling;if(!n||n===r)continue;const o=Of.getSpacer_(n);o&&o!==r&&(s.mathml.push(o),s.mathmlTree=o,s.role=tm.SPACE)}}static getSpacer_(t){if(Op(t)===Lm.MSPACE)return t;for(;Bm(t)&&1===t.childNodes.length;)if(Op(t=t.childNodes[0])===Lm.MSPACE)return t;return null}static fenceToPunct_(t){const e=Of.FENCE_TO_PUNCT_[t.role];if(e){for(;t.embellished;)t.embellished=Qp.PUNCTUATION,$m(t,tm.SUBSUP)||$m(t,tm.UNDEROVER)||(t.role=e),t=t.childNodes[0];t.type=Qp.PUNCTUATION,t.role=e}}static classifyFunction_(t,e){if(t.type===Qp.APPL||t.type===Qp.BIGOP||t.type===Qp.INTEGRAL)return"";if(e[0]&&e[0].textContent===om.functionApplication){Of.getInstance().funcAppls[t.id]=e.shift();let s=tm.SIMPLEFUNC;return If.run("simple2prefix",t),t.role!==tm.PREFIXFUNC&&t.role!==tm.LIMFUNC||(s=t.role),Of.propagateFunctionRole_(t,s),"prefix"}const s=Of.CLASSIFY_FUNCTION_[t.role];return s||((i=t).type===Qp.IDENTIFIER||i.role===tm.LATINLETTER||i.role===tm.GREEKLETTER||i.role===tm.OTHERLETTER?"simple":"");var i}static propagateFunctionRole_(t,e){if(t){if(t.type===Qp.INFIXOP)return;$m(t,tm.SUBSUP)||$m(t,tm.UNDEROVER)||(t.role=e),Of.propagateFunctionRole_(t.childNodes[0],e)}}static getFunctionOp_(t,e){if(e(t))return t;for(let s,i=0;s=t.childNodes[i];i++){const t=Of.getFunctionOp_(s,e);if(t)return t}return null}static tableToMatrixOrVector_(t){const e=t.childNodes[0];Jm(e,Qp.MULTILINE)?Of.tableToVector_(t):Of.tableToMatrix_(t),t.contentNodes.forEach(e.appendContentNode.bind(e));for(let t,s=0;t=e.childNodes[s];s++)Of.assignRoleToRow_(t,Of.getComponentRoles_(e));return e.parent=null,e}static tableToVector_(t){const e=t.childNodes[0];e.type=Qp.VECTOR,1!==e.childNodes.length?Of.binomialForm_(e):Of.tableToSquare_(t)}static binomialForm_(t){$m(t,tm.UNKNOWN)&&(2===t.childNodes.length&&(t.role=tm.BINOMIAL,t.childNodes[0].role=tm.BINOMIAL,t.childNodes[1].role=tm.BINOMIAL))}static tableToMatrix_(t){const e=t.childNodes[0];e.type=Qp.MATRIX,e.childNodes&&e.childNodes.length>0&&e.childNodes[0].childNodes&&e.childNodes.length===e.childNodes[0].childNodes.length?Of.tableToSquare_(t):e.childNodes&&1===e.childNodes.length&&(e.role=tm.ROWVECTOR)}static tableToSquare_(t){const e=t.childNodes[0];$m(e,tm.UNKNOWN)&&(Lf(t)?e.role=tm.DETERMINANT:e.role=tm.SQUAREMATRIX)}static getComponentRoles_(t){const e=t.role;return e&&e!==tm.UNKNOWN?e:t.type.toLowerCase()||tm.UNKNOWN}static tableToCases_(t,e){for(let e,s=0;e=t.childNodes[s];s++)Of.assignRoleToRow_(e,tm.CASES);return t.type=Qp.CASES,t.appendContentNode(e),ff(t)&&Of.binomialForm_(t),t}static rewriteFencedLine_(t){const e=t.childNodes[0],s=t.childNodes[0].childNodes[0],i=t.childNodes[0].childNodes[0].childNodes[0];return s.parent=t.parent,t.parent=s,i.parent=e,s.childNodes=[t],e.childNodes=[i],s}static rowToLine_(t,e){const s=e||tm.UNKNOWN;Jm(t,Qp.ROW)&&(t.type=Qp.LINE,t.role=s,1===t.childNodes.length&&Jm(t.childNodes[0],Qp.CELL)&&(t.childNodes=t.childNodes[0].childNodes,t.childNodes.forEach(function(e){e.parent=t})))}static assignRoleToRow_(t,e){Jm(t,Qp.LINE)?t.role=e:Jm(t,Qp.ROW)&&(t.role=e,t.childNodes.forEach(function(t){Jm(t,Qp.CELL)&&(t.role=e)}))}static nextSeparatorFunction_(t){let e;if(t){if(t.match(/^\s+$/))return null;e=t.replace(/\s/g,"").split("").filter(function(t){return t})}else e=[","];return function(){return e.length>1?e.shift():e[0]}}static meaningFromContent(t,e){const s=[...t.textContent].filter(t=>t.match(/[^\s]/)),i=s.map(t=>cm.Meaning.get(t));e(t,s,i)}static numberRole_(t,e,s){if(t.role===tm.UNKNOWN)return s.every(function(t){return t.type===Qp.NUMBER&&t.role===tm.INTEGER||t.type===Qp.PUNCTUATION&&t.role===tm.COMMA})?(t.role=tm.INTEGER,void("0"===e[0]&&t.addAnnotation("general","basenumber"))):void(s.every(function(t){return t.type===Qp.NUMBER&&t.role===tm.INTEGER||t.type===Qp.PUNCTUATION})?t.role=tm.FLOAT:t.role=tm.OTHERNUMBER)}static exprFont_(t){t.font===sm.UNKNOWN&&Of.compSemantics(t,"font",sm)}static compSemantics(t,e,s){const i=[...t.textContent].map(t=>cm.Meaning.get(t)).reduce(function(t,i){return t&&i[e]&&i[e]!==s.UNKNOWN&&i[e]!==t?t===s.UNKNOWN?i[e]:null:t},s.UNKNOWN);i&&(t[e]=i)}static purgeFences_(t){const e=t.rel,s=t.comp,i=[],r=[];for(;e.length>0;){const t=e.shift();let n=s.shift();cf(t)?(i.push(t),r.push(n)):(Of.fenceToPunct_(t),n.push(t),n=n.concat(s.shift()),s.unshift(n))}return r.push(s.shift()),{rel:i,comp:r}}static rewriteFencedNode_(t){const e=t.contentNodes[0],s=t.contentNodes[1];let i=Of.rewriteFence_(t,e);return t.contentNodes[0]=i.fence,i=Of.rewriteFence_(i.node,s),t.contentNodes[1]=i.fence,t.contentNodes[0].parent=t,t.contentNodes[1].parent=t,function(t){const e=cm.FencesSecondary.get(t.contentNodes[0].textContent),s=cm.FencesSecondary.get(t.contentNodes[1].textContent);e===s&&t.addAnnotation("fences",e)}(t),i.node.parent=null,i.node}static rewriteFence_(t,e){if(!e.embellished)return{node:t,fence:e};const s=e.childNodes[0],i=Of.rewriteFence_(t,s);return Jm(e,Qp.SUPERSCRIPT)||Jm(e,Qp.SUBSCRIPT)||Jm(e,Qp.TENSOR)?($m(e,tm.SUBSUP)||(e.role=t.role),s!==i.node&&(e.replaceChild(s,i.node),s.parent=t),Of.propagateFencePointer_(e,s),{node:e,fence:i.fence}):(e.replaceChild(s,i.fence),e.mathmlTree&&-1===e.mathml.indexOf(e.mathmlTree)&&e.mathml.push(e.mathmlTree),{node:i.node,fence:e})}static propagateFencePointer_(t,e){t.fencePointer=e.fencePointer||e.id.toString(),t.embellished=null}static classifyByColumns_(t,e,s,i=[]){const r=[s].concat(i);return!!(3===e.length&&Of.testColumns_(e,1,t=>Of.isPureRelation_(t,r))||2===e.length&&(Of.testColumns_(e,1,t=>Of.isEndRelation_(t,r)||Of.isPureRelation_(t,r))||Of.testColumns_(e,0,t=>Of.isEndRelation_(t,r,!0)||Of.isPureRelation_(t,r))))&&(t.role=s,!0)}static isEndRelation_(t,e,s){const i=s?t.childNodes.length-1:0;return Jm(t,Qp.RELSEQ)&&e.some(e=>$m(t,e))&&Jm(t.childNodes[i],Qp.EMPTY)}static isPureRelation_(t,e){return Jm(t,Qp.RELATION)&&e.some(e=>$m(t,e))}static computeColumns_(t){const e=[];for(let s,i=0;s=t.childNodes[i];i++)for(let t,i=0;t=s.childNodes[i];i++){e[i]?e[i].push(t):e[i]=[t]}return e}static testColumns_(t,e,s){const i=t[e];return!!i&&(i.some(function(t){return t.childNodes.length&&s(t.childNodes[0])})&&i.every(function(t){return!t.childNodes.length||s(t.childNodes[0])}))}setNodeFactory(t){Of.getInstance().factory_=t,If.updateFactory(Of.getInstance().factory_)}getNodeFactory(){return Of.getInstance().factory_}identifierNode(t,e,s){if("MathML-Unit"!==s||(i=t,[tm.DEGREE].includes(i.role)||[].includes(i.type))){if(!e&&1===t.textContent.length&&(t.role===tm.INTEGER||t.role===tm.LATINLETTER||t.role===tm.GREEKLETTER)&&t.font===sm.NORMAL)return t.font=sm.ITALIC,If.run("simpleNamedFunction",t)}else t.type=Qp.IDENTIFIER,t.role=tm.UNIT;var i;return t.type===Qp.UNKNOWN&&(t.type=Qp.IDENTIFIER),Of.exprFont_(t),If.run("simpleNamedFunction",t)}implicitNode(t){if(t=Of.getInstance().getMixedNumbers_(t),t=Of.getInstance().combineUnits_(t),1===(t=Of.getInstance().combineScripts_(t)).length)return t[0];const e=Of.getInstance().implicitNode_(t);return If.run("combine_juxtaposition",e)}text(t,e){if(Of.exprFont_(t),t.type=Qp.TEXT,e===Lm.ANNOTATIONXML)return t.role=tm.ANNOTATION,t;if(e===Lm.MS)return t.role=tm.STRING,t;if(e===Lm.MSPACE||t.textContent.match(/^\s*$/))return t.role=tm.SPACE,t;if(/\s/.exec(t.textContent))return t.role=tm.TEXT,t;const s=[...t.textContent];if(1!==s.length)return t.role=tm.UNKNOWN,t;const i=cm.Meaning.get(s[0]);return i.type===Qp.UNKNOWN||i.type===Qp.IDENTIFIER||(t.type=i.type,t.role=i.role,t.font=i.font,t.addAnnotation("general","text")),t}row(t){return 0===(t=t.filter(function(t){return!Jm(t,Qp.EMPTY)||t.hasAnnotation("empty","MFENCED")})).length?Of.getInstance().factory_.makeEmptyNode():(t=Of.getInstance().getFencesInRow_(t),t=Of.getInstance().tablesInRow(t),t=Of.getInstance().getPunctuationInRow_(t),t=Of.getInstance().getTextInRow_(t),t=Of.getInstance().getFunctionsInRow_(t),Of.getInstance().relationsInRow_(t))}limitNode(t,e){if(!e.length)return Of.getInstance().factory_.makeEmptyNode();let s=e[0],{length:i}=Of.MML_TO_LIMIT_[t];if(e=e.slice(0,i+1),[t,e]=Of.getInstance().cleanLimitNode(t,e,i),!e[1])return s;let{type:r,length:n}=Of.MML_TO_LIMIT_[t];if(1===n&&e[1].role===tm.DEGREE)return Of.getInstance().row([e[0],e[1]]);if(If.run("op_with_limits",e),bf(s)){if(1===n&&Ym(e[1])||2===n&&Ym(e[1])&&Ym(e[2])){let i=Of.MML_TO_BOUNDS_[t];return Of.getInstance().accentNode_(s,e,i.type,i.length,i.accent)}if(2===n){if(Ym(e[1]))return s=Of.getInstance().accentNode_(s,[s,e[1]],{MSUBSUP:Qp.SUBSCRIPT,MUNDEROVER:Qp.UNDERSCORE}[t],1,!0),e[2]?Of.getInstance().makeLimitNode_(s,[s,e[2]],null,Qp.LIMUPPER):s;if(e[2]&&Ym(e[2]))return s=Of.getInstance().accentNode_(s,[s,e[2]],{MSUBSUP:Qp.SUPERSCRIPT,MUNDEROVER:Qp.OVERSCORE}[t],1,!0),Of.getInstance().makeLimitNode_(s,[s,e[1]],null,Qp.LIMLOWER);e[n]||(r=Qp.LIMLOWER)}return Of.getInstance().makeLimitNode_(s,e,null,r)}const o=Of.MML_TO_BOUNDS_[t];return Of.getInstance().accentNode_(s,e,o.type,o.length,o.accent)}cleanLimitNode(t,e,s){const i=t=>(t=>!t||Jm(t,Qp.EMPTY))(t)||(t=>t&&Jm(t,Qp.TEXT)&&$m(t,tm.SPACE))(t);if(1===s)return i(e[1])?(e[0].noupdate=!0,[t,[Pf([t],e[0])]]):[t,e];const r=e[1],n=e[2];return i(r)&&i(n)?(e[0].noupdate=!0,[t,[Pf([t],e[0])]]):i(r)?[t===Lm.MSUBSUP?Lm.MSUP:Lm.MOVER,[Pf([t],e[0]),n]]:i(n)?[t===Lm.MSUBSUP?Lm.MSUB:Lm.MUNDER,[Pf([t],e[0]),r]]:[t,e]}tablesInRow(t){let e=Wm(t,uf),s=[];for(let t,i=0;t=e.rel[i];i++)s=s.concat(e.comp.shift()),s.push(Of.tableToMatrixOrVector_(t));s=s.concat(e.comp.shift()),e=Wm(s,df),s=[];for(let t,i=0;t=e.rel[i];i++){const i=e.comp.shift();mf(0,i)&&Of.tableToCases_(t,i.pop()),s=s.concat(i),(s.length||e.comp[0].length)&&(t=Of.rewriteTrivialTable(t)),s.push(t)}return s.concat(e.comp.shift())}mfenced(t,e,s,i){if(s&&i.length>0){const t=Of.nextSeparatorFunction_(s),e=[i.shift()];i.forEach(s=>{e.push(Of.getInstance().factory_.makeContentNode(t())),e.push(s)}),i=e}return t&&e?Of.getInstance().horizontalFencedNode_(Of.getInstance().factory_.makeContentNode(t),Of.getInstance().factory_.makeContentNode(e),i):(t&&i.unshift(Of.getInstance().factory_.makeContentNode(t)),e&&i.push(Of.getInstance().factory_.makeContentNode(e)),Of.getInstance().row(i))}fractionLikeNode(t,e,s,i){let r;if(!i&&function(t){if(!t)return!1;if(["negativeveryverythinmathspace","negativeverythinmathspace","negativethinmathspace","negativemediummathspace","negativethickmathspace","negativeverythickmathspace","negativeveryverythickmathspace"].includes(t))return!0;const e=t.match(/[0-9.]+/);return!!e&&0===parseFloat(e[0])}(s)){const s=Of.getInstance().factory_.makeBranchNode(Qp.LINE,[t],[]),i=Of.getInstance().factory_.makeBranchNode(Qp.LINE,[e],[]);return r=Of.getInstance().factory_.makeBranchNode(Qp.MULTILINE,[s,i],[]),Of.classifyMultiline(r)}return r=Of.getInstance().fractionNode_(t,e),i&&r.addAnnotation("general","bevelled"),r}tensor(t,e,s,i,r){const n=Of.getInstance().factory_.makeBranchNode(Qp.TENSOR,[t,Of.getInstance().scriptNode_(e,tm.LEFTSUB),Of.getInstance().scriptNode_(s,tm.LEFTSUPER),Of.getInstance().scriptNode_(i,tm.RIGHTSUB),Of.getInstance().scriptNode_(r,tm.RIGHTSUPER)],[]);return n.role=t.role,n.embellished=rf(t),n}pseudoTensor(t,e,s){const i=t=>!Jm(t,Qp.EMPTY),r=e.filter(i).length,n=s.filter(i).length;if(!r&&!n)return t;const o=r?n?Lm.MSUBSUP:Lm.MSUB:Lm.MSUP,a=[t];return r&&a.push(Of.getInstance().scriptNode_(e,tm.RIGHTSUB,!0)),n&&a.push(Of.getInstance().scriptNode_(s,tm.RIGHTSUPER,!0)),Of.getInstance().limitNode(o,a)}font(t){const e=Of.MATHJAX_FONTS[t];return e||t}proof(t,e,s){if(e.inference||e.axiom||console.log("Noise"),e.axiom){const e=Of.getInstance().cleanInference(t.childNodes),i=e.length?Of.getInstance().factory_.makeBranchNode(Qp.INFERENCE,s(e),[]):Of.getInstance().factory_.makeEmptyNode();return i.role=tm.AXIOM,i.mathmlTree=t,i}const i=Of.getInstance().inference(t,e,s);return e.proof&&(i.role=tm.PROOF,i.childNodes[0].role=tm.FINAL),i}inference(t,e,s){if(e.inferenceRule){const e=Of.getInstance().getFormulas(t,[],s);return Of.getInstance().factory_.makeBranchNode(Qp.INFERENCE,[e.conclusion,e.premises],[])}const i=e.labelledRule,r=Lp(t.childNodes),n=[];"left"!==i&&"both"!==i||n.push(Of.getInstance().getLabel(t,r,s,tm.LEFT)),"right"!==i&&"both"!==i||n.push(Of.getInstance().getLabel(t,r,s,tm.RIGHT));const o=Of.getInstance().getFormulas(t,r,s),a=Of.getInstance().factory_.makeBranchNode(Qp.INFERENCE,[o.conclusion,o.premises],n);return a.mathmlTree=t,a}getLabel(t,e,s,i){const r=Of.getInstance().findNestedRow(e,"prooflabel",i),n=Of.getInstance().factory_.makeBranchNode(Qp.RULELABEL,s(Lp(r.childNodes)),[]);return n.role=i,n.mathmlTree=r,n}getFormulas(t,e,s){const i=e.length?Of.getInstance().findNestedRow(e,"inferenceRule"):t,r="up"===Of.getSemantics(i).inferenceRule,n=r?i.childNodes[1]:i.childNodes[0],o=r?i.childNodes[0]:i.childNodes[1],a=n.childNodes[0].childNodes[0],l=Lp(a.childNodes[0].childNodes),c=[];let h=1;for(const t of l)h%2&&c.push(t.childNodes[0]),h++;const d=s(c),u=s(Lp(o.childNodes[0].childNodes))[0],p=Of.getInstance().factory_.makeBranchNode(Qp.PREMISES,d,[]);p.mathmlTree=a;const m=Of.getInstance().factory_.makeBranchNode(Qp.CONCLUSION,[u],[]);return m.mathmlTree=o.childNodes[0].childNodes[0],{conclusion:m,premises:p}}findNestedRow(t,e,s){return Of.getInstance().findNestedRow_(t,e,0,s)}cleanInference(t){return Lp(t).filter(function(t){return"MSPACE"!==Op(t)})}operatorNode(t){return t.type===Qp.UNKNOWN&&(t.type=Qp.OPERATOR),If.run("multioperator",t)}static rewriteTrivialTable(t){return Jm(e=t,Qp.MULTILINE)&&1===e.childNodes.length&&e.childNodes[0].childNodes.length&&!gf(e.childNodes[0])?Of.getInstance().unwrapTrivialTable(t):t;var e}unwrapTrivialTable(t){if(!t.childNodes[0].childNodes.length)return Of.getInstance().factory_.makeEmptyNode();const e=t.childNodes[0].childNodes[0];return e.parent=null,Pf([Lm.MTD,Lm.MTR,Lm.MTABLE],e),e}constructor(){this.funcAppls={},this.splitRoles=new Map([[tm.SUBTRACTION,tm.NEGATIVE],[tm.ADDITION,tm.POSITIVE]]),this.splitOps=["\u2212","-","\u2010","\u2011","+"],this.factory_=new Xm,If.updateFactory(this.factory_)}implicitNode_(t){const e=Of.getInstance().factory_.makeMultipleContentNodes(t.length-1,om.invisibleTimes);Of.matchSpaces_(t,e);const s=Of.getInstance().infixNode_(t,e[0]);return s.role=tm.IMPLICIT,e.forEach(function(t){t.parent=s}),s.contentNodes=e,s}infixNode_(t,e){let s=Of.getInstance().factory_.makeBranchNode(Qp.INFIXOP,t,[e],Hm(e).textContent);return s.role=e.role,s=If.run("propagateInterval",s),If.run("propagateSimpleFunction",s)}explicitMixed_(t){const e=Wm(t,function(t){return t.textContent===om.invisiblePlus});if(!e.rel.length)return t;let s=[];for(let t,i=0;t=e.rel[i];i++){const r=e.comp[i],n=e.comp[i+1],o=r.length-1;if(r[o]&&n[0]&&Jm(r[o],Qp.NUMBER)&&!$m(r[o],tm.MIXED)&&Jm(n[0],Qp.FRACTION)){const t=Of.getInstance().factory_.makeBranchNode(Qp.NUMBER,[r[o],n[0]],[]);t.role=tm.MIXED,s=s.concat(r.slice(0,o)),s.push(t),n.shift()}else s=s.concat(r),s.push(t)}return s.concat(e.comp[e.comp.length-1])}concatNode_(t,e,s){if(0===e.length)return t;const i=e.map(function(t){return Hm(t).textContent}).join(" "),r=Of.getInstance().factory_.makeBranchNode(s,[t],e,i);return e.length>1&&(r.role=tm.MULTIOP),r}prefixNode_(t,e){const s=this.splitSingles(e);let i=t;for(;s.length>0;){const t=s.pop();i=Of.getInstance().concatNode_(i,t,Qp.PREFIXOP),1===t.length&&-1!==this.splitOps.indexOf(t[0].textContent)&&(i.role=this.splitRoles.get(t[0].role))}return i}splitSingles(t){let e=0;const s=[];let i=0;for(;iJm(t,Qp.SUPERSCRIPT)&&Jm(t.childNodes[0],Qp.EMPTY)||Jm(t,Qp.SUBSCRIPT)&&Jm(t.childNodes[0],Qp.EMPTY));if(!e.rel.length)return t;let s=[];do{const t=e.comp.shift(),i=e.rel.shift();if(!t.length){s.push(i);continue}const r=t.pop();Jm(r,Qp.NUMBER)||Jm(r,Qp.IDENTIFIER)?(i.childNodes[0]=r,r.parent=i,i.role=r.type.toLowerCase(),i.addAnnotation("collapsed",r.type.toLowerCase()),s=s.concat(t),s.push(i)):Jm(r,Qp.SUBSCRIPT)&&Jm(i,Qp.SUPERSCRIPT)?(i.childNodes[0]=r,r.parent=i,i.role=r.type.toLowerCase(),i.addAnnotation("collapsed",r.type.toLowerCase()),r.role=tm.SUBSUP,s=s.concat(t),s.push(i)):(s=s.concat(t),s.push(r),s.push(i))}while(e.rel.length);return s=s.concat(e.comp.pop()),s}combineUnits_(t){const e=Wm(t,function(t){return!$m(t,tm.UNIT)});if(t.length===e.rel.length)return e.rel;const s=[];let i,r;do{const t=e.comp.shift();i=e.rel.shift();let n=null;r=s.pop(),r&&(t.length&&Tf(r)?t.unshift(r):s.push(r)),1===t.length&&(n=t.pop()),t.length>1&&(n=Of.getInstance().implicitNode_(t),n.role=tm.UNIT),n&&s.push(n),i&&s.push(i)}while(i);return s}getMixedNumbers_(t){const e=Wm(t,function(t){return Jm(t,Qp.FRACTION)&&$m(t,tm.VULGAR)});if(!e.rel.length)return t;let s=[];for(let t,i=0;t=e.rel[i];i++){const r=e.comp[i],n=r.length-1;if(r[n]&&Jm(r[n],Qp.NUMBER)&&($m(r[n],tm.INTEGER)||$m(r[n],tm.FLOAT))){const e=Of.getInstance().factory_.makeBranchNode(Qp.NUMBER,[r[n],t],[]);e.role=tm.MIXED,s=s.concat(r.slice(0,n)),s.push(e)}else s=s.concat(r),s.push(t)}return s.concat(e.comp[e.comp.length-1])}getTextInRow_(t){if(0===t.length)return t;if(1===t.length)return t[0].type===Qp.TEXT&&t[0].role===tm.UNKNOWN&&(t[0].role=tm.ANNOTATION),t;const{rel:e,comp:s}=Wm(t,t=>Jm(t,Qp.TEXT)&&!t.annotation.factor);if(0===e.length)return t;const i=[];let r=s.shift();for(;e.length>0;){let t=e.shift(),n=s.shift();const o=[];for(;!n.length&&e.length&&t.role!==tm.SPACE&&e[0].role!==tm.SPACE;)o.push(t),t=e.shift(),n=s.shift();if(o.length&&(o.push(t),t=Of.getInstance().dummyNode_(o)),t.role!==tm.UNKNOWN){const e=Df(r,t,n);if(e){r=e;continue}r.length&&i.push(Of.getInstance().row(r)),i.push(t),r=n;continue}const a=cm.Meaning.get(t.textContent);if(a.type!==Qp.UNKNOWN){t.type=a.type,t.role=a.role,t.font=a.font,t.addAnnotation("general","text"),r.push(t),r=r.concat(n);continue}if(Of.meaningFromContent(t,(t,e,s)=>{if(t.role===tm.UNKNOWN){if(Of.numberRole_(t,e,s),t.role===tm.OTHERNUMBER)return s.some(t=>t.type!==Qp.NUMBER&&t.type!==Qp.IDENTIFIER)?(t.type=Qp.TEXT,void(t.role=tm.ANNOTATION)):void(t.role=tm.UNKNOWN);t.type=Qp.NUMBER}}),t.role===tm.UNKNOWN&&(e.length||n.length?n.length&&n[0].type===Qp.FENCED?(t.type=Qp.FUNCTION,t.role=tm.PREFIXFUNC):t.role=tm.TEXT:(t.type=Qp.IDENTIFIER,t.role=tm.UNIT)),t.type!==Qp.TEXT){r.push(t),r=r.concat(n);continue}const l=Df(r,t,n);l?r=l:(r.length&&i.push(Of.getInstance().row(r)),i.push(t),r=n)}return r.length>0&&i.push(Of.getInstance().row(r)),i.length>1?[Of.getInstance().dummyNode_(i)]:i}relationsInRow_(t){const e=Wm(t,of),s=e.rel[0];if(!s)return Of.getInstance().operationsInRow_(t);if(1===t.length)return t[0];const i=e.comp.map(Of.getInstance().operationsInRow_);let r;return e.rel.some(function(t){return!t.equals(s)})?(r=Of.getInstance().factory_.makeBranchNode(Qp.MULTIREL,i,e.rel),e.rel.every(function(t){return t.role===s.role})&&(r.role=s.role),r):(r=Of.getInstance().factory_.makeBranchNode(Qp.RELSEQ,i,e.rel,Hm(s).textContent),r.role=s.role,r)}operationsInRow_(t){if(0===t.length)return Of.getInstance().factory_.makeEmptyNode();if(1===(t=Of.getInstance().explicitMixed_(t)).length)return t[0];const e=[];for(;t.length>0&&nf(t[0]);)e.push(t.shift());if(0===t.length)return Of.getInstance().prefixNode_(e.pop(),e);if(1===t.length)return Of.getInstance().prefixNode_(t[0],e);const s=qm(t=If.run("convert_juxtaposition",t),nf),i=Of.getInstance().wrapFactor(e,s);return Of.getInstance().addFactor(i,s)}wrapPostfix(t){var e;(null===(e=t.div)||void 0===e?void 0:e.role)===tm.POSTFIXOP&&(t.tail.length&&t.tail[0].type!==Qp.OPERATOR?t.div.role=tm.DIVISION:(t.head=[Of.getInstance().postfixNode_(Of.getInstance().implicitNode(t.head),[t.div])],t.div=t.tail.shift(),Of.getInstance().wrapPostfix(t)))}wrapFactor(t,e){return Of.getInstance().wrapPostfix(e),Of.getInstance().prefixNode_(Of.getInstance().implicitNode(e.head),t)}addFactor(t,e){return e.div?Of.getInstance().operationsTree_(e.tail,t,e.div):(Cf(t)&&(t.role=tm.UNIT),t)}operationsTree_(t,e,s,i=[]){if(0===t.length){if(i.unshift(s),e.type===Qp.INFIXOP){const t=Of.getInstance().postfixNode_(e.childNodes.pop(),i);return e.appendChild(t),e}return Of.getInstance().postfixNode_(e,i)}const r=qm(t,nf);if(0===r.head.length)return i.push(r.div),Of.getInstance().operationsTree_(r.tail,e,s,i);const n=Of.getInstance().wrapFactor(i,r),o=Of.getInstance().appendOperand_(e,s,n);return Of.getInstance().addFactor(o,r)}appendOperand_(t,e,s){if(t.type!==Qp.INFIXOP)return Of.getInstance().infixNode_([t,s],e);const i=Of.getInstance().appendDivisionOp_(t,e,s);return i||(Of.getInstance().appendExistingOperator_(t,e,s)?t:e.role===tm.MULTIPLICATION?Of.getInstance().appendMultiplicativeOp_(t,e,s):Of.getInstance().appendAdditiveOp_(t,e,s))}appendDivisionOp_(t,e,s){return e.role===tm.DIVISION?kf(t)?Of.getInstance().infixNode_([t,s],e):Of.getInstance().appendLastOperand_(t,e,s):t.role===tm.DIVISION?Of.getInstance().infixNode_([t,s],e):null}appendLastOperand_(t,e,s){let i=t,r=t.childNodes[t.childNodes.length-1];for(;r&&r.type===Qp.INFIXOP&&!kf(r);)i=r,r=i.childNodes[t.childNodes.length-1];const n=Of.getInstance().infixNode_([i.childNodes.pop(),s],e);return i.appendChild(n),t}appendMultiplicativeOp_(t,e,s){if(kf(t))return Of.getInstance().infixNode_([t,s],e);let i=t,r=t.childNodes[t.childNodes.length-1];for(;r&&r.type===Qp.INFIXOP&&!kf(r);)i=r,r=i.childNodes[t.childNodes.length-1];const n=Of.getInstance().infixNode_([i.childNodes.pop(),s],e);return i.appendChild(n),t}appendAdditiveOp_(t,e,s){return Of.getInstance().infixNode_([t,s],e)}appendExistingOperator_(t,e,s){return!(!t||t.type!==Qp.INFIXOP||kf(t))&&(t.contentNodes[0].equals(e)?(t.appendContentNode(e),t.appendChild(s),!0):Of.getInstance().appendExistingOperator_(t.childNodes[t.childNodes.length-1],e,s))}getFencesInRow_(t){let e=Wm(t,lf);e=Of.purgeFences_(e);const s=e.comp.shift();return Of.getInstance().fences_(e.rel,e.comp,[],[s])}fences_(t,e,s,i){if(0===t.length&&0===s.length)return i[0];const r=If.run("bracketed_interval",[t[0],t[1],...e[0]||[]],()=>null);if(r){t.shift(),t.shift(),e.shift();const n=i.pop()||[];return i.push([...n,r,...e.shift()]),Of.getInstance().fences_(t,e,s,i)}const n=t=>$m(t,tm.OPEN);if(0===t.length){const t=i.shift();for(;s.length>0;){if(n(s[0])){const e=s.shift();Of.fenceToPunct_(e),t.push(e)}else{const e=qm(s,n),r=e.head.length-1,o=Of.getInstance().neutralFences_(e.head,i.slice(0,r));i=i.slice(r),t.push(...o),e.div&&e.tail.unshift(e.div),s=e.tail}t.push(...i.shift())}return t}const o=s[s.length-1],a=t[0].role;if(a===tm.OPEN||Lf(t[0])&&(!o||!Af(t[0],o))){s.push(t.shift());const r=e.shift();return r&&i.push(r),Of.getInstance().fences_(t,e,s,i)}if(o&&a===tm.CLOSE&&o.role===tm.OPEN){const r=Of.getInstance().horizontalFencedNode_(s.pop(),t.shift(),i.pop());return i.push(i.pop().concat([r],e.shift())),Of.getInstance().fences_(t,e,s,i)}if(o&&Af(t[0],o)){if(!Rf(o)||!Sf(t[0])){s.push(t.shift());const r=e.shift();return r&&i.push(r),Of.getInstance().fences_(t,e,s,i)}const r=Of.getInstance().horizontalFencedNode_(s.pop(),t.shift(),i.pop());return i.push(i.pop().concat([r],e.shift())),Of.getInstance().fences_(t,e,s,i)}if(o&&a===tm.CLOSE&&Lf(o)&&s.some(n)){const r=qm(s,n,!0),o=i.pop(),a=i.length-r.tail.length+1,l=Of.getInstance().neutralFences_(r.tail,i.slice(a));i=i.slice(0,a);const c=Of.getInstance().horizontalFencedNode_(r.div,t.shift(),i.pop().concat(l,o));return i.push(i.pop().concat([c],e.shift())),Of.getInstance().fences_(t,e,r.head,i)}const l=t.shift();return Of.fenceToPunct_(l),i.push(i.pop().concat([l],e.shift())),Of.getInstance().fences_(t,e,s,i)}neutralFences_(t,e){if(0===t.length)return t;if(1===t.length)return Of.fenceToPunct_(t[0]),t;const s=t.shift();if(!Rf(s)){Of.fenceToPunct_(s);const i=e.shift();return i.unshift(s),i.concat(Of.getInstance().neutralFences_(t,e))}const i=qm(t,function(t){return Af(t,s)});if(!i.div){Of.fenceToPunct_(s);const i=e.shift();return i.unshift(s),i.concat(Of.getInstance().neutralFences_(t,e))}if(!Sf(i.div))return Of.fenceToPunct_(i.div),t.unshift(s),Of.getInstance().neutralFences_(t,e);const r=Of.getInstance().combineFencedContent_(s,i.div,i.head,e);if(i.tail.length>0){const t=r.shift(),e=Of.getInstance().neutralFences_(i.tail,r);return t.concat(e)}return r[0]}combineFencedContent_(t,e,s,i){if(0===s.length){const s=Of.getInstance().horizontalFencedNode_(t,e,i.shift());return i.length>0?i[0].unshift(s):i=[[s]],i}const r=i.shift(),n=s.length-1,o=i.slice(0,n),a=(i=i.slice(n)).shift(),l=Of.getInstance().neutralFences_(s,o);r.push(...l),r.push(...a);const c=Of.getInstance().horizontalFencedNode_(t,e,r);return i.length>0?i[0].unshift(c):i=[[c]],i}horizontalFencedNode_(t,e,s){const i=Of.getInstance().row(s);Jm(i,Qp.EMPTY)&&!i.mathmlTree&&t.mathmlTree&&t.mathmlTree.nextSibling!==e.mathmlTree&&(i.mathmlTree=t.mathmlTree.nextSibling,i.mathml=[t.mathmlTree.nextSibling]);let r=Of.getInstance().factory_.makeBranchNode(Qp.FENCED,[i],[t,e]);return t.role===tm.OPEN?(Of.getInstance().classifyHorizontalFence_(r),r=If.run("propagateComposedFunction",r)):r.role=t.role,r=If.run("detect_cycle",r),Of.rewriteFencedNode_(r)}classifyHorizontalFence_(t){if(If.run("interval_heuristic",t),t.role===tm.INTERVAL)return;t.role=tm.LEFTRIGHT;const e=t.childNodes;if(!function(t){return function(t){return!!t&&-1!==["{","\ufe5b","\uff5b"].indexOf(t.textContent)}(t.contentNodes[0])&&function(t){return!!t&&-1!==["}","\ufe5c","\uff5d"].indexOf(t.textContent)}(t.contentNodes[1])}(t)||e.length>1)return;if(0===e.length||e[0].type===Qp.EMPTY)return void(t.role=tm.SETEMPTY);const s=e[0].type;if(1===e.length&&vf(e[0]))return void(t.role=tm.SETSINGLE);const i=e[0].role;if(s===Qp.PUNCTUATED&&i===tm.SEQUENCE){if(e[0].contentNodes[0].role!==tm.COMMA)return 1!==e[0].contentNodes.length||e[0].contentNodes[0].role!==tm.VBAR&&e[0].contentNodes[0].role!==tm.COLON?void 0:(t.role=tm.SETEXT,void Of.getInstance().setExtension_(t));t.role=tm.SETCOLLECT}}setExtension_(t){const e=t.childNodes[0].childNodes[0];e&&e.type===Qp.INFIXOP&&1===e.contentNodes.length&&Mf(e.contentNodes[0])&&(e.addAnnotation("set","intensional"),e.contentNodes[0].addAnnotation("set","intensional"))}getPunctuationInRow_(t){if(t.length<=1)return t;const e=t=>{const e=t.type;return"punctuation"===e||"text"===e||"operator"===e||"relation"===e},s=Wm(t,function(s){if(!af(s))return!1;if(af(s)&&!$m(s,tm.ELLIPSIS))return!0;const i=t.indexOf(s);if(0===i)return!t[1]||!e(t[1]);const r=t[i-1];if(i===t.length-1)return!e(r);const n=t[i+1];return!e(r)||!e(n)});if(0===s.rel.length)return t;let i=[],r=s.comp.shift();r.length>0&&i.push(Of.getInstance().row(r));let n=0;for(;s.comp.length>0;){let t=[];const e=n;do{t.push(s.rel[n++]),r=s.comp.shift()}while(s.rel[n]&&r&&0===r.length);t=If.run("ellipses",t),s.rel.splice(e,n-e,...t),n=e+t.length,i=i.concat(t),r&&r.length>0&&i.push(Of.getInstance().row(r))}return 1===i.length&&1===s.rel.length?i:[Of.getInstance().punctuatedNode_(i,s.rel)]}punctuatedNode_(t,e){const s=Of.getInstance().factory_.makeBranchNode(Qp.PUNCTUATED,t,e);if(e.length===t.length){const t=e[0].role;if(t!==tm.UNKNOWN&&e.every(function(e){return e.role===t}))return s.role=t,s}const i=e[0];return Ef(t,e,0)?s.role=i.childNodes.length&&!i.embellished?i.role:tm.STARTPUNCT:Ef(t,e,t.length-1)?s.role=i.childNodes.length&&!i.embellished?i.role:tm.ENDPUNCT:e.every(t=>$m(t,tm.DUMMY))?s.role=tm.TEXT:e.every(t=>$m(t,tm.SPACE))?s.role=tm.SPACE:s.role=tm.SEQUENCE,s}dummyNode_(t){const e=Of.getInstance().factory_.makeMultipleContentNodes(t.length-1,om.invisibleComma);return e.forEach(function(t){t.role=tm.DUMMY}),Of.getInstance().punctuatedNode_(t,e)}accentRole_(t,e){if(!Ym(t))return!1;const s=t.textContent,i=cm.Secondary.get(s,rm.BAR)||cm.Secondary.get(s,rm.TILDE)||t.role;return t.role=e===Qp.UNDERSCORE?tm.UNDERACCENT:tm.OVERACCENT,t.addAnnotation("accent",i),!0}accentNode_(t,e,s,i,r){const n=(e=e.slice(0,i+1))[1],o=e[2];let a;if(!r&&o&&(a=Of.getInstance().factory_.makeBranchNode(Qp.SUBSCRIPT,[t,n],[]),a.role=tm.SUBSUP,e=[a,o],s=Qp.SUPERSCRIPT),r){const i=Of.getInstance().accentRole_(n,s);if(o){Of.getInstance().accentRole_(o,Qp.OVERSCORE)&&!i?(a=Of.getInstance().factory_.makeBranchNode(Qp.OVERSCORE,[t,o],[]),e=[a,n],s=Qp.UNDERSCORE):(a=Of.getInstance().factory_.makeBranchNode(Qp.UNDERSCORE,[t,n],[]),e=[a,o],s=Qp.OVERSCORE),a.role=tm.UNDEROVER}}return Of.getInstance().makeLimitNode_(t,e,a,s)}makeLimitNode_(t,e,s,i){if(i===Qp.LIMUPPER&&t.type===Qp.LIMLOWER)return t.childNodes.push(e[1]),e[1].parent=t,t.type=Qp.LIMBOTH,t;if(i===Qp.LIMLOWER&&t.type===Qp.LIMUPPER)return t.childNodes.splice(1,-1,e[1]),e[1].parent=t,t.type=Qp.LIMBOTH,t;const r=Of.getInstance().factory_.makeBranchNode(i,e,[]),n=rf(t);return s&&(s.embellished=n),r.embellished=n,r.role=t.role,r}getFunctionsInRow_(t,e){const s=e||[];if(0===t.length)return s;const i=t.shift(),r=Of.classifyFunction_(i,t);if(!r)return s.push(i),Of.getInstance().getFunctionsInRow_(t,s);const n=Of.getInstance().getFunctionsInRow_(t,[]),o=Of.getInstance().getFunctionArgs_(i,n,r);return s.concat(o)}getFunctionArgs_(t,e,s){let i,r,n;switch(s){case"integral":{const s=Of.getInstance().getIntegralArgs_(e);if(!s.intvar&&!s.integrand.length)return s.rest.unshift(t),s.rest;const i=Of.getInstance().row(s.integrand);return n=Of.getInstance().integralNode_(t,i,s.intvar),If.run("intvar_from_fraction",n),s.rest.unshift(n),s.rest}case"prefix":if(e[0]&&e[0].type===Qp.FENCED){const s=e.shift();return Lf(s)||(s.role=tm.LEFTRIGHT),n=Of.getInstance().functionNode_(t,s),e.unshift(n),e}if(i=qm(e,Qm),i.head.length)r=Of.getInstance().row(i.head),i.div&&i.tail.unshift(i.div);else{if(!i.div||!Jm(i.div,Qp.APPL))return e.unshift(t),e;r=i.div}return n=Of.getInstance().functionNode_(t,r),i.tail.unshift(n),i.tail;case"bigop":return i=qm(e,Zm),i.head.length?(r=Of.getInstance().row(i.head),n=Of.getInstance().bigOpNode_(t,r),i.div&&i.tail.unshift(i.div),i.tail.unshift(n),i.tail):(e.unshift(t),e);default:{if(0===e.length)return[t];const s=e[0];return s.type===Qp.FENCED&&!Lf(s)&&function(t){const e=t.childNodes;if(0===e.length)return!0;if(e.length>1)return!1;const s=e[0];if(s.type===Qp.INFIXOP){if(s.role!==tm.IMPLICIT)return!1;if(s.childNodes.some(t=>Jm(t,Qp.INFIXOP)))return!1}return!0}(s)?(s.role=tm.LEFTRIGHT,Of.propagateFunctionRole_(t,tm.SIMPLEFUNC),n=Of.getInstance().functionNode_(t,e.shift()),e.unshift(n),e):(e.unshift(t),e)}}}getIntegralArgs_(t,e=[]){if(0===t.length){const t=qm(e,Zm);return t.div&&t.tail.unshift(t.div),{integrand:t.head,intvar:null,rest:t.tail}}If.run("intvar_from_implicit",t);const s=t[0];if(sf(s)){const{integrand:s,rest:i}=Of.getInstance().getIntegralArgs_(e);return{integrand:s,intvar:null,rest:i.concat(t)}}if(ef(s))return s.role=tm.INTEGRAL,{integrand:e,intvar:s,rest:t.slice(1)};if(t[1]&&tf(s,t[1])){const i=Of.getInstance().prefixNode_(t[1],[s]);return i.role=tm.INTEGRAL,{integrand:e,intvar:i,rest:t.slice(2)}}return e.push(t.shift()),Of.getInstance().getIntegralArgs_(t,e)}functionNode_(t,e){const s=Of.getInstance().factory_.makeContentNode(om.functionApplication),i=Of.getInstance().funcAppls[t.id];i&&(s.mathmlTree=i.mathmlTree,s.mathml=i.mathml,s.annotation=i.annotation,s.attributes=i.attributes,delete Of.getInstance().funcAppls[t.id]),s.type=Qp.PUNCTUATION,s.role=tm.APPLICATION;const r=Of.getFunctionOp_(t,function(t){return Jm(t,Qp.FUNCTION)||Jm(t,Qp.IDENTIFIER)&&$m(t,tm.SIMPLEFUNC)});return Of.getInstance().functionalNode_(Qp.APPL,[t,e],r,[s])}bigOpNode_(t,e){const s=Of.getFunctionOp_(t,t=>Jm(t,Qp.LARGEOP));return Of.getInstance().functionalNode_(Qp.BIGOP,[t,e],s,[])}integralNode_(t,e,s){e=e||Of.getInstance().factory_.makeEmptyNode(),s=s||Of.getInstance().factory_.makeEmptyNode();const i=Of.getFunctionOp_(t,t=>Jm(t,Qp.LARGEOP));return Of.getInstance().functionalNode_(Qp.INTEGRAL,[t,e,s],i,[])}functionalNode_(t,e,s,i){const r=e[0];let n;s&&(n=s.parent,i.push(s));const o=Of.getInstance().factory_.makeBranchNode(t,e,i);return o.role=r.role,n&&(s.parent=n),o}fractionNode_(t,e){const s=Of.getInstance().factory_.makeBranchNode(Qp.FRACTION,[t,e],[]);return s.role=s.childNodes.every(function(t){return Jm(t,Qp.NUMBER)&&$m(t,tm.INTEGER)})?tm.VULGAR:s.childNodes.every(wf)?tm.UNIT:tm.DIVISION,If.run("propagateSimpleFunction",s)}scriptNode_(t,e,s){let i;switch(t.length){case 0:i=Of.getInstance().factory_.makeEmptyNode();break;case 1:if(i=t[0],s)return i;break;default:i=Of.getInstance().dummyNode_(t),i.addAnnotation("general","script")}return i.role=e,i}findNestedRow_(t,e,s,i){if(s>3)return null;for(let r,n=0;r=t[n];n++){const t=Op(r);if(t!==Lm.MSPACE){if(t===Lm.MROW)return Of.getInstance().findNestedRow_(Lp(r.childNodes),e,s+1,i);if(Of.findSemantics(r,e,i))return r}}return null}}function Df(t,e,s){const i=t[t.length-1];if(i&&(i.type===Qp.RELATION||i.type===Qp.OPERATOR))return e.addAnnotation("factor",i.type),[...t,e,...s];const r=s[0];return!r||r.type!==Qp.RELATION&&r.type!==Qp.OPERATOR?null:(e.addAnnotation("factor",r.type),[...t,e,...s])}function Pf(t,e){return t.forEach(t=>e.addAnnotation("empty",t)),e}Of.FENCE_TO_PUNCT_={[tm.METRIC]:tm.METRIC,[tm.NEUTRAL]:tm.VBAR,[tm.OPEN]:tm.OPENFENCE,[tm.CLOSE]:tm.CLOSEFENCE},Of.MML_TO_LIMIT_={[Lm.MSUB]:{type:Qp.LIMLOWER,length:1},[Lm.MUNDER]:{type:Qp.LIMLOWER,length:1},[Lm.MSUP]:{type:Qp.LIMUPPER,length:1},[Lm.MOVER]:{type:Qp.LIMUPPER,length:1},[Lm.MSUBSUP]:{type:Qp.LIMBOTH,length:2},[Lm.MUNDEROVER]:{type:Qp.LIMBOTH,length:2}},Of.MML_TO_BOUNDS_={[Lm.MSUB]:{type:Qp.SUBSCRIPT,length:1,accent:!1},[Lm.MSUP]:{type:Qp.SUPERSCRIPT,length:1,accent:!1},[Lm.MSUBSUP]:{type:Qp.SUBSCRIPT,length:2,accent:!1},[Lm.MUNDER]:{type:Qp.UNDERSCORE,length:1,accent:!0},[Lm.MOVER]:{type:Qp.OVERSCORE,length:1,accent:!0},[Lm.MUNDEROVER]:{type:Qp.UNDERSCORE,length:2,accent:!0}},Of.CLASSIFY_FUNCTION_={[tm.INTEGRAL]:"integral",[tm.SUM]:"bigop",[tm.PREFIXFUNC]:"prefix",[tm.LIMFUNC]:"prefix",[tm.SIMPLEFUNC]:"prefix",[tm.COMPFUNC]:"prefix"},Of.MATHJAX_FONTS={"-tex-caligraphic":sm.CALIGRAPHIC,"-tex-caligraphic-bold":sm.CALIGRAPHICBOLD,"-tex-calligraphic":sm.CALIGRAPHIC,"-tex-calligraphic-bold":sm.CALIGRAPHICBOLD,"-tex-oldstyle":sm.OLDSTYLE,"-tex-oldstyle-bold":sm.OLDSTYLEBOLD,"-tex-mathit":sm.ITALIC};class Bf extends Gm{static getAttribute_(t,e,s){if(!t.hasAttribute(e))return s;const i=t.getAttribute(e);return i.match(/^\s*$/)?null:i}constructor(t){super("MathML"),this.options=t,If.options=t,this.parseMap_=new Map([[Lm.SEMANTICS,this.semantics_.bind(this)],[Lm.MATH,this.rows_.bind(this)],[Lm.MROW,this.rows_.bind(this)],[Lm.MPADDED,this.rows_.bind(this)],[Lm.MSTYLE,this.rows_.bind(this)],[Lm.MFRAC,this.fraction_.bind(this)],[Lm.MSUB,this.limits_.bind(this)],[Lm.MSUP,this.limits_.bind(this)],[Lm.MSUBSUP,this.limits_.bind(this)],[Lm.MOVER,this.limits_.bind(this)],[Lm.MUNDER,this.limits_.bind(this)],[Lm.MUNDEROVER,this.limits_.bind(this)],[Lm.MROOT,this.root_.bind(this)],[Lm.MSQRT,this.sqrt_.bind(this)],[Lm.MTABLE,this.table_.bind(this)],[Lm.MLABELEDTR,this.tableLabeledRow_.bind(this)],[Lm.MTR,this.tableRow_.bind(this)],[Lm.MTD,this.tableCell_.bind(this)],[Lm.MS,this.text_.bind(this)],[Lm.MTEXT,this.text_.bind(this)],[Lm.MSPACE,this.space_.bind(this)],[Lm.ANNOTATIONXML,this.text_.bind(this)],[Lm.MI,this.identifier_.bind(this)],[Lm.MN,this.number_.bind(this)],[Lm.MO,this.operator_.bind(this)],[Lm.MFENCED,this.fenced_.bind(this)],[Lm.MENCLOSE,this.enclosed_.bind(this)],[Lm.MMULTISCRIPTS,this.multiscripts_.bind(this)],[Lm.ANNOTATION,this.empty_.bind(this)],[Lm.NONE,this.empty_.bind(this)],[Lm.MACTION,this.action_.bind(this)],[Lm.MPHANTOM,this.phantom_.bind(this)]]);const e={type:Qp.IDENTIFIER,role:tm.NUMBERSET,font:sm.DOUBLESTRUCK};["C","H","N","P","Q","R","Z","\u2102","\u210d","\u2115","\u2119","\u211a","\u211d","\u2124"].forEach((t=>this.getFactory().defaultMap.set(t,e)).bind(this))}parse(t){Of.getInstance().setNodeFactory(this.getFactory());const e=Lp(t.childNodes),s=Op(t),i=this.parseMap_.get(s),r=(i||this.dummy_.bind(this))(t,e);return r.noupdate?r:(Um(r,t),-1!==[Lm.MATH,Lm.MROW,Lm.MPADDED,Lm.MSTYLE,Lm.SEMANTICS,Lm.MACTION].indexOf(s)||(r.mathml.unshift(t),r.mathmlTree=t),r)}semantics_(t,e){return e.length?this.parse(e[0]):this.getFactory().makeEmptyNode()}rows_(t,e){const s=t.getAttribute("semantics");if(s&&s.match("bspr_"))return Of.proof(t,s,this.parseList.bind(this));let i;if(1===(e=jm(e)).length)i=this.parse(e[0]),i.type!==Qp.EMPTY||i.mathmlTree||(i.mathmlTree=t);else{const s=If.run("function_from_identifiers",t);i=s&&s!==t?s:Of.getInstance().row(this.parseList(e))}return i.mathml.unshift(t),i}fraction_(t,e){if(!e.length)return this.getFactory().makeEmptyNode();const s=this.parse(e[0]),i=e[1]?this.parse(e[1]):this.getFactory().makeEmptyNode();return Of.getInstance().fractionLikeNode(s,i,t.getAttribute("linethickness"),"true"===t.getAttribute("bevelled"))}limits_(t,e){return Of.getInstance().limitNode(Op(t),this.parseList(e))}root_(t,e){return e[1]?this.getFactory().makeBranchNode(Qp.ROOT,[this.parse(e[1]),this.parse(e[0])],[]):this.sqrt_(t,e)}sqrt_(t,e){const s=this.parseList(jm(e));return this.getFactory().makeBranchNode(Qp.SQRT,[Of.getInstance().row(s)],[])}table_(t,e){const s=t.getAttribute("semantics");if(s&&s.match("bspr_"))return Of.proof(t,s,this.parseList.bind(this));const i=this.getFactory().makeBranchNode(Qp.TABLE,this.parseList(e),[]);return i.mathmlTree=t,Of.tableToMultiline(i)}tableRow_(t,e){const s=this.getFactory().makeBranchNode(Qp.ROW,this.parseList(e),[]);return s.role=tm.TABLE,s}tableLabeledRow_(t,e){var s;if(!e.length)return this.tableRow_(t,e);const i=this.parse(e[0]);i.role=tm.LABEL,(null===(s=i.childNodes[0])||void 0===s?void 0:s.type)===Qp.TEXT&&(i.childNodes[0].role=tm.LABEL);const r=this.getFactory().makeBranchNode(Qp.ROW,this.parseList(e.slice(1)),[i]);return r.role=tm.TABLE,r}tableCell_(t,e){const s=this.parseList(jm(e));let i;i=s.length?1===s.length&&Jm(s[0],Qp.EMPTY)?s:[Of.getInstance().row(s)]:[];const r=this.getFactory().makeBranchNode(Qp.CELL,i,[]);return r.role=tm.TABLE,r}phantom_(t,e){let s;return e.length?(s=this.getFactory().makeUnprocessed(t),s.type=Qp.TEXT,s.role=tm.SPACE):s=this.empty_(t,e),s}space_(t,e){const s=t.getAttribute("width"),i=s&&s.match(/[a-z]*$/);if(!i)return this.empty_(t,e);const r=i[0],n=parseFloat(s.slice(0,i.index)),o={cm:.4,pc:.5,em:.5,ex:1,in:.15,pt:5,mm:5}[r];if(!o||isNaN(n)||n{Jm(t,Qp.EMPTY)&&t.addAnnotation("empty","MFENCED")});const i=Bf.getAttribute_(t,"separators",","),r=Bf.getAttribute_(t,"open","("),n=Bf.getAttribute_(t,"close",")"),o=Of.getInstance().mfenced(r,n,i,s);o.mathmlTree=t,o.mathml=[t];return Of.getInstance().tablesInRow([o])[0]}enclosed_(t,e){const s=this.parseList(jm(e)),i=this.getFactory().makeBranchNode(Qp.ENCLOSE,[Of.getInstance().row(s)],[]);return i.role=t.getAttribute("notation")||tm.UNKNOWN,i}multiscripts_(t,e){if(!e.length)return this.getFactory().makeEmptyNode();const s=this.parse(e.shift());if(!e.length)return s;const i=[],r=[],n=[],o=[];let a=!1,l=0;for(let t,s=0;t=e[s];s++)Op(t)!==Lm.MPRESCRIPTS?(a?1&l?i.push(t):r.push(t):1&l?n.push(t):o.push(t),l++):(a=!0,l=0);return jm(i).length||jm(r).length?Of.getInstance().tensor(s,this.parseList(r),this.parseList(i),this.parseList(o),this.parseList(n)):Of.getInstance().pseudoTensor(s,this.parseList(o),this.parseList(n))}empty_(t,e){const s=this.getFactory().makeEmptyNode();return s.mathml=[t],s.mathmlTree=t,s}action_(t,e){const s=e[t.hasAttribute("selection")?parseInt(t.getAttribute("selection"),10)-1:0],i=this.parse(s);return i.mathmlTree=s,i}dummy_(t,e){const s=this.getFactory().makeUnprocessed(t);return s.role=t.tagName,s.textContent=t.textContent,s}leaf_(t,e){if(1===e.length&&e[0].nodeType!==_p.TEXT_NODE){const s=this.getFactory().makeUnprocessed(t);return s.role=e[0].tagName,Um(s,e[0]),s}const s=this.getFactory().makeLeafNode(t.textContent,Of.getInstance().font(t.getAttribute("mathvariant")));return t.hasAttribute("data-latex")&&cm.LatexCommands.set(t.getAttribute("data-latex"),t.textContent),s}}class Ff{constructor(t,e,s=t=>!1){this.name=t,this.apply=e,this.applicable=s}}class jf extends Ff{}class Uf extends Ff{}function Hf(t,e){const s=[];for(;t.length||e.length;)t.length&&s.push(t.shift()),e.length&&s.push(e.shift());return s}const qf="data-semantic-";var Wf;!function(t){t.ADDED="data-semantic-added",t.ALTERNATIVE="data-semantic-alternative",t.CHILDREN="data-semantic-children",t.COLLAPSED="data-semantic-collapsed",t.CONTENT="data-semantic-content",t.EMBELLISHED="data-semantic-embellished",t.FENCEPOINTER="data-semantic-fencepointer",t.FONT="data-semantic-font",t.ID="data-semantic-id",t.ANNOTATION="data-semantic-annotation",t.ATTRIBUTES="data-semantic-attributes",t.OPERATOR="data-semantic-operator",t.OWNS="data-semantic-owns",t.PARENT="data-semantic-parent",t.POSTFIX="data-semantic-postfix",t.PREFIX="data-semantic-prefix",t.ROLE="data-semantic-role",t.SPEECH="data-semantic-speech",t.STRUCTURE="data-semantic-structure",t.SUMMARY="data-semantic-summary",t.TYPE="data-semantic-type"}(Wf||(Wf={}));const zf=[Wf.ADDED,Wf.ALTERNATIVE,Wf.CHILDREN,Wf.COLLAPSED,Wf.CONTENT,Wf.EMBELLISHED,Wf.FENCEPOINTER,Wf.FONT,Wf.ID,Wf.ANNOTATION,Wf.ATTRIBUTES,Wf.OPERATOR,Wf.OWNS,Wf.PARENT,Wf.POSTFIX,Wf.PREFIX,Wf.ROLE,Wf.SPEECH,Wf.STRUCTURE,Wf.SUMMARY,Wf.TYPE];function Vf(t){return t.map(function(t){return t.id}).join(",")}function Xf(t,e){t.setAttribute(Wf.TYPE,e.type);const s=e.allAttributes();for(let e,i=0;e=s[i];i++)t.setAttribute(qf+e[0].toLowerCase(),e[1]);e.childNodes.length&&t.setAttribute(Wf.CHILDREN,Vf(e.childNodes)),e.contentNodes.length&&t.setAttribute(Wf.CONTENT,Vf(e.contentNodes)),e.parent&&t.setAttribute(Wf.PARENT,e.parent.id.toString());const i=e.attributesXml();i&&t.setAttribute(Wf.ATTRIBUTES,i),function(t,e){const s=[];e.role===tm.MGLYPH&&s.push("image");e.attributes.href&&s.push("link");s.length&&t.setAttribute(Wf.POSTFIX,s.join(" "))}(t,e)}function Gf(){const t=Sp("mrow");return t.setAttribute(Wf.ADDED,"true"),t}class Jf{static fromTree(t){return Jf.fromNode(t.root)}static fromNode(t){return new Jf(Jf.fromNode_(t))}static fromString(t){return new Jf(Jf.fromString_(t))}static simpleCollapseStructure(t){return"number"==typeof t}static contentCollapseStructure(t){return!!t&&!Jf.simpleCollapseStructure(t)&&"c"===t[0]}static interleaveIds(t,e){return Hf(Jf.collapsedLeafs(t),Jf.collapsedLeafs(e))}static collapsedLeafs(...t){return t.reduce((t,e)=>{return t.concat((s=e,Jf.simpleCollapseStructure(s)?[s]:Jf.contentCollapseStructure(s[1])?s.slice(2):s.slice(1)));var s},[])}static fromStructure(t,e,s){return new Jf(Jf.tree_(t,e.root,s))}static combineContentChildren(t,e,s,i){switch(t){case Qp.RELSEQ:case Qp.INFIXOP:case Qp.MULTIREL:return Hf(i,s);case Qp.PREFIXOP:return s.concat(i);case Qp.POSTFIXOP:return i.concat(s);case Qp.MATRIX:case Qp.VECTOR:case Qp.FENCED:return i.unshift(s[0]),i.push(s[1]),i;case Qp.CASES:return i.unshift(s[0]),i;case Qp.APPL:return[i[0],s[0],i[1]];case Qp.ROOT:return[i[0],i[1]];case Qp.ROW:case Qp.LINE:return s.length&&i.push(s[0]),i;default:return i}}static makeSexp_(t){return Jf.simpleCollapseStructure(t)?t.toString():Jf.contentCollapseStructure(t)?"(c "+t.slice(1).map(Jf.makeSexp_).join(" ")+")":"("+t.map(Jf.makeSexp_).join(" ")+")"}static fromString_(t){let e=t.replace(/\(/g,"[");return e=e.replace(/\)/g,"]"),e=e.replace(/ /g,","),e=e.replace(/c/g,'"c"'),JSON.parse(e)}static fromNode_(t){if(!t)return[];const e=t.contentNodes;let s;e.length&&(s=e.map(Jf.fromNode_),s.unshift("c"));const i=t.childNodes;if(!i.length)return e.length?[t.id,s]:t.id;const r=i.map(Jf.fromNode_);return e.length&&r.unshift(s),r.unshift(t.id),r}static tree_(t,e,s,i=0,r=1,n=1){if(!e)return[];const o=e.id,a=[o];!function(t){if(yp.getInstance().mode!==rp.HTTP)return;let e=t;for(;e&&!e.evaluate;)e=e.parentNode;e&&e.evaluate?vp.currentDocument=e:t.ownerDocument&&(vp.currentDocument=t.ownerDocument)}(t);const l=function(t,e){let s;try{s=kp(t,e,vp.result.ORDERED_NODE_ITERATOR_TYPE)}catch(t){return[]}const i=[];for(let t=s.iterateNext();t;t=s.iterateNext())i.push(t);return i}(`.//self::*[@${Wf.ID}=${o}]`,t)[0];if(!e.childNodes.length)return Jf.addAria(l,i,r,n,s),e.id;const c=Jf.combineContentChildren(e.type,e.role,e.contentNodes.map(function(t){return t}),e.childNodes.map(function(t){return t}));l&&Jf.addOwns_(l,c);for(let e,r=0,n=c.length;e=c[r];r++)a.push(Jf.tree_(t,e,s,i+1,r+1,n));return Jf.addAria(l,i,r,n,s),a}static addAria(t,e,s,i,r){const n=r.tree?e?"treeitem":"tree":"treeitem";r.aria&&t&&(t.setAttribute("aria-level",e.toString()),t.setAttribute("aria-posinset",s.toString()),t.setAttribute("aria-setsize",i.toString()),t.setAttribute("role",n),t.hasAttribute(Wf.OWNS)&&t.setAttribute("aria-owns",t.getAttribute(Wf.OWNS)))}static addOwns_(t,e){const s=t.getAttribute(Wf.COLLAPSED),i=s?Jf.realLeafs_(Jf.fromString(s).array):e.map(t=>t.id);t.setAttribute(Wf.OWNS,i.join(" "))}static realLeafs_(t){if(Jf.simpleCollapseStructure(t))return[t];if(Jf.contentCollapseStructure(t))return[];let e=[];for(let s=1;sJf.simpleCollapseStructure(t)?t:Jf.contentCollapseStructure(t)?t[1]:t[0])}subtreeNodes(t){if(!this.isRoot(t))return[];const e=(t,s)=>{Jf.simpleCollapseStructure(t)?s.push(t):(Jf.contentCollapseStructure(t)&&(t=t.slice(1)),t.forEach(t=>e(t,s)))},s=this.levelsMap[t],i=[];return e(s.slice(1),i),i}}function Kf(t,e,s){let i=null;if(!t.length)return i;const r=s[s.length-1],n=r&&r.length,o=e&&e.length,a=Of.getInstance();if(n&&o){if(e[0].type===Qp.INFIXOP&&e[0].role===tm.IMPLICIT)return i=t.pop(),r.push(a.postfixNode_(r.pop(),t)),i;i=t.shift();const s=a.prefixNode_(e.shift(),t);return e.unshift(s),i}return n?(r.push(a.postfixNode_(r.pop(),t)),i):(o&&e.unshift(a.prefixNode_(e.shift(),t)),i)}function $f(t,e,s){if(!e.length)return t;const i=t.pop(),r=e.shift(),n=s.shift();if(r.type===Qp.INFIXOP&&(r.role===tm.IMPLICIT||r.role===tm.UNIT)){mp.getInstance().output("Juxta Heuristic Case 2");const o=(i?[i,r]:[r]).concat(n);return $f(t.concat(o),e,s)}if(!i)return mp.getInstance().output("Juxta Heuristic Case 3"),$f([r].concat(n),e,s);const o=n.shift();if(!o){mp.getInstance().output("Juxta Heuristic Case 9");const n=If.factory.makeBranchNode(Qp.INFIXOP,[i,e.shift()],[r],r.textContent);return n.role=tm.IMPLICIT,If.run("combine_juxtaposition",n),e.unshift(n),$f(t,e,s)}if(nf(i)||nf(o))return mp.getInstance().output("Juxta Heuristic Case 4"),$f(t.concat([i,r,o]).concat(n),e,s);let a=null;return _f(i)&&_f(o)?(mp.getInstance().output("Juxta Heuristic Case 5"),i.contentNodes.push(r),i.contentNodes=i.contentNodes.concat(o.contentNodes),i.childNodes.push(o),i.childNodes=i.childNodes.concat(o.childNodes),o.childNodes.forEach(t=>t.parent=i),r.parent=i,i.addMathmlNodes(r.mathml),i.addMathmlNodes(o.mathml),a=i):_f(i)?(mp.getInstance().output("Juxta Heuristic Case 6"),i.contentNodes.push(r),i.childNodes.push(o),o.parent=i,r.parent=i,i.addMathmlNodes(r.mathml),i.addMathmlNodes(o.mathml),a=i):_f(o)?(mp.getInstance().output("Juxta Heuristic Case 7"),o.contentNodes.unshift(r),o.childNodes.unshift(i),i.parent=o,r.parent=o,o.addMathmlNodes(r.mathml),o.addMathmlNodes(i.mathml),a=o):(mp.getInstance().output("Juxta Heuristic Case 8"),a=If.factory.makeBranchNode(Qp.INFIXOP,[i,o],[r],r.textContent),a.role=tm.IMPLICIT),t.push(a),$f(t.concat(n),e,s)}function Yf(t){return t.childNodes[0]&&t.childNodes[0].childNodes[0]&&Op(t.childNodes[0])===Lm.MPADDED&&Op(t.childNodes[0].childNodes[0])===Lm.MPADDED&&Op(t.childNodes[0].childNodes[t.childNodes[0].childNodes.length-1])===Lm.MPHANTOM}If.add(new jf("combine_juxtaposition",function(t){for(let e,s=t.childNodes.length-1;e=t.childNodes[s];s--)_f(e)&&!e.nobreaking&&(t.childNodes.splice(s,1,...e.childNodes),t.contentNodes.splice(s,0,...e.contentNodes),e.childNodes.concat(e.contentNodes).forEach(function(e){e.parent=t}),t.addMathmlNodes(e.mathml));return t})),If.add(new jf("propagateSimpleFunction",t=>(t.type!==Qp.INFIXOP&&t.type!==Qp.FRACTION||!t.childNodes.every(xf)||(t.role=tm.COMPFUNC),t),t=>"clearspeak"===If.options.domain)),If.add(new jf("simpleNamedFunction",t=>(t.role!==tm.UNIT&&-1!==["f","g","h","F","G","H"].indexOf(t.textContent)&&(t.role=tm.SIMPLEFUNC),t),t=>"clearspeak"===If.options.domain)),If.add(new jf("propagateComposedFunction",t=>(t.type===Qp.FENCED&&t.childNodes[0].role===tm.COMPFUNC&&(t.role=tm.COMPFUNC),t),t=>"clearspeak"===If.options.domain)),If.add(new jf("multioperator",t=>{t.role!==tm.UNKNOWN||t.textContent.length<=1||(Of.compSemantics(t,"role",tm),Of.compSemantics(t,"type",Qp))})),If.add(new Uf("convert_juxtaposition",t=>{let e=Wm(t,function(t){return t.textContent===om.invisibleTimes&&t.type===Qp.OPERATOR});e=e.rel.length?function(t){const e=[],s=[];let i=t.comp.shift(),r=null,n=[];for(;t.comp.length;)if(n=[],i.length)r&&e.push(r),s.push(i),r=t.rel.shift(),i=t.comp.shift();else{for(r&&n.push(r);!i.length&&t.comp.length;)i=t.comp.shift(),n.push(t.rel.shift());r=Kf(n,i,s)}n.length||i.length?(e.push(r),s.push(i)):(n.push(r),Kf(n,i,s));return{rel:e,comp:s}}(e):e,t=e.comp[0];for(let s,i,r=1;s=e.comp[r],i=e.rel[r-1];r++)t.push(i),t=t.concat(s);return e=Wm(t,function(t){return t.textContent===om.invisibleTimes&&(t.type===Qp.OPERATOR||t.type===Qp.INFIXOP)}),e.rel.length?$f(e.comp.shift(),e.rel,e.comp):t})),If.add(new jf("simple2prefix",t=>(t.textContent.length>1&&!t.textContent[0].match(/[A-Z]/)&&(t.role=tm.PREFIXFUNC),t),t=>"braille"===If.options.modality&&t.type===Qp.IDENTIFIER)),If.add(new jf("detect_cycle",t=>{t.type=Qp.MATRIX,t.role=tm.CYCLE;const e=t.childNodes[0];return e.type=Qp.ROW,e.role=tm.CYCLE,e.textContent="",e.contentNodes=[],t},t=>t.type===Qp.FENCED&&t.childNodes[0].type===Qp.INFIXOP&&t.childNodes[0].role===tm.IMPLICIT&&t.childNodes[0].childNodes.every(function(t){return t.type===Qp.NUMBER})&&t.childNodes[0].contentNodes.every(function(t){return t.role===tm.SPACE}))),If.add(new Uf("intvar_from_implicit",function(t){const e=t[0].childNodes;t.splice(0,1,...e),t.forEach(t=>t.parent=null)},t=>t[0]&&kf(t[0]))),If.add(new jf("intvar_from_fraction",function(t){const e=t.childNodes[1],s=e.childNodes[0];if(ef(s))return void(s.role=tm.INTEGRAL);if(!kf(s))return;const i=s.childNodes.length,r=s.childNodes[i-2],n=s.childNodes[i-1];if(ef(n))return void(n.role=tm.INTEGRAL);if(tf(r,n)){const t=Of.getInstance().prefixNode_(n,[r]);t.role=tm.INTEGRAL,2===i?e.childNodes[0]=t:(s.childNodes.pop(),s.contentNodes.pop(),s.childNodes[i-2]=t,t.parent=s)}},t=>{if(t.type!==Qp.INTEGRAL)return!1;const[,e,s]=t.childNodes;return s.type===Qp.EMPTY&&e.type===Qp.FRACTION})),If.add(new jf("rewrite_subcases",function(t){t.addAnnotation("Emph","top");let e=[];if(t.hasAnnotation("Emph","left")){const s=Zf(t.childNodes[0].childNodes[0].childNodes[0],!0);s.forEach(t=>t.addAnnotation("Emph","left")),e=e.concat(s);for(let e,s=0;e=t.childNodes[s];s++)e.childNodes.shift()}if(e.push(t),t.hasAnnotation("Emph","right")){const s=Zf(t.childNodes[0].childNodes[t.childNodes[0].childNodes.length-1].childNodes[0]);s.forEach(t=>t.addAnnotation("Emph","left")),e=e.concat(s),t.childNodes[0].childNodes.pop()}Of.tableToMultiline(t);const s=Of.getInstance().row(e),i=t.annotation.Emph;return t.annotation.Emph=["table"],i.forEach(t=>s.addAnnotation("Emph",t)),s},t=>{let e=!0,s=!0;const i=t.childNodes[0].childNodes[0];if(!i)return!1;if(Yf(i.mathmlTree)){for(let s,i=1;s=t.childNodes[i];i++)if(s.childNodes[0].childNodes.length){e=!1;break}}else e=!1;e&&t.addAnnotation("Emph","left");if(Yf(t.childNodes[0].childNodes[t.childNodes[0].childNodes.length-1].mathmlTree)){const e=t.childNodes[0].childNodes.length;for(let i,r=1;i=t.childNodes[r];r++)if(i.childNodes.length>=e){s=!1;break}}else s=!1;return s&&t.addAnnotation("Emph","right"),e||s}));const Qf=[Qp.PUNCTUATED,Qp.RELSEQ,Qp.MULTIREL,Qp.INFIXOP,Qp.PREFIXOP,Qp.POSTFIXOP];function Zf(t,e){if(!t.childNodes.length)return eg(t),[t];let s=null;if(t.type===Qp.PUNCTUATED&&(e?t.role===tm.ENDPUNCT:t.role===tm.STARTPUNCT)){const i=t.childNodes;eg(i[e?i.length-1:0])&&(t=i[e?0:i.length-1],s=i[e?i.length-1:0])}if(-1!==Qf.indexOf(t.type)){const i=t.childNodes;eg(i[e?i.length-1:0]);const r=Jf.combineContentChildren(t.type,t.role,t.contentNodes,t.childNodes);return s&&(e?r.push(s):r.unshift(s)),r}return s?e?[t,s]:[s,t]:[t]}const tg={[tm.METRIC]:tm.METRIC,[tm.VBAR]:tm.NEUTRAL,[tm.OPENFENCE]:tm.OPEN,[tm.CLOSEFENCE]:tm.CLOSE};function eg(t){if(t.type!==Qp.PUNCTUATION)return!1;const e=tg[t.role];return!!e&&(t.role=e,t.type=Qp.FENCE,t.addAnnotation("Emph","fence"),!0)}function sg(t,e,s,i=s){const r=[];for(;t&&t.role===s;)r.push(t),t=e.shift();return r.length?(t&&e.unshift(t),[1===r.length?r[0]:ig(r,i),e]):[t,e]}function ig(t,e){const s=If.factory.makeBranchNode(Qp.PUNCTUATION,t,[]);return s.role=e,s}function rg(t){return["[","\uff3b"].includes(t)}function ng(t){return["]","\uff3d"].includes(t)}function og(t){return["(","\u207d","\u208d"].includes(t)}function ag(t){return[")","\u207e","\u208e"].includes(t)}function lg(t){return t.role===tm.INFTY||t.type===Qp.PREFIXOP&&t.childNodes[0].role===tm.INFTY}function cg(t){const e=t.childNodes[0];if(t.type!==Qp.FENCED||(null==e?void 0:e.type)!==Qp.PUNCTUATED||3!==(null==e?void 0:e.childNodes.length)||1!==(null==e?void 0:e.contentNodes.length)||(null==e?void 0:e.childNodes[1].role)!==tm.COMMA)return!1;const s=t.childNodes[0].childNodes[0],i=t.childNodes[0].childNodes[2],r=t.contentNodes[0].textContent,n=t.contentNodes[1].textContent;return!!(rg(r)&&ag(n)||og(r)&&ng(n))||!(!og(r)||!ag(n)||!lg(s)&&!lg(i))}function hg(t){return mg(t)||function(t){return ug(t)||t.type===Qp.INFIXOP&&t.role===tm.IMPLICIT&&(2===t.childNodes.length&&(ug(t.childNodes[0])||mg(t.childNodes[0]))&&ug(t.childNodes[1])||3===t.childNodes.length&&mg(t.childNodes[0])&&ug(t.childNodes[1])&&ug(t.childNodes[2]))}(t)||function(t){return t.type===Qp.PUNCTUATED&&t.role===tm.ENDPUNCT&&2===t.childNodes.length&&t.childNodes[1].role===tm.DEGREE&&(ug(t.childNodes[0])||pg(t.childNodes[0])||t.childNodes[0].type===Qp.PREFIXOP&&t.childNodes[0].role===tm.NEGATIVE&&(ug(t.childNodes[0].childNodes[0])||pg(t.childNodes[0].childNodes[0])))}(t)||function(t){return t.type===Qp.PREFIXOP&&t.role===tm.NEGATIVE&&dg(t.childNodes[0])&&t.childNodes[0].type!==Qp.PREFIXOP&&t.childNodes[0].type!==Qp.APPL&&t.childNodes[0].type!==Qp.PUNCTUATED}(t)||function(t){return t.type===Qp.APPL&&(t.childNodes[0].role===tm.PREFIXFUNC||t.childNodes[0].role===tm.SIMPLEFUNC)&&(dg(t.childNodes[1])||t.childNodes[1].type===Qp.FENCED&&dg(t.childNodes[1].childNodes[0]))}(t)}function dg(t){return t.hasAnnotation("clearspeak","simple")}function ug(t){return t.type===Qp.IDENTIFIER&&(t.role===tm.LATINLETTER||t.role===tm.GREEKLETTER||t.role===tm.OTHERLETTER||t.role===tm.SIMPLEFUNC)}function pg(t){return t.type===Qp.NUMBER&&(t.role===tm.INTEGER||t.role===tm.FLOAT)}function mg(t){return pg(t)||function(t){if(fg("Fraction_Over")||fg("Fraction_FracOver"))return!1;if(t.type!==Qp.FRACTION||t.role!==tm.VULGAR)return!1;if(fg("Fraction_Ordinal"))return!0;const e=parseInt(t.childNodes[0].textContent,10),s=parseInt(t.childNodes[1].textContent,10);return e>0&&e<20&&s>0&&s<11}(t)}function fg(t){return yp.getInstance().options.style===t}function gg(t){return t.type===Qp.TEXT&&t.role!==tm.LABEL||t.type===Qp.PUNCTUATED&&t.role===tm.TEXT&&pg(t.childNodes[0])&&function(t){for(let e=0;e{const e=[];let s=t.shift();for(;s;)[s,t]=sg(s,t,tm.FULLSTOP,tm.ELLIPSIS),[s,t]=sg(s,t,tm.DASH),e.push(s),s=t.shift();return e},t=>t.length>1)),If.add(new Uf("op_with_limits",t=>{const e=t[0];return e.type=Qp.LARGEOP,e.role=tm.SUM,t},t=>(t[0].type===Qp.OPERATOR||t[0].type===Qp.IDENTIFIER&&"OP"===t[0].attributes.texclass)&&t.slice(1).some(t=>t.type===Qp.RELSEQ||t.type===Qp.MULTIREL||t.type===Qp.INFIXOP&&t.role===tm.ELEMENT||t.type===Qp.PUNCTUATED&&t.role===tm.SEQUENCE))),If.add(new class extends Ff{}("function_from_identifiers",t=>{const e=Lp(t.childNodes).map(t=>t.textContent.trim()).join("");if(cm.Meaning.get(e).type===Qp.UNKNOWN)return t;const s=If.factory.makeLeafNode(e,Of.getInstance().font(t.getAttribute("mathvariant")));return s.mathmlTree=t,s},t=>{const e=Lp(t.childNodes);return!(e.length<2)&&e.every(t=>Op(t)===Lm.MI&&cm.Meaning.get(t.textContent.trim()).role===tm.LATINLETTER)})),If.add(new Uf("bracketed_interval",t=>{const e=t[0],s=t[1],i=t.slice(2),r=Of.getInstance().row(i),n=If.factory.makeBranchNode(Qp.FENCED,[r],[e,s]);return n.role=tm.INTERVAL,n},t=>{const e=t[0],s=t[1],i=t.slice(2);if(!(e&&s&&(ng(e.textContent)&&(rg(s.textContent)||ng(s.textContent))||rg(s.textContent)&&(rg(e.textContent)||ng(e.textContent)))))return!1;if(1===i.length&&i[0].type===Qp.PUNCTUATED&&1===i[0].contentNodes.length)return!0;const r=Wm(i,af);return!(1!==r.rel.length||!r.comp[0].length||!r.comp[1].length)})),If.add(new jf("interval_heuristic",t=>(t.role=tm.INTERVAL,t),t=>cg(t))),If.add(new jf("propagateInterval",t=>(t.childNodes.forEach(t=>{cg(t)&&(t.role=tm.INTERVAL)}),t),t=>Mf(t))),Up(new Pp("clearspeak","simple",function(t){return hg(t)?"simple":""})),Hp("clearspeak","simple"),Up(new Pp("clearspeak","unit",function(t){return gg(t)?"unit":""})),Hp("clearspeak","unit");const bg=[Qp.MULTIREL,Qp.RELSEQ,Qp.APPL,Qp.ROW,Qp.LINE],Eg=[Qp.SUBSCRIPT,Qp.SUPERSCRIPT,Qp.OVERSCORE,Qp.UNDERSCORE];function xg(t,e){const s=t.parent;if(!s)return!1;const i=s.type;return-1!==bg.indexOf(i)||i===Qp.PREFIXOP&&s.role===tm.NEGATIVE&&!e.script&&!e.enclosed||i===Qp.PREFIXOP&&s.role===tm.GEOMETRY||!(i!==Qp.PUNCTUATED||e.enclosed&&s.role!==tm.TEXT)}Up(new Bp("nemeth","number",function(t,e){return t.childNodes.length?(-1!==Eg.indexOf(t.type)&&(e.script=!0),t.type===Qp.FENCED?(e.number=!1,e.enclosed=!0,["",e]):t.type===Qp.PREFIXOP&&t.role!==tm.GEOMETRY&&t.role!==tm.NEGATIVE?(e.number=!1,["",e]):(xg(t,e)&&(e.number=!0,e.enclosed=!1),["",e])):(xg(t,e)&&(e.number=!0,e.script=!1,e.enclosed=!1),[e.number?"number":"",{number:!1,enclosed:e.enclosed,script:e.script}])},{number:!0})),Hp("nemeth","number"),Up(new Bp("depth","depth",function(t){return t.parent?[parseInt(t.parent.annotation.depth[0])+1]:[1]})),Hp("depth","depth");class yg{static empty(){const t=Ap(""),e=new yg(t,new gp);return e.mathml=t,e}static fromNode(t,e){const s=yg.empty();return s.root=t,e&&(s.mathml=e),s}static fromRoot(t,e){let s=t;for(;s.parent;)s=s.parent;const i=yg.fromNode(s);return e&&(i.mathml=e),i}static fromXml(t){const e=yg.empty();return t.childNodes[0]&&(e.root=Vm.fromXml(t.childNodes[0])),e}constructor(t,e){this.mathml=t,this.options=e,this.parser=new Bf(e),this.root=this.parser.parse(t),this.root=Of.rewriteTrivialTable(this.root),this.collator=this.parser.getFactory().leafMap.collateMeaning();const s=this.collator.newDefault();s&&(this.parser=new Bf(e),this.parser.getFactory().defaultMap=s,this.root=this.parser.parse(t)),Ng.visit(this.root,{}),function(t){for(const e of Fp.values())e.active&&e.annotate(t);for(const e of jp.values())e.active&&e.visit(t,Object.assign({},e.def))}(this.root)}xml(t){const e=Ap(""),s=this.root.xml(e.ownerDocument,t);return e.appendChild(s),e}toString(t){return Dp(this.xml(t))}formatXml(t){return Mp(this.toString(t))}displayTree(){this.root.displayTree()}replaceNode(t,e){const s=t.parent;s?s.replaceChild(t,e):this.root=e}toJson(){const t={};return t.stree=this.root.toJson(),t}}const Ng=new Bp("general","unit",(t,e)=>(Cf(t)&&(t.role=tm.UNIT),!1));function vg(t,e){return new yg(t,e)}const Tg=[],wg=!0,Cg=new Map;function kg(t){mp.getInstance().generate(()=>["WALKING START: ",t.toString()]);const e=function(t){for(let e,s=0;e=Tg[s];s++)if(e.test(t))return e.constr(t);return null}(t);let s;if(e)return s=e.getMathml(),mp.getInstance().generate(()=>["WALKING END: ",t.toString()]),jg(s);if(1===t.mathml.length){if(mp.getInstance().output("Walktree Case 0"),!t.childNodes.length)return mp.getInstance().output("Walktree Case 0.1"),s=t.mathml[0],Xf(s,t),mp.getInstance().generate(()=>["WALKING END: ",t.toString()]),jg(s);const e=t.childNodes[0];if(1===t.childNodes.length&&e.type===Qp.EMPTY)return mp.getInstance().output("Walktree Case 0.2"),s=t.mathml[0],Xf(s,t),s.appendChild(kg(e)),mp.getInstance().generate(()=>["WALKING END: ",t.toString()]),jg(s);t.childNodes.forEach(t=>{t.mathml.length||(t.mathml=[Gg(t)])})}const i=t.contentNodes.map(Vg);Jg(t,i);const r=t.childNodes.map(kg),n=Jf.combineContentChildren(t.type,t.role,i,r);if(s=t.mathmlTree,null===s)mp.getInstance().output("Walktree Case 1"),s=_g(n,t);else{s=Xg(s);const t=Pg(n);mp.getInstance().output("Walktree Case 2"),t?(mp.getInstance().output("Walktree Case 2.1"),s=Wg(t)):(mp.getInstance().output("Walktree Case 2.2"),s=Kg(s))}return function(t,e,s){if(!e.length)return;if(1===e.length&&t===e[0])return;const i=s.role===tm.IMPLICIT&&If.flags.combine_juxtaposition?function(t,e,s){const i=[];let r=Lp(t.childNodes),n=!1;for(;r.length;){const t=r.shift();if(t.hasAttribute(Wf.TYPE)){i.push(t);continue}const s=Ag(t,e);0!==s.length&&(1!==s.length?(n?t.setAttribute("AuxiliaryImplicit",!0):n=!0,r=s.concat(r)):i.push(t))}const o=[],a=s.childNodes.map(function(t){return t.mathmlTree});for(;a.length;){const t=a.pop();if(t){if(-1!==i.indexOf(t))break;-1!==e.indexOf(t)&&o.unshift(t)}}return i.concat(o)}(t,e,s):Lp(t.childNodes);if(!i.length)return void e.forEach(function(e){t.appendChild(e)});let r=0;for(;e.length;){const s=e[0];if(i[r]===s||Og(i[r],s)){e.shift(),r++;continue}if(i[r]&&-1===e.indexOf(i[r])){r++;continue}if(Ig(s,t)){e.shift();continue}const n=i[r];if(!n){if(s.parentNode){t=Wg(s),e.shift();continue}const i=e[1];if(i&&i.parentNode){Sg(t=Wg(i),s,i),e.shift(),e.shift();continue}Sg(t,s,null),e.shift();continue}Rg(t,n,s),e.shift()}}(s,n,t),Cg.has(t.id)||(Cg.set(t.id,!0),Xf(s,t)),mp.getInstance().generate(()=>["WALKING END: ",t.toString()]),jg(s,t)}function _g(t,e){const s=function(t){const e=Pg(t);if(!e)return{type:Dg.INVALID,node:null};const s=Pg(t.slice().reverse());if(e===s)return{type:Dg.VALID,node:e};const i=Bg(e),r=function(t,e){let s=0;for(;t[s]&&-1===e.indexOf(t[s]);)s++;return t.slice(0,s+1)}(i,t),n=Bg(s,function(t){return-1!==r.indexOf(t)}),o=n[0],a=r.indexOf(o);if(-1===a)return{type:Dg.INVALID,node:null};return{type:r.length!==i.length?Dg.PRUNED:Fg(r[a+1],n[1])?Dg.VALID:Dg.INVALID,node:o}}(t);let i=s.node;const r=s.type;if(r!==Dg.VALID||!Bm(i)||!i.parentNode&&e.parent)if(mp.getInstance().output("Walktree Case 1.1"),i=Gf(),r===Dg.PRUNED)mp.getInstance().output("Walktree Case 1.1.0"),i=function(t,e,s){let i=Ug(e);if(Dm(i)){mp.getInstance().output("Walktree Case 1.1.0.0"),Lg(i,t),Lp(i.childNodes).forEach(function(e){t.appendChild(e)});const e=t;t=i,i=e}const r=s.indexOf(e);return s[r]=i,Rp(i,t),t.appendChild(i),s.forEach(function(e){t.appendChild(e)}),t}(i,s.node,t);else if(t[0]){mp.getInstance().output("Walktree Case 1.1.1");const e=Pg(t);if(e){const s=function(t,e){const s=Lp(t.childNodes);let i=1/0,r=-1/0;return e.forEach(function(t){const e=s.indexOf(t);-1!==e&&(i=Math.min(i,e),r=Math.max(r,e))}),s.slice(i,r+1)}(Wg(e),t);Rp(e,i),s.forEach(function(t){i.appendChild(t)})}else Lg(i,t[0]),i=t[0]}return e.mathmlTree||(e.mathmlTree=i),i}function Lg(t,e){for(const s of zf)t.hasAttribute(s)&&(e.setAttribute(s,t.getAttribute(s)),t.removeAttribute(s))}function Ag(t,e){const s=[];let i=Lp(t.childNodes);for(;i.length;){const t=i.shift();t.nodeType===_p.ELEMENT_NODE&&(t.hasAttribute(Wf.TYPE)||-1!==e.indexOf(t)?s.push(t):i=Lp(t.childNodes).concat(i))}return s}function Rg(t,e,s){let i=e,r=Wg(i);for(;r&&Mg(r,i)&&!i.hasAttribute("AuxiliaryImplicit")&&r!==t;)i=r,r=Wg(i);r&&(Sg(r,s,i),i.removeAttribute("AuxiliaryImplicit"))}function Sg(t,e,s){Op(t)===Lm.MACTION?Sg(Wg(t),e,t):t.insertBefore(e,s)}function Mg(t,e){if(Op(t)!==Lm.MACTION)return t.firstChild===e;const s=parseInt(t.getAttribute("selection"))||1;return t.childNodes[s-1]===e}function Ig(t,e){if(!t)return!1;do{if((t=Wg(t))===e)return!0}while(t);return!1}function Og(t,e){const s=om.functionApplication;if(t&&e&&t.textContent&&e.textContent&&t.textContent===s&&e.textContent===s&&"true"===e.getAttribute(Wf.ADDED)){for(let s,i=0;s=t.attributes[i];i++)e.hasAttribute(s.nodeName)||e.setAttribute(s.nodeName,s.nodeValue);return Rp(t,e),!0}return!1}var Dg;function Pg(t){let e=0,s=null;for(;!s&&e!1),i=[t];for(;!s(t)&&!Dm(t)&&t.parentNode;)t=Wg(t),i.unshift(t);return i}function Fg(t,e){return!(!t||!e||t.previousSibling||e.nextSibling)}function jg(t,e){var s;let i=e&&!e.hasAnnotation("empty","MFENCED")&&e.getAnnotation("empty");for(;!Dm(t)&&(Hg(t)||i&&t.parentNode&&i.includes(null===(s=Wg(t).tagName)||void 0===s?void 0:s.toUpperCase()));)t=Wg(t);return t}function Ug(t){const e=Lp(t.childNodes);if(!e)return t;const s=e.filter(function(t){return t.nodeType===_p.ELEMENT_NODE&&!Pm(t)});return 1===s.length&&Bm(s[0])&&!s[0].hasAttribute(Wf.TYPE)?Ug(s[0]):t}function Hg(t){const e=Wg(t);return!(!e||!Bm(e))&&Lp(e.childNodes).every(function(e){return e===t||qg(e)})}function qg(t){if(t.nodeType!==_p.ELEMENT_NODE)return!0;if(!t||Pm(t))return!0;const e=Lp(t.childNodes);return!(!Bm(t)&&e.length||function(t){return!!t&&Im.includes(Op(t))}(t)||t.hasAttribute(Wf.TYPE)||Fm(t))&&Lp(t.childNodes).every(qg)}function Wg(t){return t.parentNode}function zg(t,e){const s=new Jf(e);t.setAttribute(Wf.COLLAPSED,s.toString())}function Vg(t){if(t.mathml.length)return kg(t);const e=wg?Gg(t):Gf();return t.mathml=[e],e}function Xg(t){if(Op(t)!==Lm.MFENCED)return t;const e=Gf();for(let s,i=0;s=t.attributes[i];i++)-1===["open","close","separators"].indexOf(s.name)&&e.setAttribute(s.name,s.value);return Lp(t.childNodes).forEach(function(t){e.appendChild(t)}),Rp(t,e),e}function Gg(t){const e=Sp("mo"),s=(i=t.textContent,up.f.document.createTextNode(i));var i;return e.appendChild(s),Xf(e,t),e.setAttribute(Wf.ADDED,"true"),e}function Jg(t,e){const s=t.type+(t.textContent?","+t.textContent:"");e.forEach(function(t){Kg(t).setAttribute(Wf.OPERATOR,s)})}function Kg(t){if(Pm(t))return t;const e=Lp(t.childNodes);if(!e)return t;const s=e.filter(function(t){return!qg(t)}),i=[];for(let t,e=0;t=s[e];e++)if(Bm(t)&&t.getAttribute(Wf.TYPE)!==Qp.PUNCTUATION){const e=Kg(t);e&&e!==t&&i.push(e)}else i.push(t);return 1===i.length?i[0]:t}function $g(t){return Mp(t.toString()).toString().replace(new RegExp(qf,"g"),"")}function Yg(t,e){const s=!!e,i=e||[],r=t.parent,n=t.contentNodes.map(function(t){return t.id});n.unshift("c");const o=[t.id,n];for(let e,n=0;e=t.childNodes[n];n++){const t=kg(e);i.push(t);const n=Kg(t);r&&!s&&n.setAttribute(Wf.PARENT,r.id.toString()),o.push(e.id)}return o}!function(t){t.VALID="valid",t.INVALID="invalid",t.PRUNED="pruned"}(Dg||(Dg={}));class Qg{constructor(t){this.semantic=t}}class Zg extends Qg{static test(t){return!t.mathmlTree&&t.type===Qp.LINE&&t.role===tm.BINOMIAL}constructor(t){super(t),this.mml=t.mathmlTree}getMathml(){if(!this.semantic.childNodes.length)return this.mml;const t=this.semantic.childNodes[0];if(this.mml=kg(t),this.mml.hasAttribute(Wf.TYPE)){const t=Gf();Rp(this.mml,t),t.appendChild(this.mml),this.mml=t}return Xf(this.mml,this.semantic),this.mml}}class tb extends Qg{static test(t){var e,s;return!!t.getAnnotation("collapsed").length&&(null===(s=null===(e=t.mathmlTree)||void 0===e?void 0:e.parentNode)||void 0===s?void 0:s.childNodes.length)>2}getMathml(){kg(this.semantic.childNodes[0]),kg(this.semantic.childNodes[1]);const t=this.semantic.mathmlTree,e=_g([this.semantic.childNodes[0].mathmlTree,t],this.semantic);return Xf(e,this.semantic),e}}class eb extends Qg{static test(t){if(!t.mathmlTree||!t.childNodes.length)return!1;const e=Op(t.mathmlTree),s=t.childNodes[0].role;return e===Lm.MSUBSUP&&s===tm.SUBSUP||e===Lm.MUNDEROVER&&s===tm.UNDEROVER}constructor(t){super(t),this.mml=t.mathmlTree}getMathml(){const t=this.semantic.childNodes[0],e=t.childNodes[0],s=this.semantic.childNodes[1],i=t.childNodes[1],r=kg(s),n=kg(e),o=kg(i);return Xf(this.mml,this.semantic),this.mml.setAttribute(Wf.CHILDREN,Vf([e,i,s])),[n,o,r].forEach(t=>Kg(t).setAttribute(Wf.PARENT,this.mml.getAttribute(Wf.ID))),this.mml.setAttribute(Wf.TYPE,t.role),zg(this.mml,[this.semantic.id,[t.id,e.id,i.id],s.id]),this.mml}}class sb extends Qg{static multiscriptIndex(t){return t.type===Qp.PUNCTUATED&&t.contentNodes[0].role===tm.DUMMY&&t.hasAnnotation("general","script")?Yg(t):(kg(t),t.id)}static createNone_(t){const e=Sp("none");return t&&Xf(e,t),e.setAttribute(Wf.ADDED,"true"),e}constructor(t){super(t),this.mml=t.mathmlTree}completeMultiscript(t,e){const s=Lp(this.mml.childNodes).slice(1);let i=0;const r=t=>{for(const e of t){const t=s[i];if(t&&e===parseInt(t.getAttribute(Wf.ID)))t.setAttribute(Wf.PARENT,this.semantic.id.toString()),i++;else if(t&&e===parseInt(Kg(t).getAttribute(Wf.ID)))Kg(t).setAttribute(Wf.PARENT,this.semantic.id.toString()),i++;else{const s=this.semantic.querySelectorAll(t=>t.id===e);this.mml.insertBefore(sb.createNone_(s[0]),t||null)}}};r(t),s[i]&&Op(s[i])!==Lm.MPRESCRIPTS?this.mml.insertBefore(s[i],Sp("mprescripts")):i++,r(e)}}class ib extends sb{static test(t){if(!t.mathmlTree)return!1;return Op(t.mathmlTree)===Lm.MMULTISCRIPTS&&(t.type===Qp.SUPERSCRIPT||t.type===Qp.SUBSCRIPT)}constructor(t){super(t)}getMathml(){let t,e,s;if(Xf(this.mml,this.semantic),this.semantic.childNodes[0]&&this.semantic.childNodes[0].role===tm.SUBSUP){const i=this.semantic.childNodes[0];t=i.childNodes[0],e=sb.multiscriptIndex(this.semantic.childNodes[1]),s=sb.multiscriptIndex(i.childNodes[1]);const r=[this.semantic.id,[i.id,t.id,s],e];zg(this.mml,r),this.mml.setAttribute(Wf.TYPE,i.role),this.completeMultiscript(Jf.interleaveIds(s,e),[])}else{t=this.semantic.childNodes[0],e=sb.multiscriptIndex(this.semantic.childNodes[1]);const s=[this.semantic.id,t.id,e];zg(this.mml,s)}const i=Jf.collapsedLeafs(s||[],e);return Kg(kg(t)).setAttribute(Wf.PARENT,this.semantic.id.toString()),i.unshift(t.id),this.mml.setAttribute(Wf.CHILDREN,i.join(",")),this.mml}}class rb extends sb{static test(t){return!!t.mathmlTree&&t.type===Qp.TENSOR}constructor(t){super(t)}getMathml(){kg(this.semantic.childNodes[0]);const t=sb.multiscriptIndex(this.semantic.childNodes[1]),e=sb.multiscriptIndex(this.semantic.childNodes[2]),s=sb.multiscriptIndex(this.semantic.childNodes[3]),i=sb.multiscriptIndex(this.semantic.childNodes[4]);Xf(this.mml,this.semantic);const r=[this.semantic.id,this.semantic.childNodes[0].id,t,e,s,i];zg(this.mml,r);const n=Jf.collapsedLeafs(t,e,s,i);return n.unshift(this.semantic.childNodes[0].id),this.mml.setAttribute(Wf.CHILDREN,n.join(",")),this.completeMultiscript(Jf.interleaveIds(s,i),Jf.interleaveIds(t,e)),this.mml}}class nb extends Qg{static test(t){return!(!t.mathmlTree||!t.fencePointer||t.mathmlTree.getAttribute("data-semantic-type"))}static makeEmptyNode_(t){const e=Gf(),s=new Vm(t);return s.type=Qp.EMPTY,s.mathmlTree=e,s}static fencedMap_(t,e){e[t.id]=t.mathmlTree,t.embellished&&nb.fencedMap_(t.childNodes[0],e)}constructor(t){super(t),this.fenced=null,this.fencedMml=null,this.fencedMmlNodes=[],this.ofence=null,this.ofenceMml=null,this.ofenceMap={},this.cfence=null,this.cfenceMml=null,this.cfenceMap={},this.parentCleanup=[]}getMathml(){this.getFenced_(),this.fencedMml=kg(this.fenced),this.getFencesMml_(),this.fenced.type!==Qp.EMPTY||this.fencedMml.parentNode||(this.fencedMml.setAttribute(Wf.ADDED,"true"),this.cfenceMml.parentNode.insertBefore(this.fencedMml,this.cfenceMml)),this.getFencedMml_();return this.rewrite_()}fencedElement(t){return t.type===Qp.FENCED||t.type===Qp.MATRIX||t.type===Qp.VECTOR}getFenced_(){let t=this.semantic;for(;!this.fencedElement(t);)t=t.childNodes[0];this.fenced=t.childNodes[0],this.ofence=t.contentNodes[0],this.cfence=t.contentNodes[1],nb.fencedMap_(this.ofence,this.ofenceMap),nb.fencedMap_(this.cfence,this.cfenceMap)}getFencedMml_(){let t=this.ofenceMml.nextSibling;for(t=t===this.fencedMml?t:this.fencedMml;t&&t!==this.cfenceMml;)this.fencedMmlNodes.push(t),t=t.nextSibling}getFencesMml_(){let t=this.semantic;const e=Object.keys(this.ofenceMap),s=Object.keys(this.cfenceMap);for(;!(this.ofenceMml&&this.cfenceMml||t===this.fenced);)-1===e.indexOf(t.fencePointer)||this.ofenceMml||(this.ofenceMml=t.mathmlTree),-1===s.indexOf(t.fencePointer)||this.cfenceMml||(this.cfenceMml=t.mathmlTree),t=t.childNodes[0];this.ofenceMml||(this.ofenceMml=this.ofence.mathmlTree),this.cfenceMml||(this.cfenceMml=this.cfence.mathmlTree),this.ofenceMml&&(this.ofenceMml=jg(this.ofenceMml)),this.cfenceMml&&(this.cfenceMml=jg(this.cfenceMml))}rewrite_(){let t=this.semantic,e=null;const s=this.introduceNewLayer_();for(Xf(s,this.fenced.parent);!this.fencedElement(t);){const i=t.mathmlTree,r=this.specialCase_(t,i);if(r)t=r;else{Xf(i,t);const e=[];for(let s,i=1;s=t.childNodes[i];i++)e.push(kg(s));t=t.childNodes[0]}const n=Sp("dummy"),o=i.childNodes[0];Rp(i,n),Rp(s,i),Rp(i.childNodes[0],s),Rp(n,o),e||(e=i)}return kg(this.ofence),kg(this.cfence),this.cleanupParents_(),e||s}specialCase_(t,e){const s=Op(e);let i,r=null;if(s===Lm.MSUBSUP?(r=t.childNodes[0],i=eb):s===Lm.MMULTISCRIPTS&&(t.type===Qp.SUPERSCRIPT||t.type===Qp.SUBSCRIPT?i=ib:t.type===Qp.TENSOR&&(i=rb),r=i&&t.childNodes[0]&&t.childNodes[0].role===tm.SUBSUP?t.childNodes[0]:t),!r)return null;const n=r.childNodes[0],o=nb.makeEmptyNode_(n.id);return r.childNodes[0]=o,e=new i(t).getMathml(),r.childNodes[0]=n,this.parentCleanup.push(e),r.childNodes[0]}introduceNewLayer_(){const t=this.fullFence(this.ofenceMml),e=this.fullFence(this.cfenceMml);let s=Gf();if(Rp(this.fencedMml,s),this.fencedMmlNodes.forEach(t=>s.appendChild(t)),s.insertBefore(t,this.fencedMml),s.appendChild(e),!s.parentNode){const t=Gf();for(;s.childNodes.length>0;)t.appendChild(s.childNodes[0]);s.appendChild(t),s=t}return s}fullFence(t){const e=this.fencedMml.parentNode;let s=t;for(;s.parentNode&&s.parentNode!==e;)s=s.parentNode;return s}cleanupParents_(){this.parentCleanup.forEach(function(t){const e=t.childNodes[1].getAttribute(Wf.PARENT);t.childNodes[0].setAttribute(Wf.PARENT,e)})}}class ob extends Qg{static test(t){return!!t.mathmlTree&&t.hasAnnotation("Emph","top")}constructor(t){super(t),this.mrows=[],this.mml=t.mathmlTree}getMathml(){if(this.recurseToTable(this.semantic),this.mrows.length){const t=Gf();this.mml.parentNode.insertBefore(t,this.mml);for(const e of this.mrows)t.appendChild(e);t.appendChild(this.mml)}return this.mml}recurseToTable(t){var e,s;if(t.hasAnnotation("Emph","top")||t.hasAnnotation("Emph","fence")||!t.hasAnnotation("Emph","left")&&!t.hasAnnotation("Emph","right")){if(!t.mathmlTree||Op(t.mathmlTree)===Lm.MTABLE&&(null===(e=t.annotation.Emph)||void 0===e?void 0:e.length)&&"table"!==t.annotation.Emph[0]){const e=Gf();Xf(e,t),this.mrows.unshift(e)}else{if(Op(t.mathmlTree)===Lm.MTABLE&&(null===(s=t.annotation.Emph)||void 0===s?void 0:s.length)&&"table"===t.annotation.Emph[0])return void this.finalizeTable(t);Xf(t.mathmlTree,t)}if(t.childNodes.forEach(this.recurseToTable.bind(this)),t.textContent||"punctuated"===t.type){const e=t.contentNodes.map(t=>{const e=Vg(t);return e.hasAttribute("data-semantic-added")?this.mrows.unshift(e):this.recurseToTable(t),e});return void Jg(t,e)}t.contentNodes.forEach(this.recurseToTable.bind(this))}else kg(t)}finalizeTable(t){Xf(t.mathmlTree,t),t.contentNodes.forEach(t=>{kg(t)}),t.childNodes.forEach(t=>{kg(t)})}}class ab extends Qg{static test(t){if(!t.mathmlTree||!t.childNodes.length)return!1;const e=Op(t.mathmlTree),s=t.type;return(s===Qp.LIMUPPER||s===Qp.LIMLOWER)&&(e===Lm.MSUBSUP||e===Lm.MUNDEROVER)||s===Qp.LIMBOTH&&(e===Lm.MSUB||e===Lm.MUNDER||e===Lm.MSUP||e===Lm.MOVER)}static walkTree_(t){t&&kg(t)}constructor(t){super(t),this.mml=t.mathmlTree}getMathml(){const t=this.semantic.childNodes;return this.semantic.type!==Qp.LIMBOTH&&this.mml.childNodes.length>=3&&(this.mml=_g([this.mml],this.semantic)),Xf(this.mml,this.semantic),t[0].mathmlTree||(t[0].mathmlTree=this.semantic.mathmlTree),t.forEach(ab.walkTree_),this.mml}}class lb extends Qg{static test(t){return!!t.mathmlTree&&t.type===Qp.LINE}constructor(t){super(t),this.mml=t.mathmlTree}getMathml(){return this.semantic.contentNodes.length&&kg(this.semantic.contentNodes[0]),this.semantic.childNodes.length&&kg(this.semantic.childNodes[0]),Xf(this.mml,this.semantic),this.mml}}class cb extends Qg{static test(t){return!!t.mathmlTree&&(t.type===Qp.INFERENCE||t.type===Qp.PREMISES)}constructor(t){super(t),this.mml=t.mathmlTree}getMathml(){return this.semantic.childNodes.length?(this.semantic.contentNodes.forEach(function(t){kg(t),Xf(t.mathmlTree,t)}),this.semantic.childNodes.forEach(function(t){kg(t)}),Xf(this.mml,this.semantic),this.mml.getAttribute("data-semantic-id")===this.mml.getAttribute("data-semantic-parent")&&this.mml.removeAttribute("data-semantic-parent"),this.mml):this.mml}}class hb extends Qg{static test(t){return t.type===Qp.MATRIX||t.type===Qp.VECTOR||t.type===Qp.CASES}constructor(t){super(t),this.inner=[],this.mml=t.mathmlTree}getMathml(){const t=Vg(this.semantic.contentNodes[0]),e=this.semantic.contentNodes[1]?Vg(this.semantic.contentNodes[1]):null;if(this.inner=this.semantic.childNodes.map(kg),this.mml)if(Op(this.mml)===Lm.MFENCED){const s=this.mml.childNodes;this.mml.insertBefore(t,s[0]||null),e&&this.mml.appendChild(e),this.mml=Xg(this.mml)}else{const s=[t,this.mml];e&&s.push(e),this.mml=_g(s,this.semantic)}else this.mml=_g([t].concat(this.inner,[e]),this.semantic);return Xf(this.mml,this.semantic),this.mml}}class db extends Qg{static test(t){return t.type===Qp.PUNCTUATED&&(t.role===tm.TEXT||t.contentNodes.every(t=>t.role===tm.DUMMY))}constructor(t){super(t),this.mml=t.mathmlTree}getMathml(){const t=[],e=Yg(this.semantic,t);return this.mml=_g(t,this.semantic),Xf(this.mml,this.semantic),this.mml.removeAttribute(Wf.CONTENT),zg(this.mml,e),this.mml}}function ub(t,e){const s=t.cloneNode(!0);return function(t,e,s){return mp.getInstance().generate(()=>["Original MathML",$g(t)]),Cg.clear(),kg(e.root),s.structure&&t.setAttribute(Wf.STRUCTURE,Jf.fromStructure(t,e,s).toString()),mp.getInstance().generate(()=>["Semantic Tree\n",$g(e),"Semantically enriched MathML\n",$g(t)]),t}(s,vg(s,e),e)}Tg.push({test:ab.test,constr:t=>new ab(t)},{test:nb.test,constr:t=>new nb(t)},{test:tb.test,constr:t=>new tb(t)},{test:eb.test,constr:t=>new eb(t)},{test:rb.test,constr:t=>new rb(t)},{test:ib.test,constr:t=>new ib(t)},{test:lb.test,constr:t=>new lb(t)},{test:Zg.test,constr:t=>new Zg(t)},{test:cb.test,constr:t=>new cb(t)},{test:ob.test,constr:t=>new ob(t)},{test:hb.test,constr:t=>new hb(t)},{test:db.test,constr:t=>new db(t)});const pb=new op({AbsoluteValue:["Auto","AbsEnd","Cardinality","Determinant"],Bar:["Auto","Conjugate"],Caps:["Auto","SayCaps"],CombinationPermutation:["Auto","ChoosePermute"],Currency:["Auto","Position","Prefix"],Ellipses:["Auto","AndSoOn"],Enclosed:["Auto","EndEnclose"],Exponent:["Auto","AfterPower","Ordinal","OrdinalPower","Exponent"],Fraction:["Auto","EndFrac","FracOver","General","GeneralEndFrac","Ordinal","Over","OverEndFrac","Per"],Functions:["Auto","None","Reciprocal"],Inference:["Auto","Long"],ImpliedTimes:["Auto","MoreImpliedTimes","None"],Log:["Auto","LnAsNaturalLog"],Matrix:["Auto","Combinatoric","EndMatrix","EndVector","SilentColNum","SpeakColNum","Vector"],MultiLineLabel:["Auto","Case","Constraint","Equation","Line","None","Row","Step"],MultiLineOverview:["Auto","None"],MultiLinePausesBetweenColumns:["Auto","Long","Short"],MultsymbolDot:["Auto","Dot"],MultsymbolX:["Auto","By","Cross"],Paren:["Auto","CoordPoint","Interval","Silent","Speak","SpeakNestingLevel"],Prime:["Auto","Angle","Length"],Roots:["Auto","PosNegSqRoot","PosNegSqRootEnd","RootEnd"],SetMemberSymbol:["Auto","Belongs","Element","Member","In"],Sets:["Auto","SilentBracket","woAll"],TriangleSymbol:["Auto","Delta"],Trig:["Auto","ArcTrig","TrigInverse","Reciprocal"],VerticalLine:["Auto","Divides","Given","SuchThat"]}),mb="Auto";function fb(t){const e=t.split(":"),s={},i=pb.getProperties(),r=Object.keys(i);for(let t,n=0;t=e[n];n++){const e=t.split("_");if(-1===r.indexOf(e[0]))continue;const n=e[1];n&&n!==mb&&-1!==i[e[0]].indexOf(n)&&(s[e[0]]=e[1])}return s}function gb(t){const e=Object.keys(t),s=[];for(let i=0;iyp.getInstance().setup(t),xb=()=>yp.getInstance().json(),yb=t=>function(t,e){const s=Ap(t);try{return ub(s,e)}catch(t){return console.error(t),s}}(t,yp.getInstance().options),Nb=Ap,vb=function(t,e,s){if("default"===t)return e+"_"+s;const i=fb(t);return i[e]=s,gb(i)},Tb=fb,wb=gb;var Cb=function(t,e,s,i){return new(s||(s=Promise))(function(r,n){function o(t){try{l(i.next(t))}catch(t){n(t)}}function a(t){try{l(i.throw(t))}catch(t){n(t)}}function l(t){var e;t.done?r(t.value):(e=t.value,e instanceof s?e:new s(function(t){t(e)})).then(o,a)}l((i=i.apply(t,e||[])).next())})};let kb={},_b=null;function Lb(t){var e,s;const i=null==t?void 0:t.match(/^clearspeak-(.*)/);return _b=null!==(s=null!==(e=i&&i[1])&&void 0!==e?e:_b)&&void 0!==s?s:"default",_b}const Ab=new Map;const Rb=new Map;let Sb=0;function Mb(t,e){const s=Ab.get(e);!function(t,e){const s=t.pool.lookup("speechRules"),i=Lb(t.settings.speechRules);kb=Tb(i);for(const i of e)t.factory.get("variable")(t.factory,{name:"csprf_"+i,setter:t=>{kb[i]=t,s.setValue("clearspeak-"+wb(kb))},getter:()=>kb[i]||"Auto"},t.pool)}(t,Object.keys(s));const i=[];for(const t of Object.getOwnPropertyNames(s))i.push({title:t,values:s[t].map(e=>e.replace(RegExp("^"+t+"_"),"")),variable:"csprf_"+t});const r=new sp("Clearspeak Preferences","",i,"alphabetical","square",t);return{type:"command",id:"ClearspeakPreferences",content:"Select Preferences",action:()=>r.post()}}function Ib(t,e,s){return Cb(this,void 0,void 0,function*(){var i,r;const n=i=>{s(t.factory.get("subMenu")(t.factory,{items:i,id:"Clearspeak"},e))};if(!t.settings.speech||!t.settings.enrich)return void n([]);const o=t.pool.lookup("locale").getValue();if(yield function(t,e){return Cb(this,void 0,void 0,function*(){Ab.has(e)||(yield t.mathItem.generatorPool.getLocalePreferences(Ab))})}(t,o),!Ab.get(o))return void n([]);const a=Mb(t,o);let l=[];if(t.settings.speech){const e=t.mathItem,s=null===(i=null==e?void 0:e.explorers)||void 0===i?void 0:i.speech,n=Lb(t.settings.speechRules);l=l.concat(function(t){return[{type:"radio",content:"No Preferences",id:"clearspeak-default",variable:"speechRules"},{type:"radio",content:"Current Preferences",id:"clearspeak-"+t,variable:"speechRules"},{type:"rule"}]}(n));const a=null==s?void 0:s.refocus,c=null!==(r=null==a?void 0:a.getAttribute("data-semantic-id"))&&void 0!==r?r:null,h=Sb++;yield e.generatorPool.getRelevantPreferences(e,c,Rb,h);const d=Rb.get(h);if(Rb.delete(h),d){const t=function(t,e,s){const i=Ab.get(s);return[{type:"label",content:"Preferences for "+e},{type:"rule"}].concat(i[e].map(function(e){const[s,i]=e.split("_");return{type:"radioCompare",content:i,id:"clearspeak-"+vb(t,s,i),variable:"speechRules",comparator:(t,e)=>{if(t===e)return!0;if("Auto"!==i)return!1;const[r,n]=t.split("-"),[o]=e.split("-");return r===o&&!Tb(n)[s]}}}))}(n,d,o);l=l.concat(t)}}l.splice(2,0,a),n(l)})}ep.DynamicSubmenus.set("Clearspeak",[Ib,"speech"]);let Ob=null;function Db(t,e,s){if(Ob)return void s(Ob);const i=[];for(const t of bb.keys())"nemeth"!==t&&"euro"!==t&&i.push({type:"radio",id:t,content:bb.get(t)||t,variable:"locale"});i.sort((t,e)=>t.content.localeCompare(e.content,"en")),Ob=t.factory.get("subMenu")(t.factory,{items:i,id:"Language"},e),s(Ob)}ep.DynamicSubmenus.set("A11yLanguage",[Db,"speech"]);const Pb="MacOS"===ui.os;function Bb(t){const e=ui.document,s=e.createElement("textarea");s.value=t,s.setAttribute("readonly",""),s.style.cssText="height: 1px; width: 1px; padding: 1px; position: absolute; left: -10px",e.body.appendChild(s),s.select();try{e.execCommand("copy")}catch(t){alert(`Can't copy to clipboard: ${t.message}`)}e.body.removeChild(s)}function Fb(t,e,s){return(i,r,n)=>{!function(t,e,s){if(!t)return;for(const i of t.childNodes)if(i.isKind("annotation")){const t=Ub(i,e);if(t){const e=i.childNodes.reduce((t,e)=>t+e.toString(),"");s.push([t,e])}}}(function(t){var e;let s=null===(e=t.mathItem)||void 0===e?void 0:e.root;for(;s&&!s.isKind("semantics");){if(s.isToken||1!==s.childNodes.length)return null;s=s.childNodes[0]}return s}(i),e,s),n(qb(i,r,s,t))}}function jb(t){return(e,s,i)=>{const r=t.slice();t.length=0,i(qb(e,s,r,()=>Bb(Hb.trim())))}}function Ub(t,e){const s=t.attributes.get("encoding");for(const t of Object.keys(e))if(e[t].includes(s))return t;return null}let Hb="";function qb(t,e,s,i){return t.factory.get("subMenu")(t.factory,{items:s.map(([t,e])=>({type:"command",id:t,content:t,action:()=>{Hb=e,i()}})),id:"annotations"},e)}class Wb extends ho{static post(t){return super.post(t)}html(t){var e;null!==(e=t.extraNodes)&&void 0!==e||(t.extraNodes=[]);const s=t.adaptor.node("input",{type:"button",value:"Copy to Clipboard","data-drag":"none"});return s.addEventListener("click",this.copyToClipboard.bind(this)),t.extraNodes.push(s),t.code&&(t.message="
"+this.formatSource(t.message)+"
"),super.html(t)}formatSource(t){return t.trim().replace(/&/g,"&").replace(//g,">")}}class zb extends Du{static fromJson(t,{content:e,variable:s,id:i,comparator:r},n){return new this(n,e,s,i,r)}constructor(t,e,s,i,r){super(t,e,s,i),this.comparator=r,this.role="menuitemradiocompare"}updateAria(){this.html.setAttribute("aria-checked",this.comparator(this.variable.getValue(),this.id)?"true":"false")}updateSpan(){this.span.style.display=this.comparator(this.variable.getValue(),this.id)?"":"none"}}class Vb extends $n{constructor(){super(...arguments),this.options={filterSRE:!0,filterTex:!0,texHints:!0,semantics:!1},this.mathItem=null}visitTree(t,e=null,s={}){return this.mathItem=e,Pi(this.options,s),this.visitNode(t,"")}visitTeXAtomNode(t,e){return this.options.texHints?super.visitDefault(t,e):t.childNodes[0]&&1===t.childNodes[0].childNodes.length?this.visitNode(t.childNodes[0],e):`${e}\n`+this.childNodeMml(t,e+" ","\n")+`${e}`}visitMathNode(t,e){if(!this.options.semantics||"TeX"!==this.mathItem.inputJax.name)return super.visitDefault(t,e);const s=t.childNodes.length&&t.childNodes[0].childNodes.length>1;return`${e}\n${e} \n`+(s?e+" \n":"")+this.childNodeMml(t,e+(s?" ":" "),"\n")+(s?e+" \n":"")+`${e} `+this.mathItem.math+`\n${e} \n${e}`}getAttributeList(t){const e=super.getAttributeList(t);if(this.options.filterTex&&(delete e["data-latex"],delete e["data-latex-item"]),this.options.filterSRE){const t=Object.keys(e).filter(t=>t.match(/^(?:data-semantic-.*?|data-speech-node|role|aria-(?:level|posinset|setsize|owns))$/));for(const s of t)delete e[s]}return e}}var Xb=function(t,e,s,i){return new(s||(s=Promise))(function(r,n){function o(t){try{l(i.next(t))}catch(t){n(t)}}function a(t){try{l(i.throw(t))}catch(t){n(t)}}function l(t){var e;t.done?r(t.value):(e=t.value,e instanceof s?e:new s(function(t){t(e)})).then(o,a)}l((i=i.apply(t,e||[])).next())})};const Gb=hi;class Jb{get isLoading(){return Jb.loading>0}get loadingPromise(){return this.isLoading?(Jb._loadingPromise||(Jb._loadingPromise=new Promise((t,e)=>{Jb._loadingOK=t,Jb._loadingFailed=e})),Jb._loadingPromise):Promise.resolve()}about(){const t=[];if(t.push("Input Jax: "+this.document.inputJax.map(t=>t.name).join(", ")),t.push("Output Jax: "+this.document.outputJax.name),t.push("Document Type: "+this.document.kind),Gb&&Gb.loader){t.push("
Modules Loaded:");const e=Gb._.components.package.Package,s=Gb.loader.versions;for(const i of Array.from(e.packages.keys()).sort(this.sortPackages)){const r=s.get(e.resolvePath(i));r&&t.push(`    ${i} (${r})`)}}ho.post({title:"MathJax v"+Zn.version+"",message:t.join("
"),adaptor:this.document.adaptor,styles:{".mjx-dialog":{"max-height":"calc(min(20em, 85%))"},"mjx-dialog > div":{"white-space":"nowrap"},"dialog.mjx-dialog-help > mjx-dialog > div":{"white-space":"normal"},"mjx-v":{"font-size":"80%"}},extraNodes:[this.document.adaptor.node("a",{href:"https://www.mathjax.org","data-drag":"false"},[this.document.adaptor.text("https://www.mathjax.org")])]})}sortPackages(t,e){const[s,i]=t.includes("/")?t.split(/\//):["",t],[r,n]=e.includes("/")?e.split(/\//):["",e];return s===r?iMathJax is a JavaScript library that allows page"," authors to include mathematics within their web pages."," As a reader, you don't need to do anything to make that happen.

","

Browsers: MathJax works with all modern browsers including"," Edge, Firefox, Chrome, Safari, Opera, and most mobile browsers.

","

Math Menu: MathJax adds a contextual menu to equations."," Right-click or CTRL-click on any mathematics to access the menu.

",'
',"

Show Math As: These options allow you to view the formula's"," source markup (as MathML or in its original format).

","

Copy to Clipboard: These options copy the formula's source markup,"," as MathML or in its original format, to the clipboard"," (in browsers that support that).

","

Math Settings: These give you control over features of MathJax,"," such the size of the mathematics, the mechanism used to display equations,"," how to handle equations that are too wide, and the language to use for"," MathJax's menus and error messages (not yet implemented in v4).","

","

Accessibility: MathJax can work with screen"," readers to make mathematics accessible to the visually impaired."," Turn on speech or braille generation to enable creation of speech strings"," and the ability to investigate expressions interactively. You can control"," the style of the explorer in its menu.

","
","

Math Zoom: If you are having difficulty reading an"," equation, MathJax can enlarge it to help you see it better, or"," you can scale all the math on the page to make it larger."," Turn these features on in the Math Settings menu.

","

Preferences: MathJax uses your browser's localStorage database"," to save the preferences set via this menu locally in your browser. These"," are not used to track you, and are not transferred or used remotely by"," MathJax in any way.

"].join("\n"),adaptor:this.document.adaptor,extraNodes:[this.document.adaptor.node("a",{href:"https://www.mathjax.org","data-drag":"none"},[this.document.adaptor.text("https://www.mathjax.org")])]})}mathMLCode(){Wb.post({title:"MathJax MathML Expression",message:this.menu.mathItem?this.toMML(this.menu.mathItem):"",adaptor:this.document.adaptor,code:!0})}originalText(){var t,e;Wb.post({title:"MathJax Original Source",message:null!==(e=null===(t=this.menu.mathItem)||void 0===t?void 0:t.math)&&void 0!==e?e:"",adaptor:this.document.adaptor,code:!0})}annotationBox(){Wb.post({title:"MathJax Annotation Text",message:Hb,adaptor:this.document.adaptor,code:!0})}svgImage(){return Xb(this,void 0,void 0,function*(){Wb.post({title:"MathJax SVG Image",message:yield this.toSVG(this.menu.mathItem),adaptor:this.document.adaptor,code:!0})})}speechText(){var t,e,s;Wb.post({title:"MathJax Speech Text",message:null!==(s=null===(e=null===(t=this.menu.mathItem)||void 0===t?void 0:t.outputData)||void 0===e?void 0:e.speech)&&void 0!==s?s:"",adaptor:this.document.adaptor,code:!0})}brailleText(){var t,e,s;Wb.post({title:"MathJax Braille Text",message:null!==(s=null===(e=null===(t=this.menu.mathItem)||void 0===t?void 0:t.outputData)||void 0===e?void 0:e.braille)&&void 0!==s?s:"",adaptor:this.document.adaptor,code:!0})}errorMessage(){Wb.post({title:"MathJax Error Message",message:this.menu.mathItem?this.menu.errorMsg:"",adaptor:this.document.adaptor,code:!0})}zoomBox(){let t="";if(this.menu.mathItem){const e=this.menu.mathItem.typesetRoot,s=this.document.adaptor.fontSize(e),i=e.cloneNode(!0);i.style.margin="0";t=`
${i.outerHTML}
`}ho.post({title:"MathJax Zoomed Expression",message:t,adaptor:this.document.adaptor,styles:{"mjx-dialog > div":{padding:"1.8em"}}})}constructor(t,e={}){this.settings=null,this.defaultSettings=null,this.menu=null,this.current=null,this.MmlVisitor=new Vb,this.jax={CHTML:null,SVG:null},this.rerenderStart=or.LAST,this.requiredExtensions=[],this.document=t,this.options=Pi(Di({},this.constructor.OPTIONS),e),this.initSettings(),this.mergeUserSettings(),this.initMenu(),this.applySettings()}initSettings(){var t;this.settings=this.options.settings,this.jax=this.options.jax;const e=this.document.outputJax;this.jax[e.name]=e,this.settings.renderer=e.name,this.settings.scale=e.options.scale,e.options.displayOverflow&&(this.settings.overflow=e.options.displayOverflow.substring(0,1).toUpperCase()+e.options.displayOverflow.substring(1).toLowerCase()),this.settings.breakInline=null===(t=e.options.linebreaks)||void 0===t?void 0:t.inline,this.defaultSettings=Object.assign({},this.document.options.a11y,this.settings),this.setA11y({roleDescription:this.settings.roleDescription})}initMenu(){const t=new Ku([["contextMenu",ep.fromJson.bind(ep)],["radioCompare",zb.fromJson.bind(zb)]]);this.menu=t.parse({type:"contextMenu",id:"MathJax_Menu",pool:[this.variable("showSRE"),this.variable("showTex"),this.variable("texHints"),this.variable("semantics"),this.variable("zoom"),this.variable("zscale"),this.variable("renderer",t=>this.setRenderer(t)),this.variable("overflow",t=>this.setOverflow(t)),this.variable("breakInline",t=>this.setInlineBreaks(t)),this.variable("alt"),this.variable("cmd"),this.variable("ctrl"),this.variable("shift"),this.variable("scale",t=>this.setScale(t)),this.a11yVar("speech",t=>this.setSpeech(t)),this.a11yVar("braille",t=>this.setBraille(t)),this.variable("brailleCode",t=>this.setBrailleCode(t)),this.a11yVar("brailleSpeech",t=>this.setBrailleSpeech(t)),this.a11yVar("brailleCombine",t=>this.setBrailleCombine(t)),this.a11yVar("highlight",t=>this.setHighlight(t)),this.a11yVar("backgroundColor",t=>this.setColor("bg",t)),this.a11yVar("backgroundOpacity",t=>this.setColor("bg",null,t)),this.a11yVar("foregroundColor",t=>this.setColor("fg",t)),this.a11yVar("foregroundOpacity",t=>this.setColor("fg",null,t)),this.a11yVar("subtitles"),this.a11yVar("viewBraille"),this.a11yVar("voicing"),this.a11yVar("roleDescription",()=>this.setRoleDescription()),this.a11yVar("help"),this.a11yVar("locale",t=>this.setLocale(t)),this.variable("speechRules",t=>{const[e,s]=t.split("-");this.document.options.sre.domain=e,this.document.options.sre.style=s,this.rerender(or.COMPILED)}),this.a11yVar("magnification"),this.a11yVar("magnify"),this.a11yVar("treeColoring"),this.a11yVar("infoType"),this.a11yVar("infoRole"),this.a11yVar("infoPrefix"),this.variable("autocollapse"),this.variable("collapsible",t=>this.setCollapsible(t)),this.variable("enrich",t=>this.setEnrichment(t)),this.a11yVar("inTabOrder",t=>this.setTabOrder(t)),this.a11yVar("tabSelects"),this.variable("assistiveMml",t=>this.setAssistiveMml(t))],items:[this.submenu("Show","Show Math As",[this.command("MathMLcode","MathML Code",()=>this.mathMLCode()),this.command("Original","Original Form",()=>this.originalText()),this.rule(),this.command("Speech","Speech Text",()=>this.speechText(),{disabled:!0}),this.command("Braille","Braille Code",()=>this.brailleText(),{disabled:!0}),this.command("SVG","SVG Image",()=>this.svgImage(),{disabled:!0}),this.submenu("ShowAnnotation","Annotation"),this.rule(),this.command("Error","Error Message",()=>this.errorMessage(),{disabled:!0})]),this.submenu("Copy","Copy to Clipboard",[this.command("MathMLcode","MathML Code",()=>this.copyMathML()),this.command("Original","Original Form",()=>this.copyOriginal()),this.rule(),this.command("Speech","Speech Text",()=>this.copySpeechText(),{disabled:!0}),this.command("Braille","Braille Code",()=>this.copyBrailleText(),{disabled:!0}),this.command("SVG","SVG Image",()=>this.copySvgImage(),{disabled:!0}),this.submenu("CopyAnnotation","Annotation"),this.rule(),this.command("Error","Error Message",()=>this.copyErrorMessage(),{disabled:!0})]),this.rule(),this.submenu("Settings","Math Settings",[this.submenu("Renderer","Math Renderer",this.radioGroup("renderer",[["CHTML"],["SVG"]])),this.submenu("Overflow","Wide Expressions",[this.radioGroup("overflow",[["Overflow"],["Scroll"],["Linebreak"],["Scale"],["Truncate"],["Elide"]]),this.rule(),this.checkbox("BreakInline","Allow In-line Breaks","breakInline")]),this.rule(),this.submenu("MathmlIncludes","MathML/SVG has",[this.checkbox("showSRE","Semantic attributes","showSRE"),this.checkbox("showTex","LaTeX attributes","showTex"),this.checkbox("texHints","TeX hints","texHints"),this.checkbox("semantics","Original as annotation","semantics")]),this.submenu("Language","Language"),this.rule(),this.submenu("ZoomTrigger","Zoom Trigger",[this.command("ZoomNow","Zoom Once Now",()=>this.zoom(null,"")),this.rule(),this.radioGroup("zoom",[["Click"],["DoubleClick","Double-Click"],["NoZoom","No Zoom"]]),this.rule(),this.label("TriggerRequires","Trigger Requires:"),this.checkbox(Pb?"Option":"Alt",Pb?"Option":"Alt","alt"),this.checkbox("Command","Command","cmd",{hidden:!Pb}),this.checkbox("Control","Control","ctrl",{hidden:Pb}),this.checkbox("Shift","Shift","shift")]),this.submenu("ZoomFactor","Zoom Factor",this.radioGroup("zscale",[["150%"],["175%"],["200%"],["250%"],["300%"],["400%"]])),this.rule(),this.command("Scale","Scale All Math...",()=>this.scaleAllMath()),this.rule(),this.command("Reset","Reset to defaults",()=>this.resetDefaults())]),this.rule(),this.label("Accessibility","\xa0\xa0 Accessibility:"),this.submenu("Speech","\xa0 \xa0 Speech",[this.checkbox("Generate","Generate","speech"),this.checkbox("Subtitles","Show Subtitles","subtitles"),this.checkbox("Auto Voicing","Auto Voicing","voicing"),this.rule(),this.label("Rules","Rules:"),this.submenu("Mathspeak","Mathspeak",this.radioGroup("speechRules",[["mathspeak-default","Verbose"],["mathspeak-brief","Brief"],["mathspeak-sbrief","Superbrief"]])),this.submenu("Clearspeak","Clearspeak",this.radioGroup("speechRules",[["clearspeak-default","Auto"]])),this.rule(),this.submenu("A11yLanguage","Language")]),this.submenu("Braille","\xa0 \xa0 Braille",[this.checkbox("Generate","Generate","braille"),this.checkbox("Subtitles","Show Subtitles","viewBraille"),this.checkbox("BrailleSpeech","Replace Speech","brailleSpeech",{hidden:!0}),this.checkbox("BrailleCombine","Combine with Speech","brailleCombine"),this.rule(),this.label("Code","Code Format:"),this.radioGroup("brailleCode",[["nemeth","Nemeth"],["ueb","UEB"],["euro","Euro"]])]),this.submenu("Explorer","\xa0 \xa0 Explorer",[this.submenu("Highlight","Highlight",[this.submenu("Background","Background",this.radioGroup("backgroundColor",[["Blue"],["Red"],["Green"],["Yellow"],["Cyan"],["Magenta"],["White"],["Black"]])),{type:"slider",variable:"backgroundOpacity",content:" "},this.submenu("Foreground","Foreground",this.radioGroup("foregroundColor",[["Black"],["White"],["Magenta"],["Cyan"],["Yellow"],["Green"],["Red"],["Blue"]])),{type:"slider",variable:"foregroundOpacity",content:" "},this.rule(),this.radioGroup("highlight",[["None"],["Hover"],["Flame"]]),this.rule(),this.checkbox("TreeColoring","Tree Coloring","treeColoring")]),this.submenu("Magnification","Magnification",[this.radioGroup("magnification",[["None"],["Keyboard"],["Mouse"]]),this.rule(),this.radioGroup("magnify",[["200%"],["300%"],["400%"],["500%"]])]),this.submenu("Semantic Info","Semantic Info",[this.checkbox("Type","Type","infoType"),this.checkbox("Role","Role","infoRole"),this.checkbox("Prefix","Prefix","infoPrefix")]),this.rule(),this.submenu("Role Description","Describe math as",[this.radioGroup("roleDescription",[["MathJax expression"],["MathJax"],["math"],["clickable math"],["explorable math"],["none"]])]),this.checkbox("Math Help","Help message on focus","help")]),this.submenu("Options","\xa0 \xa0 Options",[this.checkbox("Enrich","Semantic Enrichment","enrich"),this.checkbox("Collapsible","Collapsible Math","collapsible"),this.checkbox("AutoCollapse","Auto Collapse","autocollapse",{disabled:!0}),this.rule(),this.checkbox("InTabOrder","Include in Tab Order","inTabOrder"),this.submenu("TabSelects","Tabbing Focuses on",[this.radioGroup("tabSelects",[["all","Whole Expression"],["last","Last Explored Node"]])]),this.rule(),this.checkbox("AssistiveMml","Include Hidden MathML","assistiveMml")]),this.rule(),this.command("About","About MathJax",()=>this.about()),this.command("Help","MathJax Help",()=>this.help())]});const e=this.menu;e.settings=this.settings,e.findID("Settings","Overflow","Elide").disable(),e.findID("Braille","ueb").hide(),e.setJax(this.jax),this.checkLoadableItems();const s=[];ep.DynamicSubmenus.set("ShowAnnotation",[Fb(()=>this.annotationBox(),this.options.annotationTypes,s),""]),ep.DynamicSubmenus.set("CopyAnnotation",[jb(s),""]),function(t){tp(Object.assign(Object.assign({},Qu),Zu),t)}(this.document.document)}checkLoadableItems(){var t,e,s,i,r,n;if(Gb&&Gb._&&Gb.loader&&Gb.startup){const o=this.settings,a=this.document.options;(o.enrich||o.speech&&a.enableSpeech||o.braille&&a.enableBraille)&&!(null===(e=null===(t=Gb._)||void 0===t?void 0:t.a11y)||void 0===e?void 0:e.explorer)&&this.loadA11y("explorer"),o.collapsible&&!(null===(i=null===(s=Gb._)||void 0===s?void 0:s.a11y)||void 0===i?void 0:i.complexity)&&this.loadA11y("complexity"),o.assistiveMml&&!(null===(n=null===(r=Gb._)||void 0===r?void 0:r.a11y)||void 0===n?void 0:n["assistive-mml"])&&this.loadA11y("assistive-mml")}else{const t=this.menu;for(const e of Object.keys(this.jax))this.jax[e]||t.findID("Settings","Renderer",e).disable();t.findID("Speech").disable(),t.findID("Braille").disable(),t.findID("Explorer").disable(),t.findID("Options","AutoCollapse").disable(),t.findID("Options","Collapsible").disable(),t.findID("Options","Enrich").disable(),t.findID("Options","AssistiveMml").disable()}}enableAccessibilityItems(t,e){const s=this.menu.findID(t).submenu;for(const t of s.items.slice(1))t instanceof Pu||(!e||t instanceof Lu&&!t.submenu.items.length?t.disable():t.enable())}mergeUserSettings(){try{const t=localStorage.getItem(Jb.MENU_STORAGE);if(!t)return;Object.assign(this.settings,JSON.parse(t)),this.setA11y(this.settings)}catch(t){console.log("MathJax localStorage error: "+t.message)}}saveUserSettings(){const t={};for(const e of Object.keys(this.settings))this.settings[e]!==this.defaultSettings[e]&&(t[e]=this.settings[e]);try{Object.keys(t).length?localStorage.setItem(Jb.MENU_STORAGE,JSON.stringify(t)):localStorage.removeItem(Jb.MENU_STORAGE)}catch(t){console.log("MathJax localStorage error: "+t.message)}}setA11y(t){var e,s;(null===(s=null===(e=Gb._)||void 0===e?void 0:e.a11y)||void 0===s?void 0:s.explorer)&&Gb._.a11y.explorer_ts.setA11yOptions(this.document,t)}getA11y(t){var e,s;if(null===(s=null===(e=Gb._)||void 0===e?void 0:e.a11y)||void 0===s?void 0:s.explorer)return void 0!==this.document.options.a11y[t]?this.document.options.a11y[t]:this.document.options.sre[t]}applySettings(){this.setTabOrder(this.settings.inTabOrder);this.document.options.enableAssistiveMml=this.settings.assistiveMml,this.enableAccessibilityItems("Speech",this.settings.speech),this.enableAccessibilityItems("Braille",this.settings.braille),this.setAccessibilityMenus();const t=this.settings.renderer.replace(/[^a-zA-Z0-9]/g,"")||"CHTML";(Jb._loadingPromise||Promise.resolve()).then(()=>{const e=this.settings;if(this.applyRendererOptions(this.document.outputJax),!e.speechRules){const t=this.document.options.sre;e.speechRules=`${t.domain||"clearspeak"}-${t.style||"default"}`}t!==this.defaultSettings.renderer&&this.document.whenReady(()=>this.setRenderer(t,!1))})}setOverflow(t){this.document.outputJax.options.displayOverflow=t.toLowerCase(),Jb.loading||this.document.rerenderPromise()}setInlineBreaks(t){this.document.outputJax.options.linebreaks.inline=t,Jb.loading||this.document.rerenderPromise()}setScale(t){this.document.outputJax.options.scale=parseFloat(t),Jb.loading||this.document.rerenderPromise()}setRenderer(t,e=!0){if(Object.hasOwn(this.jax,t)&&this.jax[t])return this.applyRendererOptions(this.jax[t]),this.setOutputJax(t,e);const s=t.toLowerCase();return new Promise((i,r)=>{this.loadComponent("output/"+s,()=>{const n=Gb.startup;if(!(s in n.constructors))return r(new Error(`Component ${s} not loaded`));n.useOutput(s,!0),n.output=this.applyRendererOptions(n.getOutputJax()),n.output.setAdaptor(this.document.adaptor),n.output.initialize(),this.jax[t]=n.output,this.setOutputJax(t,e).then(()=>i()).catch(t=>r(t))})})}applyRendererOptions(t){const e=this.settings,s=t.options;return s.scale=parseFloat(e.scale),s.displayOverflow=e.overflow.toLowerCase(),s.linebreaks&&(s.linebreaks.inline=e.breakInline),t}setOutputJax(t,e=!0){this.jax[t].setAdaptor(this.document.adaptor),this.document.outputJax=this.jax[t];const s=this.loadRequiredExtensions();return e?s.then(()=>Zn.handleRetriesFor(()=>this.rerender())):s.then(()=>{})}loadRequiredExtensions(){const t=this.document.outputJax.name.toLowerCase(),e=[];for(const s of this.requiredExtensions)e.push(Gb.loader.load(`[${s}]/${t}`));return this.requiredExtensions=[],Promise.all(e)}addRequiredExtensions(t){if(t){const e=new Set([...this.requiredExtensions,...t]);this.requiredExtensions=[...e]}}setTabOrder(t){const e=this.menu.findID("Options","TabSelects");t?e.enable():e.disable(),this.menu.store.inTaborder(t)}setAssistiveMml(t){var e,s;this.document.options.enableAssistiveMml=t,t&&this.noRerender(()=>{this.settings.speech&&this.menu.pool.lookup("speech").setValue(!1),this.settings.braille&&this.menu.pool.lookup("braille").setValue(!1)}),!t||(null===(s=null===(e=Gb._)||void 0===e?void 0:e.a11y)||void 0===s?void 0:s["assistive-mml"])?this.rerender():this.loadA11y("assistive-mml")}setAccessibilityMenus(){const t=this.settings.enrich,e=t?"enable":"disable";["Speech","Braille","Explorer"].forEach(t=>this.menu.findID(t)[e]());const s=this.document.options;s.enableSpeech=s.enableBraille=s.enableExplorer=t,t||(this.settings.collapsible=!1,this.document.options.enableCollapsible=!1)}setSpeech(t){var e,s;this.enableAccessibilityItems("Speech",t),this.document.options.enableSpeech=t,t&&(this.settings.assistiveMml&&this.noRerender(()=>this.menu.pool.lookup("assistiveMml").setValue(!1)),this.settings.brailleSpeech&&this.noRerender(()=>this.menu.pool.lookup("brailleSpeech").setValue(!1))),!t||(null===(s=null===(e=Gb._)||void 0===e?void 0:e.a11y)||void 0===s?void 0:s.explorer)?this.rerender(or.COMPILED):this.loadA11y("explorer")}setBraille(t){var e,s;this.enableAccessibilityItems("Braille",t),this.document.options.enableBraille=t,t&&this.settings.assistiveMml&&this.noRerender(()=>this.menu.pool.lookup("assistiveMml").setValue(!1)),!t||(null===(s=null===(e=Gb._)||void 0===e?void 0:e.a11y)||void 0===s?void 0:s.explorer)?this.rerender(or.COMPILED):this.loadA11y("explorer")}setBrailleCode(t){this.document.options.sre.braille=t,this.rerender(or.COMPILED)}setBrailleSpeech(t){t&&this.settings.speech?this.noRerender(()=>this.menu.pool.lookup("speech").setValue(!1)):this.enableAccessibilityItems("Speech",!0),this.settings.brailleCombine=this.document.options.a11y.brailleCombine=!1,this.rerender(or.COMPILED)}setBrailleCombine(t){this.settings.brailleSpeech&&this.menu.pool.lookup("brailleSpeech").setValue(!1),this.settings.brailleSpeech=this.document.options.a11y.brailleSpeech=!1,this.rerender(or.COMPILED)}setLocale(t){this.document.options.sre.locale=t,this.rerender(or.COMPILED)}setRoleDescription(){this.rerender(or.COMPILED)}setEnrichment(t){var e,s;this.document.options.enableEnrichment=t,this.setAccessibilityMenus(),!t||(null===(s=null===(e=Gb._)||void 0===e?void 0:e.a11y)||void 0===s?void 0:s.explorer)?this.rerender(or.COMPILED):this.loadA11y("explorer")}setCollapsible(t){var e,s;this.document.options.enableComplexity=t,t&&!this.settings.enrich&&(this.settings.enrich=this.document.options.enableEnrichment=!0,this.setAccessibilityMenus()),t||this.menu.pool.lookup("highlight").setValue("None"),!t||(null===(s=null===(e=Gb._)||void 0===e?void 0:e.a11y)||void 0===s?void 0:s.complexity)?this.rerender(or.COMPILED):this.loadA11y("complexity")}setHighlight(t){var e,s;if("None"!==t){if(!this.settings.collapsible){const t=this.menu.pool.lookup("collapsible");t.setValue(!0),null===(s=null===(e=t.items[0])||void 0===e?void 0:e.executeCallbacks_)||void 0===s||s.call(e)}Jb.loadingPromises.has("a11y/complexity")||this.rerender(or.COMPILED)}}setColor(t,e,s){const i=this.document.options.a11y;e||(e=i["fg"===t?"foregroundColor":"backgroundColor"]),s||(s=i["fg"===t?"foregroundOpacity":"backgroundOpacity"]),Gb._.a11y.explorer.Region.LiveRegion.setColor(t,1,e.toLowerCase(),parseInt(s)/100)}scaleAllMath(){const t=(100*parseFloat(this.settings.scale)).toFixed(1).replace(/.0$/,""),e=prompt("Scale all mathematics (compared to surrounding text) by",t+"%");if(this.current){const t=this.menu.mathItem.explorers.speech;t.refocus=this.current,t.focus()}if(e)if(e.match(/^\s*\d+(\.\d*)?\s*%?\s*$/)){const t=parseFloat(e)/100;t?this.menu.pool.lookup("scale").setValue(String(t)):alert("The scale should not be zero")}else alert("The scale should be a percentage (e.g., 120%)")}resetDefaults(){this.noRerender(()=>{const t=this.menu.pool,e=this.defaultSettings;for(const s of Object.keys(e)){const i=t.lookup(s);if(i){if(i.getValue()!==e[s]){i.setValue(e[s]);const t=i.items[0];t&&t.executeCallbacks_()}}else Object.hasOwn(this.settings,s)&&(this.settings[s]=e[s])}}),this.rerender(or.COMPILED)}checkComponent(t){const e=Jb.loadingPromises.get(t);e&&Zn.retryAfter(e)}loadComponent(t,e){if(Jb.loadingPromises.has(t))return;const s=Gb.loader;if(!s)return;Jb.loading++;const i=s.load(t).then(()=>{Jb.loading--,Jb.loadingPromises.delete(t),0===Jb.loading&&Jb._loadingPromise&&(Jb._loadingPromise=null,Jb._loadingOK()),e()}).catch(t=>{Jb._loadingPromise?(Jb._loadingPromise=null,Jb._loadingFailed(t)):console.log(t)});Jb.loadingPromises.set(t,i)}loadA11y(t){const e=!or.ENRICHED;this.loadComponent("a11y/"+t,()=>{var s,i;const r=Gb.startup;Zn.handlers.unregister(r.handler),r.handler=r.getHandler(),Zn.handlers.register(r.handler);const n=this.document;this.document=r.document=r.getDocument(),this.document.processed=n.processed,this.document.menu=this,n.webworker&&(this.document.webworker=n.webworker),this.setA11y(this.settings),this.defaultSettings=Object.assign({},this.document.options.a11y,(null===(i=null===(s=Gb.config)||void 0===s?void 0:s.options)||void 0===i?void 0:i.a11y)||{},this.defaultSettings),this.document.outputJax.reset(),this.transferMathList(n),this.document.processed=n.processed,Jb._loadingPromise||(this.document.outputJax.reset(),Zn.handleRetriesFor(()=>{this.rerender("complexity"===t||e?or.COMPILED:or.TYPESET)}))})}transferMathList(t){const e=this.document.options.MathItem;for(const s of t.math){const t=new e;Object.assign(t,s),this.document.math.push(t)}}toMML(t){return this.MmlVisitor.visitTree(t.root,t,{filterSRE:!this.settings.showSRE,filterTex:!this.settings.showTex,texHints:this.settings.texHints,semantics:this.settings.semantics&&"MathML"!==t.inputJax.name})}toSVG(t){return Xb(this,void 0,void 0,function*(){const e=this.jax.SVG;if(!e)return"SVG can't be produced.
Try switching to SVG output first.";const s=e.adaptor,i=e.options.fontCache,r=!!t.root.getProperty("process-breaks");if("global"!==i&&(t.display||!r)&&"SVG"===s.getAttribute(t.typesetRoot,"jax"))for(const e of s.childNodes(t.typesetRoot))if("svg"===s.kind(e))return this.formatSvg(s.serializeXML(e));return this.typesetSVG(t,i,r)})}typesetSVG(t,e,s){return Xb(this,void 0,void 0,function*(){const i=this.jax.SVG,r=i.html("div");"global"===e&&(i.options.fontCache="local");const n=t.root;return t.root=n.copy(!0),t.root.setInheritedAttributes({},t.display,0,!1),s&&(i.unmarkInlineBreaks(t.root),t.root.setProperty("inlineMarked",!1)),yield Zn.handleRetriesFor(()=>{i.toDOM(t,r,i.document)}),t.root=n,i.options.fontCache=e,this.formatSvg(i.adaptor.serializeXML(r))})}formatSvg(t){const e=this.constructor.SvgCss,s=(t=(t=t.match(/^/)?t.replace(//,``):t.replace(/^()/,`$1`)).replace(/ (?:role|focusable)=".*?"/g,"").replace(/"currentColor"/g,'"black"')).split(/(<\/?[a-zA-Z].*?>)/);for(let t=2,e="";t\n${t}`}zoom(t,e){t&&!this.isZoomEvent(t,e)||this.zoomBox()}isZoomEvent(t,e){return this.settings.zoom===e&&(!this.settings.alt||t.altKey)&&(!this.settings.ctrl||t.ctrlKey)&&(!this.settings.cmd||t.metaKey)&&(!this.settings.shift||t.shiftKey)}rerender(t=or.TYPESET){this.rerenderStart=Math.min(t,this.rerenderStart),!Jb.loading&&Gb.startup.hasTypeset&&this.document.whenReady(()=>Xb(this,void 0,void 0,function*(){this.rerenderStart<=or.COMPILED&&this.document.reset({inputJax:[]}),yield this.document.rerenderPromise(this.rerenderStart),this.rerenderStart=or.LAST}))}noRerender(t){Jb.loading++;try{t(),Jb.loading--}catch(t){throw Jb.loading--,t}}copyMathML(){Bb(this.toMML(this.menu.mathItem))}copyOriginal(){Bb(this.menu.mathItem.math.trim())}copySvgImage(){this.toSVG(this.menu.mathItem).then(t=>{Bb(t)})}copySpeechText(){Bb(this.menu.mathItem.outputData.speech)}copyBrailleText(){Bb(this.menu.mathItem.outputData.braille)}copyErrorMessage(){Bb(this.menu.errorMsg.trim())}addMenu(t){this.addEvents(t),this.menu.store.insert(t.typesetRoot),t.typesetRoot.tabIndex=this.settings.inTabOrder?0:-1}addEvents(t){const e=t.typesetRoot;e.addEventListener("mousedown",()=>{var e,s;this.menu.mathItem=t,this.current=null===(s=null===(e=t.explorers)||void 0===e?void 0:e.speech)||void 0===s?void 0:s.current},!0),e.addEventListener("contextmenu",()=>{var e;this.menu.mathItem=t;const s=null===(e=t.explorers)||void 0===e?void 0:e.speech;s&&(t.outputData.nofocus=!this.current,s.refocus=this.current)},!0),e.addEventListener("keydown",()=>this.menu.mathItem=t,!0),e.addEventListener("click",t=>this.zoom(t,"Click"),!0),e.addEventListener("dblclick",t=>this.zoom(t,"DoubleClick"),!0)}clear(){this.menu.store.clear()}variable(t,e){return{name:t,getter:()=>this.settings[t],setter:s=>{this.settings[t]=s,e&&e(s),this.saveUserSettings()}}}a11yVar(t,e){return{name:t,getter:()=>this.getA11y(t),setter:s=>{this.settings[t]=s,this.setA11y({[t]:s}),e&&e(s),this.saveUserSettings()}}}submenu(t,e,s=[],i=!1){let r=[];for(const t of s)Array.isArray(t)?r=r.concat(t):r.push(t);return{type:"submenu",id:t,content:e,menu:{items:r},disabled:0===r.length||i}}command(t,e,s,i={}){return Object.assign({type:"command",id:t,content:e,action:s},i)}checkbox(t,e,s,i={}){return Object.assign({type:"checkbox",id:t,content:e,variable:s},i)}radioGroup(t,e){return e.map(e=>this.radio(e[0],e[1]||e[0],t))}radio(t,e,s,i={}){return Object.assign({type:"radio",id:t,content:e,variable:s},i)}label(t,e){return{type:"label",id:t,content:e}}rule(){return{type:"rule"}}}function Kb(t){return class extends t{addMenu(t,e=!1){this.state()>=or.CONTEXT_MENU||(this.isEscaped||!t.options.enableMenu&&!e||t.menu.addMenu(this),this.state(or.CONTEXT_MENU))}getMenus(t){t.menu.menu.store.sort()}checkLoading(t){t.checkLoading()}}}function $b(t){var e;return e=class extends t{constructor(...t){super(...t),this.menu=new this.options.MenuClass(this,this.options.menuOptions);const e=this.constructor.ProcessBits;e.has("context-menu")||e.allocate("context-menu"),this.options.MathItem=Kb(this.options.MathItem);const s=this.menu.settings,i=this.options,r=i.enableEnrichment=s.enrich;i.enableSpeech=s.speech&&r,i.enableBraille=s.braille&&r,i.enableComplexity=s.collapsible&&r,i.enableExplorer=r}addMenu(){if(!this.processed.isSet("context-menu")){for(const t of this.math)t.addMenu(this);this.processed.set("context-menu")}return this}getMenus(){this.menu.menu.store.sort()}checkLoading(){let t=!0;try{this._checkLoading(),t=!1}catch(t){if(!t.retry)throw t}return t}_checkLoading(){return this.menu.isLoading&&Zn.retryAfter(this.menu.loadingPromise.catch(t=>console.log(t))),this.options.enableComplexity&&this.menu.checkComponent("a11y/complexity"),this.options.enableExplorer&&this.menu.checkComponent("a11y/explorer"),this}state(t,e=!1){return super.state(t,e),tconsole.warn("Enrichment Error:",s)},t.OPTIONS),{MenuClass:Jb,menuOptions:Jb.OPTIONS,enableMenu:!0,sre:t.OPTIONS.sre||Ri({}),a11y:t.OPTIONS.a11y||Ri({}),renderActions:Ri(Object.assign(Object.assign({},t.OPTIONS.renderActions),{addMenu:[or.CONTEXT_MENU],getMenus:[or.INSERTED+5,!1],checkLoading:[or.UNPROCESSED+1,t=>t.checkLoading(),"",!1]}))}),e}function Yb(t){return t.documentClass=$b(t.documentClass),t}Jb.MENU_STORAGE="MathJax-Menu-Settings",Jb.OPTIONS={settings:{showSRE:!1,showTex:!1,texHints:!0,semantics:!1,zoom:"NoZoom",zscale:"200%",renderer:"CHTML",alt:!0,cmd:!1,ctrl:!1,shift:!1,scale:1,overflow:"Scroll",breakInline:!0,autocollapse:!1,collapsible:!1,enrich:!0,assistiveMml:!1,speech:!0,braille:!0,brailleCode:"nemeth",brailleSpeech:!1,brailleCombine:!1,speechRules:"clearspeak-default",roleDescription:"math",inTabOrder:!0,tabSelects:"all",help:!0},jax:{CHTML:null,SVG:null},annotationTypes:Ri({TeX:["TeX","LaTeX","application/x-tex"],StarMath:["StarMath 5.0"],Maple:["Maple"],ContentMathML:["MathML-Content","application/mathml-content+xml"],OpenMath:["OpenMath"]})},Jb.SvgCss=["svg a{fill:blue;stroke:blue}",'[data-mml-node="merror"]>g{fill:red;stroke:red}','[data-mml-node="merror"]>rect[data-background]{fill:yellow;stroke:none}',"[data-frame],[data-line]{stroke-width:70px;fill:none}",".mjx-dashed{stroke-dasharray:140}",".mjx-dotted{stroke-linecap:round;stroke-dasharray:0,140}","use[data-c]{stroke-width:3px}"].join("\n"),Jb.loading=0,Jb.loadingPromises=new Map,Jb._loadingPromise=null,Jb._loadingOK=null,Jb._loadingFailed=null,ar("CONTEXT_MENU",170),MathJax.loader&&MathJax.loader.checkVersion("ui/menu",ii,"ui"),ci({_:{a11y:{speech:{SpeechMenu:Bs}},ui:{menu:{AnnotationMenu:js,MJContextMenu:Ds,Menu:qs,MenuHandler:Ws,MenuUtil:Fs,MmlVisitor:Hs,RadioCompare:Us}}}}),MathJax.startup&&di&&MathJax.startup.extendHandler(t=>Yb(t),20),MathJax.loader&&MathJax.loader.checkVersion("a11y/sre",ii,"a11y"),ci({_:{a11y:{sre_ts:Ps}}}),ar("ENRICHED",or.COMPILED+10);class Qb extends $n{visitTree(t,e){this.mactionId=0;const s=super.visitTree(t);return this.mactionId&&(e.inputData.hasMaction=!0),s}visitHtmlNode(t,e){return t.getSerializedXML()}visitMactionNode(t,e){const[s,i]=0===t.childNodes.length?["",""]:["\n",e],r=this.childNodeMml(t,e+" ",s);let n=this.getAttributes(t);if("toggle"===t.attributes.get("actiontype")){const e=++this.mactionId;t.setProperty("mactionId",e),n=` data-maction-id="${e}" selection="${t.attributes.get("selection")}"`+n.replace(/ selection="\d+"/,"").replace(/ data-maction-id="\d+"/,"")}return`${e}`+(r.match(/\S/)?s+r+i:"")+""}}function Zb(t,e,s){return class extends t{constructor(){super(...arguments),this.toMathML=s}serializeMml(t){if("outerHTML"in t)return t.outerHTML;if("undefined"!=typeof Element&&"undefined"!=typeof window&&t instanceof Element){const e=window.document.createElement("div");return e.appendChild(t),e.innerHTML}return t.toString()}enrich(t,s=!1){if(!(this.state()>=or.ENRICHED)){if(!this.isEscaped&&(t.options.enableEnrichment||s)){const s=new t.options.MathItem("",e);try{let e;e=this.inputData.originalMml?this.adjustSelections():this.inputData.originalMml=this.toMathML(this.root,this);const i=yb(e);this.inputData.enrichedMml=s.math=this.serializeMml(i),s.math=s.math.replace(/ role="treeitem"/g,' data-speech-node="true"').replace(/ aria-level/g," data-semantic-level-number").replace(/ aria-(?:posinset|owns|setsize)=".*?"/g,""),s.display=this.display,s.compile(t),this.root=s.root}catch(e){t.options.enrichError(t,this,e)}}this.state(or.ENRICHED)}}toEnriched(t){return this.serializeMml(yb(t))}unEnrich(t){const s=this.inputData.originalMml;if(!s)return;const i=new t.options.MathItem("",e);i.math=s,i.display=this.display,i.compile(t),this.root=i.root}adjustSelections(){const t=this.inputData.originalMml;if(!this.inputData.hasMaction)return t;const e=[];return this.root.walkTree(t=>{t.isKind("maction")&&(e[t.attributes.get("data-maction-id")]=t)}),t.replace(/(data-maction-id="(\d+)" selection=)"\d+"/g,(t,s,i)=>`${s}"${e[i].attributes.get("selection")}"`)}}}function tE(t,e){var s;return(s=class extends t{constructor(...t){super(...t),e.setMmlFactory(this.mmlFactory);const s=this.constructor.ProcessBits;s.has("enriched")||s.allocate("enriched");const i=new Qb(this.mmlFactory);this.options.MathItem=Zb(this.options.MathItem,e,(t,e)=>i.visitTree(t,e))}enrich(){if(!this.processed.isSet("enriched")){if(this.options.enableEnrichment){Eb(this.options.sre);for(const t of this.math)t.enrich(this)}this.processed.set("enriched")}return this}enrichError(t,e,s){console.warn("Enrichment error:",s)}state(t,e=!1){if(super.state(t,e),t=or.COMPILED))for(const t of this.math)t.unEnrich(this);return this}}).OPTIONS=Object.assign(Object.assign({},t.OPTIONS),{enableEnrichment:!0,enrichError:(t,e,s)=>t.enrichError(t,e,s),renderActions:Ri(Object.assign(Object.assign({},t.OPTIONS.renderActions),{enrich:[or.ENRICHED]})),sre:Ri({speech:"none",locale:"en",domain:"clearspeak",style:"default",braille:"nemeth",structure:!0,aria:!0})}),s}function eE(t,e){return e.setAdaptor(t.adaptor),t.documentClass=tE(t.documentClass,e),t}MathJax.loader&&MathJax.loader.checkVersion("a11y/semantic-enrich",ii,"a11y"),ci({_:{a11y:{"semantic-enrich":zs}}}),MathJax.startup&&MathJax.startup.extendHandler(t=>eE(t,new _c({allowHtmlInTokenNodes:!0})));const sE=["pitch","rate","volume"];function iE(t){const e=Nb(t),s=[],i=[];return rE(Array.from(e.childNodes),s,i),[i.join(" "),s]}function rE(t,e,s,i={}){for(const r of t){if(3===r.nodeType){const t=r.textContent.trim();t&&(s.push(t),e.push(Object.assign({text:t},i)));continue}if(1===r.nodeType){const t=r,n=t.tagName;if("speak"===n)continue;if("prosody"===n){rE(Array.from(r.childNodes),e,s,oE(t,i));continue}switch(n){case"break":e.push({pause:t.getAttribute("time")});break;case"mark":e.push({mark:t.getAttribute("name")});break;case"say-as":{const r=t.textContent;e.push(Object.assign({text:r,character:!0},i)),s.push(r);break}}}}}const nE={pitch:(t,e)=>t/100*1,volume:(t,e)=>t/100*.5,rate:(t,e)=>t/100*1};function oE(t,e){const s={};for(const i of sE)if(t.hasAttribute(i)){const[r,n]=lE(t.getAttribute(i));if(!r){s[i]="volume"===i?.5:1;continue}let o=e[i];o=o||("volume"===i?.5:1);const a=nE[i](parseInt(n,10),r);s[i]="-"===r?o-a:o+a}return s}const aE=/([+-]?)([0-9]+)%/;function lE(t){const e=t.match(aE);return e?[e[1],e[2]]:(console.warn("Something went wrong with the prosody matching."),["","100"])}function cE(t,e,s,i=" "){if(!t)return"";const r=[t];return e&&r.unshift(e),s&&r.push(s),r.join(i)}function hE(t,e="en",s="100"){return iE(`${t}`)}function dE(){const t=new AudioContext,e=t.createOscillator();e.frequency.value=300,e.connect(t.destination),e.start(t.currentTime),e.stop(t.currentTime+.05)}var uE,pE;!function(t){t[t.NONE=0]="NONE",t[t.DEPTH=1]="DEPTH",t[t.SUMMARY=2]="SUMMARY"}(uE||(uE={})),function(t){t.SPEECH="data-semantic-speech-none",t.SPEECH_SSML="data-semantic-speech",t.SUMMARY="data-semantic-summary-none",t.SUMMARY_SSML="data-semantic-summary",t.PREFIX="data-semantic-prefix-none",t.PREFIX_SSML="data-semantic-prefix",t.POSTFIX="data-semantic-postfix-none",t.POSTFIX_SSML="data-semantic-postfix",t.BRAILLE="data-semantic-braille"}(pE||(pE={}));class mE{constructor(){this.promise=Promise.resolve(),this.adaptor=null,this._options={},this._init=!1}set element(t){this._element=t}get element(){return this._element}set options(t){this._options=Object.assign({},(null==t?void 0:t.sre)||{},{enableSpeech:t.enableSpeech,enableBraille:t.enableBraille}),delete this._options.custom}get options(){return this._options}init(t,e,s){this.options=t,this._init||(this.adaptor=e,this.webworker=s,this._init=!0)}update(t){Object.assign(this.options,t)}Speech(t){const e=t.outputData.mml,s=Object.assign({},this.options,{modality:"speech"});return this.promise=this.webworker.Speech(e,s,t)}SpeechFor(t,e){const s=Object.assign({},this.options,{modality:"speech"});return this.webworker.speechFor(e,s,t)}cancel(t){var e;null===(e=this.webworker)||void 0===e||e.Cancel(t)}updateRegions(t,e,s){e.Update(this.getLabel(t)),s.Update(this.getBraille(t))}getOptions(t){var e,s,i,r;return{locale:null!==(e=this.adaptor.getAttribute(t,"data-semantic-locale"))&&void 0!==e?e:"",domain:null!==(s=this.adaptor.getAttribute(t,"data-semantic-domain"))&&void 0!==s?s:"",style:null!==(i=this.adaptor.getAttribute(t,"data-semantic-style"))&&void 0!==i?i:"",domain2style:null!==(r=this.adaptor.getAttribute(t,"data-semantic-domain2style"))&&void 0!==r?r:""}}nextRules(t){const e=this.getOptions(t.typesetRoot);return this.update(e),this.promise=this.webworker.nextRules(t.outputData.mml,Object.assign({},this.options,{modality:"speech"}),t)}nextStyle(t,e){const s=this.getOptions(e.typesetRoot);return this.update(s),this.promise=this.webworker.nextStyle(e.outputData.mml,Object.assign({},this.options,{modality:"speech"}),this.adaptor.getAttribute(t,"data-semantic-id"),e)}getLabel(t,e="",s=" "){const i=this.adaptor;return cE(i.getAttribute(t,pE.SPEECH_SSML),i.getAttribute(t,pE.PREFIX_SSML),i.getAttribute(t,pE.POSTFIX_SSML),s)||i.getAttribute(t,"aria-label")}getBraille(t){const e=this.adaptor;return e.getAttribute(t,"aria-braillelabel")||e.getAttribute(t,pE.BRAILLE)}getLocalePreferences(t){return this.promise=this.webworker.clearspeakLocalePreferences(this.options,t)}getRelevantPreferences(t,e,s,i){const r=t.outputData.mml;return this.promise=this.webworker.clearspeakRelevantPreferences(r,e,s,i)}}var fE=function(t,e,s,i){return new(s||(s=Promise))(function(r,n){function o(t){try{l(i.next(t))}catch(t){n(t)}}function a(t){try{l(i.throw(t))}catch(t){n(t)}}function l(t){var e;t.done?r(t.value):(e=t.value,e instanceof s?e:new s(function(t){t(e)})).then(o,a)}l((i=i.apply(t,e||[])).next())})};class gE{constructor(t,e,s,i){this.cmd=t,this.item=e,this.resolve=s,this.reject=i}}class bE{constructor(t,e){this.adaptor=t,this.options=e,this.ready=!1,this.tasks=[],this.Commands={Ready(t,e){t.ready=!0,t.postNext()},Finished(t,e){const s=t.tasks.shift();e.success?s.resolve(e.result):s.reject(e.error),t.postNext()},Log(t,e){t.options.debug&&console.log("Log:",e)}}}Start(){return fE(this,void 0,void 0,function*(){if(this.ready)throw Error("Worker already started");this.worker=yield this.adaptor.createWorker(this.Listener.bind(this),this.options)})}debug(t,...e){this.options.debug&&console.info(t,...e)}Listener(t){this.debug("Worker >>> Client:",t.data),Object.hasOwn(this.Commands,t.data.cmd)?this.Commands[t.data.cmd](this,t.data.data):this.debug("Invalid command from worker: "+t.data.cmd)}Post(t,e){const s=new Promise((s,i)=>{this.tasks.push(new gE(t,e,s,i))});return this.ready&&1===this.tasks.length&&this.postNext(),s}postNext(){if(this.tasks.length){const t=Object.assign({},this.tasks[0].cmd,{debug:this.options.debug});this.worker.postMessage(t)}}Cancel(t){const e=this.tasks.findIndex(e=>e.item===t);e>0&&(this.tasks[e].reject(`Task ${this.tasks[e].cmd.cmd} cancelled`),this.tasks.splice(e,1))}Setup(t){return this.Post({cmd:"setup",data:{domain:t.domain,style:t.style,locale:t.locale,modality:t.modality}})}Speech(t,e,s){return fE(this,void 0,void 0,function*(){this.Attach(s,e.enableSpeech,e.enableBraille,yield this.Post({cmd:"speech",data:{mml:t,options:e}},s))})}nextRules(t,e,s){return fE(this,void 0,void 0,function*(){this.Attach(s,e.enableSpeech,e.enableBraille,yield this.Post({cmd:"nextRules",data:{mml:t,options:e}},s))})}nextStyle(t,e,s,i){return fE(this,void 0,void 0,function*(){this.Attach(i,e.enableSpeech,e.enableBraille,yield this.Post({cmd:"nextStyle",data:{mml:t,options:e,nodeId:s}},i))})}speechFor(t,e,s){return fE(this,void 0,void 0,function*(){const i=yield this.Post({cmd:"speech",data:{mml:t,options:e}},s);return JSON.parse(i)})}Attach(t,e,s,i){const r=JSON.parse(i),n=t.typesetRoot;if(!n)return;this.setSpecialAttributes(n,r.options,"data-semantic-",["locale","domain","style","domain2style"]);const o=this.adaptor;this.setSpecialAttributes(n,r.translations,"data-semantic-");for(const[t,e]of Object.entries(r.mactions)){let s=o.getElement("#"+t,n);s&&o.childNodes(s)[0]&&(s=o.childNodes(s)[0],"rect"===o.kind(s)&&(s=o.next(s)),o.setAttribute(s,"data-semantic-type","dummy"),this.setSpecialAttributes(s,e,""))}for(const t of o.childNodes(n))"mjx-math"!==o.kind(t)&&"svg"!==o.kind(t)||this.setSpeechAttributes(t,"",r,e,s);e&&(r.label&&(o.setAttribute(n,pE.SPEECH,r.label),o.setAttribute(n,pE.SPEECH_SSML,r.ssml),t.outputData.speech=r.label),o.setAttribute(n,"data-speech-attached","true")),s&&(r.braillelabel&&(o.setAttribute(n,pE.BRAILLE,r.braillelabel),t.outputData.braille=r.braillelabel),r.braille&&o.setAttribute(n,"data-braille-attached","true"))}setSpeechAttribute(t,e,s,i){var r,n;const o=this.adaptor,a=o.getAttribute(t,"data-semantic-id");if(o.removeAttribute(t,"data-speech-node"),s&&e.speech[a]["speech-none"]){o.setAttribute(t,"data-speech-node","true");for(let[s,i]of Object.entries(e.speech[a]))s=s.replace(/-ssml$/,""),i&&o.setAttribute(t,`data-semantic-${s}`,i)}if(i&&(null===(n=null===(r=e.braille)||void 0===r?void 0:r[a])||void 0===n?void 0:n["braille-none"])){o.setAttribute(t,"data-speech-node","true");const s=e.braille[a]["braille-none"];o.setAttribute(t,pE.BRAILLE,s)}}setSpeechAttributes(t,e,s,i,r){const n=this.adaptor;if(!t||"#text"===n.kind(t)||"#comment"===n.kind(t))return e;n.hasAttribute(t,"data-semantic-id")&&(this.setSpeechAttribute(t,s,i,r),e||n.hasAttribute(t,"data-semantic-parent")||(e=n.getAttribute(t,"data-semantic-id")));for(const o of Array.from(n.childNodes(t)))e=this.setSpeechAttributes(o,e,s,i,r);return e}setSpecialAttributes(t,e,s,i){if(e){i=i||Object.keys(e);for(const r of i){const i=e[r];i&&this.adaptor.setAttribute(t,`${s}${r.toLowerCase()}`,i)}}}Detach(t){const e=t.typesetRoot;this.adaptor.removeAttribute(e,"data-speech-attached"),this.adaptor.removeAttribute(e,"data-braille-attached"),this.detachSpeech(e)}detachSpeech(t){const e=this.adaptor,s=e.childNodes(t);if(s){if("#text"!==e.kind(t))for(const s of["none","summary-none","speech","speech-none","summary","braille"])e.removeAttribute(t,`data-semantic-${s}`);for(const t of s)this.detachSpeech(t)}}Terminate(){this.debug("Terminating pending tasks");for(const t of this.tasks)t.reject(`${t.cmd.data.cmd} cancelled by WorkerHandler termination`);return this.tasks=[],this.debug("Terminating worker"),this.worker.terminate()}Stop(){return fE(this,void 0,void 0,function*(){if(!this.worker)throw Error("Worker has not been started");yield this.Terminate(),this.worker=null,this.ready=!1})}clearspeakLocalePreferences(t,e){return fE(this,void 0,void 0,function*(){yield this.Post({cmd:"localePreferences",data:{options:t}}).then(s=>{e.set(t.locale,JSON.parse(s))})})}clearspeakRelevantPreferences(t,e,s,i){return fE(this,void 0,void 0,function*(){yield this.Post({cmd:"relevantPreferences",data:{mml:t,id:e}}).then(t=>{s.set(i,t)})})}}const EE=hi.config||{},xE=()=>(EE?.loader?.paths?.mathjax||EE?.__dirname||"/")+"/sre";var yE=function(t,e,s,i){return new(s||(s=Promise))(function(r,n){function o(t){try{l(i.next(t))}catch(t){n(t)}}function a(t){try{l(i.throw(t))}catch(t){n(t)}}function l(t){var e;t.done?r(t.value):(e=t.value,e instanceof s?e:new s(function(t){t(e)})).then(o,a)}l((i=i.apply(t,e||[])).next())})};function NE(t){return class extends t{constructor(){super(...arguments),this.generatorPool=new mE}attachSpeech(t){if(this.outputData.speechPromise=null,this.state()>=or.ATTACHSPEECH)return;if(this.state(or.ATTACHSPEECH),this.isEscaped||!t.options.enableSpeech&&!t.options.enableBraille||!t.options.enableEnrichment)return;t.getWebworker(),this.generatorPool.init(t.options,t.adaptor,t.webworker),this.outputData.mml=this.toMathML(this.root,this);const e=this.generatorPool.Speech(this).catch(e=>t.options.speechError(t,this,e));t.savePromise(e),this.outputData.speechPromise=e}detachSpeech(t){t.webworker.Detach(this)}speechFor(t){return yE(this,void 0,void 0,function*(){t=this.toEnriched(t);const e=yield this.generatorPool.SpeechFor(this,t);return[e.label,e.braillelabel]})}clear(){this.generatorPool.cancel(this)}}}function vE(t){var e;return e=class extends t{constructor(...t){super(...t),this.webworker=null;const e=this.constructor.ProcessBits;e.has("attach-speech")||e.allocate("attach-speech"),this.options.MathItem=NE(this.options.MathItem)}getWebworker(){this.webworker||(this.webworker=new bE(this.adaptor,this.options.worker),this.webworker.Start())}attachSpeech(){if(!this.processed.isSet("attach-speech")){const t=this.options;if(t.enableEnrichment&&(t.enableSpeech||t.enableBraille)){this.getWebworker();for(const t of this.math)t.attachSpeech(this)}this.processed.set("attach-speech")}return this}speechError(t,e,s){console.warn("Speech generation error:",s)}state(t,e=!1){if(super.state(t,e),t=or.TYPESET))for(const t of this.math)t.detachSpeech(this);return this}done(){const t=Object.create(null,{done:{get:()=>super.done}});return yE(this,void 0,void 0,function*(){var e;return yield null===(e=this.webworker)||void 0===e?void 0:e.Stop(),t.done.call(this)})}},e.OPTIONS=Object.assign(Object.assign({},t.OPTIONS),{enableSpeech:!0,enableBraille:!0,speechError:(t,e,s)=>t.speechError(t,e,s),renderActions:Ri(Object.assign(Object.assign({},t.OPTIONS.renderActions),{attachSpeech:[or.ATTACHSPEECH]})),worker:{path:xE(),maps:xE().replace(/[cm]js\/a11y\/sre$/,"bundle/sre/mathmaps"),worker:"speech-worker.js",debug:!1},a11y:Ri({speech:!0,braille:!0})}),e}function TE(t,e){return!t.documentClass.prototype.enrich&&e&&(t=eE(t,e)),t.documentClass=vE(t.documentClass),t}if(ar("ATTACHSPEECH",or.INSERTED+10),MathJax.loader&&MathJax.loader.checkVersion("a11y/speech",ii,"a11y"),ci({_:{a11y:{speech_ts:Js,speech:{GeneratorPool:Xs,SpeechUtil:Vs,WebWorker:Gs}}}}),MathJax.loader){let t=mi.resolvePath("[sre]",!1),e=mi.resolvePath("[mathmaps]",!1);if(ui.window)t=new URL(t,location).href,e=new URL(e,location).href;else{const s="undefined"!=typeof require?require:MathJax.config.loader.require;s?.resolve?(t=ui.path(s.resolve(`${t}/require.mjs`)).replace(/\/[^\/]*$/,""),e=ui.path(s.resolve(`${e}/base.json`)).replace(/\/[^\/]*$/,"")):t=e=""}t&&li(MathJax.config,"options",{worker:{path:t,maps:e}})}MathJax.startup&&MathJax.startup.extendHandler(t=>TE(t));class wE{constructor(t){this.document=t,this.CLASS=this.constructor,this.AddStyles()}static get sheetId(){return"MJX-"+this.name+"-styles"}static get styleSheet(){return document.head.querySelector("#"+this.sheetId)}AddStyles(){const t=this.CLASS.sheetId;if(!this.CLASS.style||this.document.adaptor.head().querySelector("#"+t))return;const e=this.document.adaptor.node("style",{id:t});e.innerHTML=this.CLASS.style.cssText,this.document.adaptor.head().appendChild(e)}AddElement(){if(this.div)return;const t=this.document.adaptor.node("div");t.classList.add(this.CLASS.className),this.div=t,this.inner=this.document.adaptor.node("div"),this.div.appendChild(this.inner),this.document.adaptor.body(this.document.adaptor.document).appendChild(this.div)}Show(t){this.AddElement(),this.position(t),this.div.classList.add(this.CLASS.className+"_Show")}Hide(){this.div&&(this.div.remove(),this.div=null,this.inner=null)}stackRegions(t){const e=t.getBoundingClientRect();let s=0,i=Number.POSITIVE_INFINITY;const r=this.document.adaptor.document.getElementsByClassName(this.CLASS.className+"_Show");for(let t,e=0;t=r[e];e++)t!==this.div&&(s=Math.max(t.getBoundingClientRect().bottom,s),i=Math.min(t.getBoundingClientRect().left,i));const n=(s||e.bottom+10)+window.scrollY,o=(i div`]:{"border-radius":"inherit",padding:"0 2px"},"@media (prefers-color-scheme: dark)":{["."+_E.className]:{"background-color":"#222025","box-shadow":"0px 5px 20px #000",border:"1px solid #7C7C7C"}}});class LE extends kE{static setColor(t,e,s,i){const r=this.styleSheet;if(r){const n=r.sheet.cssRules[0].style,o=`--mjx-${t}${e}-color`,a=`rgba(var(--mjx-${t}-${s}), ${1===i?1:`var(--mjx-${t}${e}-alpha)`})`;n.getPropertyValue(o)!==a&&n.setProperty(o,a);const l=`--mjx-${t}${e}-alpha`;n.getPropertyValue(l)!==String(i)&&(n.setProperty(l,i),r.sheet.cssRules[1].cssRules[0].style.setProperty(l,Math.pow(i,.7071)))}}}LE.className="MJX_LiveRegion",LE.priority={primary:1,secondary:2},LE.style=new oo({":root":{"--mjx-fg-red":"255, 0, 0","--mjx-fg-green":"0, 255, 0","--mjx-fg-blue":"0, 0, 255","--mjx-fg-yellow":"255, 255, 0","--mjx-fg-cyan":"0, 255, 255","--mjx-fg-magenta":"255, 0, 255","--mjx-fg-white":"255, 255, 255","--mjx-fg-black":"0, 0, 0","--mjx-bg-red":"255, 0, 0","--mjx-bg-green":"0, 255, 0","--mjx-bg-blue":"0, 0, 255","--mjx-bg-yellow":"255, 255, 0","--mjx-bg-cyan":"0, 255, 255","--mjx-bg-magenta":"255, 0, 255","--mjx-bg-white":"255, 255, 255","--mjx-bg-black":"0, 0, 0","--mjx-live-bg-color":"white","--mjx-live-shadow-color":"#888","--mjx-live-border-color":"#CCCCCC","--mjx-bg1-color":"rgba(var(--mjx-bg-blue), var(--mjx-bg-alpha))","--mjx-fg1-color":"rgba(var(--mjx-fg-black), 1)","--mjx-bg2-color":"rgba(var(--mjx-bg-red), 1)","--mjx-fg2-color":"rgba(var(--mjx-fg-black), 1)","--mjx-bg1-alpha":.2,"--mjx-fg1-alpha":1,"--mjx-bg2-alpha":1,"--mjx-fg2-alpha":1},"@media (prefers-color-scheme: dark)":{":root":{"--mjx-bg-blue":"132, 132, 255","--mjx-bg-white":"0, 0, 0","--mjx-bg-black":"255, 255, 255","--mjx-fg-white":"0, 0, 0","--mjx-fg-black":"255, 255, 255","--mjx-live-bg-color":"#222025","--mjx-live-shadow-color":"black","--mjx-live-border-color":"#7C7C7C","--mjx-bg1-alpha":.3,"--mjx-fg1-alpha":1,"--mjx-bg2-alpha":1,"--mjx-fg2-alpha":1}},[`.${LE.className}`]:{position:"absolute",top:0,display:"none",width:"auto",height:"auto",padding:0,opacity:1,"z-index":"202",left:0,right:0,margin:"0 auto","background-color":"var(--mjx-live-bg-color)","box-shadow":"0px 5px 20px var(--mjx-live-shadow-color)",border:"2px solid var(--mjx-live-border-color)"},[`.${LE.className}_Show`]:{display:"block"},[`.${LE.className} > div`]:{color:"var(--mjx-fg1-color)","background-color":"var(--mjx-bg1-color)"},"mjx-container [data-sre-highlight-1]:not([data-mjx-collapsed], rect)":{color:"var(--mjx-fg1-color) ! important",fill:"var(--mjx-fg1-color) ! important"},[["mjx-container:not([data-mjx-clone-container])","[data-sre-highlight-1]:not([data-sre-enclosed], rect)"].join(" ")]:{"background-color":"var(--mjx-bg1-color) ! important"},"mjx-container rect[data-sre-highlight-1]:not([data-sre-enclosed])":{fill:"var(--mjx-bg1-color) ! important"},"mjx-container [data-sre-highlight-2]":{color:"var(--mjx-fg2-color) ! important","background-color":"var(--mjx-bg2-color) ! important",fill:"var(--mjx-fg2-color) ! important"},"mjx-container rect[data-sre-highlight-2]":{fill:"var(--mjx-bg2-color) ! important"}});class AE extends LE{constructor(){super(...arguments),this.active=!1,this.node=null,this.clear=!1,this.voiceRequest=!1,this.voiceCancelled=!1}Show(t){super.Update("\xa0"),this.node=t,super.Show(t)}Update(t){if(this.voiceRequest)return void this.makeVoice(t);speechSynthesis.onvoiceschanged=(()=>this.voiceRequest=!0).bind(this);new Promise(t=>{setTimeout(()=>{this.voiceRequest?t(!0):setTimeout(()=>{this.voiceRequest=!0,t(!0)},100)},100)}).then(()=>this.makeVoice(t))}makeVoice(t){this.active=this.document.options.a11y.voicing&&!!speechSynthesis.getVoices().length,speechSynthesis.cancel(),this.clear=!0;const[e,s]=hE(t,this.document.options.sre.locale,this.document.options.sre.rate);super.Update(e),this.active&&e&&this.makeUtterances(s,this.document.options.sre.locale)}makeUtterances(t,e){this.voiceCancelled=!1;let s=null;for(const i of t)if(i.mark){if(!s){this.highlightNode(i.mark,!0);continue}s.addEventListener("end",t=>{this.voiceCancelled||this.highlightNode(i.mark)})}else{if(i.pause){const t=parseInt(i.pause.match(/^[0-9]+/)[0]);if(isNaN(t)||!s)continue;s.addEventListener("end",e=>{speechSynthesis.pause(),setTimeout(()=>{speechSynthesis.resume()},t)});continue}s=new SpeechSynthesisUtterance(i.text),i.rate&&(s.rate=i.rate),i.pitch&&(s.pitch=i.pitch),s.lang=e,speechSynthesis.speak(s)}s&&s.addEventListener("end",t=>{this.highlighter.unhighlight()})}Hide(){this.cancelVoice(),super.Hide()}cancelVoice(){this.voiceCancelled=!0,speechSynthesis.cancel(),this.highlighter.unhighlight()}highlightNode(t,e=!1){this.highlighter.unhighlight();const s=Array.from(this.node.querySelectorAll(`[data-semantic-id="${t}"]`));this.clear&&!e||this.highlighter.highlight(s),this.clear=!1}}AE.style=null;class RE extends wE{position(t){const e=t.getBoundingClientRect(),s=this.div.getBoundingClientRect();let i,r=e.left+e.width/2-s.width/2;switch(r=r<0?0:r,r+=window.scrollX,this.document.options.a11y.align){case"top":i=e.top-s.height-10;break;case"bottom":i=e.bottom+10;break;default:i=e.top+e.height/2-s.height/2}i+=window.scrollY,i=i<0?0:i,this.div.style.top=i+"px",this.div.style.left=r+"px"}Show(t){this.AddElement(),this.div.style.fontSize=this.document.options.a11y.magnify,this.Update(t),super.Show(t)}Clear(){this.div&&(this.inner.textContent="",this.inner.style.top="",this.inner.style.backgroundColor="")}Update(t){if(!this.div)return;this.Clear();const e=this.cloneNode(t),s=e.querySelector("[data-mjx-clone]");this.inner.style.backgroundColor=t.style.backgroundColor,s.style.backgroundColor="",s.classList.remove("mjx-selected"),this.inner.appendChild(e),this.position(t)}cloneNode(t){let e=t.cloneNode(!0);if(e.setAttribute("data-mjx-clone","true"),"MJX-CONTAINER"!==e.nodeName){"g"!==e.nodeName&&(e.style.marginLeft=e.style.marginRight="0");const s=t.closest("mjx-container");if("MJX-MATH"!==e.nodeName&&"svg"!==e.nodeName){let i=s.firstChild;"MJX-BBOX"===i.nodeName&&(i=i.nextSibling),e=i.cloneNode(!1).appendChild(e).parentElement;const r=Array.from(s.querySelectorAll("[data-sre-enclosed]"));"svg"===i.nodeName?this.svgClone(t,r,e,s):this.chtmlClone(t,r,e)}e=s.cloneNode(!1).appendChild(e).parentElement,e.style.margin="0",e.style.minWidth=""}return e.setAttribute("data-mjx-clone-container","true"),e}chtmlClone(t,e,s){for(const i of e)if(i!==t){const t=i.getAttribute("data-semantic-id");t&&s.querySelector(`[data-semantic-id="${t}"]`)||s.appendChild(i.cloneNode(!0))}}svgClone(t,e,s,i){var r;let{x:n,y:o,width:a,height:l}=t.getBBox();if(e.length){s.firstChild.remove();const r=i.querySelector("g").cloneNode(!1);for(const s of e){const e=r.appendChild(s.cloneNode(!0));s===t&&e.setAttribute("data-mjx-clone","true");const[i,n]=this.xy(s);e.setAttribute("transform",`translate(${i}, ${n})`)}s.appendChild(r);const c=t.previousSibling,h=c.getBBox();a=h.width,l=h.height;const[d,u]=this.xy(c);n=d,o=u+h.y}const c=i.querySelector("g");if("full"===i.getAttribute("width")&&c.firstChild.lastChild===t)return s.innerHTML="",s.appendChild(i.cloneNode(!0).firstChild),s.querySelector(".mjx-selected").setAttribute("data-mjx-clone","true"),void(null===(r=s.querySelector("[data-sre-highlighter-added]"))||void 0===r||r.remove());s.firstChild.setAttribute("transform","scale(1, -1)");const h=parseFloat((s.getAttribute("viewBox")||s.getAttribute("data-mjx-viewBox")).split(/ /)[2]),d=parseFloat(s.style.minWidth||s.getAttribute("width"));s.setAttribute("viewBox",[n,-(o+l),a,l].join(" ")),s.removeAttribute("style"),s.setAttribute("width",d/h*a+"ex"),s.setAttribute("height",d/h*l+"ex")}xy(t){const e=DOMPoint.fromPoint({x:0,y:0}).matrixTransform(t.getCTM().inverse());return[-e.x,-e.y]}}RE.className="MJX_HoverRegion",RE.style=new oo({[`.${RE.className}`]:{display:"block",position:"absolute",width:"max-content",height:"auto",padding:0,opacity:1,"z-index":"202",margin:"0 auto","background-color":"white","line-height":0,"box-shadow":"0px 10px 20px #888",border:"2px solid #CCCCCC"},[`.${RE.className} > div`]:{overflow:"hidden",color:"var(--mjx-fg1-color)","background-color":"var(--mjx-bg1-color)"},"@media (prefers-color-scheme: dark)":{["."+RE.className]:{"background-color":"#222025","box-shadow":"0px 5px 20px #000",border:"1px solid #7C7C7C"}},"mjx-container[data-mjx-clone-container]":{padding:"2px ! important"},"mjx-math > mjx-mlabeledtr":{display:"inline-block","margin-right":".5em ! important"},"mjx-math > mjx-mtd":{float:"right"}});class SE{get highlighter(){return this.pool.highlighter}static stopEvent(t){t.preventDefault?t.preventDefault():t.returnValue=!1,t.stopImmediatePropagation?t.stopImmediatePropagation():t.stopPropagation&&t.stopPropagation(),t.cancelBubble=!0}static create(t,e,s,i,...r){return new this(t,e,s,i,...r)}constructor(t,e,s,i,...r){this.document=t,this.pool=e,this.region=s,this.node=i,this.stoppable=!0,this.events=[],this._active=!1}Events(){return this.events}get active(){return this._active}set active(t){this._active=t}Attach(){this.AddEvents()}Detach(){this.RemoveEvents()}Start(){this.active=!0}Stop(){this.active&&(this.region.Clear(),this.region.Hide(),this.active=!1)}AddEvents(){for(const[t,e]of this.events)this.node.addEventListener(t,e)}RemoveEvents(){for(const[t,e]of this.events)this.node.removeEventListener(t,e)}Update(t=!1){}stopEvent(t){this.stoppable&&SE.stopEvent(t)}}var ME=function(t,e,s,i){return new(s||(s=Promise))(function(r,n){function o(t){try{l(i.next(t))}catch(t){n(t)}}function a(t){try{l(i.throw(t))}catch(t){n(t)}}function l(t){var e;t.done?r(t.value):(e=t.value,e instanceof s?e:new s(function(t){t(e)})).then(o,a)}l((i=i.apply(t,e||[])).next())})};const IE="Windows"===ui.os,OE=Array(40).fill("\u2800").join(""),DE="[data-speech-node]";function PE(t){return t.matches("mjx-container")}function BE(t,e=!0){return t.shiftKey&&e||t.metaKey||t.altKey||t.ctrlKey}class FE extends SE{static helpMessage(t,e,s){return`\n

Exploring expressions ${t}

\n\n

The mathematics on this page is being rendered by MathJax, which\n generates both the text spoken by screen readers, as well as the\n visual layout for sighted users.

\n\n

Expressions typeset by MathJax can be explored interactively, and\n are focusable. You can use the Tab key to move to a typeset\n expression${e}. Initially, the expression will be read in full,\n but you can use the following keys to explore the expression\n further:

\n\n
    \n\n
  • Down Arrow moves one level deeper into the\n expression to allow you to explore the current subexpression term by\n term.
  • \n\n
  • Up Arrow moves back up a level within the\n expression.
  • \n\n
  • Right Arrow moves to the next term in the\n current subexpression.
  • \n\n
  • Left Arrow moves to the next term in the\n current subexpression.
  • \n\n
  • Shift+Arrow moves to a\n neighboring cell within a table.
  • \n\n
  • 0-9+0-9 jumps to a cell\n by its index in the table, where 0 = 10.
  • \n\n
  • Home takes you to the top of the\n expression.
  • \n\n
  • Enter or Return clicks a\n link or activates an active subexpression.
  • \n\n
  • Space opens the MathJax contextual menu\n where you can view or copy the source format of the expression, or\n modify MathJax's settings.
  • \n\n
  • Escape exits the expression\n explorer.
  • \n\n
  • x gives a summary of the current\n subexpression.
  • \n\n
  • z gives the full text of a collapsed\n expression.
  • \n\n
  • d gives the current depth within the\n expression.
  • \n\n
  • s starts or stops auto-voicing with\n synchronized highlighting.
  • \n\n
  • v marks the current position in the\n expression.
  • \n\n
  • p cycles through the marked positions in\n the expression.
  • \n\n
  • u clears all marked positions and returns\n to the starting position.
  • \n\n
  • > cycles through the available speech\n rule sets (MathSpeak, ClearSpeak).
  • \n\n
  • < cycles through the verbosity levels\n for the current rule set.
  • \n\n
  • b toggles whether Braille notation is combined\n with speech text for tactile Braille devices, as discussed\n below.\n\n
  • h produces this help listing.
  • \n
\n\n

The MathJax contextual menu allows you to enable or disable speech\n or Braille generation for mathematical expressions, the language to\n use for the spoken mathematics, and other features of MathJax. In\n particular, the Explorer submenu allows you to specify how the\n mathematics should be identified in the page (e.g., by saying "math"\n when the expression is spoken), and whether or not to include a\n message about the letter "h" bringing up this dialog box. Turning off\n speech and Braille will disable the expression explorer, its\n highlighting, and its help icon.

\n\n

Support for tactile Braille devices varies across screen readers,\n browsers, and operative systems. If you are using a Braille output\n device, you may need to select the "Combine with Speech" option in the\n contextual menu's Braille submenu in order to obtain Nemeth or Euro\n Braille output rather than the speech text on your Braille\n device. ${s}

\n\n

The contextual menu also provides options for viewing or copying a\n MathML version of the expression or its original source format,\n creating an SVG version of the expression, and viewing various other\n information.

\n\n

Finally, selecting the "Insert Hidden MathML" item from the options\n submenu will turn of MathJax's speech and Braille generation and\n instead use visually hidden MathML that some screen readers can voice,\n though support for this is not universal across all screen readers and\n operating systems. Selecting speech or Braille generation in their\n submenus will remove the hidden MathML again.

\n\n

For more help, see the MathJax accessibility documentation.

\n `}get generators(){var t;return null===(t=this.item)||void 0===t?void 0:t.generatorPool}get role(){return this.item.ariaRole}get description(){return this.item.roleDescription}get none(){return this.document.options.a11y.brailleSpeech?this.item.brailleNone:this.item.none}get brailleNone(){return this.item.brailleNone}FocusIn(t){t.target.closest("mjx-html")||(this.item.outputData.nofocus?this.item.outputData.nofocus=!1:(this.clicked||(this.Start(),this.backTab=t.target===this.img),this.clicked=null))}FocusOut(t){this.current&&!this.focusSpeech&&(this.document.options.keepRegions||(this.setCurrent(null),this.Stop()),document.hasFocus()||this.focusTop())}KeyDown(t){if(this.pendingIndex.shift(),this.region.cancelVoice(),BE(t,!1))return;const e=this.constructor,s=1===t.key.length?t.key.toLowerCase():t.key,[i,r]=e.keyMap.get(s)||[],n=i?void 0===r||this.active?i(this,t):r:this.undefinedKey(t);n||(this.stopEvent(t),!1===n&&this.sound&&this.NoMove())}MouseDown(t){var e;if(this.pendingIndex=[],this.region.cancelVoice(),BE(t)||2===t.buttons)return void(this.item.outputData.nofocus=!0);const s=this.findClicked(t.target,t.x,t.y);s!==this.document.infoIcon?(null===(e=document.getSelection())||void 0===e||e.removeAllRanges(),t.target.getAttribute("sre-highlighter-added")?this.refocus=s:this.clicked=s):this.stopEvent(t)}Click(t){if(BE(t)||2===t.buttons||"Range"===document.getSelection().type)return void this.FocusOut(null);const e=this.findClicked(t.target,t.x,t.y);if(e===this.document.infoIcon)return this.stopEvent(t),void this.help();this.clicked||e&&!this.node.contains(e)||(this.refocus=e,this.triggerLinkMouse()||this.Start())}DblClick(t){var e;const s=null!==(e=document.getSelection().direction)&&void 0!==e?e:"none";BE(t)||2===t.buttons||"none"!==s?this.FocusOut(null):(this.refocus=this.rootNode(),this.Start())}spaceKey(){return this.refocus=this.current,!0}hKey(){if(!this.document.options.enableExplorerHelp)return!0;this.refocus=this.current,this.help()}escapeKey(t){return t.target.closest("mjx-html")?(this.refocus=t.target.closest(DE),this.Start()):(this.Stop(),this.focusTop(),this.setCurrent(null)),!0}tabKey(t){var e;const s=null!==(e=this.current)&&void 0!==e?e:this.node.contains(document.activeElement)?document.activeElement:null;if(0===this.tabs.length||!s)return!0;if(this.backTab)return!t.shiftKey||void this.tabTo(this.tabs[this.tabs.length-1]);const[i,r,n]=t.shiftKey?[this.tabs.slice(0).reverse(),Node.DOCUMENT_POSITION_PRECEDING,this.current&&this.isLink()?this.getAnchor():s]:[this.tabs,Node.DOCUMENT_POSITION_FOLLOWING,s];for(const t of i)if(n.compareDocumentPosition(t)&r)return void this.tabTo(t);return t.shiftKey&&this.current===this.rootNode()&&this.tabOut(),!0}tabTo(t){t.getAttribute("data-mjx-href")?this.setCurrent(this.linkFor(t)):t.focus()}tabOut(){const t=Array.from(this.node.querySelectorAll("mjx-html"));t.length&&(t.forEach(t=>{t.style.display="none"}),setTimeout(()=>{t.forEach(t=>{t.style.display=""})},0))}enterKey(t){if(this.active)if(this.triggerLinkKeyboard(t))this.Stop();else{const t=this.actionable(this.current);if(t)return this.refocus=t,void t.dispatchEvent(new Event("click"));const e=this.getInternalTabs(this.current).filter(t=>!t.getAttribute("data-mjx-href"));if(e.length)return void e[0].focus()}else this.Start()}homeKey(){this.setCurrent(this.rootNode())}moveDown(t){return t?this.moveToNeighborCell(1,0):this.moveTo(this.firstNode(this.current))}moveUp(t){return t?this.moveToNeighborCell(-1,0):this.moveTo(this.getParent(this.current))}moveRight(t){return t?this.moveToNeighborCell(0,1):this.moveTo(this.nextSibling(this.current))}moveLeft(t){return t?this.moveToNeighborCell(0,-1):this.moveTo(this.prevSibling(this.current))}moveTo(t){if(!t)return!1;this.setCurrent(t)}moveToNeighborCell(t,e){const s=this.tableCell(this.current);if(!s)return!1;const[i,r]=this.cellPosition(s);if(null==i)return!1;const n=this.cellAt(this.cellTable(s),i+t,r+e);if(!n)return!1;this.setCurrent(n)}undefinedKey(t){return!this.active||BE(t)}addMark(){this.current===this.marks[this.marks.length-1]?this.setCurrent(this.current):(this.currentMark=this.marks.length-1,this.marks.push(this.current),this.speak("Position marked"))}prevMark(){if(this.currentMark<0){if(0===this.marks.length)return void this.setCurrent(this.lastMark||this.rootNode());this.currentMark=this.marks.length-1}const t=this.currentMark;this.setCurrent(this.marks[t]),this.currentMark=t-1}clearMarks(){this.marks=[],this.currentMark=-1,this.prevMark()}autoVoice(){const t=!this.document.options.a11y.voicing;this.document.menu?this.document.menu.menu.pool.lookup("voicing").setValue(t):this.document.options.a11y.voicing=t,this.Update()}toggleBraille(){const t=!this.document.options.a11y.brailleCombine;this.document.menu?this.document.menu.menu.pool.lookup("brailleCombine").setValue(t):this.document.options.a11y.brailleCombine=t}numberKey(t){if(!this.tableCell(this.current))return!1;if(0===t&&(t=10),this.pendingIndex.length){const e=this.cellTable(this.tableCell(this.current)),s=this.cellAt(e,this.pendingIndex[0]-1,t-1);if(this.pendingIndex=[],this.speak(String(t)),!s)return!1;setTimeout(()=>this.setCurrent(s),500)}else this.pendingIndex=[null,t],this.speak(`Jump to row ${t} and column`)}depth(){var t,e,s;if("d"===this.speechType)return void this.setCurrent(this.current);this.speechType="d";const i=[[null!==(t=this.node.getAttribute("data-semantic-level"))&&void 0!==t?t:"Level",null!==(e=this.current.getAttribute("data-semantic-level-number"))&&void 0!==e?e:"0"].join(" ").trim()],r=this.actionable(this.current);r&&i.unshift(null!==(s=this.node.getAttribute("1"===r.getAttribute("toggle")?"data-semantic-expandable":"data-semantic-collapsible"))&&void 0!==s?s:""),this.speak(i.join(" "),this.current.getAttribute(pE.BRAILLE))}summary(){if("x"===this.speechType)return void this.setCurrent(this.current);this.speechType="x";const t=this.current.getAttribute(pE.SUMMARY);this.speak(t,this.current.getAttribute(pE.BRAILLE),this.SsmlAttributes(this.current,pE.SUMMARY_SSML))}nextRules(){this.node.removeAttribute("data-speech-attached"),this.restartAfter(this.generators.nextRules(this.item))}nextStyle(){this.node.removeAttribute("data-speech-attached"),this.restartAfter(this.generators.nextStyle(this.current,this.item))}details(){const t=this.actionable(this.current);if(!t||!t.getAttribute("data-collapsible")||"1"!==t.getAttribute("toggle")||"z"===this.speechType)return void this.setCurrent(this.current);this.speechType="z";const e=this.nodeId(this.current);let s;this.item.root.walkTree(t=>{t.attributes.get("data-semantic-id")===e&&(s=t)});let i=this.item.toMathML(s,this.item);s.isKind("math")||(i=`${i}`),i=i.replace(/ (?:data-semantic-|aria-|data-speech-|data-latex).*?=".*?"/g,""),this.item.speechFor(i).then(([t,e])=>this.speak(t,e))}help(){if(!this.document.options.enableExplorerHelp)return;const t=this.constructor,[e,s,i]=t.helpData.get(ui.os);ho.post({title:"MathJax Expression Explorer Help",message:t.helpMessage(e,s,i),node:this.node,adaptor:this.document.adaptor,styles:{".mjx-dialog":{"max-height":"calc(min(35em, 90%))"},"mjx-dialog mjx-title":{"font-size":"133%",margin:".5em 1.75em"},"mjx-dialog h2":{"font-size":"20px",margin:".5em 0"},"mjx-dialog ul":{"list-style-type":"none"},"mjx-dialog li":{"margin-bottom":".5em"}}})}setCurrent(t,e=!1){if(this.backTab=!1,this.speechType="",document.hasFocus()||(this.refocus=this.current),this.node.setAttribute("aria-busy","true"),this.current){this.pool.unhighlight();for(const t of Array.from(this.node.querySelectorAll(".mjx-selected")))t.classList.remove("mjx-selected");"last"===this.document.options.a11y.tabSelects&&(this.refocus=this.current),t||(this.lastMark=this.current,this.removeSpeech()),this.current=null}if(this.current=t,this.currentMark=-1,this.current){const s=[...this.getSplitNodes(this.current)];this.highlighter.encloseNodes(s,this.node);for(const t of s)t.getAttribute("data-sre-enclosed")||t.classList.add("mjx-selected");this.pool.highlight(s),this.addSpeech(t,e),this.node.setAttribute("tabindex","-1"),this.Update()}this.node.removeAttribute("aria-busy")}getSplitNodes(t){const e=this.nodeId(t);if(!e)return[t];if(this.cacheParts.has(e))return this.cacheParts.get(e);const s=Array.from(this.node.querySelectorAll(`[data-semantic-id="${e}"]`)),i=this.subtree(e,s);return this.cacheParts.set(e,[...s,...i]),this.cacheParts.get(e)}subtree(t,e){const s=this.subtrees.get(t),i=new Set;for(const t of e)Array.from(t.querySelectorAll("[data-semantic-id]")).forEach(t=>i.add(this.nodeId(t)));return[...function(t,e){if(!t)return new Set;if(!e)return t;return new Set([...t].filter(t=>!e.has(t)))}(s,i)].map(t=>this.getNode(t)).filter(t=>null!==t)}addSpeech(t,e){var s;if(!this.document.options.enableSpeech&&!this.document.options.enableBraille)return;this.anchors.length?setTimeout(()=>{var t;return null===(t=this.img)||void 0===t?void 0:t.remove()},10):null===(s=this.img)||void 0===s||s.remove();let i=this.addComma([t.getAttribute(pE.PREFIX),t.getAttribute(pE.SPEECH),t.getAttribute(pE.POSTFIX)]).join(" ").trim();if(e){let t=this.description===this.none?"":", "+this.description;this.document.options.a11y.help&&this.document.options.enableExplorerHelp&&(t+=", press h for help"),i+=t}this.speak(i,t.getAttribute(pE.BRAILLE),this.SsmlAttributes(t,pE.SPEECH_SSML))}addComma(t){return t[2]&&(t[1]||t[0])&&(t[1]+=","),t}removeSpeech(){this.speech&&(this.unspeak(this.speech),this.speech=null,this.img&&this.node.append(this.img),this.node.setAttribute("tabindex",this.tabIndex))}speak(t,e="",s=null,i=this.none){const r=this.speech,n=this.speech=document.createElement("mjx-speech");if(n.setAttribute("role",this.role),n.setAttribute("aria-label",t||this.none),n.setAttribute("aria-roledescription",i||this.none),n.setAttribute(pE.SPEECH,t),s&&(n.setAttribute(pE.PREFIX_SSML,s[0]||""),n.setAttribute(pE.SPEECH_SSML,s[1]||""),n.setAttribute(pE.POSTFIX_SSML,s[2]||"")),e&&(this.document.options.a11y.brailleSpeech&&(n.setAttribute("aria-label",e),n.setAttribute("aria-roledescription",this.brailleNone)),n.setAttribute("aria-braillelabel",e),n.setAttribute("aria-brailleroledescription",this.brailleNone),this.document.options.a11y.brailleCombine&&n.setAttribute("aria-label",e+OE+t)),n.setAttribute("tabindex","0"),IE){const t=document.createElement("mjx-speech-container");t.setAttribute("role","application"),t.setAttribute("aria-roledescription",this.none),t.setAttribute("aria-brailleroledescription",this.brailleNone),t.append(n),this.node.append(t),n.setAttribute("role","img")}else this.node.append(n);this.focusSpeech=!0,n.focus(),this.focusSpeech=!1,this.Update(),r&&setTimeout(()=>this.unspeak(r),100)}unspeak(t){IE&&(t=t.parentElement),t.remove()}attachSpeech(){var t;const e=this.item,s=this.node;if(!s.hasAttribute("has-speech")){for(const t of Array.from(s.childNodes))t.setAttribute("aria-hidden","true");s.setAttribute("has-speech","true")}const i=e.roleDescription,r=(s.getAttribute(pE.SPEECH)||"")+(i?", "+i:"");null===(t=this.img)||void 0===t||t.remove(),this.img=this.document.adaptor.node("mjx-speech",{"aria-label":r,role:"img","aria-roledescription":e.none});const n=s.getAttribute(pE.BRAILLE);n&&(this.document.options.a11y.brailleSpeech&&(this.img.setAttribute("aria-label",n),this.img.setAttribute("aria-roledescription",this.brailleNone)),this.img.setAttribute("aria-braillelabel",n),this.img.setAttribute("aria-brailleroledescription",this.brailleNone),this.document.options.a11y.brailleCombine&&this.img.setAttribute("aria-label",n+OE+r)),s.appendChild(this.img),this.adjustAnchors(),this.getTabs()}detachSpeech(){var t;const e=this.node;null===(t=this.img)||void 0===t||t.remove(),e.removeAttribute("has-speech");for(const t of Array.from(e.childNodes))t.removeAttribute("aria-hidden");this.restoreAnchors()}adjustAnchors(){this.anchors=Array.from(this.node.querySelectorAll("a[href]"));for(const t of this.anchors){const e=t.getAttribute("href");t.setAttribute("data-mjx-href",e),t.removeAttribute("href")}this.anchors.length&&this.img.setAttribute("tabindex","0")}restoreAnchors(){for(const t of this.anchors)t.setAttribute("href",t.getAttribute("data-mjx-href")),t.removeAttribute("data-mjx-href");this.anchors=[]}getTabs(){this.tabs=this.getInternalTabs(this.node)}getInternalTabs(t){return Array.from(t.querySelectorAll('button, [data-mjx-href], input, select, textarea, [tabindex]:not([tabindex="-1"],mjx-speech)'))}focus(){this.node.focus()}nodeId(t){return t.getAttribute("data-semantic-id")}parentId(t){return t.getAttribute("data-semantic-parent")}getNode(t){return t?this.node.querySelector(`[data-semantic-id="${t}"]`):null}getParent(t){return this.getNode(this.parentId(t))}childArray(t){return t?t.getAttribute("data-semantic-children").split(/,/):[]}isCell(t){return!!t&&this.cellTypes.includes(t.getAttribute("data-semantic-type"))}isRow(t){return!!t&&"row"===t.getAttribute("data-semantic-type")}tableCell(t){for(;t&&t!==this.node;){if(this.isCell(t))return t;t=t.parentNode}return null}cellTable(t){const e=this.getParent(t);return this.isRow(e)?this.getParent(e):e}cellPosition(t){const e=this.getParent(t),s=this.childArray(e).indexOf(this.nodeId(t));if(!this.isRow(e))return[s,1];const i=this.getParent(e);return[this.childArray(i).indexOf(this.nodeId(e)),s]}cellAt(t,e,s){const i=this.getNode(this.childArray(t)[e]);if(!this.isRow(i))return 1===s?i:null;return this.getNode(this.childArray(i)[s])}firstNode(t){const e=t.getAttribute("data-semantic-owns");if(!e)return t.querySelector(DE);const s=e.split(/ /);for(const t of s){const e=this.getNode(t);if(null==e?void 0:e.hasAttribute("data-speech-node"))return e}return t.querySelector(DE)}rootNode(){const t=this.node.querySelector("[data-semantic-structure]");if(!t)return this.node.querySelector(DE);const e=t.getAttribute("data-semantic-structure").split(/ /)[0].replace("(","");return this.getNode(e)}nextSibling(t){var e;const s=this.parentId(t);if(!s)return null;const i=null===(e=this.getNode(s).getAttribute("data-semantic-owns"))||void 0===e?void 0:e.split(/ /);if(!i)return null;let r,n=i.indexOf(this.nodeId(t));do{r=this.getNode(i[++n])}while(r&&!r.hasAttribute("data-speech-node"));return r}prevSibling(t){var e;const s=this.parentId(t);if(!s)return null;const i=null===(e=this.getNode(s).getAttribute("data-semantic-owns"))||void 0===e?void 0:e.split(/ /);if(!i)return null;let r,n=i.indexOf(this.nodeId(t));do{r=this.getNode(i[--n])}while(r&&!r.hasAttribute("data-speech-node"));return r}findClicked(t,e,s){const i=this.document.infoIcon;if(i===t||i.contains(t))return i;if("SVG"!==this.node.getAttribute("jax"))return t.closest(DE);let r=null,n=this.node;for(;n;){n.matches(DE)&&(r=n);const t=Array.from(n.childNodes);n=null;for(const i of t)if(i!==this.speech&&i!==this.img&&i.tagName&&"rect"!==i.tagName.toLowerCase()){const{left:t,right:r,top:o,bottom:a}=i.getBoundingClientRect();if(t<=e&&e<=r&&o<=s&&s<=a){n=i;break}}}return r}isLink(t=this.current){var e;return!!(null===(e=null==t?void 0:t.getAttribute("data-semantic-attributes"))||void 0===e?void 0:e.includes("href:"))}getAnchor(t=this.current){const e=t.closest("a");return e&&this.node.contains(e)?e:null}linkFor(t){return null==t?void 0:t.querySelector('[data-semantic-attributes*="href:"]')}parentLink(t){const e=null==t?void 0:t.closest('[data-semantic-attributes*="href:"]');return e&&this.node.contains(e)?e:null}focusTop(){this.focusSpeech=!0,this.node.focus(),this.focusSpeech=!1}SsmlAttributes(t,e){return[t.getAttribute(pE.PREFIX_SSML),t.getAttribute(e),t.getAttribute(pE.POSTFIX_SSML)]}restartAfter(t){return ME(this,void 0,void 0,function*(){yield t,this.attachSpeech();const e=this.current;this.current=null,this.pool.unhighlight(),this.setCurrent(e)})}constructor(t,e,s,i,r,n,o,a){super(t,e,null,i),this.document=t,this.pool=e,this.region=s,this.node=i,this.brailleRegion=r,this.magnifyRegion=n,this.item=a,this.sound=!1,this.current=null,this.clicked=null,this.refocus=null,this.focusSpeech=!1,this.restarted=null,this.speech=null,this.speechType="",this.img=null,this.attached=!1,this.eventsAttached=!1,this.marks=[],this.currentMark=-1,this.lastMark=null,this.pendingIndex=[],this.cellTypes=["cell","line"],this.backTab=!1,this.events=super.Events().concat([["focusin",this.FocusIn.bind(this)],["focusout",this.FocusOut.bind(this)],["keydown",this.KeyDown.bind(this)],["mousedown",this.MouseDown.bind(this)],["click",this.Click.bind(this)],["dblclick",this.DblClick.bind(this)]]),this.subtrees=null,this.cacheParts=new Map}findStartNode(){let t=this.refocus||this.current;return!t&&this.restarted&&(t=this.node.querySelector(this.restarted)),this.refocus=this.restarted=null,t}Start(){const t=Object.create(null,{Start:{get:()=>super.Start}});return ME(this,void 0,void 0,function*(){if(this.subtrees||(this.subtrees=new Map,this.getSubtrees()),!this.attached||this.active)return;if(this.document.activeItem=this.item,this.item.state(){t.contains(document.activeElement)&&(e instanceof KeyboardEvent?(this.clicked=null,"Tab"!==e.key&&"Escape"!==e.key&&e.stopPropagation()):this.clicked=e.target)};t.addEventListener("mousedown",e),t.addEventListener("click",e),t.addEventListener("keydown",e),t.addEventListener("dblclick",e)}}actionable(t){const e=null==t?void 0:t.parentNode;return e&&this.highlighter.isMactionNode(e)?e:null}triggerLinkKeyboard(t){return this.current?this.triggerLink(this.current):t.target instanceof HTMLAnchorElement&&(t.target.dispatchEvent(new MouseEvent("click")),!0)}triggerLink(t){if(this.isLink(t)){const e=this.getAnchor(t);return e.classList.add("mjx-visited"),setTimeout(()=>this.FocusOut(null),50),window.location.href=e.getAttribute("data-mjx-href"),!0}return!1}triggerLinkMouse(){const t=this.parentLink(this.refocus);return!!this.triggerLink(t)}semanticFocus(){const t=[];let e="data-semantic-id",s=this.current||this.refocus||this.node;const i=this.actionable(s);i&&(e=i.hasAttribute("data-maction-id")?"data-maction-id":"id",s=i,t.push(DE));const r=s.getAttribute(e);return r&&t.unshift(`[${e}="${r}"]`),t.join(" ")}getSubtrees(){const t=this.node.querySelector("[data-semantic-structure]");if(!t)return;const e=t.getAttribute("data-semantic-structure");const s=function(t){const e=[[]];for(const s of t)if("("===s){const t=[];e[e.length-1].push(t),e.push(t)}else")"===s?e.pop():e[e.length-1].push(s);return e[0][0]}(e.replace(/\(/g," ( ").replace(/\)/g," ) ").trim().split(/\s+/));jE(s,this.subtrees)}}function jE(t,e){if("string"==typeof t)return e.has(t)||e.set(t,new Set),new Set;const[s,...i]=t,r=s,n=new Set;for(const t of i){const s="string"==typeof t?t:t[0],i=jE(t,e);n.add(s),i.forEach(t=>n.add(t))}return e.set(r,n),n}FE.helpData=new Map([["MacOS",["on MacOS and iOS using VoiceOver",", or the VoiceOver arrow keys to select an expression",""]],["Windows",["in Windows using NVDA or JAWS",". The screen reader should enter focus or forms mode automatically\n when the expression gets the browser focus, but if not, you can toggle\n focus mode using NVDA+space in NVDA; for JAWS, Enter should start\n forms mode while Numpad Plus leaves it. Also note that you can use\n the NVDA or JAWS key plus the arrow keys to explore the expression\n even in browse mode, and you can use NVDA+shift+arrow keys to\n navigate out of an expression that has the focus in NVDA","NVDA users need to select this option, while JAWS users should be able\n to get Braille output without changing this setting."]],["Unix",["in Unix using Orca",", and Orca should enter focus mode automatically. If not, use the\n Orca+a key to toggle focus mode on or off. Also note that you can use\n Orca+arrow keys to explore expressions even in browse mode",""]],["unknown",["with a Screen Reader.","",""]]]),FE.keyMap=new Map([["Tab",[(t,e)=>t.tabKey(e)]],["Escape",[(t,e)=>t.escapeKey(e)]],["Enter",[(t,e)=>t.enterKey(e)]],["Home",[t=>t.homeKey()]],["ArrowDown",[(t,e)=>t.moveDown(e.shiftKey),!0]],["ArrowUp",[(t,e)=>t.moveUp(e.shiftKey),!0]],["ArrowLeft",[(t,e)=>t.moveLeft(e.shiftKey),!0]],["ArrowRight",[(t,e)=>t.moveRight(e.shiftKey),!0]],[" ",[t=>t.spaceKey()]],["h",[t=>t.hKey()]],[">",[t=>t.nextRules(),!1]],["<",[t=>t.nextStyle(),!1]],["x",[t=>t.summary(),!1]],["z",[t=>t.details(),!1]],["d",[t=>t.depth(),!1]],["v",[t=>t.addMark(),!1]],["p",[t=>t.prevMark(),!1]],["u",[t=>t.clearMarks(),!1]],["s",[t=>t.autoVoice(),!1]],["b",[t=>t.toggleBraille(),!1]],...[..."0123456789"].map(t=>[t,[e=>e.numberKey(parseInt(t)),!1]])]);class UE extends SE{constructor(){super(...arguments),this.events=super.Events().concat([["mouseover",this.MouseOver.bind(this)],["mouseout",this.MouseOut.bind(this)]])}MouseOver(t){this.Start()}MouseOut(t){this.Stop()}}class HE extends UE{constructor(t,e,s,i,r,n){super(t,e,s,i),this.document=t,this.pool=e,this.region=s,this.node=i,this.nodeQuery=r,this.nodeAccess=n}MouseOut(t){this.highlighter.unhighlight(),this.region.Hide(),super.MouseOut(t)}MouseOver(t){super.MouseOver(t);const e=t.target,[s,i]=this.getNode(e);s&&(this.highlighter.unhighlight(),this.highlighter.highlight([s]),this.region.Update(i),this.region.Show(s))}getNode(t){const e=t;for(;t&&t!==this.node;){if(this.nodeQuery(t))return[t,this.nodeAccess(t)];t=t.parentNode}for(t=e;t;){if(this.nodeQuery(t))return[t,this.nodeAccess(t)];const e=t.childNodes[0];t=e&&"defs"===e.tagName?t.childNodes[1]:e}return[null,null]}}class qE extends HE{}class WE extends HE{}class zE extends HE{constructor(t,e,s,i){super(t,e,new CE(t),i,t=>this.highlighter.isMactionNode(t),()=>{}),this.document=t,this.pool=e,this.node=i}}class VE extends SE{constructor(t,e,s,i,r){super(t,e,null,i),this.document=t,this.pool=e,this.region=s,this.node=i,this.mml=r,this.stoppable=!1}Attach(){super.Attach(),this.Start()}Detach(){this.Stop(),super.Detach()}}class XE extends VE{Start(){this.active||(this.active=!0,this.highlighter.highlightAll(this.node))}Stop(){this.active&&this.highlighter.unhighlightAll(),this.active=!1}}class GE extends VE{constructor(){super(...arguments),this.contrast=new JE,this.leaves=[],this.modality="data-semantic-foreground"}Start(){this.active||(this.active=!0,this.node.hasAttribute("hasforegroundcolor")||(this.colorLeaves(),this.node.setAttribute("hasforegroundcolor","true")),this.leaves.forEach(t=>this.colorize(t)))}Stop(){this.active&&this.leaves.forEach(t=>this.uncolorize(t)),this.active=!1}colorLeaves(){this.leaves=Array.from(this.node.querySelectorAll("[data-semantic-id]:not([data-semantic-children])"));for(const t of this.leaves)t.setAttribute(this.modality,this.contrast.generate()),this.contrast.increment()}colorize(t){t.hasAttribute(this.modality)&&(t.setAttribute(this.modality+"-old",t.style.color),t.style.color=t.getAttribute(this.modality))}uncolorize(t){const e=this.modality+"-old";t.hasAttribute(e)&&(t.style.color=t.getAttribute(e))}}class JE{constructor(){this.hue=10,this.sat=100,this.light=50,this.incr=53}generate(){return JE.hsl2rgb(this.hue,this.sat,this.light)}increment(){this.hue=(this.hue+this.incr)%360}static hsl2rgb(t,e,s){e=e>1?e/100:e,s=s>1?s/100:s;const i=(1-Math.abs(2*s-1))*e,r=i*(1-Math.abs(t/60%2-1)),n=s-i/2;let o=0,a=0,l=0;return 0<=t&&t<60?[o,a,l]=[i,r,0]:60<=t&&t<120?[o,a,l]=[r,i,0]:120<=t&&t<180?[o,a,l]=[0,i,r]:180<=t&&t<240?[o,a,l]=[0,r,i]:240<=t&&t<300?[o,a,l]=[r,0,i]:300<=t&&t<360&&([o,a,l]=[i,0,r]),`rgb(${255*(o+n)}, ${255*(a+n)}, ${255*(l+n)})`}}const KE={color:"blue",alpha:.2},$E={color:"black",alpha:1},YE={ENCLOSED:"data-sre-enclosed",BBOX:"data-sre-highlighter-bbox",ADDED:"data-sre-highlighter-added"};class QE{constructor(t){this.currentHighlights=[],this.priority=t,this.ATTR="data-sre-highlight-"+t}highlight(t){this.currentHighlights.push(t);for(const e of t)this.highlightNode(e),this.setHighlighted(e)}highlightAll(t){const e=this.getMactionNodes(t);for(const t of e)this.highlight([t])}unhighlight(){const t=this.currentHighlights.pop();t&&t.forEach(t=>{this.isHighlighted(t)&&(this.unhighlightNode(t),this.unsetHighlighted(t))})}unhighlightAll(){for(;this.currentHighlights.length>0;)this.unhighlight()}encloseNodes(t,e){if(1===t.length)return t;const s=this.constructor,i=s.lineSelector,r=s.lineAttr,n=new Map;for(const e of t){const t=e.closest(i),s=t?t.getAttribute(r):"";n.has(s)||n.set(s,[]),n.get(s).push(e)}for(const s of n.values())if(s.length>1){let[i,r,n,o]=[1/0,1/0,-1/0,-1/0];for(const t of s){t.setAttribute(YE.ENCLOSED,"true");const{left:e,top:s,right:a,bottom:l}=t.getBoundingClientRect();s===l&&e===a||(eo&&(o=l),a>n&&(n=a))}const a=this.createEnclosure(i,o,n-i,o-r,e,s[0]);t.push(a)}return t}setColorCSS(t,e,s){var i,r;const n=null!==(i=e.color)&&void 0!==i?i:s.color,o=null!==(r=e.alpha)&&void 0!==r?r:s.alpha;LE.setColor(t,this.priority,n,o)}setColor(t,e){this.setColorCSS("fg",e,$E),this.setColorCSS("bg",t,KE)}isHighlighted(t){return t.hasAttribute(this.ATTR)}setHighlighted(t){t.setAttribute(this.ATTR,"true")}unsetHighlighted(t){t.removeAttribute(this.ATTR),t.removeAttribute(YE.ENCLOSED)}}class ZE extends QE{highlightNode(t){if(this.isHighlighted(t)||"svg"===t.tagName||"MJX-CONTAINER"===t.tagName||t.hasAttribute(YE.BBOX)||t.hasAttribute(YE.ENCLOSED))return;const{x:e,y:s,width:i,height:r}=t.getBBox(),n=this.createRect(e,s,i,r,t.getAttribute("transform"));this.setHighlighted(n),t.parentNode.insertBefore(n,t)}unhighlightNode(t){if(t.hasAttribute(YE.BBOX))return void t.remove();const e=t.previousSibling;(null==e?void 0:e.hasAttribute(YE.ADDED))&&e.remove()}createEnclosure(t,e,s,i,r,n){const[o,a]=this.screen2svg(t,e,n),[l,c]=this.screen2svg(t+s,e-i,n),h=this.createRect(o,a,l-o,c-a,n.getAttribute("transform"));return h.setAttribute(YE.BBOX,"true"),n.parentNode.insertBefore(h,n),h}screen2svg(t,e,s){const i=s,r=DOMPoint.fromPoint({x:t,y:e}).matrixTransform(i.getScreenCTM().inverse());return[r.x,r.y]}createRect(t,e,s,i,r){const n=document.createElementNS("http://www.w3.org/2000/svg","rect");return n.setAttribute(YE.ADDED,"true"),n.setAttribute("x",String(t-40)),n.setAttribute("y",String(e-40)),n.setAttribute("width",String(s+80)),n.setAttribute("height",String(i+80)),r&&n.setAttribute("transform",r),n}isMactionNode(t){return"maction"===t.getAttribute("data-mml-node")}getMactionNodes(t){return Array.from(t.querySelectorAll('[data-mml-node="maction"]'))}}ZE.lineSelector="[data-mjx-linebox]",ZE.lineAttr="data-mjx-lineno";class tx extends QE{highlightNode(t){}unhighlightNode(t){"mjx-bbox"===t.tagName.toLowerCase()&&t.remove()}createEnclosure(t,e,s,i,r){const n=r.getBoundingClientRect(),o=document.createElement("mjx-bbox");return o.style.width=s+"px",o.style.height=i+"px",o.style.left=t-n.left+"px",o.style.top=e-i-n.top+"px",o.style.position="absolute",r.prepend(o),o}isMactionNode(t){var e;return"mjx-maction"===(null===(e=t.tagName)||void 0===e?void 0:e.toLowerCase())}getMactionNodes(t){return Array.from(t.querySelectorAll("mjx-maction"))}}function ex(t,e,s,i){const r=new sx[i](t);return r.setColor(e,s),r}tx.lineSelector="mjx-linebox",tx.lineAttr="lineno";const sx={SVG:ZE,CHTML:tx,generic:tx};class ix{constructor(t){this.document=t,this.speechRegion=new AE(this.document),this.brailleRegion=new LE(this.document),this.magnifier=new RE(this.document),this.tooltip1=new _E(this.document),this.tooltip2=new _E(this.document),this.tooltip3=new _E(this.document)}}const rx={speech:(t,e,s,...i)=>{const r=FE.create(t,e,t.explorerRegions.speechRegion,s,t.explorerRegions.brailleRegion,t.explorerRegions.magnifier,i[0],i[1]);return r.sound=!0,r},mouseMagnifier:(t,e,s,...i)=>WE.create(t,e,t.explorerRegions.magnifier,s,t=>t.hasAttribute("data-semantic-type"),t=>t),hover:(t,e,s,...i)=>zE.create(t,e,null,s),infoType:(t,e,s,...i)=>qE.create(t,e,t.explorerRegions.tooltip1,s,t=>t.hasAttribute("data-semantic-type"),t=>t.getAttribute("data-semantic-type")),infoRole:(t,e,s,...i)=>qE.create(t,e,t.explorerRegions.tooltip2,s,t=>t.hasAttribute("data-semantic-role"),t=>t.getAttribute("data-semantic-role")),infoPrefix:(t,e,s,...i)=>qE.create(t,e,t.explorerRegions.tooltip3,s,t=>{var e;return null===(e=t.hasAttribute)||void 0===e?void 0:e.call(t,"data-semantic-prefix-none")},t=>{var e;return null===(e=t.getAttribute)||void 0===e?void 0:e.call(t,"data-semantic-prefix-none")}),flame:(t,e,s,...i)=>XE.create(t,e,null,s),treeColoring:(t,e,s,...i)=>GE.create(t,e,null,s,...i)};class nx{constructor(){this.explorers={},this.attached=[],this._restart=[],this.speechExplorerKeys=["speech","braille","keyMagnifier"]}get highlighter(){if(this._renderer!==this.document.outputJax.name)return this._renderer=this.document.outputJax.name,this.setPrimaryHighlighter(),this._highlighter;const[t,e]=this.colorOptions();return this._highlighter.setColor(e,t),this._highlighter}init(t,e,s,i){this.document=t,this.mml=s,this.node=e,this.setPrimaryHighlighter();for(const t of Object.keys(rx))this.explorers[t]=rx[t](this.document,this,this.node,this.mml,i);this.setSecondaryHighlighter(),this.attach()}attach(){this.attached=[];const t=[],e=this.document.options.a11y;for(const[s,i]of Object.entries(this.explorers))i instanceof FE?(i.stoppable=!1,t.unshift(i),this.speechExplorerKeys.some(t=>this.document.options.a11y[t])?(i.Attach(),this.attached.push(s)):i.Detach()):e[s]||"speech"===s&&(e.braille||e.keyMagnifier)?(i.Attach(),this.attached.push(s)):i.Detach();for(const e of t)if(e.attached){e.stoppable=!0;break}}reattach(){for(const t of this.attached){const e=this.explorers[t];e.active&&(this._restart.push(t),e.Stop())}}restart(){this._restart.forEach(t=>{this.explorers[t].Start()}),this._restart=[]}setPrimaryHighlighter(){const[t,e]=this.colorOptions();this._highlighter=ex(LE.priority.primary,e,t,this.document.outputJax.name)}setSecondaryHighlighter(){this.secondaryHighlighter=ex(LE.priority.secondary,{color:"red",alpha:.8},{color:"black"},this.document.outputJax.name),this.speech.region.highlighter=this.secondaryHighlighter}highlight(t){this.highlighter.highlight(t)}unhighlight(){this.secondaryHighlighter.unhighlight(),this.highlighter.unhighlight()}get speech(){return this.explorers.speech}colorOptions(){const t=this.document.options.a11y;return[{color:t.foregroundColor.toLowerCase(),alpha:t.foregroundOpacity/100},{color:t.backgroundColor.toLowerCase(),alpha:t.backgroundOpacity/100}]}}const ox="Unix"===ui.os;function ax(t,e){var s;return s=class extends t{constructor(){super(...arguments),this.refocus=null}get ariaRole(){return this.constructor.ariaRole}get roleDescription(){const t=this.constructor;return"none"===t.roleDescription?t.none:t.roleDescription}get none(){return this.constructor.none}get brailleNone(){return this.constructor.brailleNone}attachSpeech(t){var e,s;super.attachSpeech(t),null===(s=null===(e=this.outputData.speechPromise)||void 0===e?void 0:e.then(()=>this.explorers.speech.attachSpeech()))||void 0===s||s.then(()=>{var t;(null===(t=this.explorers)||void 0===t?void 0:t.speech)&&(this.explorers.speech.restarted=this.refocus),this.refocus=null,this.explorers&&this.explorers.restart()})}detachSpeech(t){super.detachSpeech(t),this.explorers.speech.detachSpeech()}explorable(t,s=!1){if(!(this.state()>=or.EXPLORER)){if(!this.isEscaped&&(t.options.enableExplorer||s)){const s=this.typesetRoot,i=e(this.root);this.explorers||(this.explorers=new nx),this.explorers.init(t,s,i,this)}this.state(or.EXPLORER)}}state(t=null,e=!1){if(tsetTimeout(()=>t.remove(),100))}}},s.ariaRole=ox?"tree":"application",s.roleDescription="math",s.none="\x91",s.brailleNone="\u2800",s}function lx(t){var e;return e=class extends t{constructor(...t){super(...t),this.explorerRegions=null,this.activeItem=null;const e=this.constructor.ProcessBits;e.has("explorer")||e.allocate("explorer");const s=new $n(this.mmlFactory),i=this.options;i.a11y.speechRules||(i.a11y.speechRules=`${i.sre.domain}-${i.sre.style}`);const r=i.MathItem=ax(i.MathItem,t=>s.visitTree(t));r.roleDescription=i.roleDescription,this.explorerRegions=new ix(this),"addStyles"in this&&this.addStyles(this.constructor.speechStyles);const n=this.adaptor,o="http://www.w3.org/2000/svg";this.infoIcon=n.node("mjx-help",{},[n.node("svg",{viewBox:"0 0 18 18",xmlns:o,"aria-hidden":"true"},[n.node("circle",{stroke:"none"},[],o),n.node("circle",{},[],o),n.node("line",{x1:9,y1:9,x2:9,y2:13},[],o),n.node("line",{x1:9,y1:5.5,x2:9,y2:5.5},[],o)],o)]),this.tmpFocus=n.node("mjx-focus",{tabIndex:0,style:{outline:"none",display:"block",position:"absolute",top:0,left:"-10px",width:"1px",height:"1px",overflow:"hidden"},role:r.ariaRole,"aria-label":r.none,"aria-roledescription":r.none})}explorable(){if(!this.processed.isSet("explorer")){if(this.options.enableExplorer)for(const t of this.math)t.explorable(this);this.processed.set("explorer")}return this}rerender(t){const e=this.activeItem,s=null==e?void 0:e.setTemporaryFocus(this);return super.rerender(t),null==e||e.clearTemporaryFocus(s),this}state(t,e=!1){return super.state(t,e),t mjx-help":{display:"none",position:"absolute",top:"-.3em",right:"-.5em",width:".6em",height:".6em",cursor:"pointer"},'mjx-container[display="true"] > mjx-help':{position:"sticky",inset:"-100% 0 100% 0",margin:"-.3em -.5em 0 -.1em",right:0,top:"initial"},"mjx-help > svg":{stroke:"black",width:"100%",height:"100%"},"mjx-help > svg > circle":{"stroke-width":"1.5px",cx:"9px",cy:"9px",r:"9px",fill:"white"},"mjx-help > svg > circle:nth-child(2)":{fill:"var(--mjx-bg1-color)",r:"7px"},"mjx-help > svg > line":{"stroke-width":"2.5px","stroke-linecap":"round"},"mjx-help:hover > svg > circle:nth-child(2)":{fill:"white"},"mjx-container.mjx-explorer-active > mjx-help":{display:"inline-flex","align-items":"center"},"@media (prefers-color-scheme: dark) /* explorer */":{"mjx-help > svg":{stroke:"#E0E0E0"},"mjx-help > svg > circle":{fill:"#404040"},"mjx-help > svg > circle:nth-child(2)":{fill:"rgba(132, 132, 255, .3)"},"mjx-help:hover > svg > circle:nth-child(2)":{stroke:"#AAAAAA",fill:"#404040"}}},e}function cx(t,e=null){return t.documentClass.prototype.attachSpeech||(t=TE(t,e)),t.documentClass=lx(t.documentClass),t}function hx(t,e){var s;const i=xb();for(const s in e)void 0!==t.options.a11y[s]?dx(t,s,e[s]):void 0!==i[s]&&(t.options.sre[s]=e[s]);e.roleDescription&&(t.options.MathItem.roleDescription=e.roleDescription);for(const e of t.math)null===(s=null==e?void 0:e.explorers)||void 0===s||s.attach()}function dx(t,e,s){switch(e){case"speechRules":{const[e,i]=s.split("-");t.options.sre.domain=e,t.options.sre.style=i;break}case"magnification":switch(s){case"None":t.options.a11y.magnification=s,t.options.a11y.keyMagnifier=!1,t.options.a11y.mouseMagnifier=!1;break;case"Keyboard":t.options.a11y.magnification=s,t.options.a11y.keyMagnifier=!0,t.options.a11y.mouseMagnifier=!1;break;case"Mouse":t.options.a11y.magnification=s,t.options.a11y.keyMagnifier=!1,t.options.a11y.mouseMagnifier=!0}break;case"highlight":switch(s){case"None":t.options.a11y.highlight=s,t.options.a11y.hover=!1,t.options.a11y.flame=!1;break;case"Hover":t.options.a11y.highlight=s,t.options.a11y.hover=!0,t.options.a11y.flame=!1;break;case"Flame":t.options.a11y.highlight=s,t.options.a11y.hover=!1,t.options.a11y.flame=!0}break;case"locale":t.options.sre.locale=s;break;default:t.options.a11y[e]=s}}ar("EXPLORER",or.INSERTED+30),MathJax.loader&&MathJax.loader.checkVersion("a11y/explorer",ii,"a11y"),ci({_:{a11y:{explorer_ts:si,explorer:{Explorer:$s,ExplorerPool:ei,Highlighter:ti,KeyExplorer:Ys,MouseExplorer:Qs,Region:Ks,TreeExplorer:Zs}}}}),MathJax.startup&&di&&MathJax.startup.extendHandler(t=>cx(t)),Ni.preLoaded("a11y/sre","a11y/semantic-enrich","a11y/speech","a11y/explorer","input/mml"),Ni.preLoaded("loader","startup","core","input/tex","input/mml","output/chtml","ui/menu"),Ni.saveVersion("tex-mml-chtml"),function(t,e){ru.loadFont(t,"chtml",Zd,e)}(function(t){return Ni.load(...Ti.load).then(()=>(t||function(){})()).then(()=>Ti.ready()).catch(t=>Ti.failed(t))},!0)})()})(); \ No newline at end of file diff --git a/docs/_static/mermaid-intrinsic-size.js b/docs/_static/mermaid-intrinsic-size.js new file mode 100644 index 0000000..fbf1f96 --- /dev/null +++ b/docs/_static/mermaid-intrinsic-size.js @@ -0,0 +1,79 @@ +// Force every mermaid SVG to render at its intrinsic viewBox width. +// +// Mermaid emits width="100%" on the SVG element, even when its config is +// told useMaxWidth=false (the option is not honoured by every diagram type). +// That makes diagrams with smaller viewBoxes scale up more than diagrams +// with bigger viewBoxes, so two class diagrams on the same page render at +// visibly different text sizes. Pinning width/height to the viewBox makes +// every diagram render at 1 viewBox unit = 1 CSS pixel, which gives a +// consistent per-character pixel size across the page. Wider diagrams stay +// inside the column thanks to `max-width: 100%` in custom.css. +(function () { + function viewBoxOf(svg) { + var viewBox = svg.getAttribute("viewBox"); + if (!viewBox) return null; + var parts = viewBox.split(/\s+|,/).map(parseFloat); + if (parts.length !== 4 || parts.some(isNaN)) return null; + return { w: parts[2], h: parts[3] }; + } + + function pinAll() { + var svgs = Array.from( + document.querySelectorAll("pre.mermaid svg, .mermaid svg") + ); + if (svgs.length === 0) return; + + // Compute the maximum intrinsic width across every mermaid SVG on + // the page, and the available container width (use the first + // mermaid SVG's offset parent as the column). + var maxIntrinsicW = 0; + svgs.forEach(function (svg) { + var vb = viewBoxOf(svg); + if (vb && vb.w > maxIntrinsicW) maxIntrinsicW = vb.w; + }); + if (maxIntrinsicW === 0) return; + + var container = svgs[0].parentElement; + // Walk up to find an element with a real width (the .mermaid
+        // itself may be width:auto and report 0 before we pin its child).
+        var containerW = 0;
+        var node = container;
+        while (node && containerW === 0) {
+            containerW = node.clientWidth || 0;
+            node = node.parentElement;
+        }
+        if (containerW === 0) containerW = 720; // sane default
+
+        // One factor for the whole page: scale every diagram by the same
+        // amount so per-character pixel size is identical. The widest
+        // diagram fits exactly inside the column, narrower diagrams stay
+        // proportional and look smaller (which is correct, they have
+        // less content to show).
+        var factor = Math.min(1, containerW / maxIntrinsicW);
+
+        svgs.forEach(function (svg) {
+            var vb = viewBoxOf(svg);
+            if (!vb) return;
+            var w = vb.w * factor;
+            var h = vb.h * factor;
+            svg.setAttribute("width", w);
+            svg.setAttribute("height", h);
+            svg.style.setProperty("width", w + "px", "important");
+            svg.style.setProperty("height", h + "px", "important");
+            svg.style.setProperty("max-width", "100%", "important");
+        });
+    }
+
+    // Mermaid renders client-side after DOMContentLoaded. Watch for new
+    // SVGs being added inside .mermaid blocks and pin them as they appear.
+    var observer = new MutationObserver(function () { pinAll(); });
+    function start() {
+        observer.observe(document.body, { childList: true, subtree: true });
+        pinAll();
+    }
+    if (document.readyState === "loading") {
+        document.addEventListener("DOMContentLoaded", start);
+    } else {
+        start();
+    }
+})();
diff --git a/docs/api/index.rst b/docs/api/index.rst
index e0ecd31..18acc07 100644
--- a/docs/api/index.rst
+++ b/docs/api/index.rst
@@ -28,8 +28,7 @@ Sphere
 .. doxygenclass:: geodex::Sphere
    :members:
 
-.. doxygenstruct:: geodex::SphereRoundMetric
-   :members:
+.. doxygentypedef:: geodex::SphereRoundMetric
 
 .. doxygenstruct:: geodex::SphereExponentialMap
    :members:
@@ -43,8 +42,7 @@ Euclidean
 .. doxygenclass:: geodex::Euclidean
    :members:
 
-.. doxygenstruct:: geodex::EuclideanStandardMetric
-   :members:
+.. doxygentypedef:: geodex::EuclideanStandardMetric
 
 
 Torus
@@ -53,8 +51,7 @@ Torus
 .. doxygenclass:: geodex::Torus
    :members:
 
-.. doxygenstruct:: geodex::TorusFlatMetric
-   :members:
+.. doxygentypedef:: geodex::TorusFlatMetric
 
 SE(2)
 ^^^^^
@@ -71,28 +68,112 @@ Configuration Space
 Metrics
 -------
 
-.. doxygenstruct:: geodex::ConstantSPDMetric
+.. doxygenclass:: geodex::IdentityMetric
+   :members:
+
+.. doxygenclass:: geodex::ConstantSPDMetric
+   :members:
+
+.. doxygenclass:: geodex::SE2LeftInvariantMetric
+   :members:
+
+.. doxygenclass:: geodex::KineticEnergyMetric
+   :members:
+
+.. doxygenclass:: geodex::JacobiMetric
+   :members:
+
+.. doxygenclass:: geodex::PullbackMetric
+   :members:
+
+.. doxygenclass:: geodex::WeightedMetric
+   :members:
+
+.. doxygenclass:: geodex::SDFConformalMetric
+   :members:
+
+Collision
+---------
+
+.. doxygenclass:: geodex::collision::DistanceGrid
+   :members:
+
+.. doxygenclass:: geodex::collision::GridSDF
+   :members:
+
+.. doxygenclass:: geodex::collision::InflatedSDF
+   :members:
+
+.. doxygenclass:: geodex::collision::PolygonFootprint
    :members:
 
-.. doxygenstruct:: geodex::SE2LeftInvariantMetric
+.. doxygenclass:: geodex::collision::FootprintGridChecker
    :members:
 
-.. doxygenstruct:: geodex::KineticEnergyMetric
+.. doxygenclass:: geodex::collision::CircleSDF
    :members:
 
-.. doxygenstruct:: geodex::JacobiMetric
+.. doxygenclass:: geodex::collision::CircleSmoothSDF
    :members:
 
-.. doxygenstruct:: geodex::PullbackMetric
+.. doxygenstruct:: geodex::collision::RectObstacle
    :members:
 
-.. doxygenstruct:: geodex::IdentityTaskMetric
+.. doxygenclass:: geodex::collision::RectSmoothSDF
    :members:
 
-.. doxygenstruct:: geodex::WeightedMetric
+.. doxygenfunction:: geodex::collision::rects_overlap
+
+Sampling
+--------
+
+.. doxygenclass:: geodex::StochasticSampler
+   :members:
+
+.. doxygenclass:: geodex::HaltonSampler
+   :members:
+
+.. doxygenconcept:: geodex::Sampler
+
+.. doxygenconcept:: geodex::SeedableSampler
+
+Heuristics
+----------
+
+.. doxygenstruct:: geodex::EuclideanHeuristic
    :members:
 
 Algorithms
 ----------
 
 .. doxygenfunction:: geodex::distance_midpoint
+
+.. doxygenstruct:: geodex::InterpolationSettings
+   :members:
+
+.. doxygenenum:: geodex::InterpolationStatus
+
+.. doxygenstruct:: geodex::InterpolationResult
+   :members:
+
+.. doxygenstruct:: geodex::InterpolationCache
+   :members:
+
+.. doxygenfunction:: geodex::discrete_geodesic
+
+Batched inner product
+~~~~~~~~~~~~~~~~~~~~~
+
+.. doxygenconcept:: geodex::HasBatchInnerMatrix
+
+OMPL Integration
+----------------
+
+.. doxygenclass:: geodex::integration::ompl::GeodexStateSpace
+   :members:
+
+.. doxygenclass:: geodex::integration::ompl::GeodexState
+   :members:
+
+.. doxygenclass:: geodex::integration::ompl::GeodexStateSampler
+   :members:
diff --git a/docs/concepts/architecture.rst b/docs/concepts/architecture.rst
new file mode 100644
index 0000000..faa0502
--- /dev/null
+++ b/docs/concepts/architecture.rst
@@ -0,0 +1,189 @@
+Concept Hierarchy and Architecture
+==================================
+
+**geodex** is built around a small set of C++20 concepts that define what it means to
+be a manifold, a metric, a retraction, and so on. These concepts compose through a
+*policy-based design*: a manifold class like ``Sphere`` is parameterized by
+interchangeable metric, retraction, and sampler policies, and the compiler statically
+verifies that the assembled type satisfies the full ``RiemannianManifold`` concept.
+
+Concept Hierarchy
+-----------------
+
+The central abstraction is a two-level hierarchy. ``Manifold`` captures the bare
+topology (points, tangent vectors, dimension, sampling), while ``RiemannianManifold``
+adds the geometric structure needed for distance computation and motion planning.
+
+.. mermaid::
+
+   %%{init: {'theme':'base','themeVariables':{'primaryColor':'#e7f0fa','primaryTextColor':'#1a1a1a','primaryBorderColor':'#2980b9','lineColor':'#2980b9','secondaryColor':'#e7f0fa','tertiaryColor':'#f7fbfe','background':'transparent'}}}%%
+   classDiagram
+       direction TB
+
+       class Manifold {
+           <>
+           +Scalar
+           +Point
+           +Tangent
+           +dim() int
+           +random_point() Point
+       }
+
+       class HasMetric {
+           <>
+           +inner(p, u, v)
+           +norm(p, v)
+       }
+
+       class HasDistance {
+           <>
+           +distance(p, q)
+       }
+
+       class HasGeodesic {
+           <>
+           +geodesic(p, q, t)
+           +exp(p, v)
+           +log(p, q)
+       }
+
+       class HasInjectivityRadius {
+           <>
+           +injectivity_radius()
+       }
+
+       class RiemannianManifold {
+           <>
+       }
+
+       Manifold <|-- HasMetric
+       Manifold <|-- HasDistance
+       Manifold <|-- HasGeodesic
+       Manifold <|-- HasInjectivityRadius
+       HasMetric <|-- RiemannianManifold
+       HasDistance <|-- RiemannianManifold
+       HasGeodesic <|-- RiemannianManifold
+
+``RiemannianManifold`` is deliberately monolithic: any type satisfying it provides the
+complete interface that algorithms need. For finer-grained constraints, geodex also
+defines three orthogonal trait concepts: ``HasMetric``, ``HasDistance``, and
+``HasGeodesic``. These allow algorithms to require only the operations they actually
+use. For example, an algorithm that only needs exp/log can constrain on
+``HasGeodesic`` without requiring a full metric. ``HasInjectivityRadius`` optionally
+exposes the local injectivity radius on manifolds that support it.
+
+Two further policy concepts plug into a manifold from the side. ``Retraction<>`` is the
+contract every retraction policy satisfies, with just ``retract(p, v)`` and
+``inverse_retract(p, q)``. ``Sampler`` and its refinement ``SeedableSampler`` allow
+drawing uniform samples on manifolds.
+
+.. mermaid::
+
+   %%{init: {'theme':'base','themeVariables':{'primaryColor':'#e7f0fa','primaryTextColor':'#1a1a1a','primaryBorderColor':'#2980b9','lineColor':'#2980b9','secondaryColor':'#e7f0fa','tertiaryColor':'#f7fbfe','background':'transparent'}}}%%
+   classDiagram
+       direction TB
+
+       class Manifold {
+           <>
+       }
+
+       class Retraction {
+           <>
+           +retract(p, v)
+           +inverse_retract(p, q)
+       }
+
+       class Sampler {
+           <>
+           +sample_box(d, out)
+       }
+
+       class SeedableSampler {
+           <>
+           +seed(s)
+       }
+
+       Manifold <-- Retraction : exp / log
+       Manifold <-- Sampler : random_point
+       Sampler <|-- SeedableSampler
+
+How It All Fits Together
+------------------------
+
+Three families of policies (metrics, retractions, samplers) feed into the manifold
+classes, and algorithms consume those manifolds through the ``RiemannianManifold``
+concept.
+
+.. graphviz::
+
+   digraph geodex {
+       rankdir=LR;
+       bgcolor="transparent";
+       compound=true;
+       pad="0.3";
+       nodesep="0.35";
+       ranksep="0.9";
+       node [shape=box, style="filled",
+             fillcolor="#e7f0fa", color="#2980b9", penwidth="1.2",
+             fontname="Helvetica", fontsize=11, fontcolor="#1a1a1a",
+             margin="0.18,0.10", height="0.45"];
+       edge [color="#2980b9", penwidth="1.1",
+             fontname="Helvetica", fontsize=10, fontcolor="#34495e",
+             arrowsize="0.8"];
+       graph [fontname="Helvetica", fontsize=11, fontcolor="#1a1a1a",
+              color="#2980b9", penwidth="1.0",
+              style="filled", fillcolor="#f7fbfe"];
+
+       subgraph cluster_metrics {
+           label=<Metrics>;
+           ConstantSPDMetric;
+           WeightedMetric;
+           KineticEnergyMetric;
+           JacobiMetric;
+           PullbackMetric;
+           SE2LeftInvariantMetric;
+       }
+
+       subgraph cluster_retractions {
+           label=<Retractions>;
+           SphereExponentialMap;
+           SphereProjectionRetraction;
+           SE2ExponentialMap;
+           SE2EulerRetraction;
+       }
+
+       subgraph cluster_samplers {
+           label=<Samplers>;
+           StochasticSampler;
+           HaltonSampler;
+       }
+
+       subgraph cluster_manifolds {
+           label=<Manifolds>;
+           Sphere       [label="Sphere"];
+           Euclidean    [label="Euclidean"];
+           Torus        [label="Torus"];
+           SE2          [label="SE2"];
+           ConfigurationSpace;
+       }
+
+       subgraph cluster_algorithms {
+           label=<Algorithms>;
+           distance_midpoint;
+           discrete_geodesic;
+       }
+
+       JacobiMetric          -> Sphere    [ltail=cluster_metrics,
+                                            lhead=cluster_manifolds,
+                                            label="metric"];
+       SE2EulerRetraction    -> SE2       [ltail=cluster_retractions,
+                                            lhead=cluster_manifolds,
+                                            label="retraction"];
+       HaltonSampler         -> Euclidean [ltail=cluster_samplers,
+                                            lhead=cluster_manifolds,
+                                            label="sampler"];
+       ConfigurationSpace    -> distance_midpoint
+                                          [ltail=cluster_manifolds,
+                                           lhead=cluster_algorithms,
+                                           label="RiemannianManifold"];
+   }
diff --git a/docs/concepts/discrete-geodesic-interpolation.rst b/docs/concepts/discrete-geodesic-interpolation.rst
new file mode 100644
index 0000000..eea6b97
--- /dev/null
+++ b/docs/concepts/discrete-geodesic-interpolation.rst
@@ -0,0 +1,368 @@
+Discrete Geodesic Interpolation
+===============================
+
+``discrete_geodesic`` is the core interpolation function in geodex.
+Given a manifold :math:`\mathcal{M}`, a start point :math:`q_s`, and a target :math:`q_t`, it returns a sequence of points on :math:`\mathcal{M}` approximating a length-minimizing geodesic between them.
+The same subroutine drives midpoint distance estimation, edge interpolation in motion planners, and any code path that needs a geodesic on a manifold whose true logarithm is unavailable, expensive, or inconsistent with the metric in use. 
+This page explains how the algorithm works, the design decisions behind it, how to tune its parameters, and how to call it from both C++ and Python.
+
+Problem statement
+-----------------
+
+.. image:: figs/discrete-geodesic-schematic.svg
+   :align: center
+   :width: 85%
+   :alt: Discrete geodesic iterates on a convex manifold with tangent spaces and descent directions.
+
+.. raw:: html
+
+   
+ +We minimize the squared Riemannian distance to the target, + +.. math:: + + \varphi(x) \;=\; \tfrac{1}{2}\, d_g^2(x,\, q_t), + +starting from :math:`x_0 = q_s` and taking Riemannian gradient steps. Every successful +iterate is recorded as a waypoint, so on convergence the returned path traces a +discrete approximation of the geodesic from :math:`q_s` to :math:`q_t`. + +At each iterate :math:`x_k`, the descent direction lives in the tangent space +:math:`\mathcal{T}_{x_k}\mathcal{M}` and points along :math:`-\log_{x_k}(q_t)`. The +next iterate :math:`x_{k+1}` is obtained by retracting back to :math:`\mathcal{M}` +along that direction, capped at the current step length. + +How the algorithm works +----------------------- + +Each iteration computes a descent direction in :math:`\mathcal{T}_x\mathcal{M}`, +caps its Riemannian length at the current step budget, and moves to the next iterate +through the manifold's retraction. + +Fast path +^^^^^^^^^ + +When the manifold's log is the Riemannian logarithm of the metric in use, the +gradient of :math:`\varphi` has a closed form: + +.. math:: + + \nabla_g \!\left[ \tfrac{1}{2}\, d_g^2(\cdot,\, q_t) \right]\!(x) \;=\; -\log_x(q_t). + +The algorithm uses this direction directly, normalizes it, scales by the current step +cap, and retracts. This is by far the cheapest path: one ``log``, one ``retract``, +and a progress check per iteration. + +Whether this fast path executes is decided by the resolver ``is_riemannian_log(m)``, +which collapses a compile-time trait (``M::has_riemannian_log``) and a runtime hook +(``m.has_riemannian_log_runtime()``) into a single boolean. Built-in manifolds like +``Sphere``, ``Euclidean``, ``Torus``, and ``SE2`` under their standard metrics return +``true`` at compile time, while ``ConfigurationSpace`` and callable metrics resolve the +flag at runtime by asking whether the attached metric matches the base manifold's log. +Manifolds that do not opt in always fall through to the finite-difference path below. + +There are cases where the closed-form direction is still geometrically useful even +when the chosen metric is not the one implied by ``log``. Setting +``force_log_direction = true`` skips this resolver and always uses +:math:`-\log_x(q_t)` as the descent direction; the metric's ``norm`` and +``distance`` continue to drive step sizing and convergence, but the resulting path +follows the base retraction's geodesic rather than the Riemannian geodesic of the +configured metric. + +.. note:: + + The identity :math:`\nabla_g \tfrac{1}{2} d_g^2 = -\log` is standard; + see :cite:`Lee2018`. + +Finite-difference fallback +^^^^^^^^^^^^^^^^^^^^^^^^^^ + +When ``log`` is not the Riemannian logarithm of the chosen metric (anything built on +``ConstantSPDMetric``, ``KineticEnergyMetric``, ``JacobiMetric``, ``PullbackMetric``, +or any callable metric), or when the closed-form direction from fast path fails the progress check, +the iteration falls back to a finite-difference natural gradient computed from the +metric's ``inner`` product: + +1. Build an orthonormal tangent basis :math:`\{e_i\}` at the current point. If the + manifold exposes a ``project`` method, ambient seed vectors are projected to + :math:`\mathcal{T}_x\mathcal{M}` before Gram-Schmidt orthonormalization. +2. Assemble the metric tensor in this basis, + :math:`G_{ij} = g_x(e_i, e_j)`. When the metric provides a batched + ``inner_matrix``, the whole Gram matrix is filled in one call. +3. Estimate the coordinate-space gradient :math:`g_i = \partial_{e_i} \varphi(x)` by + central finite differences along each basis direction. The :math:`d_g^2` samples + use a third-order-accurate midpoint surrogate guarded by the Riemannian-midpoint + identity :math:`\log_m(a) = -\log_m(b)`; when the relative deviation exceeds + ``fd_midpoint_guard_tau``, the sample falls back to :math:`\|\log_a(b)\|_g` for + that basis direction and the count is reported on + ``InterpolationResult::fd_midpoint_fallbacks``. +4. Solve :math:`G\,\alpha = -g` via Cholesky. The natural gradient in + ambient coordinates is :math:`v = \sum_i \alpha_i\, e_i`. + +The fallback engages on a per-step basis, so a single walk can mix fast-path and +finite-difference iterations as the geometry demands. + +Adaptive step control and termination +------------------------------------- + +A retraction is only an approximation of the exponential map, and on a curved +manifold an aggressive step can either overshoot the target or land somewhere whose +realized length differs noticeably from the requested length. After each candidate +step, the algorithm measures :math:`\|\log_x(x_{\text{next}})\|_g` and compares it to +the requested step length. The fallback is two-stage: when the fast-path candidate +fails either due to the progress check or the distortion ratio, the iteration falls +through to the finite-difference path at the same step cap, without counting a +halving. When the FD candidate also fails, the step cap is halved, the iteration +retries, and ``distortion_halvings`` increments. After a successful step, the cap +regrows by ``growth_factor`` until it reaches ``step_size`` again. This +trust-region behavior keeps the walk stable under heavy curvature without forcing +the user to pick a tiny global step size. + +The loop ends with one of the following statuses: + +``Converged`` + The Riemannian distance to the target dropped below ``convergence_tol`` or below + ``convergence_rel * initial_distance``. The returned path ends at, or very close + to, ``target``. + +``MaxStepsReached`` + The iteration budget was exhausted. The path is still a valid descent sequence, + but it has not reached the target. Inspect ``final_distance`` to decide whether + it is good enough. + +``GradientVanished`` + The Riemannian gradient norm collapsed at a non-target point. This is rare in + practice and usually indicates that the metric or finite-difference step is + misconfigured. + +``CutLocus`` + ``log`` returned (numerically) zero while the ambient gap to the target is + nonzero. The classic example is exact antipodal points on the sphere, where the + logarithm is multivalued. This is the correct response, not a bug. + +``StepShrunkToZero`` + The distortion guard halved the step cap below ``min_step_size``. This usually + means the retraction is incompatible with the metric in this neighborhood. + +``DegenerateInput`` + ``start`` and ``target`` were the same point (within tolerance) at entry. + +Beyond the status, the result carries diagnostic counters that are useful for +understanding how the walk went. ``iterations`` is the number of accepted steps, +equal to the returned path length minus one. ``distortion_halvings`` counts how +many times the FD path forced a step-cap halving, and a nonzero value under an +otherwise fast-path-eligible manifold signals a poor retraction-metric match in +this neighbourhood. ``fd_midpoint_fallbacks`` counts how many FD basis samples the +Riemannian-midpoint guard rejected, which flags non-Riemannian retractions, +cut-locus crossings, or non-smooth metric features within the finite-difference +neighbourhood. + +Tuning the parameters +--------------------- + +Every parameter lives on ``InterpolationSettings``. Defaults are sensible for moderate +problems on the unit sphere; you should expect to revisit ``step_size`` and +``max_steps`` for tighter state spaces or heavier metrics. + +.. list-table:: + :header-rows: 1 + :widths: 30 15 58 + + * - Parameter + - Default + - Effect + * - ``step_size`` + - 0.5 + - Maximum Riemannian step per iteration. Also the effective path resolution: + consecutive returned points are at most ``step_size`` apart in the metric. + Smaller values give a denser path and a smoother walk under aggressive + curvature, at the cost of more iterations. + * - ``convergence_tol`` + - 1e-4 + - Absolute stop threshold on the Riemannian distance to the target. + * - ``convergence_rel`` + - 1e-3 + - Relative stop threshold; the walk also stops when the distance drops below + ``convergence_rel * initial_distance``. Useful when the working scale of the + problem is much larger or smaller than the absolute tolerance. + * - ``max_steps`` + - 100 + - Successful gradient steps before giving up. Distortion retries do not count. + * - ``force_log_direction`` + - false + - Force the log-based descent direction even when ``is_riemannian_log(m)`` + would return false. The metric still drives norm, distance, and convergence, + but the path follows the base retraction's geodesic rather than the + Riemannian geodesic of the configured metric. Use when the FD fallback's + natural oscillation is visible and a smooth path matters more than strict + metric fidelity. + * - ``fd_epsilon`` + - 0.0 + - Central finite-difference step. Zero auto-selects + :math:`\max(10^{-8},\, 10^{-5} \cdot \max(1, d_0))` from the initial distance, + which is the right choice in nearly all cases. + * - ``fd_midpoint_guard_tau`` + - 0.25 + - Relative-error threshold above which the midpoint-distance surrogate used + inside the FD gradient is rejected and the sample falls back to + :math:`\|\log\|_g` for that basis direction. Lower values are stricter; set to + 0 to force the log-based sample on every basis direction. + * - ``distortion_ratio`` + - 1.5 + - How much the realized step length is allowed to exceed the requested length + before the retraction is considered to have overshot. Lower this for + retractions that drift visibly from the exponential map. + * - ``growth_factor`` + - 1.5 + - How quickly the step cap regrows after a successful iteration. Set to ``1.0`` + to disable growth and keep the cap fixed at whatever the distortion guard + last permitted. + * - ``min_step_size`` + - 1e-12 + - Floor on the step cap. The walk fails with ``StepShrunkToZero`` once it is + crossed. + * - ``gradient_eps`` + - 1e-12 + - Riemannian-norm threshold below which the gradient is considered vanished. + * - ``cut_locus_eps`` + - 1e-10 + - Threshold on :math:`\|\log_x(q_t)\|_g` that, combined with a nonzero ambient + gap, flags a cut-locus situation. + +In day-to-day use, the three parameters worth reaching for first are ``step_size``, +``convergence_tol``, and ``distortion_ratio``. ``step_size`` has the most impact: +halving it doubles both the path resolution and the iteration count, but it also +makes the walk far more tolerant of curvature and metric anisotropy. +``convergence_tol`` and ``convergence_rel`` together set how tightly the final +iterate must approach the target; loosen them when the downstream consumer only +needs a coarse path. ``distortion_ratio`` is the safety valve for retractions that +are not isometries, such as ``SphereProjectionRetraction`` under an anisotropic +metric or ``SE2EulerRetraction`` away from :math:`\theta = 0`. + +For hot loops, pass an ``InterpolationCache`` to reuse the basis matrix, Gram +matrix, and gradient buffers across calls. The cache is resized once on first use +and then avoids all per-iteration heap allocations. + +Worked example: :math:`\mathbf{S}^2` with an anisotropic metric +--------------------------------------------- + +The example below runs ``discrete_geodesic`` twice on the unit 2-sphere between the +north pole and a target in the upper hemisphere. The first call uses the default +round metric, so the fast path executes and the walk traces the great circle exactly. +The second call swaps in a constant SPD metric :math:`A = \mathrm{diag}(25, 1, 1)` +that heavily penalizes motion in the :math:`x` direction; the finite-difference +fallback runs, and the resulting path bends visibly away from the great circle in +order to spend less length along the penalized axis. + +.. tabs:: + + .. code-tab:: c++ + + #include + #include + + using namespace geodex; + + int main() { + const Eigen::Vector3d start(0.0, 0.0, 1.0); + const Eigen::Vector3d target( + std::sin(1.3) * std::cos(0.5), + std::sin(1.3) * std::sin(0.5), + std::cos(1.3)); + + InterpolationSettings s; + s.step_size = 0.05; + s.max_steps = 500; + + // 1. Round sphere — fast path, traces the great circle. + Sphere<> round_sphere; + auto great = discrete_geodesic(round_sphere, start, target, s); + + // 2. Anisotropic constant-SPD metric — finite-difference fallback. + Eigen::Matrix3d A = Eigen::Matrix3d::Identity(); + A(0, 0) = 25.0; + Sphere<2, ConstantSPDMetric<3>> stretched{ConstantSPDMetric<3>{A}}; + auto bent = discrete_geodesic(stretched, start, target, s); + + // great.path and bent.path are std::vector waypoints. + } + + .. code-tab:: py + + import numpy as np + import geodex + + start = np.array([0.0, 0.0, 1.0]) + target = np.array([ + np.sin(1.3) * np.cos(0.5), + np.sin(1.3) * np.sin(0.5), + np.cos(1.3), + ]) + + settings = geodex.InterpolationSettings(step_size=0.05, max_steps=500) + + # 1. Round sphere — fast path, traces the great circle. + round_sphere = geodex.Sphere() + great = geodex.discrete_geodesic(round_sphere, start, target, settings) + + # 2. Anisotropic constant-SPD metric, attached via ConfigurationSpace. + A = np.diag([25.0, 1.0, 1.0]) + stretched = geodex.ConfigurationSpace(round_sphere, geodex.ConstantSPDMetric(A)) + bent = geodex.discrete_geodesic(stretched, start, target, settings) + +The two paths visualised on :math:`\mathbb{S}^2`: + +.. image:: figs/discrete-geodesic-s2.svg + :align: center + :width: 50% + :alt: Discrete geodesic walks on the 2-sphere under round and anisotropic metrics. + +The blue curve is the great circle path returned by the fast path under the +round metric. The orange curve is the natural-gradient walk under +:math:`A = \mathrm{diag}(25, 1, 1)`; both endpoints are identical, but the second +path leaves the great circle to favour motion along :math:`y` and :math:`z`, where +the metric is cheaper. + +Common pitfalls +--------------- + +.. warning:: + + - Anisotropic metrics combined with first-order retractions such as + ``SphereProjectionRetraction`` rely on the distortion guard to stay stable. + Do not raise ``distortion_ratio`` past 2 unless you have measured what the + retraction actually does in your neighborhood. + - Near-antipodal inputs on the sphere may legitimately terminate with + ``CutLocus``. The logarithm is multivalued there, and no descent direction is + well defined. Pre-split the problem if you need to traverse the cut. + - The default ``step_size = 0.5`` is large for tight state spaces or heavy metrics. + If you see ``MaxStepsReached`` or many distortion halvings in + ``distortion_halvings``, halve ``step_size`` first and re-run. + - Always check ``result.status`` before consuming ``result.path``. A walk that + stopped on ``MaxStepsReached`` still returns a valid descent sequence, but its + last point is not the target. + - SE(2) under an anisotropic or clearance-based metric tends to produce a + visibly bumpy path because the FD natural gradient reacts to small-scale + metric variation between samples. When a smooth path matters more than strict + Riemannian fidelity, set ``force_log_direction = true`` and inspect + ``fd_midpoint_fallbacks`` to confirm the FD guard was indeed tripping on the + original run. + +See also +-------- + +- :doc:`architecture` for the policy types that ``discrete_geodesic`` consumes. +- :doc:`/tutorials/geodex-basics` for end-to-end use of the library. +- :doc:`/api/index` for the full API reference of ``discrete_geodesic``, + ``InterpolationSettings``, ``InterpolationResult``, and + ``InterpolationCache``. + +References +---------- + +Full details are in our WAFR 2026 paper :cite:`kyaw2026geometry`. +This page is a usage-oriented summary of the same algorithm. + +.. bibliography:: + :filter: docname in docnames diff --git a/docs/concepts/figs/discrete-geodesic-s2.svg b/docs/concepts/figs/discrete-geodesic-s2.svg new file mode 100644 index 0000000..5fe1d7c --- /dev/null +++ b/docs/concepts/figs/discrete-geodesic-s2.svg @@ -0,0 +1,422 @@ + + + + + + + + 2026-04-08T13:34:04.369535 + image/svg+xml + + + Matplotlib v3.10.8, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/concepts/figs/discrete-geodesic-schematic.svg b/docs/concepts/figs/discrete-geodesic-schematic.svg new file mode 100644 index 0000000..b5bcfcc --- /dev/null +++ b/docs/concepts/figs/discrete-geodesic-schematic.svg @@ -0,0 +1,1001 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/concepts/figs/manifold.svg b/docs/concepts/figs/manifold.svg new file mode 100644 index 0000000..0558233 --- /dev/null +++ b/docs/concepts/figs/manifold.svg @@ -0,0 +1,382 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/concepts/index.rst b/docs/concepts/index.rst index 8b722ad..d422a79 100644 --- a/docs/concepts/index.rst +++ b/docs/concepts/index.rst @@ -1,184 +1,23 @@ Core Concepts ============= -This document starts with the minimal geometric background needed to understand geodex, -then explains how these concepts are encoded in the library's implementation. -Readers already familiar with Riemannian geometry may skip directly to the implementation details. - -Mathematical Background ------------------------ - -This section provides the minimal vocabulary necessary to follow the rest of the documentation and use geodex effectively. -It is not an exhaustive introduction to differential geometry. -For a rigorous treatment of Riemannian geometry, see :cite:`Lee2018`. -For readers interested in the computational aspects relevant to this library, see :cite:`Boumal2023` and :cite:`Absil2008`. - -**Riemannian Geometry** - -A **smooth manifold** :math:`\mathcal{M}` is a topological space that locally looks like a familiar Euclidean space :math:`\mathbb{R}^n`. -Each point :math:`p \in \mathcal{M}` has an associated **tangent space** :math:`\mathcal{T}_p\mathcal{M}` — the vector space of all instantaneous velocities passing through :math:`p`. -Tangent vectors :math:`v \in \mathcal{T}_p\mathcal{M}` are the directions in which you can move on the manifold. - -.. image:: ../tutorials/figs/manifold.svg - :class: responsive-img - :align: center - -A **Riemannian metric** :math:`g` equips every tangent space with a smoothly varying inner product: - -.. math:: - - g_p : \mathcal{T}_p\mathcal{M} \times \mathcal{T}_p\mathcal{M} \to \mathbb{R} - -This inner product allows us to define lengths and angles on the manifold. -The **norm** of a tangent vector :math:`v \in \mathcal{T}_p\mathcal{M}` is defined as: - -.. math:: - - \|v\|_p = \sqrt{g_p(v, v)} - -**Geodesics** :math:`\gamma` are the generalization of straight lines in flat spaces to manifolds — they are locally length-minimizing curves with zero acceleration. - -The **exponential map** :math:`\exp_p : \mathcal{T}_p\mathcal{M} \to \mathcal{M}` follows the geodesic starting at :math:`p` with initial velocity :math:`v`: - -.. math:: - - \exp_p(v) = \gamma(1), \quad \dot\gamma(0) = v - -The **logarithmic map** :math:`\log_p : \mathcal{M} \to \mathcal{T}_p\mathcal{M}` is the local inverse of exponential map, that is, it returns the tangent vector at :math:`p` pointing toward :math:`q`: - -.. math:: - - \log_p(q) = v \quad\Longleftrightarrow\quad \exp_p(v) = q - -The **geodesic distance** between two points is the length of the shortest connecting geodesic: - -.. math:: - - d(p, q) = \|\log_p(q)\|_p - -(This formula requires exact exp/log. When only approximations are available, -geodex falls back to the midpoint approximation — see :ref:`distance_midpoint ` in the API reference). - -**Retractions** are first- or second-order approximations to the exponential -map. They are cheaper to evaluate and preserve the manifold topology, but -unlike the true exp, they are not isometries. geodex separates retractions -from metrics as independent policy types (see the :doc:`/tutorials/geodex-basics` tutorial for usage). - -Concept Hierarchy ------------------ - -**geodex** is built around a small set of C++20 concepts that define what it means to be a manifold, a metric, a retraction, and so on. -These concepts compose through a *policy-based design*; for example, a manifold class like ``Sphere`` is parameterized by interchangeable metric and retraction policies, and the compiler statically verifies that the assembled type satisfies the full ``RiemannianManifold`` interface. - -The central abstraction is a two-level concept hierarchy. ``Manifold`` captures the bare topology (points, tangent vectors, etc), while ``RiemannianManifold`` adds the geometric structure needed for distance computation and motion planning. - -.. mermaid:: - - %%{init: {"theme": "neutral"}}%% - classDiagram - direction TB - - class Manifold { - <> - +Scalar - +Point - +Tangent - +dim() int - +random_point() Point - } - - class RiemannianManifold { - <> - +inner(p, u, v) Scalar - +norm(p, v) Scalar - +distance(p, q) Scalar - +geodesic(p, q, t) Point - +exp(p, v) Point - +log(p, q) Tangent - } - - class HasInjectivityRadius { - <> - +injectivity_radius() Scalar - } - - Manifold <|-- RiemannianManifold - Manifold <|-- HasInjectivityRadius - -``RiemannianManifold`` is deliberately monolithic: any type satisfying it provides the complete interface that algorithms need. -For finer-grained constraints, geodex also defines three orthogonal trait concepts: - -.. mermaid:: - - %%{init: {"theme": "neutral"}}%% - classDiagram - direction LR - - class Manifold { - <> - } - - class HasMetric { - <> - +inner(p, u, v) Scalar - +norm(p, v) Scalar - } - - class HasDistance { - <> - +distance(p, q) Scalar - } - - class HasGeodesic { - <> - +geodesic(p, q, t) Point - +exp(p, v) Point - +log(p, q) Tangent - } - - Manifold <|-- HasMetric - Manifold <|-- HasDistance - Manifold <|-- HasGeodesic - -These allow algorithms to require only the operations they actually use. -For example, an algorithm that only needs exp/log can constrain on ``HasGeodesic`` without requiring a full metric. - -How It All Fits Together ------------------------- - -The following diagram shows the full picture: concepts define interfaces, -policies provide implementations, and manifold classes compose them into -concrete types that satisfy the concepts. - -.. mermaid:: - - %%{init: {"theme": "neutral"}}%% - flowchart TB - subgraph Concepts["Concepts (compile-time)"] - Manifold - RiemannianManifold - Retraction["Retraction<R, Point, Tangent>"] - end - - subgraph Policies["Policies (swappable)"] - Metric["MetricT
e.g. SphereRoundMetric"] - Retr["RetractionT
e.g. SphereExponentialMap"] - end - - subgraph Concrete["Concrete Manifold"] - Sphere["Sphere<MetricT, RetractionT>"] - end - - Metric -->|"inner, norm"| Sphere - Retr -->|"retract, inverse_retract"| Sphere - Sphere -.->|"satisfies"| RiemannianManifold - RiemannianManifold -.->|"refines"| Manifold - Retr -.->|"satisfies"| Retraction - -.. The following pages detail the implementation and usage of these core architectural components: - -References ----------- - -.. bibliography:: - :filter: docname in docnames +This section gathers the conceptual background needed to use **geodex** effectively. It +starts with the geometric vocabulary that underpins the library, then describes how +those ideas are encoded as C++20 concepts and policy types, and finally walks through +the main algorithms that consume them. Readers already comfortable with Riemannian +geometry can skip directly to the architecture and algorithm pages. + +.. toctree:: + :maxdepth: 1 + + riemannian-geometry + architecture + discrete-geodesic-interpolation + +**See also** + +- :doc:`/tutorials/geodex-basics` for a hands-on walk-through with runnable C++ and + Python snippets. +- :doc:`/tutorials/minimum-energy-planning` for composing ``KineticEnergyMetric`` and + ``JacobiMetric`` to plan minimum-energy motions. +- :doc:`/api/index` for the full reference of every class and concept named here. diff --git a/docs/concepts/riemannian-geometry.rst b/docs/concepts/riemannian-geometry.rst new file mode 100644 index 0000000..0ce87f4 --- /dev/null +++ b/docs/concepts/riemannian-geometry.rst @@ -0,0 +1,73 @@ +Riemannian Geometry +=================== + +This page provides the minimal vocabulary necessary to follow the rest of the +documentation and use geodex effectively. It is not an exhaustive introduction to +differential geometry. For a rigorous treatment of Riemannian geometry, see +:cite:`Lee2018`. For readers interested in the computational aspects relevant to this +library, see :cite:`Boumal2023` and :cite:`Absil2008`. + +A **smooth manifold** :math:`\mathcal{M}` is a topological space that locally looks +like a familiar Euclidean space :math:`\mathbb{R}^n`. Each point :math:`p \in +\mathcal{M}` has an associated **tangent space** :math:`\mathcal{T}_p\mathcal{M}`, the +vector space of all instantaneous velocities passing through :math:`p`. Tangent vectors +:math:`v \in \mathcal{T}_p\mathcal{M}` are the directions in which you can move on the +manifold. + +.. image:: figs/manifold.svg + :class: responsive-img + :align: center + +A **Riemannian metric** :math:`g` equips every tangent space with a smoothly varying +inner product: + +.. math:: + + g_p : \mathcal{T}_p\mathcal{M} \times \mathcal{T}_p\mathcal{M} \to \mathbb{R} + +This inner product allows us to define lengths and angles on the manifold. The **norm** +of a tangent vector :math:`v \in \mathcal{T}_p\mathcal{M}` is defined as: + +.. math:: + + \|v\|_p = \sqrt{g_p(v, v)} + +**Geodesics** :math:`\gamma` are the generalization of straight lines in flat spaces to +manifolds. They are locally length-minimizing curves with zero acceleration. + +The **exponential map** :math:`\exp_p : \mathcal{T}_p\mathcal{M} \to \mathcal{M}` +follows the geodesic starting at :math:`p` with initial velocity :math:`v`: + +.. math:: + + \exp_p(v) = \gamma(1), \quad \dot\gamma(0) = v + +The **logarithmic map** :math:`\log_p : \mathcal{M} \to \mathcal{T}_p\mathcal{M}` is +the local inverse of the exponential map: it returns the tangent vector at :math:`p` +pointing toward :math:`q`: + +.. math:: + + \log_p(q) = v \quad\Longleftrightarrow\quad \exp_p(v) = q + +The **geodesic distance** between two points is the length of the shortest connecting +geodesic: + +.. math:: + + d(p, q) = \|\log_p(q)\|_p + +This formula requires exact exp/log. When only approximations are available, geodex +falls back to the midpoint approximation, which is covered alongside the discrete +interpolation algorithm in :doc:`discrete-geodesic-interpolation`. + +**Retractions** are first- or second-order approximations to the exponential map. They +are cheaper to evaluate and preserve the manifold topology, but unlike the true +exponential they are not isometries. geodex separates retractions from metrics as +independent policy types, as discussed in :doc:`architecture`. + +References +---------- + +.. bibliography:: + :filter: docname in docnames diff --git a/docs/conf.py b/docs/conf.py index b312526..8e5eea2 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -1,18 +1,43 @@ """Sphinx configuration for geodex documentation.""" project = "geodex" -copyright = "2026, geodex contributors" +copyright = ( + "2026, Space and Terrestrial Autonomous Robotic Systems (STARS) Lab" +) author = "geodex contributors" extensions = [ "breathe", "sphinx.ext.mathjax", + "sphinx.ext.graphviz", "sphinxcontrib.mermaid", "sphinx_tabs.tabs", "sphinx_togglebutton", "sphinxcontrib.bibtex", ] +# MathJax: render math with TeX Gyre Termes (Times family). MathJax's default +# TeX font diverges from what the project's LaTeX manuscripts render, most +# visibly on the calligraphic alphabets. Termes is the closest match we found +# across body italics, digits, and the script letters. +# +# Alternate fonts ship only in MathJax v4 (v3 carries the TeX font alone), and +# we vendor both the core bundle and the active font package under +# ``docs/_static/mathjax/`` so offline builds work without hitting jsdelivr. +# To swap fonts: run ``python3 docs/scripts/vendor_mathjax.py `` and +# change the three ``termes`` occurrences below to the new name. The +# ``[mathjax]`` marker in ``loader.paths`` is a MathJax built-in that resolves +# to the directory of the main JS at runtime, so it works from every page. +mathjax_path = "mathjax/tex-mml-chtml.js" +mathjax3_config = { + "loader": { + "paths": { + "mathjax-termes": "[mathjax]/fonts/termes", + }, + }, + "chtml": {"font": "mathjax-termes"}, +} + # Bibliography bibtex_bibfiles = ["refs.bib"] bibtex_default_style = "alpha" @@ -22,10 +47,47 @@ breathe_projects = {"geodex": "../build/docs/doxygen/xml"} breathe_default_project = "geodex" +# Graphviz: render diagrams as SVG so they stay crisp at any zoom level, +# and pass -Gdpi to tools that still emit raster. +graphviz_output_format = "svg" +graphviz_dot_args = [ + "-Gfontname=Helvetica", + "-Nfontname=Helvetica", + "-Efontname=Helvetica", +] + +# Mermaid: force every diagram to render at its intrinsic viewBox width +# (1 viewBox unit = 1 CSS pixel) instead of stretching to width="100%". +# Without this, mermaid emits width="100%" on the SVG element, which makes +# diagrams with smaller viewBoxes scale up more than diagrams with bigger +# viewBoxes, so two class diagrams on the same page render with visibly +# different text sizes. Setting useMaxWidth=false on every diagram type +# yields a consistent per-character pixel size across the page. +# +# This dict is consumed by sphinxcontrib-mermaid and serialised into +# mermaid.initialize({...}) at page-load time. +mermaid_init_config = { + "startOnLoad": False, + "theme": "base", + "themeVariables": { + "primaryColor": "#e7f0fa", + "primaryTextColor": "#1a1a1a", + "primaryBorderColor": "#2980b9", + "lineColor": "#2980b9", + "secondaryColor": "#e7f0fa", + "tertiaryColor": "#f7fbfe", + "background": "transparent", + "fontFamily": "Helvetica,Arial,sans-serif", + }, + "class": {"useMaxWidth": False}, + "classDiagram": {"useMaxWidth": False}, + "flowchart": {"useMaxWidth": False}, + "sequence": {"useMaxWidth": False}, +} # HTML theme html_theme = "sphinx_rtd_theme" - +html_show_sphinx = True html_theme_options = { 'navigation_depth': 3, 'collapse_navigation': True @@ -35,6 +97,9 @@ html_css_files = [ 'custom.css', ] +html_js_files = [ + 'mermaid-intrinsic-size.js', +] # Exclude patterns exclude_patterns = ["_build", "Thumbs.db", ".DS_Store"] diff --git a/docs/index.rst b/docs/index.rst index 6fe5ed2..5d6cd15 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -1,56 +1,105 @@ geodex ====== -A general-purpose software framework for planning on Riemannian manifolds. +**geodex** is a general-purpose software framework for motion planning on Riemannian manifolds. -geodex provides: +We ship ready-to-use manifolds (:math:`\mathbb{R}^n`, :math:`S^n`, :math:`T^n`, and :math:`\mathrm{SE}(2)`), all built from swappable metric, retraction, and sampler policies, along with efficient algorithms for geodesic distance and interpolation. -- **C++20 concepts** for manifolds, metrics, retractions, and geodesics -- **Concrete manifold implementations**: sphere :math:`S^2`, Euclidean :math:`\mathbb{R}^n`, flat torus :math:`T^n`, SE(2) -- **Policy-based design**: manifolds parameterized by interchangeable metric and retraction policies -- **Algorithms**: geodesic distance approximation via midpoint method -- **Python bindings**: First-class support for Python (``pip install geodex``) +The core engine of geodex is written purely in C++20 for performance, with first-class Python support (``pip install geodex``). +We are also actively working on integrating popular motion planning frameworks (OMPL, VAMP) and ROS 2 stacks (Nav2, MoveIt 2) into geodex. + +.. raw:: html + + Roadmap ------- .. list-table:: :header-rows: 1 + :widths: 40 55 20 * - Integration - Description - Status * - `OMPL `_ and `VAMP `_ integrations - - | Planning on Riemannian manifolds with - | state-of-the-art sampling-based planners + - Planning on Riemannian manifolds with state-of-the-art sampling-based planners - In progress * - `Nav2 `_ and `MoveIt 2 `_ plugins - - | Geometry-aware planning for ROS 2 - | mobile robots and manipulators + - Geometry-aware planning for ROS 2 mobile robots and manipulators - Planned Citation -------- - geodex accompanies the paper - `Geometry-Aware Sampling-Based Motion Planning on Riemannian Manifolds `_, - accepted to `WAFR 2026 `_. +geodex accompanies the paper +`Geometry-Aware Sampling-Based Motion Planning on Riemannian Manifolds `_, +accepted to `WAFR 2026 `_. If you use geodex in your research, consider citing: .. code-block:: bibtex - @article{kyaw2026geometry, - title={Geometry-Aware Sampling-Based Motion Planning on Riemannian Manifolds}, - author={Kyaw, Phone Thiha and Kelly, Jonathan}, - journal={arXiv preprint arXiv:2602.00992}, - year={2026} - } + @inproceedings{kyaw2026geometry, + address = {Oulu, Finland}, + author = {Phone Thiha Kyaw and Jonathan Kelly}, + booktitle = {Proceedings of the 17th World Symposium on the Algorithmic Foundations of Robotics {(WAFR)}}, + date = {2026-06-15/2026-06-17}, + month = {Jun. 15--17}, + title = {Geometry-Aware Sampling-Based Motion Planning on {Riemannian} Manifolds}, + url = {https://arxiv.org/abs/2602.00992}, + year = {2026} + } .. toctree:: - :maxdepth: 2 :hidden: getting-started/index diff --git a/docs/refs.bib b/docs/refs.bib index d6863f8..8282696 100644 --- a/docs/refs.bib +++ b/docs/refs.bib @@ -1,8 +1,14 @@ -@article{kyaw2026geometry, - title={Geometry-Aware Sampling-Based Motion Planning on Riemannian Manifolds}, - author={Kyaw, Phone Thiha and Kelly, Jonathan}, - journal={arXiv preprint arXiv:2602.00992}, - year={2026} +@inproceedings{kyaw2026geometry, + abstract = {In many robot motion planning problems, task objectives and physical constraints induce non-Euclidean geometry on the configuration space, yet many planners operate using Euclidean distances that ignore this structure. We address the problem of planning collision-free motions that minimize length under configuration-dependent Riemannian metrics, corresponding to geodesics on the configuration manifold. Conventional numerical methods for computing such paths do not scale well to high-dimensional systems, while sampling-based planners trade scalability for geometric fidelity. To bridge this gap, we propose a sampling-based motion planning framework that operates directly on Riemannian manifolds. We introduce a computationally efficient midpoint-based approximation of the Riemannian geodesic distance and prove that it matches the true Riemannian distance with third-order accuracy. Building on this approximation, we design a local planner that traces the manifold using first-order retractions guided by Riemannian natural gradients. Experiments on a two-link planar arm and a 7-DoF Franka manipulator under a kinetic-energy metric, as well as on rigid-body planning in SE(2) with non-holonomic motion constraints, demonstrate that our approach consistently produces lower-cost trajectories than Euclidean-based planners and classical numerical geodesic-solver baselines.}, + address = {Oulu, Finland}, + author = {Phone Thiha Kyaw and Jonathan Kelly}, + booktitle = {Proceedings of the 17th World Symposium on the Algorithmic Foundations of Robotics {(WAFR)}}, + date = {2026-06-15/2026-06-17}, + month = {Jun. 15--17}, + note = {To Appear}, + title = {Geometry-Aware Sampling-Based Motion Planning on {Riemannian} Manifolds}, + url = {https://arxiv.org/abs/2602.00992}, + year = {2026} } @inproceedings{jaquier2022riemannian, diff --git a/docs/scripts/vendor_mathjax.py b/docs/scripts/vendor_mathjax.py new file mode 100644 index 0000000..cf098a0 --- /dev/null +++ b/docs/scripts/vendor_mathjax.py @@ -0,0 +1,123 @@ +#!/usr/bin/env python3 +"""Vendor MathJax core and a named font package into ``docs/_static/mathjax/``. + +Why: the docs build normally loads MathJax from jsdelivr. Vendoring the core JS +and the active font makes offline builds work and pins the exact version we +ship, at the cost of ~1.5 MB committed into the repo. + +Usage:: + + python3 docs/scripts/vendor_mathjax.py # refresh current (termes) + python3 docs/scripts/vendor_mathjax.py newcm # swap to a different font + python3 docs/scripts/vendor_mathjax.py --clean ... # remove other fonts first + +After swapping, also update ``docs/conf.py`` so the three occurrences of the +font name match the one you just vendored. + +Supported font names: termes, newcm, modern, stix2, tex, pagella, fira, +schola, bonum, asana (anything published as ``@mathjax/mathjax--font``). +""" + +from __future__ import annotations + +import argparse +import json +import shutil +import sys +import urllib.request +from pathlib import Path + +REPO_ROOT = Path(__file__).resolve().parents[2] +MATHJAX_DIR = REPO_ROOT / "docs" / "_static" / "mathjax" + + +def fetch(url: str, out_path: Path) -> None: + out_path.parent.mkdir(parents=True, exist_ok=True) + with urllib.request.urlopen(url) as r: + out_path.write_bytes(r.read()) + + +def npm_latest(pkg: str) -> str: + """Resolve the ``latest`` dist-tag of ``pkg`` to an exact version.""" + url = f"https://registry.npmjs.org/{pkg.replace('/', '%2F')}" + with urllib.request.urlopen(url) as r: + meta = json.load(r) + return meta["dist-tags"]["latest"] + + +def vendor_core() -> None: + version = npm_latest("mathjax") + url = f"https://cdn.jsdelivr.net/npm/mathjax@{version}/tex-mml-chtml.js" + out = MATHJAX_DIR / "tex-mml-chtml.js" + print(f"core: mathjax@{version}") + fetch(url, out) + print(f" -> {out.relative_to(REPO_ROOT)} ({out.stat().st_size:,} bytes)") + + +def vendor_font(font_name: str) -> None: + package = f"@mathjax/mathjax-{font_name}-font" + resolved_version = npm_latest(package) + print(f"font: {package}@{resolved_version}") + listing_url = f"https://data.jsdelivr.com/v1/packages/npm/{package}@{resolved_version}" + with urllib.request.urlopen(listing_url) as r: + data = json.load(r) + + base = f"https://cdn.jsdelivr.net/npm/{package}@{resolved_version}" + dest_root = MATHJAX_DIR / "fonts" / font_name + + total = 0 + count = 0 + + def walk(files, rel_prefix: str, dest_prefix: Path) -> None: + nonlocal total, count + for f in files: + p = rel_prefix + f["name"] + dest = dest_prefix / f["name"] + if f["type"] == "file": + # CHTML runtime only: the top-level chtml.js entry point and + # the on-demand chtml/ dynamic chunks plus woff2s. svg.js, + # cjs/, mjs/, tex-mml-*-font.js and the SVG tree are ~10 MB + # of source/Node modules / SVG-output assets we never hit. + keep = p == "chtml.js" or p.startswith("chtml/") + if keep: + fetch(f"{base}/{p}", dest) + total += dest.stat().st_size + count += 1 + else: + walk(f.get("files", []), p + "/", dest) + + walk(data["files"], "", dest_root) + print(f" -> {count} files, {total:,} bytes under " + f"{dest_root.relative_to(REPO_ROOT)}/") + + +def clean_other_fonts(keep: str) -> None: + fonts_dir = MATHJAX_DIR / "fonts" + if not fonts_dir.exists(): + return + for child in fonts_dir.iterdir(): + if child.is_dir() and child.name != keep: + print(f"clean: removing {child.relative_to(REPO_ROOT)}/") + shutil.rmtree(child) + + +def main() -> int: + ap = argparse.ArgumentParser(description=__doc__.splitlines()[0]) + ap.add_argument("font", nargs="?", default="termes", + help="font package name (default: termes)") + ap.add_argument("--clean", action="store_true", + help="remove other vendored fonts to keep the repo lean") + args = ap.parse_args() + + print(f"Vendoring MathJax core + {args.font} font") + print(f"Target: {MATHJAX_DIR.relative_to(REPO_ROOT)}/") + vendor_core() + vendor_font(args.font) + if args.clean: + clean_other_fonts(keep=args.font) + print("Done. Update docs/conf.py so the font name matches if you swapped.") + return 0 + + +if __name__ == "__main__": + sys.exit(main()) diff --git a/docs/tutorials/figs/minimum-energy-planning/arm.gif b/docs/tutorials/figs/minimum-energy-planning/arm.gif new file mode 100644 index 0000000..35eef83 Binary files /dev/null and b/docs/tutorials/figs/minimum-energy-planning/arm.gif differ diff --git a/docs/tutorials/figs/jacobi_combined.svg b/docs/tutorials/figs/minimum-energy-planning/jacobi_combined.svg similarity index 100% rename from docs/tutorials/figs/jacobi_combined.svg rename to docs/tutorials/figs/minimum-energy-planning/jacobi_combined.svg diff --git a/docs/tutorials/figs/ke_metric.svg b/docs/tutorials/figs/minimum-energy-planning/ke_metric.svg similarity index 100% rename from docs/tutorials/figs/ke_metric.svg rename to docs/tutorials/figs/minimum-energy-planning/ke_metric.svg diff --git a/docs/tutorials/figs/minimum-energy-planning/planning_result.svg b/docs/tutorials/figs/minimum-energy-planning/planning_result.svg new file mode 100644 index 0000000..75257b5 --- /dev/null +++ b/docs/tutorials/figs/minimum-energy-planning/planning_result.svg @@ -0,0 +1,285070 @@ + + + + + + + + 2026-04-21T12:41:48.592937 + image/svg+xml + + + Matplotlib v3.10.8, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/tutorials/figs/minimum_energy_planning.svg b/docs/tutorials/figs/minimum_energy_planning.svg deleted file mode 100644 index c11c3b4..0000000 --- a/docs/tutorials/figs/minimum_energy_planning.svg +++ /dev/null @@ -1,293407 +0,0 @@ - - - - - - - - 2026-02-25T12:44:09.690907 - image/svg+xml - - - Matplotlib v3.10.8, https://matplotlib.org/ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/docs/tutorials/figs/se2-planning/clearance_comparison.svg b/docs/tutorials/figs/se2-planning/clearance_comparison.svg new file mode 100644 index 0000000..901527f --- /dev/null +++ b/docs/tutorials/figs/se2-planning/clearance_comparison.svg @@ -0,0 +1,33551 @@ + + + + + + + + 2026-04-21T13:48:08.189985 + image/svg+xml + + + Matplotlib v3.10.8, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/tutorials/figs/se2-planning/conformal_factor.svg b/docs/tutorials/figs/se2-planning/conformal_factor.svg new file mode 100644 index 0000000..f4c0694 --- /dev/null +++ b/docs/tutorials/figs/se2-planning/conformal_factor.svg @@ -0,0 +1,1463 @@ + + + + + + + + 2026-04-21T13:48:06.447892 + image/svg+xml + + + Matplotlib v3.10.8, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/tutorials/figs/se2-planning/diff_clearance_result.svg b/docs/tutorials/figs/se2-planning/diff_clearance_result.svg new file mode 100644 index 0000000..c138325 --- /dev/null +++ b/docs/tutorials/figs/se2-planning/diff_clearance_result.svg @@ -0,0 +1,14392 @@ + + + + + + + + 2026-04-21T13:48:05.578669 + image/svg+xml + + + Matplotlib v3.10.8, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/tutorials/figs/se2-planning/diff_clearance_sweep.gif b/docs/tutorials/figs/se2-planning/diff_clearance_sweep.gif new file mode 100644 index 0000000..355a5fb Binary files /dev/null and b/docs/tutorials/figs/se2-planning/diff_clearance_sweep.gif differ diff --git a/docs/tutorials/figs/se2-planning/diff_drive_result.svg b/docs/tutorials/figs/se2-planning/diff_drive_result.svg new file mode 100644 index 0000000..26f1528 --- /dev/null +++ b/docs/tutorials/figs/se2-planning/diff_drive_result.svg @@ -0,0 +1,11971 @@ + + + + + + + + 2026-04-21T13:48:04.384518 + image/svg+xml + + + Matplotlib v3.10.8, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/tutorials/figs/se2-planning/diff_drive_sweep.gif b/docs/tutorials/figs/se2-planning/diff_drive_sweep.gif new file mode 100644 index 0000000..c12e3d1 Binary files /dev/null and b/docs/tutorials/figs/se2-planning/diff_drive_sweep.gif differ diff --git a/docs/tutorials/figs/se2-planning/footprint_checking.svg b/docs/tutorials/figs/se2-planning/footprint_checking.svg new file mode 100644 index 0000000..90fc812 --- /dev/null +++ b/docs/tutorials/figs/se2-planning/footprint_checking.svg @@ -0,0 +1,2489 @@ + + + + + + + + 2026-04-13T08:26:50.778728 + image/svg+xml + + + Matplotlib v3.10.8, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/tutorials/figs/se2-planning/holonomic_result.svg b/docs/tutorials/figs/se2-planning/holonomic_result.svg new file mode 100644 index 0000000..0bd6347 --- /dev/null +++ b/docs/tutorials/figs/se2-planning/holonomic_result.svg @@ -0,0 +1,23104 @@ + + + + + + + + 2026-04-21T13:48:03.158213 + image/svg+xml + + + Matplotlib v3.10.8, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/tutorials/figs/se2-planning/holonomic_sweep.gif b/docs/tutorials/figs/se2-planning/holonomic_sweep.gif new file mode 100644 index 0000000..6202532 Binary files /dev/null and b/docs/tutorials/figs/se2-planning/holonomic_sweep.gif differ diff --git a/docs/tutorials/figs/se2-planning/inflation.svg b/docs/tutorials/figs/se2-planning/inflation.svg new file mode 100644 index 0000000..eb05025 --- /dev/null +++ b/docs/tutorials/figs/se2-planning/inflation.svg @@ -0,0 +1,764 @@ + + + + + + + + 2026-04-13T08:26:50.656081 + image/svg+xml + + + Matplotlib v3.10.8, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/tutorials/figs/se2-planning/parking_footprints.gif b/docs/tutorials/figs/se2-planning/parking_footprints.gif new file mode 100644 index 0000000..fb941cd Binary files /dev/null and b/docs/tutorials/figs/se2-planning/parking_footprints.gif differ diff --git a/docs/tutorials/figs/se2-planning/parking_lot.svg b/docs/tutorials/figs/se2-planning/parking_lot.svg new file mode 100644 index 0000000..10e2907 --- /dev/null +++ b/docs/tutorials/figs/se2-planning/parking_lot.svg @@ -0,0 +1,1209 @@ + + + + + + + + 2026-04-21T13:48:10.489669 + image/svg+xml + + + Matplotlib v3.10.8, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/tutorials/figs/se2-planning/parking_result.svg b/docs/tutorials/figs/se2-planning/parking_result.svg new file mode 100644 index 0000000..b16e601 --- /dev/null +++ b/docs/tutorials/figs/se2-planning/parking_result.svg @@ -0,0 +1,17062 @@ + + + + + + + + 2026-04-21T13:48:09.742169 + image/svg+xml + + + Matplotlib v3.10.8, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/tutorials/figs/se2-planning/poses_and_footprints.svg b/docs/tutorials/figs/se2-planning/poses_and_footprints.svg new file mode 100644 index 0000000..a244029 --- /dev/null +++ b/docs/tutorials/figs/se2-planning/poses_and_footprints.svg @@ -0,0 +1,757 @@ + + + + + + + + 2026-04-13T08:26:50.580712 + image/svg+xml + + + Matplotlib v3.10.8, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/tutorials/figs/se2-planning/willow_corridor.svg b/docs/tutorials/figs/se2-planning/willow_corridor.svg new file mode 100644 index 0000000..de1061e --- /dev/null +++ b/docs/tutorials/figs/se2-planning/willow_corridor.svg @@ -0,0 +1,1393 @@ + + + + + + + + 2026-04-20T18:19:20.125571 + image/svg+xml + + + Matplotlib v3.10.8, https://matplotlib.org/ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/docs/tutorials/geodex-basics.rst b/docs/tutorials/geodex-basics.rst index 0e6c7ce..0db1972 100644 --- a/docs/tutorials/geodex-basics.rst +++ b/docs/tutorials/geodex-basics.rst @@ -34,7 +34,8 @@ The simplest way to get started is with the 2-sphere, defined as the set of unit \mathbb{S}^2 = \bigl\{ p \in \mathbb{R}^3 : \|p\| = 1 \bigr\}. -In geodex, the ``Sphere<>`` class models :math:`\mathbb{S}^2`. +In geodex, the ``Sphere`` class template models :math:`\mathbb{S}^n` for any +:math:`n \geq 1`. ``Sphere<>`` is shorthand for ``Sphere<2>`` — the default 2-sphere. Creating one is straightforward: .. tabs:: @@ -49,17 +50,25 @@ Creating one is straightforward: sphere = geodex.Sphere() print("dim =", sphere.dim()) # 2 -The empty angle brackets ``<>`` mean we are using the default **metric** (``SphereRoundMetric``) and the default **retraction** (``SphereExponentialMap``). -Writing ``Sphere<>`` is equivalent to writing the fully-qualified type: +The empty angle brackets ``<>`` mean we are using the default intrinsic dimension +(``2``), the default **metric** (``SphereRoundMetric``), and the default **retraction** +(``SphereExponentialMap``). Writing ``Sphere<>`` is equivalent to writing the +fully-qualified type: .. code-block:: cpp - geodex::Sphere sphere; + geodex::Sphere<2, geodex::SphereRoundMetric, geodex::SphereExponentialMap> sphere; + +The default names ``SphereRoundMetric``, ``EuclideanStandardMetric``, and +``TorusFlatMetric`` are type aliases for ``ConstantSPDMetric`` with an identity +matrix — the ambient identity inner product. This is the **policy-based design** at the heart of geodex: the manifold is parameterized by a metric policy (what "length" means) and a retraction policy (how to move along the manifold). We will explore both in later sections. -Points on the sphere are ``Eigen::Vector3d`` unit vectors, and tangent vectors are also ``Eigen::Vector3d`` (orthogonal to the base point). +Points on :math:`\mathbb{S}^n` are ``Eigen::Vector`` unit vectors, and +tangent vectors share the same type (orthogonal to the base point). For the default +``Sphere<>`` (:math:`\mathbb{S}^2`), both are ``Eigen::Vector3d``. Manifolds at a Glance ^^^^^^^^^^^^^^^^^^^^^ @@ -76,10 +85,10 @@ The table below summarises their essential properties: - Point type - dim - Default metric - * - ``Sphere<>`` - - :math:`\mathbb{S}^2` - - ``Eigen::Vector3d`` - - 2 + * - ``Sphere`` + - :math:`\mathbb{S}^N` + - ``Eigen::Vector`` + - N - ``SphereRoundMetric`` * - ``Euclidean`` - :math:`\mathbb{R}^N` @@ -502,9 +511,9 @@ The distribution depends on the manifold: geodex::SE2<> se2; auto p1 = sphere.random_point(); // uniform on S² - auto p2 = R3.random_point(); // standard normal in R³ + auto p2 = R3.random_point(); // uniform in [-1, 1]³ auto p3 = T2.random_point(); // uniform in [0, 2π)² - auto p4 = se2.random_point(); // uniform in workspace bounds + auto p4 = se2.random_point(); // uniform in sampling bounds .. code-tab:: py @@ -514,17 +523,30 @@ The distribution depends on the manifold: se2 = geodex.SE2() p1 = sphere.random_point() # uniform on S² - p2 = euclidean.random_point() # standard normal in R³ + p2 = euclidean.random_point() # uniform in [-1, 1]³ p3 = torus.random_point() # uniform in [0, 2π)² - p4 = se2.random_point() # uniform in workspace bounds + p4 = se2.random_point() # uniform in sampling bounds -The sphere uses the standard technique of normalizing a Gaussian vector to obtain a uniform distribution on :math:`\mathbb{S}^2`. -Euclidean space draws each coordinate from a standard normal distribution. +The sphere uses the standard technique of normalizing a Gaussian vector to obtain a +uniform distribution on :math:`\mathbb{S}^n`. Euclidean space draws each coordinate +uniformly from :math:`[-1, 1]`; call ``set_sampling_bounds(lo, hi)`` to change the box. The torus samples each angle uniformly from :math:`[0, 2\pi)`. .. note:: - For SE(2), ``random_point()`` samples the position :math:`(x, y)` uniformly within workspace bounds (default: :math:`[0, 10]^2`) and the heading :math:`\theta` uniformly from :math:`[-\pi, \pi)`. + ``Euclidean``, ``Torus``, and ``SE2`` take a ``SamplerT`` policy template parameter + that drives ``random_point()``. The default is ``StochasticSampler`` (``mt19937``). + Swap in ``HaltonSampler`` for deterministic low-discrepancy quasi-random sampling — + useful for reproducible benchmarks and for planners that benefit from better + space coverage than pseudo-random draws. + + .. code-block:: cpp + + geodex::Euclidean<3, geodex::EuclideanStandardMetric<3>, geodex::HaltonSampler> R3_halton; + +.. note:: + + For SE(2), ``random_point()`` samples the position :math:`(x, y)` uniformly within the configured sampling bounds (default: :math:`[0, 10]^2`) and the heading :math:`\theta` uniformly from :math:`[-\pi, \pi)`. The bounds can be configured via the constructor. @@ -768,7 +790,7 @@ Here we use it on the sphere: Eigen::Matrix3d A = Eigen::Vector3d(4, 1, 1).asDiagonal(); geodex::ConstantSPDMetric<3> weighted{A}; - geodex::Sphere> sphere_weighted{weighted}; + geodex::Sphere<2, geodex::ConstantSPDMetric<3>> sphere_weighted{weighted}; Eigen::Vector3d p{0, 0, 1}; Eigen::Vector3d u{1, 0, 0}; @@ -817,7 +839,7 @@ This is cheaper than the true exponential map (no trigonometric functions) but o .. code-tab:: c++ - using ProjSphere = geodex::Sphere; ProjSphere sphere; diff --git a/docs/tutorials/index.rst b/docs/tutorials/index.rst index 78c46df..80d162e 100644 --- a/docs/tutorials/index.rst +++ b/docs/tutorials/index.rst @@ -9,3 +9,4 @@ Hands-on guides for using geodex. Each tutorial assumes familiarity with the geodex-basics minimum-energy-planning + se2-planning diff --git a/docs/tutorials/minimum-energy-planning.rst b/docs/tutorials/minimum-energy-planning.rst index 569d287..c4cebab 100644 --- a/docs/tutorials/minimum-energy-planning.rst +++ b/docs/tutorials/minimum-energy-planning.rst @@ -240,7 +240,7 @@ A physically larger ellipse indicates the metric is "looser" in that region, mea In both figures below, the background color maps the determinant of the metric tensor. -.. figure:: figs/ke_metric.svg +.. figure:: figs/minimum-energy-planning/ke_metric.svg :align: center :alt: KE metric ellipses over T² @@ -250,7 +250,7 @@ The kinetic energy metric ellipses, representing the unit balls of :math:`M(q)^{ Near :math:`q_2 = 0` (arm extended), the coupling between shoulder and elbow is strongest and the ellipses are elongated along :math:`q_1`, reflecting the shoulder's higher effective inertia. Near :math:`q_2 = \pm\pi` (arm folded back), the links decouple and both joints share a similar effective inertia, resulting in nearly circular ellipses. -.. figure:: figs/jacobi_combined.svg +.. figure:: figs/minimum-energy-planning/jacobi_combined.svg :align: center :alt: Jacobi metric ellipses at three energy levels @@ -280,17 +280,126 @@ Reproducing the figures: ./build/minimum_energy_grid minimum_energy_grid.json # Render SVG figures - python scripts/visualize_metric_grid.py minimum_energy_grid.json + python scripts/visualize_metric_grid.py minimum_energy_grid.json \ + --output-dir docs/tutorials/figs/minimum-energy-planning Planning with Asymptotically Optimal Planners --------------------------------------------- .. note:: - OMPL integration is coming in a future release. - This will allow plugging any Riemannian metric directly into OMPL's - asymptotically optimal planners (RRT*, BIT*, etc.) via the - ``GeodexStateSpace`` and ``GeodexOptimizationObjective`` adapters. + This example requires OMPL, which must be built from source with modern CMake targets. + See the `OMPL installation guide `_ for details. + +With a clear picture of how these metrics reshape the geometry, we can now plan actual motions on it. +We will run the motion planner three times on the same start and goal pairs, once with the Euclidean metric, once with the kinetic energy metric, and once with the Jacobi metric, and compare the resulting paths. + +geodex provides an OMPL integration layer that wraps any ``RiemannianManifold`` as an ``ompl::base::StateSpace``. +The two key classes are ``GeodexStateSpace`` (which delegates ``distance()`` and ``interpolate()`` to the manifold) and ``GeodexOptimizationObjective`` (which uses geodesic distance as the path cost). +Together, these allow you to plug any Riemannian metric into OMPL's asymptotically optimal planners without needing to modify the underlying planner itself. +The following snippet shows how to set up and solve using RRT* algorithm with each of the three metrics (see the full example for details): + +.. tabs:: + + .. code-tab:: c++ + + #include + #include + #include + #include + #include + + namespace ob = ompl::base; + namespace og = ompl::geometric; + using geodex::integration::ompl::GeodexStateSpace; + using geodex::integration::ompl::GeodexOptimizationObjective; + + // -- Flat metric (identity on R^2) -- + geodex::Euclidean<2> flat_euclidean; + + // -- Kinetic energy metric -- + PlanarArmMassMatrix mass_fn; // functor from above + geodex::KineticEnergyMetric ke_metric{mass_fn}; + geodex::ConfigurationSpace cspace_ke{geodex::Euclidean<2>{}, ke_metric}; + + // -- Jacobi metric -- + constexpr double H = 1.2 * pmax; + geodex::JacobiMetric jacobi_metric{mass_fn, potential, H}; + geodex::ConfigurationSpace cspace_j{geodex::Euclidean<2>{}, jacobi_metric}; + + // Wrap any of the above as an OMPL state space (example: Jacobi) + ob::RealVectorBounds bounds(2); + bounds.setLow(-M_PI); + bounds.setHigh(M_PI); + auto space = std::make_shared>(cspace_j, bounds); + + og::SimpleSetup ss(space); + // ... set start, goal, planner ... + auto objective = std::make_shared< + GeodexOptimizationObjective>( + ss.getSpaceInformation(), goal_coords); + ss.setOptimizationObjective(objective); + ss.setPlanner(std::make_shared(ss.getSpaceInformation())); + ss.solve(5.0); + + .. code-tab:: py + + # Python bindings do not support OMPL integration. + +.. figure:: figs/minimum-energy-planning/planning_result.svg + :align: center + :alt: RRT* under Euclidean, KE, and Jacobi metrics + + Figure: RRT* trees and solution paths under Euclidean (left), kinetic energy (centre), and Jacobi (right) metrics. Background colour maps the determinant of the respective metric tensor. + +Under the Euclidean metric, the planner treats all joint displacements equally. +The background is uniform (:math:`\det(I) = 1` everywhere) and the solution path is just a straight line in joint space. + +The kinetic energy metric biases the planner toward configurations where the effective inertia is lower. +The background shows :math:`\det(M(q))`, which varies with the elbow angle. +The path naturally curves toward folded-arm configurations (:math:`q_2` near :math:`\pm\pi`) to minimize kinematic effort. + +The Jacobi metric explicitly penalises high-potential regions through its conformal factor :math:`2(H - P(q))`. +The background shows :math:`\det(J(q))`, which shrinks toward zero near the potential ridge. +Because distances grow to infinity as :math:`P(q)` approaches :math:`H`, the planner is forced to route around the ridge. +The resulting path safely avoids configurations where the arm would fight gravity, even if it requires a longer coordinate-space detour. + +This tutorial demonstrates how the choice of Riemannian metric elegantly encodes physics directly into the planning objective. +The Euclidean metric ignores physics, the kinetic energy metric respects inertial coupling, and the Jacobi metric accounts for both inertia and gravitational potential simultaneously. + +Seeing the Arm in Motion +------------------------ + +The animation below traces the two-link arm along all three solutions side by side. + +.. figure:: figs/minimum-energy-planning/arm.gif + :align: center + :width: 95% + :alt: Two-link planar arm under the Euclidean, kinetic-energy, and Jacobi metrics. + + Figure: Planar arm sweeping along the Euclidean, kinetic-energy, and Jacobi + minimum-energy paths. + +Reproducing the figures: + +.. toggle:: + + .. code-block:: sh + + # Requires matplotlib and LaTeX + pip install matplotlib + sudo apt update && sudo apt install -y texlive-latex-extra dvipng cm-super + + # Configure and build (requires OMPL) + cmake -B build -DBUILD_OMPL_EXAMPLES=ON -Dompl_DIR=/path/to/ompl/install/share/ompl/cmake + cmake --build build --target minimum_energy_planning + + # Run the planning example + ./build/examples/ompl/minimum_energy_planning minimum_energy_planning.json + + # Render SVG figure and animation + python scripts/visualize_minimum_energy_planning.py minimum_energy_planning.json \ + --output-dir docs/tutorials/figs/minimum-energy-planning References ---------- diff --git a/docs/tutorials/se2-planning.rst b/docs/tutorials/se2-planning.rst new file mode 100644 index 0000000..17881e9 --- /dev/null +++ b/docs/tutorials/se2-planning.rst @@ -0,0 +1,773 @@ +SE(2) Motion Planning +===================== + +This tutorial walks through motion planning in :math:`\mathrm{SE}(2)` for three +increasingly constrained robot types: a holonomic circular robot, a differential-drive +robot with a rectangular footprint, and a car-like vehicle that parks between obstacles. +Along the way we will also go through the geodex collision checking module, polygon footprint +validation, SDF-based clearance metrics, and the full OMPL planning and smoothing +pipeline. By the end you will know how to set up an :math:`\mathrm{SE}(2)` planner +on an occupancy grid or among rectangle obstacles, and how to tune the clearance metric +so planned paths maintain safe distance from walls. + +.. note:: + + This tutorial assumes you have :doc:`installed geodex ` with + OMPL support (see `OMPL installation guide `_) + and are familiar with the basic geodex operations covered in :doc:`geodex-basics`. + All the code will be in C++ only since the OMPL adapter layer does not have Python bindings support yet. + +Poses and Footprints +-------------------- + +A pose in :math:`\mathrm{SE}(2) = \mathbb{R}^2 \rtimes \mathrm{SO}(2)` is a triple +:math:`(x, y, \theta)` that encodes a planar position and orientation. In geodex the +:cpp:class:`geodex::SE2` class represents this Lie group, with poses stored as ``Eigen::Vector3d``: + +.. code-block:: cpp + + #include + #include + + geodex::SE2<> se2; + Eigen::Vector3d pose{5.0, 3.0, M_PI / 4.0}; // (x, y, theta) + +A real robot is not a point. Its physical shape, the **footprint**, is a set of +body-frame points that move rigidly with the pose. Footprint shape is purely +geometric and independent of the kinematic model: a differential-drive or car-like +robot can be approximated by a disc, and a holonomic robot can just as easily +carry a rectangular or polygonal outline. A disc reduces collision to a single point +query against an inflated distance field, while rectangles and convex polygons capture +elongated or asymmetric shapes at the cost of a heading-dependent test. +The figure below shows the three robots at a pose with body-frame axes +:math:`x` (red, forward) and :math:`y` (green, left). + +.. figure:: figs/se2-planning/poses_and_footprints.svg + :align: center + :width: 95% + :alt: Three robot types with poses and footprints + +In code, a circular footprint is captured by its radius alone; the collision +checking module uses this radius to inflate the obstacle distance field. +Non-circular shapes use :cpp:class:`geodex::collision::PolygonFootprint`, which stores body-frame +perimeter samples of a convex polygon. +Both the ``rectangle`` factory and the general constructor take a ``samples_per_edge`` +argument that sets how many uniformly-spaced points are placed along each edge: + +.. code-block:: cpp + + // Circular footprint: a single radius. Collision reduces to a point query + // against an obstacle distance field inflated by this value. + constexpr double robot_radius = 0.3; + + // Rectangular footprint via the factory. + auto rect_fp = geodex::collision::PolygonFootprint::rectangle( + /*half_length=*/0.35, /*half_width=*/0.25, /*samples_per_edge=*/6); + + // Arbitrary convex polygon from ordered body-frame vertices (counter-clockwise). + std::vector verts = { + {-0.35, -0.30}, // rear-right + { 0.35, -0.20}, // front-right + { 0.35, 0.20}, // front-left + {-0.35, 0.30}, // rear-left + }; + geodex::collision::PolygonFootprint poly_fp(verts, /*samples_per_edge=*/4); + +More samples give tighter collision detection at a small runtime cost; four to six +per edge works well for most robot footprints at centimeter-scale grid resolutions. + + +Left-Invariant Metrics on SE(2) +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +The choice of Riemannian metric determines what "shortest path" means. +:cpp:class:`geodex::SE2LeftInvariantMetric` defines a diagonal inner product on +:math:`\mathrm{SE}(2)`: + +.. math:: + + \langle u, v \rangle_q = w_x\, u_x v_x + w_y\, u_y v_y + w_\theta\, u_\theta v_\theta + +where :math:`w_x, w_y, w_\theta > 0` are positive weights. +By adjusting these weights, we can create different motion preferences and kinematic models: + +.. list-table:: + :header-rows: 1 + :widths: 12 12 12 48 22 + + * - :math:`w_x` + - :math:`w_y` + - :math:`w_\theta` + - Behavior + - Kinematic model + * - 1.0 + - 1.0 + - 0.5 + - Isotropic translation, cheap rotation + - Holonomic + * - 1.0 + - 10.0 + - 1.0 + - Penalizes lateral sliding + - Differential drive + * - 1.0 + - 20.0 + - 2.25 + - With effective turning radius 1.5 m + - Car-like + +.. code-block:: cpp + + // Holonomic: isotropic translation. + geodex::SE2LeftInvariantMetric metric_holo{1.0, 1.0, 0.5}; + + // Differential drive: moderate lateral penalty. + geodex::SE2LeftInvariantMetric metric_diff{1.0, 10.0, 1.0}; + + // Car-like: effective turning radius of 1.5 m, lateral penalty 20. + auto metric_car = geodex::SE2LeftInvariantMetric::car_like( + /*turning_radius=*/1.5, /*lateral_penalty=*/20.0); + +The convenience factory ``car_like(turning_radius, lateral_penalty)`` sets +:math:`w_\theta = \text{turning\_radius}^2` and :math:`w_y = \text{lateral\_penalty}`, +so that the geodesic turning radius is approximately +:math:`r_\text{eff} \approx \sqrt{w_\theta / w_x}` and a large ``lateral_penalty`` +strongly discourages sideslip. This is a soft constraint: the metric penalizes +tight turns but does not forbid them. + + +Preparing the Environment +------------------------- + +Occupancy Maps and Distance Grids +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +Many indoor environments are described by an occupancy grid: a raster image where dark +pixels represent walls and light pixels represent free space. Before we can plan, we +convert this image into a **distance grid**, a precomputed Euclidean distance transform +that stores the signed distance to the nearest obstacle at every cell. The C++ class +:cpp:class:`geodex::collision::DistanceGrid` loads and queries this grid with bilinear +interpolation. + +The Willow Garage map (1222 x 966 pixels at 0.05 m/pixel) is large enough that a small +robot becomes hard to see. For this tutorial we crop it into a smaller section of approximately +18 x 12 m, which provides narrow hallways and corners that make collision checking and +clearance metrics visually interesting: + +.. figure:: figs/se2-planning/willow_corridor.svg + :align: center + :width: 90% + :alt: Cropped Willow Garage corridor with distance heatmap + + A smaller section cropped from the Willow Garage map. Left: the occupancy grid. + Right: the Euclidean distance transform over the free space, with walls shown + in black; lighter colors indicate higher clearance. + +In C++, loading the distance grid is a single call: + +.. code-block:: cpp + + geodex::collision::DistanceGrid grid; + grid.load("willow_corridor_dist.txt"); + + // World dimensions in meters. + double world_w = grid.width() * grid.resolution(); + double world_h = grid.height() * grid.resolution(); + +Synthetic Parking Lot +^^^^^^^^^^^^^^^^^^^^^ + +For the car-like parking scenario we define obstacles directly in code as oriented +rectangles (:cpp:class:`geodex::collision::RectObstacle`). Four parked cars line the +curb with a gap in the middle for the ego vehicle: + +.. code-block:: cpp + + using RectObstacle = geodex::collision::RectObstacle; + constexpr double car_hl = 2.25, car_hw = 0.9; // 4.5 x 1.8 m + + std::vector obstacles = { + {5.0, 1.35, 0.0, car_hl, car_hw}, // parked car 1 + {10.0, 1.35, 0.0, car_hl, car_hw}, // parked car 2 + {21.0, 1.35, 0.0, car_hl, car_hw}, // parked car 3 + {26.0, 1.35, 0.0, car_hl, car_hw}, // parked car 4 + {15.0, -0.05, 0.0, 15.0, 0.05}, // curb + {15.0, 10.05, 0.0, 15.0, 0.05}, // sidewalk + }; + +.. figure:: figs/se2-planning/parking_lot.svg + :align: center + :width: 90% + :alt: Synthetic parking lot environment + + The parallel parking scenario. Parked vehicles (salmon) create a gap between cars + 2 and 3. The ego vehicle approaches from the right (green) and must park in the gap + (orange star). + + +Holonomic Circular Robot +------------------------ + +The simplest case is a holonomic robot with a circular footprint of radius :math:`r`. +It can translate in any direction and rotate freely, so we use the isotropic metric +``SE2LeftInvariantMetric{1.0, 1.0, 1.0}``. + +Collision Checking for a Disc +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +For a circular robot, collision checking reduces to a point query: the robot is +collision-free if and only if the signed distance at its center exceeds the robot +radius plus a small safety buffer. A bilinear-interpolated +``DistanceGrid::distance_at`` query is enough: + +.. code-block:: cpp + + constexpr double robot_radius = 0.3; + constexpr double safety_margin = 0.10; // extra buffer beyond the robot radius + + auto is_valid = [&grid, robot_radius](const Eigen::Vector3d& q) { + return grid.distance_at(q[0], q[1]) > robot_radius + safety_margin; + }; + +For the clearance metric later in this tutorial we will also want a continuous +signed distance field that already accounts for the robot radius. That is what +:cpp:class:`geodex::collision::GridSDF` and :cpp:class:`geodex::collision::InflatedSDF` +provide: ``GridSDF`` wraps the distance grid as a callable, and ``InflatedSDF`` +subtracts the robot radius so its output is positive exactly when the disc fits. + +.. figure:: figs/se2-planning/inflation.svg + :align: center + :width: 80% + :alt: Inflation of obstacle boundary by robot radius + + Inflating the obstacle by the robot radius :math:`r`. The original boundary + (solid) becomes the inflated boundary (dashed). A circular robot whose center lies + outside the dashed line is guaranteed to be collision-free. + +Setting Up the Planner +^^^^^^^^^^^^^^^^^^^^^^ + +The OMPL pipeline begins with wrapping our geodex manifold as an OMPL state space. +:cpp:class:`geodex::integration::ompl::GeodexStateSpace` handles this automatically: +it delegates distance, interpolation, and sampling to the underlying manifold. The +validity checker and optimization objective complete the setup: + +.. code-block:: cpp + + namespace ob = ompl::base; + namespace og = ompl::geometric; + + // 1. Create manifold and state space. + geodex::SE2LeftInvariantMetric metric{1.0, 1.0, 1.0}; + geodex::SE2<> manifold{metric, geodex::SE2ExponentialMap{}, + Eigen::Vector3d(0, 0, -M_PI), + Eigen::Vector3d(world_w, world_h, M_PI)}; + + ob::RealVectorBounds bounds(3); + bounds.setLow(0, 0.0); bounds.setHigh(0, world_w); + bounds.setLow(1, 0.0); bounds.setHigh(1, world_h); + bounds.setLow(2, -M_PI); bounds.setHigh(2, M_PI); + + auto space = std::make_shared>(manifold, bounds); + space->setCollisionResolution(grid.resolution()); + + // 2. SimpleSetup with validity checker. + og::SimpleSetup ss(space); + ss.setStateValidityChecker( + make_validity_checker( + ss.getSpaceInformation(), is_valid)); + + // 3. Start and goal. + using SS = geodex::integration::ompl::GeodexStateSpace; + ob::ScopedState start(space), goal(space); + start->values[0] = 2.0; start->values[1] = 5.0; start->values[2] = 0.0; + goal->values[0] = 12.0; goal->values[1] = 6.0; goal->values[2] = -M_PI/2; + ss.setStartAndGoalStates(start, goal, 0.5); + + // 4. Optimization objective. + Eigen::Vector3d goal_coords{12.0, 6.0, -M_PI/2}; + auto objective = std::make_shared< + GeodexOptimizationObjective>( + ss.getSpaceInformation(), goal_coords); + ss.setOptimizationObjective(objective); + + // 5. Plan with Informed RRT*. + ss.setPlanner(std::make_shared(ss.getSpaceInformation())); + ss.solve(0.5); + +Path Smoothing +^^^^^^^^^^^^^^ + +The raw RRT* solution is piecewise-geodesic with unnecessary detours. The +``smooth_path`` function refines it in two phases: random shortcutting removes +redundant waypoints, then L-BFGS energy minimization pulls the remaining path +toward the metric geodesic while respecting collision constraints: + +.. code-block:: cpp + + // Extract waypoints from the OMPL solution path. + auto& solution = ss.getSolutionPath(); + std::vector waypoints; + for (const auto* state : solution.getStates()) { + const auto* s = state->as(); + waypoints.push_back({s->values[0], s->values[1], s->values[2]}); + } + + auto result = geodex::algorithm::smooth_path(manifold, is_valid, waypoints); + +.. figure:: figs/se2-planning/holonomic_result.svg + :align: center + :width: 90% + :alt: Holonomic circular robot planning result + + Planning result under the isotropic metric. The RRT* tree (gray), + raw path (dashed red), and smoothed path (solid blue) are shown with + circular footprints drawn at intervals along the smoothed trajectory. + +.. figure:: figs/se2-planning/holonomic_sweep.gif + :align: center + :width: 70% + :alt: Animated holonomic robot sweep + + The circular robot following the smoothed path through the corridor. + +Reproducing the figures: + +.. toggle:: + + .. code-block:: sh + + cmake -B build -DBUILD_OMPL_EXAMPLES=ON -Dompl_DIR=/path/to/ompl + cmake --build build --target se2_tutorial + + DIST=examples/ompl/willow_corridor_dist.txt + ./build/examples/ompl/se2_tutorial $DIST \ + --scenario=holonomic -o se2_tutorial_holonomic.json --time=0.5 --seed=1 + + python scripts/visualize_se2_tutorial.py \ + se2_tutorial_holonomic.json \ + -o docs/tutorials/figs/se2-planning/holonomic_result.svg \ + --map examples/ompl/willow_corridor.png + + python scripts/animate_se2_tutorial.py \ + se2_tutorial_holonomic.json \ + -o docs/tutorials/figs/se2-planning/holonomic_sweep.gif \ + --map examples/ompl/willow_corridor.png + + +Differential-Drive Robot +------------------------ + +A differential-drive robot has two independently driven wheels. It can move forward, +backward, and rotate in place, but it cannot slide sideways without rotating first. +This kinematic constraint is captured by an anisotropic metric that penalizes lateral +motion, independently of footprint shape. We also switch to a rectangular footprint +for this scenario to illustrate orientation-dependent collision checking, though the +same metric applies just as well to a circular chassis. + + +Polygon Footprint Collision Checking +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +For a non-circular robot the inflated SDF trick no longer works: whether the robot +collides or not now depends on both its position and its heading. The geodex collision module +provides :cpp:class:`geodex::collision::PolygonFootprint` and +:cpp:class:`geodex::collision::FootprintGridChecker` for this purpose. + +``PolygonFootprint`` precomputes a set of body-frame **perimeter samples** around the +robot outline. At query time, ``FootprintGridChecker`` transforms all samples to world +coordinates (using a single ``sincos`` call shared across all points), batch-queries the +distance grid with SIMD-accelerated bilinear interpolation, and returns the minimum +signed distance across all samples. If this minimum is positive, the entire footprint is +collision-free: + +.. code-block:: cpp + + auto footprint = geodex::collision::PolygonFootprint::rectangle( + /*half_length=*/0.35, /*half_width=*/0.25, /*samples_per_edge=*/6); + + geodex::collision::FootprintGridChecker checker{&grid, footprint, /*safety_margin=*/0.10}; + + auto is_valid = [&checker](const auto& q) { + return checker.is_valid(q); + }; + +.. figure:: figs/se2-planning/footprint_checking.svg + :align: center + :width: 90% + :alt: Polygon footprint collision checking + + Left: body-frame perimeter samples around the rectangular footprint. Right: the + samples transformed to world frame and checked against the distance grid. Orange + dotted lines show the distance query from each sample to the nearest wall. + + +Anisotropic Metric for Differential Drive +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +A differential-drive robot prefers forward and backward motion over lateral sliding. We +express this by setting :math:`w_y > w_x` in the left-invariant metric, which makes +lateral motion "expensive" in the Riemannian sense. The planner then naturally produces +paths with forward-facing arcs and in-place rotations at turns rather than diagonal +sliding motions: + +.. code-block:: cpp + + geodex::SE2LeftInvariantMetric metric{1.0, 10.0, 1.0}; + geodex::SE2<> manifold{metric, geodex::SE2ExponentialMap{}, + Eigen::Vector3d(0, 0, -M_PI), + Eigen::Vector3d(world_w, world_h, M_PI)}; + +The planner setup is identical to the holonomic case, substituting this manifold and the +footprint-based validity checker for the inflated SDF one. + +.. figure:: figs/se2-planning/diff_drive_result.svg + :align: center + :width: 90% + :alt: Differential-drive robot planning result + + A differential-drive robot navigating the corridor. The anisotropic metric produces + paths with clear forward-facing motion and rotation at waypoints. + +.. figure:: figs/se2-planning/diff_drive_sweep.gif + :align: center + :width: 70% + :alt: Animated differential-drive robot sweep + + A differential-drive robot under (anisotropic) left-invariant Riemannian metric. + +Reproducing the figures: + +.. toggle:: + + .. code-block:: sh + + ./build/examples/ompl/se2_tutorial $DIST \ + --scenario=diff_drive -o se2_tutorial_diff_drive.json --time=0.5 --seed=1 + + python scripts/visualize_se2_tutorial.py \ + se2_tutorial_diff_drive.json \ + -o docs/tutorials/figs/se2-planning/diff_drive_result.svg \ + --map examples/ompl/willow_corridor.png + + python scripts/animate_se2_tutorial.py \ + se2_tutorial_diff_drive.json \ + -o docs/tutorials/figs/se2-planning/diff_drive_sweep.gif \ + --map examples/ompl/willow_corridor.png + + +Clearance-Aware Planning +------------------------ + +The paths produced so far are geometrically shortest under the chosen metric, but they +may brush close to walls. A real robot needs clearance: it should prefer routes through +the middle of a corridor even if they are slightly longer. The geodex +**conformal clearance metric** achieves this by warping the Riemannian geometry near +obstacles. + +The Conformal Clearance Metric +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +:cpp:class:`geodex::SDFConformalMetric` wraps any base metric and conformally scales it +by a factor that grows near obstacles: + +.. math:: + + c(q) = 1 + \kappa \exp\bigl(-\beta \cdot \mathrm{sdf}(q)\bigr) + +where :math:`\mathrm{sdf}(q)` is the signed distance from the robot to the nearest +obstacle (positive in free space), :math:`\kappa` controls the strength of the +repulsion, and :math:`\beta` controls the falloff rate. The inner product becomes + +.. math:: + + \langle u, v \rangle_q^{\text{clear}} = c(q) \cdot \langle u, v \rangle_q^{\text{base}} + +so that paths near obstacles become "longer" in the metric sense. The planner, which +minimizes path cost, naturally routes through regions where :math:`c(q) \approx 1` +(high clearance). + +.. figure:: figs/se2-planning/conformal_factor.svg + :align: center + :width: 80% + :alt: Conformal factor heatmap + + The conformal factor :math:`c(q)` overlaid on the corridor map with + :math:`\kappa = 1.5` and :math:`\beta = 1.5`. Warm colors near walls indicate + high metric cost; cool regions in the corridor center have + :math:`c(q) \approx 1`. + +To apply the clearance metric we create a +:cpp:class:`geodex::ConfigurationSpace` that overlays the clearance-weighted metric on +the base :math:`\mathrm{SE}(2)` topology. The base manifold provides the exponential +and logarithmic maps, while the custom metric provides all geometry (inner product, +norm, distance): + +.. code-block:: cpp + + // Base metric and SDF (inflated by robot radius for a circular robot). + geodex::SE2LeftInvariantMetric base_metric{1.0, 1.0, 1.0}; + geodex::collision::InflatedSDF inflated_sdf{ + geodex::collision::GridSDF{&grid}, 0.3}; + + // Conformal clearance metric: kappa=1.5, beta=1.5. + geodex::SDFConformalMetric clearance_metric{ + base_metric, inflated_sdf, 1.5, 1.5}; + + // Compose: SE(2) topology + clearance geometry. + geodex::SE2<> se2{base_metric, geodex::SE2ExponentialMap{}, + Eigen::Vector3d(0, 0, -M_PI), + Eigen::Vector3d(world_w, world_h, M_PI)}; + geodex::ConfigurationSpace cspace{se2, clearance_metric}; + +The ``cspace`` object satisfies the ``RiemannianManifold`` concept and can be passed +to ``GeodexStateSpace``, ``smooth_path``, and any other geodex algorithm. + +With vs Without Clearance +^^^^^^^^^^^^^^^^^^^^^^^^^ + +.. figure:: figs/se2-planning/clearance_comparison.svg + :align: center + :width: 90% + :alt: Planning with and without clearance metric + + Holonomic robot in the corridor. Left: baseline isotropic metric (the path cuts + close to walls). Right: clearance metric with :math:`\kappa=1.5, \beta=1.5` + (the path maintains safe distance from walls throughout). + + +Clearance for the Differential-Drive Robot +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +An appealing property of ``FootprintGridChecker`` is that its ``operator()`` returns a +continuous signed distance (the minimum grid distance across all perimeter samples minus +the safety margin), not just a binary collision result. This makes it directly usable as +the SDF input to ``SDFConformalMetric``. The same object serves double duty: binary +validity checking for the planner, and continuous clearance field for the metric: + +.. code-block:: cpp + + auto footprint = geodex::collision::PolygonFootprint::rectangle(0.35, 0.25, 6); + geodex::collision::FootprintGridChecker checker{&grid, footprint, 0.05}; + + // Binary validity for the planner. + auto is_valid = [&checker](const auto& q) { return checker.is_valid(q); }; + + // Continuous SDF for the clearance metric (same object). + geodex::SE2LeftInvariantMetric base_metric{1.0, 10.0, 1.0}; + geodex::SDFConformalMetric clearance_metric{base_metric, checker, 1.5, 1.5}; + + geodex::SE2<> se2{base_metric, geodex::SE2ExponentialMap{}, + Eigen::Vector3d(0, 0, -M_PI), + Eigen::Vector3d(world_w, world_h, M_PI)}; + geodex::ConfigurationSpace cspace{se2, clearance_metric}; + +.. figure:: figs/se2-planning/diff_clearance_result.svg + :align: center + :width: 90% + :alt: Differential-drive robot with clearance metric + + A Differential-drive robot under the clearance metric. The combined effect of + anisotropic weights (preferring forward motion) and conformal scaling (avoiding + walls) produces paths that track the corridor center with smooth forward-facing arcs. + +.. figure:: figs/se2-planning/diff_clearance_sweep.gif + :align: center + :width: 70% + :alt: Animated differential-drive robot with clearance + + A Differential-drive robot following the smoothed path with the clearance metric active. + +Reproducing the figures: + +.. toggle:: + + .. code-block:: sh + + ./build/examples/ompl/se2_tutorial $DIST \ + --scenario=holo_clearance -o se2_tutorial_holo_clearance.json --time=0.5 --seed=1 + ./build/examples/ompl/se2_tutorial $DIST \ + --scenario=diff_clearance -o se2_tutorial_diff_clearance.json --time=0.5 --seed=1 + + FIGS=docs/tutorials/figs/se2-planning + MAP=examples/ompl/willow_corridor.png + + python scripts/visualize_se2_tutorial.py \ + se2_tutorial_holo_clearance.json \ + -o $FIGS/conformal_factor.svg --map $MAP --mode conformal + + python scripts/visualize_se2_tutorial.py \ + se2_tutorial_holonomic.json se2_tutorial_holo_clearance.json \ + -o $FIGS/clearance_comparison.svg --map $MAP --mode comparison + + python scripts/visualize_se2_tutorial.py \ + se2_tutorial_diff_clearance.json \ + -o $FIGS/diff_clearance_result.svg --map $MAP + + python scripts/animate_se2_tutorial.py \ + se2_tutorial_diff_clearance.json \ + -o $FIGS/diff_clearance_sweep.gif --map $MAP + + +Car-Like Robot in a Parking Lot +------------------------------- + +The most constrained robot type is a car-like vehicle with an effective minimum turning +radius and no lateral motion. We use the synthetic parking lot defined earlier and plan a +parallel parking maneuver. + +The Car-Like Metric +^^^^^^^^^^^^^^^^^^^ + +The ``car_like(r, lp)`` factory creates metric weights that produce geodesics with an +effective turning radius of approximately :math:`r`. A moderate lateral penalty +(:math:`w_y = 20`) strongly discourages sideslip while keeping the metric landscape +tractable for an RRT\* tree, so the planner produces smooth arcs rather than +diagonal motions: + +.. code-block:: cpp + + auto metric = geodex::SE2LeftInvariantMetric::car_like(1.5, 20.0); + // Weights: wx=1.0, wy=20.0, w_theta=2.25 (= 1.5^2) + +Note that this is a soft constraint. Near the start and goal, the optimizer may produce +short segments of in-place rotation where a real Ackermann vehicle would need a +multi-point turn. + +Rectangle Obstacles and RectSmoothSDF +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +The parking scenario uses :cpp:class:`geodex::collision::RectSmoothSDF` to compute a +smooth signed distance field over the oriented rectangle obstacles. Like +``CircleSmoothSDF``, it uses log-sum-exp to produce a differentiable approximation to +the min-distance, but with SIMD-accelerated rectangle SDF evaluation internally: + +.. code-block:: cpp + + geodex::collision::RectSmoothSDF sdf{obstacles, 20.0, car_hw}; + // beta=20 (smoothness), inflation=car_hw (half-width of ego vehicle) + +The ``inflation`` parameter performs Minkowski expansion: it subtracts the ego vehicle's +half-width from all obstacle distances inside the SIMD loop, effectively growing +obstacles by the robot's lateral extent. This gives the clearance metric an +inflation-aware SDF without requiring a separate wrapper. + +For the binary validity check we use the exact separating-axis-theorem (SAT) test +:cpp:func:`geodex::collision::rects_overlap`, which checks whether the ego vehicle's +oriented bounding box overlaps any obstacle: + +.. code-block:: cpp + + auto is_valid = [&](const auto& q) { + RectObstacle ego{q[0], q[1], q[2], car_hl, car_hw}; + for (const auto& obs : obstacles) { + if (geodex::collision::rects_overlap(ego, obs)) return false; + } + return true; + }; + + +Full Parking Pipeline +^^^^^^^^^^^^^^^^^^^^^ + +Putting it all together: the car-like metric is wrapped with ``SDFConformalMetric`` for +clearance-aware planning, and the composite +``ConfigurationSpace`` is passed to the OMPL planner. Higher :math:`\kappa` values +(we use 8.0 here) keep the vehicle further from parked cars during the approach: + +.. code-block:: cpp + + auto base_metric = geodex::SE2LeftInvariantMetric::car_like(1.5, 20.0); + geodex::collision::RectSmoothSDF sdf{obstacles, 20.0, car_hw}; + geodex::SDFConformalMetric clearance_metric{base_metric, sdf, 8.0, 3.0}; + + geodex::SE2 se2{ + geodex::SE2LeftInvariantMetric::car_like(1.5, 20.0), + geodex::SE2ExponentialMap{}, + Eigen::Vector3d(0, 0, -M_PI), + Eigen::Vector3d(30.0, 12.0, M_PI)}; + geodex::ConfigurationSpace cspace{se2, clearance_metric}; + + // Smoothing with tighter interpolation for car-like metric. + geodex::algorithm::PathSmoothingSettings car_smooth; + car_smooth.interp.step_size = 0.02; + car_smooth.interp.max_steps = 2000; + car_smooth.collision_resolution = 0.1; + +.. figure:: figs/se2-planning/parking_result.svg + :align: center + :width: 90% + :alt: Car-like parallel parking result + + Parallel parking with the car-like metric. The vehicle approaches from the right and + executes a reverse maneuver to park between vehicles. Rectangular + footprints at intervals show the pose progression. + +.. figure:: figs/se2-planning/parking_footprints.gif + :align: center + :width: 85% + :alt: Animated parking footprint sweep + + Animated footprint sweep along the parking path. + +Reproducing the figures: + +.. toggle:: + + .. code-block:: sh + + ./build/examples/ompl/se2_tutorial dummy \ + --scenario=parking -o se2_tutorial_parking.json --time=0.5 --seed=1 + + python scripts/visualize_se2_tutorial.py \ + se2_tutorial_parking.json \ + -o docs/tutorials/figs/se2-planning/parking_result.svg + + python scripts/visualize_se2_tutorial.py \ + se2_tutorial_parking.json \ + -o docs/tutorials/figs/se2-planning/parking_lot.svg --mode env + + python scripts/animate_se2_tutorial.py \ + se2_tutorial_parking.json \ + -o docs/tutorials/figs/se2-planning/parking_footprints.gif --fps 15 + + +Summary +------- + +This tutorial covered the full SE(2) planning pipeline in geodex with three robot types, +progressively adding complexity at each stage: + +.. list-table:: + :header-rows: 1 + :class: scroll-table + + * - Metric + - Robot + - Collision + - Clearance SDF + - Env + * - Isotropic (1, 1, 1) + - Holonomic (circle) + - ``InflatedSDF`` + - ``InflatedSDF`` + - Willow corridor + * - Anisotropic (1, 10, 1) + - Diff-drive (rect) + - ``FootprintGridChecker`` + - ``FootprintGridChecker`` + - Willow corridor + * - ``car_like(1.5, 20)`` + - Car-like (rect) + - SAT ``rects_overlap`` + - ``RectSmoothSDF`` + - Parking lot + +See also +^^^^^^^^ + +- :doc:`geodex-basics` for an introduction to manifolds, metrics, and geodesics +- :doc:`minimum-energy-planning` for planning with configuration-dependent metrics +- The :doc:`/api/index` for full documentation of the collision module and OMPL adapters + + diff --git a/examples/CMakeLists.txt b/examples/CMakeLists.txt index 9d76172..e89833e 100644 --- a/examples/CMakeLists.txt +++ b/examples/CMakeLists.txt @@ -4,5 +4,16 @@ target_link_libraries(sphere_basics PRIVATE geodex) add_executable(sphere_distance sphere_distance.cpp) target_link_libraries(sphere_distance PRIVATE geodex) +add_executable(sphere_interpolation sphere_interpolation.cpp) +target_link_libraries(sphere_interpolation PRIVATE geodex) + add_executable(minimum_energy_grid minimum_energy_grid.cpp) target_link_libraries(minimum_energy_grid PRIVATE geodex) + +install(TARGETS + sphere_basics + sphere_distance + sphere_interpolation + minimum_energy_grid + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} +) diff --git a/examples/minimum_energy_grid.cpp b/examples/minimum_energy_grid.cpp index 7c14243..c2bf82d 100644 --- a/examples/minimum_energy_grid.cpp +++ b/examples/minimum_energy_grid.cpp @@ -8,15 +8,17 @@ /// Usage: /// ./minimum_energy_grid [output.json] -#include -#include #include + #include #include #include #include #include +#include +#include + namespace { /// 2-link planar arm parameters. @@ -53,9 +55,7 @@ double potential(const Eigen::Vector2d& q, const ArmParams& p) { /// Analytical upper bound on potential energy. /// Pmax = g * (m1*lc1 + m2*(l1 + lc2)) -double pmax_analytical(const ArmParams& p) { - return p.g * (p.m1 * p.lc1 + p.m2 * (p.l1 + p.lc2)); -} +double pmax_analytical(const ArmParams& p) { return p.g * (p.m1 * p.lc1 + p.m2 * (p.l1 + p.lc2)); } /// Write a 2x2 matrix as [[a,b],[c,d]]. void write_matrix2d(std::ostream& out, const Eigen::Matrix2d& M) { diff --git a/examples/ompl/CMakeLists.txt b/examples/ompl/CMakeLists.txt new file mode 100644 index 0000000..09cd686 --- /dev/null +++ b/examples/ompl/CMakeLists.txt @@ -0,0 +1,11 @@ +add_executable(minimum_energy_planning minimum_energy_planning.cpp) +target_link_libraries(minimum_energy_planning PRIVATE geodex ompl::ompl) + +add_executable(se2_tutorial se2_tutorial.cpp) +target_link_libraries(se2_tutorial PRIVATE geodex ompl::ompl) + +install(TARGETS + minimum_energy_planning + se2_tutorial + RUNTIME DESTINATION ${CMAKE_INSTALL_BINDIR} +) diff --git a/examples/ompl/minimum_energy_planning.cpp b/examples/ompl/minimum_energy_planning.cpp new file mode 100644 index 0000000..1222731 --- /dev/null +++ b/examples/ompl/minimum_energy_planning.cpp @@ -0,0 +1,300 @@ +#include + +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +#include "geodex/algorithm/path_smoothing.hpp" +#include "geodex/integration/ompl/geodex_optimization_objective.hpp" +#include "geodex/integration/ompl/geodex_state_space.hpp" +#include "geodex/manifold/configuration_space.hpp" +#include "geodex/manifold/euclidean.hpp" +#include "geodex/metrics/jacobi.hpp" +#include "geodex/metrics/kinetic_energy.hpp" + +namespace ob = ompl::base; +namespace og = ompl::geometric; + +struct RunResult { + std::string label; + std::string metric_info; + std::vector> raw_path; + std::vector> smoothed_path; + std::vector, 2>> tree; + bool solved = false; +}; + +struct RunConfig { + double lo = -M_PI, hi = M_PI; + double start_x = 0.0, start_y = 0.0; + double goal_x = 0.0, goal_y = 0.0; +}; + +using PlannerFactory = std::function; + +/// Run RRT* on a given manifold. +template +RunResult run_planner(ManifoldT manifold, const std::string& label, const std::string& metric_info, + const PlannerFactory& make_planner, double solve_time, const RunConfig& cfg, + double range = 0.0) { + using StateSpace = geodex::integration::ompl::GeodexStateSpace; + using StateType = geodex::integration::ompl::GeodexState; + + RunResult result; + result.label = label; + result.metric_info = metric_info; + + ob::RealVectorBounds bounds(2); + bounds.setLow(cfg.lo); + bounds.setHigh(cfg.hi); + auto space = std::make_shared(manifold, bounds); + + og::SimpleSetup ss(space); + + // Always-valid checker (no obstacles) + ss.setStateValidityChecker([](const ob::State*) { return true; }); + + ob::ScopedState start(space); + start->values[0] = cfg.start_x; + start->values[1] = cfg.start_y; + + ob::ScopedState goal(space); + goal->values[0] = cfg.goal_x; + goal->values[1] = cfg.goal_y; + + ss.setStartAndGoalStates(start, goal); + + // Set optimization objective + typename ManifoldT::Point goal_coords; + goal_coords[0] = cfg.goal_x; + goal_coords[1] = cfg.goal_y; + auto objective = + std::make_shared>( + ss.getSpaceInformation(), goal_coords); + ss.setOptimizationObjective(objective); + + auto planner = make_planner(ss.getSpaceInformation()); + if (range > 0.0) { + if (auto* rrt = dynamic_cast(planner.get())) { + rrt->setRange(range); + } + } + ss.setPlanner(planner); + + ob::PlannerStatus status = ss.solve(solve_time); + + if (status) { + result.solved = true; + auto& path = ss.getSolutionPath(); + + using Point = typename ManifoldT::Point; + std::vector raw_points; + raw_points.reserve(path.getStateCount()); + for (const auto* state : path.getStates()) { + const auto* s = state->as(); + Point p; + p[0] = s->values[0]; + p[1] = s->values[1]; + raw_points.push_back(p); + result.raw_path.push_back({s->values[0], s->values[1]}); + } + + if (raw_points.size() >= 3) { + geodex::algorithm::PathSmoothingSettings settings; + settings.max_shortcut_attempts = 0; + auto smoothed = geodex::algorithm::smooth_path( + manifold, [](const Point&) { return true; }, raw_points, settings); + for (const auto& p : smoothed.path) { + result.smoothed_path.push_back({p[0], p[1]}); + } + } else { + result.smoothed_path = result.raw_path; + } + + ob::PlannerData pdata(ss.getSpaceInformation()); + ss.getPlannerData(pdata); + + unsigned int nv = pdata.numVertices(); + for (unsigned int i = 0; i < nv; ++i) { + std::vector edges; + pdata.getEdges(i, edges); + const auto* vi = pdata.getVertex(i).getState()->as(); + for (unsigned int j : edges) { + const auto* vj = pdata.getVertex(j).getState()->as(); + result.tree.push_back({{{vi->values[0], vi->values[1]}, {vj->values[0], vj->values[1]}}}); + } + } + + std::cout << label << ": found solution (" << nv << " tree vertices, " << path.getStateCount() + << " path waypoints)\n"; + } else { + std::cerr << label << ": no solution found.\n"; + } + + return result; +} + +/// 2-link planar arm mass matrix (matching tutorial parameters). +struct PlanarArmMassMatrix { + double l1 = 1.0, l2 = 1.0, m1 = 1.0, m2 = 1.0; + double lc1 = 0.5, lc2 = 0.5; + double I1 = 1.0 / 12.0, I2 = 1.0 / 12.0; + + Eigen::Matrix2d operator()(const Eigen::Vector2d& q) const { + double c2 = std::cos(q[1]); + double h = l1 * lc2 * c2; + + Eigen::Matrix2d M; + M(0, 0) = I1 + I2 + m1 * lc1 * lc1 + m2 * (l1 * l1 + lc2 * lc2 + 2.0 * h); + M(0, 1) = I2 + m2 * (lc2 * lc2 + h); + M(1, 0) = M(0, 1); + M(1, 1) = I2 + m2 * lc2 * lc2; + return M; + } +}; + +void write_json(const std::string& filename, const std::vector& runs, + const RunConfig& cfg, const PlanarArmMassMatrix& arm, double H) { + std::ofstream out(filename); + if (!out) { + std::cerr << "Error: cannot open " << filename << "\n"; + return; + } + + out << std::fixed << std::setprecision(8); + out << "{\n"; + out << " \"start\": [" << cfg.start_x << ", " << cfg.start_y << "],\n"; + out << " \"goal\": [" << cfg.goal_x << ", " << cfg.goal_y << "],\n"; + out << " \"arm\": {\n"; + out << " \"l1\": " << arm.l1 << ", \"l2\": " << arm.l2 << ",\n"; + out << " \"m1\": " << arm.m1 << ", \"m2\": " << arm.m2 << ",\n"; + out << " \"lc1\": " << arm.lc1 << ", \"lc2\": " << arm.lc2 << ",\n"; + out << " \"I1\": " << arm.I1 << ", \"I2\": " << arm.I2 << ",\n"; + out << " \"g\": 9.81\n"; + out << " },\n"; + out << " \"H\": " << H << ",\n"; + out << " \"runs\": [\n"; + + for (size_t r = 0; r < runs.size(); ++r) { + const auto& run = runs[r]; + out << " {\n"; + out << " \"label\": \"" << run.label << "\",\n"; + out << " \"metric_info\": \"" << run.metric_info << "\",\n"; + + out << " \"raw_path\": [\n"; + for (size_t i = 0; i < run.raw_path.size(); ++i) { + out << " [" << run.raw_path[i][0] << ", " << run.raw_path[i][1] << "]"; + if (i + 1 < run.raw_path.size()) out << ","; + out << "\n"; + } + out << " ],\n"; + + out << " \"smoothed_path\": [\n"; + for (size_t i = 0; i < run.smoothed_path.size(); ++i) { + out << " [" << run.smoothed_path[i][0] << ", " << run.smoothed_path[i][1] << "]"; + if (i + 1 < run.smoothed_path.size()) out << ","; + out << "\n"; + } + out << " ],\n"; + + out << " \"tree\": [\n"; + for (size_t i = 0; i < run.tree.size(); ++i) { + out << " [[" << run.tree[i][0][0] << ", " << run.tree[i][0][1] << "], [" + << run.tree[i][1][0] << ", " << run.tree[i][1][1] << "]]"; + if (i + 1 < run.tree.size()) out << ","; + out << "\n"; + } + out << " ]\n"; + + out << " }"; + if (r + 1 < runs.size()) out << ","; + out << "\n"; + } + + out << " ]\n"; + out << "}\n"; + + std::cout << "Wrote " << filename << "\n"; +} + +int main(int argc, char* argv[]) { + std::string output_file = "minimum_energy_planning.json"; + if (argc > 1) output_file = argv[1]; + + // Arm parameters (matching tutorial) + PlanarArmMassMatrix mass_fn; + + // Gravitational potential + auto potential = [&mass_fn](const Eigen::Vector2d& q) { + constexpr double g = 9.81; + return mass_fn.m1 * g * mass_fn.lc1 * std::sin(q[0]) + + mass_fn.m2 * g * (mass_fn.l1 * std::sin(q[0]) + mass_fn.lc2 * std::sin(q[0] + q[1])); + }; + + // Jacobi metric energy level: H = 1.2 * Pmax + constexpr double g = 9.81; + const double pmax = g * (mass_fn.m1 * mass_fn.lc1 + mass_fn.m2 * (mass_fn.l1 + mass_fn.lc2)); + const double H = 1.2 * pmax; + + // Planning configuration: [-pi, pi] bounds + RunConfig cfg; + cfg.lo = -M_PI; + cfg.hi = M_PI; + cfg.start_x = -M_PI / 4.0; + cfg.start_y = -M_PI / 4.0; + cfg.goal_x = 3 * M_PI / 4.0; + cfg.goal_y = 3 * M_PI / 4.0; + + auto rrt_star = [](const ob::SpaceInformationPtr& si) { + return std::make_shared(si); + }; + + constexpr double solve_time = 2.0; + std::vector runs; + + // 1. Flat metric on R^2 + { + geodex::Euclidean<2> manifold; + runs.push_back(run_planner(manifold, "Flat", "M = I", rrt_star, solve_time, cfg)); + } + + // 2. Kinetic energy metric + { + geodex::KineticEnergyMetric ke_metric{mass_fn}; + geodex::ConfigurationSpace cspace{geodex::Euclidean<2>{}, ke_metric}; + + // Compute range: ~0.3 coordinate units scaled by Riemannian factor at domain midpoint + Eigen::Vector2d mid((cfg.start_x + cfg.goal_x) / 2, (cfg.start_y + cfg.goal_y) / 2); + Eigen::Vector2d unit(1.0, 0.0); + double range = 0.3 * cspace.norm(mid, unit); + + runs.push_back( + run_planner(cspace, "Kinetic Energy", "M = M(q)", rrt_star, solve_time, cfg, range)); + } + + // 3. Jacobi metric + { + geodex::JacobiMetric jacobi_metric{mass_fn, potential, H}; + geodex::ConfigurationSpace cspace{geodex::Euclidean<2>{}, jacobi_metric}; + + // Compute range: ~0.3 coordinate units scaled by Riemannian factor at domain midpoint + Eigen::Vector2d mid((cfg.start_x + cfg.goal_x) / 2, (cfg.start_y + cfg.goal_y) / 2); + Eigen::Vector2d unit(1.0, 0.0); + double range = 0.3 * cspace.norm(mid, unit); + + runs.push_back( + run_planner(cspace, "Jacobi", "J = 2(H-P)M(q)", rrt_star, solve_time, cfg, range)); + } + + write_json(output_file, runs, cfg, mass_fn, H); + + return 0; +} diff --git a/examples/ompl/se2_tutorial.cpp b/examples/ompl/se2_tutorial.cpp new file mode 100644 index 0000000..d40b50d --- /dev/null +++ b/examples/ompl/se2_tutorial.cpp @@ -0,0 +1,799 @@ +/// @file se2_tutorial.cpp +/// @brief SE(2) planning tutorial example: holonomic, differential-drive, and car-like +/// robots with footprint collision checking, clearance metrics, and path smoothing. +/// +/// This consolidated example accompanies the "SE(2) Motion Planning" tutorial. +/// It supports five scenarios via the --scenario flag: +/// - holonomic: circular robot, isotropic metric, grid SDF +/// - holo_clearance: circular robot, isotropic + SDFConformalMetric +/// - diff_drive: rectangular robot, anisotropic metric, footprint checker +/// - diff_clearance: rectangular robot, anisotropic + SDFConformalMetric +/// - parking: car-like robot, rectangle obstacles, parallel parking +/// +/// Usage: +/// se2_tutorial --scenario=holonomic -o output.json [--time=1.0] [--seed=42] +/// se2_tutorial dummy --scenario=parking -o parking.json + +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include + +#include "geodex/algorithm/path_smoothing.hpp" +#include "geodex/collision/collision.hpp" +#include "geodex/integration/ompl/geodex_optimization_objective.hpp" +#include "geodex/integration/ompl/geodex_state_space.hpp" +#include "geodex/integration/ompl/validity_checker.hpp" +#include "geodex/manifold/configuration_space.hpp" +#include "geodex/manifold/se2.hpp" +#include "geodex/metrics/clearance.hpp" + +namespace ob = ompl::base; +namespace og = ompl::geometric; + +using DistanceGrid = geodex::collision::DistanceGrid; +using GridSDF = geodex::collision::GridSDF; +using RectObstacle = geodex::collision::RectObstacle; +using RectSmoothSDF = geodex::collision::RectSmoothSDF; + +// --------------------------------------------------------------------------- +// Run result +// --------------------------------------------------------------------------- + +struct RunResult { + std::string label; + std::string metric_info; + std::vector> raw_path; + std::vector> smoothed_path; + std::vector, 2>> tree; + bool solved = false; + double planning_time_ms = 0.0; + double smoothing_time_ms = 0.0; + int vertices_removed = 0; + int smooth_iterations = 0; + int backward_segments = 0; +}; + +// --------------------------------------------------------------------------- +// Planner runner (generic over manifold and validity function) +// --------------------------------------------------------------------------- + +using PlannerFactory = std::function; + +// Default StateSpace interpolation settings used during OMPL tree expansion. +// Scenarios can override this per-experiment by passing a custom value as the +// last argument to run_planner. +inline geodex::InterpolationSettings default_state_interp() { + geodex::InterpolationSettings s; + s.step_size = 1.0; + s.convergence_tol = 1e-2; + s.convergence_rel = 1e-2; + s.max_steps = 20; + s.force_log_direction = true; + return s; +} + +template +RunResult run_planner(ManifoldT manifold, const std::string& label, const std::string& metric_info, + const PlannerFactory& make_planner, const double solve_time, + const ob::RealVectorBounds& bounds, + const std::array& start_pose, + const std::array& goal_pose, ValidityFn validity, + geodex::algorithm::PathSmoothingSettings smooth_settings = {}, + const double range = 0.0, const double collision_resolution = 0.1, + geodex::InterpolationSettings state_space_interp = default_state_interp(), + const double rewire_factor = 0.5) { + using StateSpace = geodex::integration::ompl::GeodexStateSpace; + using StateType = geodex::integration::ompl::GeodexState; + + RunResult result; + result.label = label; + result.metric_info = metric_info; + + auto space = std::make_shared(manifold, bounds); + space->setCollisionResolution(collision_resolution); + space->setInterpolationSettings(state_space_interp); + + og::SimpleSetup ss(space); + ss.setStateValidityChecker(geodex::integration::ompl::make_validity_checker( + ss.getSpaceInformation(), validity)); + + ob::ScopedState start(space); + start->values[0] = start_pose[0]; + start->values[1] = start_pose[1]; + start->values[2] = start_pose[2]; + + ob::ScopedState goal(space); + goal->values[0] = goal_pose[0]; + goal->values[1] = goal_pose[1]; + goal->values[2] = goal_pose[2]; + ss.setStartAndGoalStates(start, goal, 0.5); + + typename ManifoldT::Point goal_coords; + goal_coords[0] = goal_pose[0]; + goal_coords[1] = goal_pose[1]; + goal_coords[2] = goal_pose[2]; + auto objective = + std::make_shared>( + ss.getSpaceInformation(), goal_coords); + ss.setOptimizationObjective(objective); + + auto planner = make_planner(ss.getSpaceInformation()); + if (range > 0.0) { + planner->params().setParam("range", std::to_string(range)); + } + planner->params().setParam("rewire_factor", std::to_string(rewire_factor)); + ss.setPlanner(planner); + + // --- Planning --- + auto t0 = std::chrono::steady_clock::now(); + ob::PlannerStatus status = ss.solve(solve_time); + auto t1 = std::chrono::steady_clock::now(); + result.planning_time_ms = std::chrono::duration(t1 - t0).count(); + + const bool is_exact = (status == ob::PlannerStatus::EXACT_SOLUTION); + const bool is_approx = (status == ob::PlannerStatus::APPROXIMATE_SOLUTION); + if (is_exact || is_approx) { + result.solved = is_exact; + auto& path = ss.getSolutionPath(); + + // Extract planner waypoints. + std::vector waypoints; + for (const auto* state : path.getStates()) { + const auto* s = state->as(); + typename ManifoldT::Point p; + p[0] = s->values[0]; + p[1] = s->values[1]; + p[2] = s->values[2]; + waypoints.push_back(p); + } + + // Densify raw path via discrete_geodesic with log direction. + geodex::InterpolationSettings dense_interp; + dense_interp.step_size = 0.3; + dense_interp.convergence_tol = 1e-3; + dense_interp.max_steps = 50; + dense_interp.force_log_direction = true; + for (std::size_t i = 0; i < waypoints.size(); ++i) { + result.raw_path.push_back({waypoints[i][0], waypoints[i][1], waypoints[i][2]}); + if (i + 1 < waypoints.size()) { + auto geo = + geodex::discrete_geodesic(manifold, waypoints[i], waypoints[i + 1], dense_interp); + for (std::size_t k = 1; k + 1 < geo.path.size(); ++k) { + result.raw_path.push_back({geo.path[k][0], geo.path[k][1], geo.path[k][2]}); + } + } + } + + // --- Post-planning: metric-aware smoothing --- + auto t2 = std::chrono::steady_clock::now(); + { + auto smooth_result = + geodex::algorithm::smooth_path(manifold, validity, waypoints, smooth_settings); + result.vertices_removed = smooth_result.vertices_removed; + result.smooth_iterations = smooth_result.smooth_iterations; + + // Check for backward segments. + for (std::size_t k = 0; k + 1 < smooth_result.path.size(); ++k) { + auto v = manifold.log(smooth_result.path[k], smooth_result.path[k + 1]); + if (v[0] < -1e-10) ++result.backward_segments; + } + + // Densify smoothed path. + for (std::size_t i = 0; i < smooth_result.path.size(); ++i) { + result.smoothed_path.push_back( + {smooth_result.path[i][0], smooth_result.path[i][1], smooth_result.path[i][2]}); + if (i + 1 < smooth_result.path.size()) { + auto geo = geodex::discrete_geodesic(manifold, smooth_result.path[i], + smooth_result.path[i + 1], dense_interp); + for (std::size_t k = 1; k + 1 < geo.path.size(); ++k) { + result.smoothed_path.push_back({geo.path[k][0], geo.path[k][1], geo.path[k][2]}); + } + } + } + } + auto t3 = std::chrono::steady_clock::now(); + result.smoothing_time_ms = std::chrono::duration(t3 - t2).count(); + + // Extract tree. + ob::PlannerData pdata(ss.getSpaceInformation()); + ss.getPlannerData(pdata); + const unsigned int nv = pdata.numVertices(); + if (nv < 20000) { + for (unsigned int i = 0; i < nv; ++i) { + std::vector edges; + pdata.getEdges(i, edges); + const auto* vi = pdata.getVertex(i).getState()->as(); + for (unsigned int j : edges) { + const auto* vj = pdata.getVertex(j).getState()->as(); + result.tree.push_back({{{vi->values[0], vi->values[1], vi->values[2]}, + {vj->values[0], vj->values[1], vj->values[2]}}}); + } + } + } + + std::cout << label << ": " << (is_exact ? "EXACT" : "APPROX") << " in " + << result.planning_time_ms << " ms" + << " (tree=" << nv << ", raw=" << result.raw_path.size() + << ", smoothed=" << result.smoothed_path.size() << ", shortcut=-" + << result.vertices_removed << ", lbfgs=" << result.smooth_iterations + << ", bwd=" << result.backward_segments << ", smooth=" << result.smoothing_time_ms + << " ms)\n"; + } else { + std::cerr << label << ": FAILED (no solution found).\n"; + } + + return result; +} + +// --------------------------------------------------------------------------- +// JSON output +// --------------------------------------------------------------------------- + +struct TutorialOutput { + std::string scenario; + std::array start{}, goal{}; + + // Robot description. + std::string robot_type; // "circle" or "rectangle" + double robot_radius = 0.0; // for circle + double robot_hl = 0.0, robot_hw = 0.0; // for rectangle + + // Grid-based environment (corridor scenarios). + const DistanceGrid* grid = nullptr; + std::string map_file; + + // Rectangle obstacles (parking scenario). + std::vector rect_obstacles; + + // Run results. + std::vector runs; + + // Optional conformal factor grid (for heatmap visualization). + std::vector conformal_values; + int conformal_w = 0, conformal_h = 0; + double conformal_res = 0.0; +}; + +void write_json(const std::string& filename, const TutorialOutput& out) { + std::ofstream f(filename); + if (!f) { + std::cerr << "Error: cannot open " << filename << "\n"; + return; + } + + f << std::fixed << std::setprecision(8); + f << "{\n"; + f << " \"scenario\": \"" << out.scenario << "\",\n"; + f << " \"start\": [" << out.start[0] << ", " << out.start[1] << ", " << out.start[2] << "],\n"; + f << " \"goal\": [" << out.goal[0] << ", " << out.goal[1] << ", " << out.goal[2] << "],\n"; + + // Robot. + f << " \"robot\": { \"type\": \"" << out.robot_type << "\""; + if (out.robot_type == "circle") { + f << ", \"radius\": " << out.robot_radius; + } else { + f << ", \"half_length\": " << out.robot_hl << ", \"half_width\": " << out.robot_hw; + } + f << " },\n"; + + // Map (grid-based environment). + if (out.grid) { + f << " \"map\": { \"width\": " << out.grid->width() << ", \"height\": " << out.grid->height() + << ", \"resolution\": " << out.grid->resolution() << ", \"file\": \"" << out.map_file + << "\" },\n"; + } + + // Rectangle obstacles. + if (!out.rect_obstacles.empty()) { + f << " \"rect_obstacles\": [\n"; + for (std::size_t i = 0; i < out.rect_obstacles.size(); ++i) { + const auto& o = out.rect_obstacles[i]; + f << " {\"center\": [" << o.cx << ", " << o.cy << "], \"theta\": " << o.theta + << ", \"half_length\": " << o.half_length << ", \"half_width\": " << o.half_width << "}"; + if (i + 1 < out.rect_obstacles.size()) f << ","; + f << "\n"; + } + f << " ],\n"; + } + + // Conformal factor grid. + if (!out.conformal_values.empty()) { + f << " \"conformal_grid\": { \"width\": " << out.conformal_w + << ", \"height\": " << out.conformal_h << ", \"resolution\": " << out.conformal_res + << ", \"values\": ["; + for (std::size_t i = 0; i < out.conformal_values.size(); ++i) { + if (i > 0) f << ", "; + f << out.conformal_values[i]; + } + f << "] },\n"; + } + + // Runs. + f << " \"runs\": [\n"; + for (std::size_t r = 0; r < out.runs.size(); ++r) { + const auto& run = out.runs[r]; + f << " {\n"; + f << " \"label\": \"" << run.label << "\",\n"; + f << " \"metric_info\": \"" << run.metric_info << "\",\n"; + f << " \"solved\": " << (run.solved ? "true" : "false") << ",\n"; + f << " \"planning_time_ms\": " << run.planning_time_ms << ",\n"; + f << " \"smoothing_time_ms\": " << run.smoothing_time_ms << ",\n"; + f << " \"vertices_removed\": " << run.vertices_removed << ",\n"; + f << " \"smooth_iterations\": " << run.smooth_iterations << ",\n"; + f << " \"backward_segments\": " << run.backward_segments << ",\n"; + + f << " \"raw_path\": [\n"; + for (std::size_t i = 0; i < run.raw_path.size(); ++i) { + f << " [" << run.raw_path[i][0] << ", " << run.raw_path[i][1] << ", " + << run.raw_path[i][2] << "]"; + if (i + 1 < run.raw_path.size()) f << ","; + f << "\n"; + } + f << " ],\n"; + + f << " \"smoothed_path\": [\n"; + for (std::size_t i = 0; i < run.smoothed_path.size(); ++i) { + f << " [" << run.smoothed_path[i][0] << ", " << run.smoothed_path[i][1] << ", " + << run.smoothed_path[i][2] << "]"; + if (i + 1 < run.smoothed_path.size()) f << ","; + f << "\n"; + } + f << " ],\n"; + + f << " \"tree\": [\n"; + for (std::size_t i = 0; i < run.tree.size(); ++i) { + f << " [[" << run.tree[i][0][0] << ", " << run.tree[i][0][1] << ", " + << run.tree[i][0][2] << "], [" << run.tree[i][1][0] << ", " << run.tree[i][1][1] << ", " + << run.tree[i][1][2] << "]]"; + if (i + 1 < run.tree.size()) f << ","; + f << "\n"; + } + f << " ]\n"; + + f << " }"; + if (r + 1 < out.runs.size()) f << ","; + f << "\n"; + } + + f << " ]\n"; + f << "}\n"; + + std::cout << "Wrote " << filename << "\n"; +} + +// --------------------------------------------------------------------------- +// Helper: sample conformal factor grid +// --------------------------------------------------------------------------- + +template +std::vector sample_conformal_grid(const SDFFn& sdf, const double kappa, const double beta, + const int width, const int height, + const double resolution) { + std::vector values(static_cast(width) * height); + for (int row = 0; row < height; ++row) { + for (int col = 0; col < width; ++col) { + const double x = (col + 0.5) * resolution; + const double y = (row + 0.5) * resolution; + const Eigen::Vector3d q{x, y, 0.0}; + const double d = sdf(q); + values[static_cast(row) * width + col] = 1.0 + kappa * std::exp(-beta * d); + } + } + return values; +} + +// --------------------------------------------------------------------------- +// Helper: shared bounds and planner factory +// --------------------------------------------------------------------------- + +ob::RealVectorBounds make_bounds(const double world_w, const double world_h) { + ob::RealVectorBounds bounds(3); + bounds.setLow(0, 0.0); + bounds.setHigh(0, world_w); + bounds.setLow(1, 0.0); + bounds.setHigh(1, world_h); + bounds.setLow(2, -std::numbers::pi); + bounds.setHigh(2, std::numbers::pi); + return bounds; +} + +PlannerFactory make_irrt() { + return [](const ob::SpaceInformationPtr& si) -> ob::PlannerPtr { + return std::make_shared(si); + }; +} + +PlannerFactory make_rrt() { + return [](const ob::SpaceInformationPtr& si) -> ob::PlannerPtr { + return std::make_shared(si); + }; +} + +// --------------------------------------------------------------------------- +// Scenario: holonomic circular robot (baseline, no clearance) +// --------------------------------------------------------------------------- + +TutorialOutput run_holonomic(const DistanceGrid& grid, const std::string& map_file, + const double solve_time) { + constexpr double robot_radius = 0.3; + // Safety margin beyond the robot radius. Pushes the tree (and the raw path) + // away from walls so L-BFGS has room to round corners. + constexpr double safety_margin = 0.10; + const double world_w = grid.width() * grid.resolution(); + const double world_h = grid.height() * grid.resolution(); + + TutorialOutput out; + out.scenario = "holonomic"; + out.start = {2.0, 5.0, 0.0}; + out.goal = {12.0, 6.0, -std::numbers::pi / 2.0}; + out.robot_type = "circle"; + out.robot_radius = robot_radius; + out.grid = &grid; + out.map_file = map_file; + + auto validity = [&grid, robot_radius](const auto& q) { + return grid.distance_at(q[0], q[1]) > robot_radius + safety_margin; + }; + + geodex::SE2LeftInvariantMetric metric{1.0, 1.0, 1.0}; + geodex::SE2<> manifold{metric, geodex::SE2ExponentialMap{}, + Eigen::Vector3d(0.0, 0.0, -std::numbers::pi), + Eigen::Vector3d(world_w, world_h, std::numbers::pi)}; + + // Per-scenario StateSpace interp. Fine step_size gives OMPL metric-consistent + // distances during tree growth so the raw path already tracks the geodesic. + geodex::InterpolationSettings state_interp; + state_interp.step_size = 0.2; + state_interp.convergence_tol = 1e-3; + state_interp.convergence_rel = 1e-3; + state_interp.max_steps = 80; + state_interp.force_log_direction = true; + + constexpr double planner_range = 4.5; + constexpr double rewire_factor = 0.5; + + auto bounds = make_bounds(world_w, world_h); + out.runs.push_back(run_planner(manifold, "Holonomic (isotropic)", "w=(1,1,1)", make_irrt(), + solve_time, bounds, out.start, out.goal, validity, {}, + planner_range, grid.resolution(), state_interp, rewire_factor)); + return out; +} + +// --------------------------------------------------------------------------- +// Scenario: holonomic + clearance metric +// --------------------------------------------------------------------------- + +TutorialOutput run_holo_clearance(const DistanceGrid& grid, const std::string& map_file, + const double solve_time) { + constexpr double robot_radius = 0.3; + constexpr double safety_margin = 0.10; + constexpr double kappa = 1.5, beta = 1.5; + const double world_w = grid.width() * grid.resolution(); + const double world_h = grid.height() * grid.resolution(); + + TutorialOutput out; + out.scenario = "holo_clearance"; + out.start = {2.0, 5.0, 0.0}; + out.goal = {12.0, 6.0, -std::numbers::pi / 2.0}; + out.robot_type = "circle"; + out.robot_radius = robot_radius; + out.grid = &grid; + out.map_file = map_file; + + auto validity = [&grid, robot_radius](const auto& q) { + return grid.distance_at(q[0], q[1]) > robot_radius + safety_margin; + }; + + geodex::SE2LeftInvariantMetric base_metric{1.0, 1.0, 1.0}; + geodex::collision::InflatedSDF inflated_sdf{GridSDF{&grid}, robot_radius}; + geodex::SDFConformalMetric clearance_metric{base_metric, inflated_sdf, kappa, beta}; + + geodex::SE2<> se2{base_metric, geodex::SE2ExponentialMap{}, + Eigen::Vector3d(0.0, 0.0, -std::numbers::pi), + Eigen::Vector3d(world_w, world_h, std::numbers::pi)}; + geodex::ConfigurationSpace cspace{se2, clearance_metric}; + + // Per-scenario StateSpace interp. Clearance metric inflates distance near + // walls so we need fine geodesic stepping to track the warped geometry. + geodex::InterpolationSettings state_interp; + state_interp.step_size = 0.2; + state_interp.convergence_tol = 1e-3; + state_interp.convergence_rel = 1e-3; + state_interp.max_steps = 80; + state_interp.force_log_direction = true; + + constexpr double planner_range = 3.5; + constexpr double rewire_factor = 0.5; + + auto bounds = make_bounds(world_w, world_h); + out.runs.push_back(run_planner(cspace, "Holonomic + clearance", "k=1.5 b=1.5", make_irrt(), + solve_time, bounds, out.start, out.goal, validity, {}, + planner_range, grid.resolution(), state_interp, rewire_factor)); + + // Sample conformal factor grid for heatmap visualization. + out.conformal_w = grid.width(); + out.conformal_h = grid.height(); + out.conformal_res = grid.resolution(); + out.conformal_values = + sample_conformal_grid(inflated_sdf, kappa, beta, grid.width(), grid.height(), + grid.resolution()); + + return out; +} + +// --------------------------------------------------------------------------- +// Scenario: differential-drive rectangular robot +// --------------------------------------------------------------------------- + +TutorialOutput run_diff_drive(const DistanceGrid& grid, const std::string& map_file, + const double solve_time) { + constexpr double robot_hl = 0.35, robot_hw = 0.25; + constexpr double safety_margin = 0.10; + const double world_w = grid.width() * grid.resolution(); + const double world_h = grid.height() * grid.resolution(); + + TutorialOutput out; + out.scenario = "diff_drive"; + out.start = {2.0, 5.0, 0.0}; + out.goal = {12.0, 6.0, -std::numbers::pi / 2.0}; + out.robot_type = "rectangle"; + out.robot_hl = robot_hl; + out.robot_hw = robot_hw; + out.grid = &grid; + out.map_file = map_file; + + auto footprint = geodex::collision::PolygonFootprint::rectangle(robot_hl, robot_hw, 6); + geodex::collision::FootprintGridChecker checker{&grid, footprint, safety_margin}; + auto validity = [&checker](const auto& q) { return checker.is_valid(q); }; + + geodex::SE2LeftInvariantMetric metric{1.0, 10.0, 1.0}; + geodex::SE2<> manifold{metric, geodex::SE2ExponentialMap{}, + Eigen::Vector3d(0.0, 0.0, -std::numbers::pi), + Eigen::Vector3d(world_w, world_h, std::numbers::pi)}; + + // Per-scenario StateSpace interp. Anisotropic metric (w_y = 10) means a + // metric step of 0.3 is only ~0.095 m laterally, so finer stepping is needed + // to track the true geodesic during tree growth. + geodex::InterpolationSettings state_interp; + state_interp.step_size = 0.3; + state_interp.convergence_tol = 1e-3; + state_interp.convergence_rel = 1e-3; + state_interp.max_steps = 80; + state_interp.force_log_direction = true; + + constexpr double planner_range = 7.0; + constexpr double rewire_factor = 1.1; + + auto bounds = make_bounds(world_w, world_h); + out.runs.push_back(run_planner(manifold, "Diff-drive (anisotropic)", "w=(1,10,1)", make_irrt(), + solve_time, bounds, out.start, out.goal, validity, {}, + planner_range, grid.resolution(), state_interp, rewire_factor)); + return out; +} + +// --------------------------------------------------------------------------- +// Scenario: differential-drive + clearance metric +// --------------------------------------------------------------------------- + +TutorialOutput run_diff_clearance(const DistanceGrid& grid, const std::string& map_file, + const double solve_time) { + constexpr double robot_hl = 0.35, robot_hw = 0.25; + constexpr double safety_margin = 0.01; + constexpr double kappa = 1.5, beta = 1.5; + const double world_w = grid.width() * grid.resolution(); + const double world_h = grid.height() * grid.resolution(); + + TutorialOutput out; + out.scenario = "diff_clearance"; + out.start = {2.0, 5.0, 0.0}; + out.goal = {12.0, 6.0, -std::numbers::pi / 2.0}; + out.robot_type = "rectangle"; + out.robot_hl = robot_hl; + out.robot_hw = robot_hw; + out.grid = &grid; + out.map_file = map_file; + + auto footprint = geodex::collision::PolygonFootprint::rectangle(robot_hl, robot_hw, 6); + geodex::collision::FootprintGridChecker checker{&grid, footprint, safety_margin}; + auto validity = [&checker](const auto& q) { return checker.is_valid(q); }; + + // Use FootprintGridChecker as continuous SDF for the clearance metric. + // operator() returns min grid distance across perimeter samples minus safety margin. + geodex::SE2LeftInvariantMetric base_metric{1.0, 10.0, 1.0}; + geodex::SDFConformalMetric clearance_metric{base_metric, checker, kappa, beta}; + + geodex::SE2<> se2{base_metric, geodex::SE2ExponentialMap{}, + Eigen::Vector3d(0.0, 0.0, -std::numbers::pi), + Eigen::Vector3d(world_w, world_h, std::numbers::pi)}; + geodex::ConfigurationSpace cspace{se2, clearance_metric}; + + // Per-scenario StateSpace interp. + geodex::InterpolationSettings state_interp; + state_interp.step_size = 0.3; + state_interp.convergence_tol = 1e-3; + state_interp.convergence_rel = 1e-3; + state_interp.max_steps = 100; + state_interp.force_log_direction = true; + + constexpr double planner_range = 5.5; + constexpr double rewire_factor = 0.5; + + // RRT* (not InformedRRT*) — informed heuristic is too loose for + // anisotropic+clearance on the Willow corridor. + auto bounds = make_bounds(world_w, world_h); + out.runs.push_back(run_planner(cspace, "Diff-drive + clearance", "w=(1,10,1) k=1.5 b=1.5", + make_rrt(), solve_time, bounds, out.start, out.goal, validity, + {}, planner_range, grid.resolution(), state_interp, + rewire_factor)); + return out; +} + +// --------------------------------------------------------------------------- +// Scenario: car-like parallel parking +// --------------------------------------------------------------------------- + +TutorialOutput run_parking(const double solve_time) { + constexpr double car_hl = 2.25, car_hw = 0.9; // 4.5 x 1.8 m sedan + constexpr double world_w = 30.0, world_h = 12.0; + constexpr double turning_radius = 1.5, lateral_penalty = 20.0; + constexpr double kappa = 8.0, beta = 3.0; + + std::vector obstacles = { + {5.0, 1.35, 0.0, car_hl, car_hw}, // parked car 1 + {10.0, 1.35, 0.0, car_hl, car_hw}, // parked car 2 + {21.0, 1.35, 0.0, car_hl, car_hw}, // parked car 3 + {26.0, 1.35, 0.0, car_hl, car_hw}, // parked car 4 + {15.0, -0.05, 0.0, 15.0, 0.05}, // curb + {15.0, 10.05, 0.0, 15.0, 0.05}, // sidewalk + }; + + TutorialOutput out; + out.scenario = "parking"; + out.start = {25.0, 6.0, std::numbers::pi}; + out.goal = {15.5, 1.35, 0.0}; + out.robot_type = "rectangle"; + out.robot_hl = car_hl; + out.robot_hw = car_hw; + out.rect_obstacles = obstacles; + + auto bounds = make_bounds(world_w, world_h); + + // SAT-based polygon collision checking. + auto validity = [&obstacles, car_hl, car_hw, &bounds](const auto& q) { + const double x = q[0], y = q[1], theta = q[2]; + if (x - car_hl < bounds.low[0] || x + car_hl > bounds.high[0] || + y - car_hw < bounds.low[1] || y + car_hw > bounds.high[1]) + return false; + RectObstacle ego{x, y, theta, car_hl, car_hw}; + for (const auto& obs : obstacles) { + if (geodex::collision::rects_overlap(ego, obs)) return false; + } + return true; + }; + + auto base_metric = geodex::SE2LeftInvariantMetric::car_like(turning_radius, lateral_penalty); + RectSmoothSDF sdf{obstacles, 20.0, car_hw}; + geodex::SDFConformalMetric clearance_metric{base_metric, sdf, kappa, beta}; + + geodex::SE2 se2{ + geodex::SE2LeftInvariantMetric::car_like(turning_radius, lateral_penalty), + geodex::SE2ExponentialMap{}, Eigen::Vector3d(0.0, 0.0, -std::numbers::pi), + Eigen::Vector3d(world_w, world_h, std::numbers::pi)}; + geodex::ConfigurationSpace cspace{se2, clearance_metric}; + + geodex::algorithm::PathSmoothingSettings car_smooth; + car_smooth.interp.step_size = 0.02; + car_smooth.interp.max_steps = 2000; + car_smooth.collision_resolution = 0.1; + + // Per-scenario StateSpace interp. + geodex::InterpolationSettings state_interp; + state_interp.step_size = 0.5; + state_interp.convergence_tol = 1e-3; + state_interp.convergence_rel = 1e-3; + state_interp.max_steps = 80; + state_interp.force_log_direction = true; + + out.runs.push_back(run_planner(cspace, "Car-like parallel parking", "r=1.5 lp=20 k=8 b=3", + make_rrt(), solve_time, bounds, out.start, out.goal, validity, + car_smooth, 4.0, 0.1, state_interp, 0.5)); + return out; +} + +// --------------------------------------------------------------------------- +// Main +// --------------------------------------------------------------------------- + +int main(int argc, char* argv[]) { + if (argc < 2) { + std::cerr << "Usage: " << argv[0] + << " --scenario= [-o output.json] [--time=] [--seed=]\n" + << "\nScenarios: holonomic, holo_clearance, diff_drive, diff_clearance, parking\n"; + return 1; + } + + std::string dist_map_file = argv[1]; + std::string output_file; + std::string scenario = "holonomic"; + double time_override = 0.0; + int seed = -1; + + for (int i = 2; i < argc; ++i) { + std::string arg = argv[i]; + if (arg.starts_with("--scenario=")) { + scenario = arg.substr(11); + } else if (arg.starts_with("-o")) { + if (arg.size() > 2) + output_file = arg.substr(2); + else if (i + 1 < argc) + output_file = argv[++i]; + } else if (arg.starts_with("--time=")) { + time_override = std::stod(arg.substr(7)); + } else if (arg.starts_with("--seed=")) { + seed = std::stoi(arg.substr(7)); + } else { + output_file = arg; + } + } + + if (output_file.empty()) { + output_file = "se2_tutorial_" + scenario + ".json"; + } + + // Set OMPL random seed for reproducibility. + if (seed >= 0) { + ompl::RNG::setSeed(static_cast(seed)); + } + + // Default planning times per scenario. + const double solve_time = (time_override > 0.0) ? time_override + : (scenario == "parking") ? 2.0 + : 1.0; + + TutorialOutput result; + + if (scenario == "parking") { + result = run_parking(solve_time); + } else { + // All non-parking scenarios need the distance grid. + DistanceGrid grid; + if (!grid.load(dist_map_file)) { + std::cerr << "Error: could not load distance grid: " << dist_map_file << "\n"; + return 1; + } + + std::cout << "Loaded grid: " << grid.width() << "x" << grid.height() + << " (" << grid.width() * grid.resolution() << " x " + << grid.height() * grid.resolution() << " m)\n"; + + if (scenario == "holonomic") { + result = run_holonomic(grid, dist_map_file, solve_time); + } else if (scenario == "holo_clearance") { + result = run_holo_clearance(grid, dist_map_file, solve_time); + } else if (scenario == "diff_drive") { + result = run_diff_drive(grid, dist_map_file, solve_time); + } else if (scenario == "diff_clearance") { + result = run_diff_clearance(grid, dist_map_file, solve_time); + } else { + std::cerr << "Unknown scenario: " << scenario << "\n"; + return 1; + } + } + + write_json(output_file, result); + + return 0; +} diff --git a/examples/ompl/willow_corridor.png b/examples/ompl/willow_corridor.png new file mode 100644 index 0000000..382e74e Binary files /dev/null and b/examples/ompl/willow_corridor.png differ diff --git a/examples/ompl/willow_corridor_dist.txt b/examples/ompl/willow_corridor_dist.txt new file mode 100644 index 0000000..73891c4 --- /dev/null +++ b/examples/ompl/willow_corridor_dist.txt @@ -0,0 +1,241 @@ +360 240 0.05 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6194 1.6279 1.6378 1.6492 1.6621 1.6621 1.6492 1.6378 1.6279 1.6194 1.6125 1.6070 1.6031 1.6008 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.5500 1.5000 1.4500 1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6070 1.6125 1.6194 1.6279 1.6279 1.6194 1.6125 1.6070 1.6031 1.6008 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6008 1.6031 1.6070 1.6125 1.6194 1.6279 1.6378 1.6279 1.6194 1.6125 1.6070 1.6031 1.6008 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6008 1.6031 1.6070 1.6125 1.6194 1.6279 1.6378 1.6492 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.5628 1.5700 1.5788 1.5890 1.6008 1.6140 1.6140 1.6008 1.5890 1.5788 1.5700 1.5628 1.5572 1.5532 1.5508 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5000 1.4500 1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.5532 1.5572 1.5628 1.5700 1.5788 1.5788 1.5700 1.5628 1.5572 1.5532 1.5508 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5508 1.5532 1.5572 1.5628 1.5700 1.5788 1.5890 1.5788 1.5700 1.5628 1.5572 1.5532 1.5508 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5508 1.5532 1.5572 1.5628 1.5700 1.5788 1.5890 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5075 1.5133 1.5207 1.5297 1.5403 1.5524 1.5660 1.5660 1.5524 1.5403 1.5297 1.5207 1.5133 1.5075 1.5033 1.5008 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.4500 1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5008 1.5033 1.5075 1.5133 1.5207 1.5297 1.5297 1.5207 1.5133 1.5075 1.5033 1.5008 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5008 1.5033 1.5075 1.5133 1.5207 1.5297 1.5403 1.5297 1.5207 1.5133 1.5075 1.5033 1.5008 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5008 1.5033 1.5075 1.5133 1.5207 1.5297 1.5403 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.4534 1.4577 1.4637 1.4714 1.4807 1.4916 1.5042 1.5182 1.5182 1.5042 1.4916 1.4807 1.4714 1.4637 1.4577 1.4534 1.4509 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.4500 1.4509 1.4534 1.4577 1.4637 1.4714 1.4807 1.4807 1.4714 1.4637 1.4577 1.4534 1.4509 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4509 1.4534 1.4577 1.4637 1.4714 1.4807 1.4916 1.4807 1.4714 1.4637 1.4577 1.4534 1.4509 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4509 1.4534 1.4577 1.4637 1.4714 1.4807 1.4916 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4009 1.4036 1.4080 1.4142 1.4221 1.4318 1.4431 1.4560 1.4705 1.4705 1.4560 1.4431 1.4318 1.4221 1.4142 1.4080 1.4036 1.4009 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4000 1.4000 1.4009 1.4036 1.4080 1.4142 1.4221 1.4318 1.4318 1.4221 1.4142 1.4080 1.4036 1.4009 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4009 1.4036 1.4080 1.4142 1.4221 1.4318 1.4431 1.4318 1.4221 1.4142 1.4080 1.4036 1.4009 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4009 1.4036 1.4080 1.4142 1.4221 1.4318 1.4431 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.3500 1.3509 1.3537 1.3583 1.3647 1.3730 1.3829 1.3946 1.4080 1.4230 1.4230 1.4080 1.3946 1.3829 1.3730 1.3647 1.3583 1.3537 1.3509 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.3500 1.3500 1.3500 1.3509 1.3537 1.3583 1.3647 1.3730 1.3829 1.3829 1.3730 1.3647 1.3583 1.3537 1.3509 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3509 1.3537 1.3583 1.3647 1.3730 1.3829 1.3946 1.3829 1.3730 1.3647 1.3583 1.3537 1.3509 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3509 1.3537 1.3583 1.3647 1.3730 1.3829 1.3946 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3000 1.3000 1.3010 1.3038 1.3086 1.3153 1.3238 1.3342 1.3463 1.3601 1.3757 1.3757 1.3601 1.3463 1.3342 1.3238 1.3153 1.3086 1.3038 1.3010 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3000 1.3000 1.3000 1.3000 1.3010 1.3038 1.3086 1.3153 1.3238 1.3342 1.3342 1.3238 1.3153 1.3086 1.3038 1.3010 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3010 1.3038 1.3086 1.3153 1.3238 1.3342 1.3463 1.3342 1.3238 1.3153 1.3086 1.3038 1.3010 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3010 1.3038 1.3086 1.3153 1.3238 1.3342 1.3463 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.2500 1.2500 1.2500 1.2510 1.2540 1.2590 1.2659 1.2748 1.2855 1.2981 1.3124 1.3285 1.3285 1.3124 1.2981 1.2855 1.2748 1.2659 1.2590 1.2540 1.2510 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2510 1.2540 1.2590 1.2659 1.2748 1.2855 1.2855 1.2748 1.2659 1.2590 1.2540 1.2510 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2510 1.2540 1.2590 1.2659 1.2748 1.2855 1.2981 1.2855 1.2748 1.2659 1.2590 1.2540 1.2510 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2510 1.2540 1.2590 1.2659 1.2748 1.2855 1.2981 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2000 1.2000 1.2000 1.2000 1.2010 1.2042 1.2093 1.2166 1.2258 1.2369 1.2500 1.2649 1.2816 1.2816 1.2649 1.2500 1.2369 1.2258 1.2166 1.2093 1.2042 1.2010 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2010 1.2042 1.2093 1.2166 1.2258 1.2369 1.2369 1.2258 1.2166 1.2093 1.2042 1.2010 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2010 1.2042 1.2093 1.2166 1.2258 1.2369 1.2500 1.2369 1.2258 1.2166 1.2093 1.2042 1.2010 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2010 1.2042 1.2093 1.2166 1.2258 1.2369 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1511 1.1543 1.1597 1.1673 1.1769 1.1885 1.2021 1.2176 1.2349 1.2349 1.2176 1.2021 1.1885 1.1769 1.1673 1.1597 1.1543 1.1511 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1511 1.1543 1.1597 1.1673 1.1769 1.1885 1.1885 1.1769 1.1673 1.1597 1.1543 1.1511 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1511 1.1543 1.1597 1.1673 1.1769 1.1885 1.2000 1.1885 1.1769 1.1673 1.1597 1.1543 1.1511 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1511 1.1543 1.1597 1.1673 1.1769 1.1885 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1011 1.1045 1.1102 1.1180 1.1281 1.1402 1.1543 1.1705 1.1885 1.1885 1.1705 1.1543 1.1402 1.1281 1.1180 1.1102 1.1045 1.1011 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1011 1.1045 1.1102 1.1180 1.1281 1.1402 1.1402 1.1281 1.1180 1.1102 1.1045 1.1011 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1011 1.1045 1.1102 1.1180 1.1281 1.1402 1.1500 1.1402 1.1281 1.1180 1.1102 1.1045 1.1011 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1011 1.1045 1.1102 1.1180 1.1281 1.1402 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0512 1.0548 1.0607 1.0689 1.0794 1.0920 1.1068 1.1236 1.1424 1.1424 1.1236 1.1068 1.0920 1.0794 1.0689 1.0607 1.0548 1.0512 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0512 1.0548 1.0607 1.0689 1.0794 1.0920 1.0920 1.0794 1.0689 1.0607 1.0548 1.0512 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0512 1.0548 1.0607 1.0689 1.0794 1.0920 1.1000 1.0920 1.0794 1.0689 1.0607 1.0548 1.0512 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0512 1.0548 1.0607 1.0689 1.0794 1.0920 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0012 1.0050 1.0112 1.0198 1.0308 1.0440 1.0595 1.0770 1.0966 1.0966 1.0770 1.0595 1.0440 1.0308 1.0198 1.0112 1.0050 1.0012 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0012 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0012 1.0050 1.0112 1.0198 1.0308 1.0440 1.0440 1.0308 1.0198 1.0112 1.0050 1.0012 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0012 1.0050 1.0112 1.0198 1.0308 1.0440 1.0500 1.0440 1.0308 1.0198 1.0112 1.0050 1.0012 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0012 1.0050 1.0112 1.0198 1.0308 1.0440 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9513 0.9552 0.9618 0.9708 0.9823 0.9962 1.0124 1.0308 1.0512 1.0512 1.0308 1.0124 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9552 0.9513 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9513 0.9552 0.9618 0.9708 0.9823 0.9962 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9513 0.9552 0.9618 0.9708 0.9823 0.9962 1.0000 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9513 0.9552 0.9618 0.9708 0.9823 0.9962 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9014 0.9055 0.9124 0.9220 0.9341 0.9487 0.9657 0.9849 1.0062 1.0062 0.9849 0.9657 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9124 0.9055 0.9014 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9014 0.9055 0.9124 0.9220 0.9341 0.9487 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9014 0.9055 0.9124 0.9220 0.9341 0.9487 0.9500 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9014 0.9055 0.9124 0.9220 0.9341 0.9487 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8515 0.8559 0.8631 0.8732 0.8860 0.9014 0.9192 0.9394 0.9618 0.9618 0.9394 0.9192 0.9014 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8515 0.8559 0.8631 0.8732 0.8860 0.9000 0.9000 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8515 0.8559 0.8631 0.8732 0.8860 0.9000 0.9000 0.9000 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8515 0.8559 0.8631 0.8732 0.8860 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8016 0.8062 0.8139 0.8246 0.8382 0.8544 0.8732 0.8944 0.9179 0.9179 0.8944 0.8732 0.8544 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8016 0.8062 0.8139 0.8246 0.8382 0.8500 0.8500 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8016 0.8062 0.8139 0.8246 0.8382 0.8500 0.8500 0.8500 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8016 0.8062 0.8139 0.8246 0.8382 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8078 0.8276 0.8500 0.8746 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8000 0.8000 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8000 0.8000 0.8000 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7500 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7500 0.7500 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7500 0.7500 0.7500 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.7000 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7000 0.7000 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7000 0.7000 0.7000 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6500 0.6500 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6500 0.6500 0.6500 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6000 0.6000 0.6000 0.6000 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6000 0.6000 0.6000 0.6000 0.6000 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5500 0.5500 0.5500 0.5500 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5500 0.5500 0.5500 0.5500 0.5500 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5000 0.5000 0.5000 0.5000 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5000 0.5000 0.5000 0.5000 0.5000 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4500 0.4500 0.4500 0.4500 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4500 0.4500 0.4500 0.4500 0.4500 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1118 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9513 1.0012 1.0512 1.1011 1.1511 1.2010 1.1511 1.1011 1.0512 1.0012 0.9513 0.9014 0.8515 0.8016 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9552 1.0050 1.0548 1.1045 1.1543 1.2042 1.1543 1.1045 1.0548 1.0050 0.9552 0.9055 0.8559 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9618 1.0112 1.0607 1.1102 1.1597 1.2093 1.1597 1.1102 1.0607 1.0112 0.9618 0.9124 0.8631 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 +1.4000 1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9220 0.9708 1.0198 1.0689 1.1180 1.1673 1.2166 1.1673 1.1180 1.0689 1.0198 0.9708 0.9220 0.8732 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 +1.4009 1.3509 1.3010 1.2510 1.2010 1.1511 1.1011 1.0512 1.0012 0.9513 0.9014 0.8515 0.8016 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9341 0.9823 1.0308 1.0794 1.1281 1.1769 1.2258 1.1769 1.1281 1.0794 1.0308 0.9823 0.9341 0.8860 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 +1.4036 1.3537 1.3038 1.2540 1.2042 1.1543 1.1045 1.0548 1.0050 0.9552 0.9055 0.8559 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9487 0.9962 1.0440 1.0920 1.1402 1.1885 1.2369 1.1885 1.1402 1.0920 1.0440 0.9962 0.9487 0.9014 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 +1.4080 1.3583 1.3086 1.2590 1.2093 1.1597 1.1102 1.0607 1.0112 0.9618 0.9124 0.8631 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8732 0.9192 0.9657 1.0124 1.0595 1.1068 1.1543 1.2021 1.2500 1.2021 1.1543 1.1068 1.0595 1.0124 0.9657 0.9192 0.8732 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 +1.4142 1.3647 1.3153 1.2659 1.2166 1.1673 1.1180 1.0689 1.0198 0.9708 0.9220 0.8732 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8944 0.9394 0.9849 1.0308 1.0770 1.1236 1.1705 1.2176 1.2649 1.2176 1.1705 1.1236 1.0770 1.0308 0.9849 0.9394 0.8944 0.8500 0.8062 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 +1.4221 1.3730 1.3238 1.2748 1.2258 1.1769 1.1281 1.0794 1.0308 0.9823 0.9341 0.8860 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8322 0.8746 0.9179 0.9618 1.0062 1.0512 1.0966 1.1424 1.1885 1.2349 1.2816 1.2349 1.1885 1.1424 1.0966 1.0512 1.0062 0.9618 0.9179 0.8746 0.8322 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 +1.4318 1.3829 1.3342 1.2855 1.2369 1.1885 1.1402 1.0920 1.0440 0.9962 0.9487 0.9014 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8602 0.9014 0.9434 0.9862 1.0296 1.0735 1.1180 1.1630 1.2083 1.2540 1.3000 1.2540 1.2083 1.1630 1.1180 1.0735 1.0296 0.9862 0.9434 0.9014 0.8602 0.8201 0.7810 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 +1.4431 1.3946 1.3463 1.2981 1.2500 1.2021 1.1543 1.1068 1.0595 1.0124 0.9657 0.9192 0.8732 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7778 0.8139 0.8515 0.8902 0.9301 0.9708 1.0124 1.0548 1.0977 1.1413 1.1853 1.2298 1.2748 1.3200 1.2748 1.2298 1.1853 1.1413 1.0977 1.0548 1.0124 0.9708 0.9301 0.8902 0.8515 0.8139 0.7778 0.7433 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 +1.4560 1.4080 1.3601 1.3124 1.2649 1.2176 1.1705 1.1236 1.0770 1.0308 0.9849 0.9394 0.8944 0.8500 0.8062 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7810 0.8139 0.8485 0.8846 0.9220 0.9605 1.0000 1.0404 1.0817 1.1236 1.1662 1.2093 1.2530 1.2971 1.3416 1.2971 1.2530 1.2093 1.1662 1.1236 1.0817 1.0404 1.0000 0.9605 0.9220 0.8846 0.8485 0.8139 0.7810 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 +1.4705 1.4230 1.3757 1.3285 1.2816 1.2349 1.1885 1.1424 1.0966 1.0512 1.0062 0.9618 0.9179 0.8746 0.8322 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.8201 0.8515 0.8846 0.9192 0.9552 0.9925 1.0308 1.0700 1.1102 1.1511 1.1927 1.2349 1.2777 1.3210 1.3647 1.3210 1.2777 1.2349 1.1927 1.1511 1.1102 1.0700 1.0308 0.9925 0.9552 0.9192 0.8846 0.8515 0.8201 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 +1.4866 1.4396 1.3928 1.3463 1.3000 1.2540 1.2083 1.1630 1.1180 1.0735 1.0296 0.9862 0.9434 0.9014 0.8602 0.8201 0.7810 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8602 0.8902 0.9220 0.9552 0.9899 1.0259 1.0630 1.1011 1.1402 1.1800 1.2207 1.2619 1.3038 1.3463 1.3892 1.3463 1.3038 1.2619 1.2207 1.1800 1.1402 1.1011 1.0630 1.0259 0.9899 0.9552 0.9220 0.8902 0.8602 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 +1.5042 1.4577 1.4116 1.3657 1.3200 1.2748 1.2298 1.1853 1.1413 1.0977 1.0548 1.0124 0.9708 0.9301 0.8902 0.8515 0.8139 0.7778 0.7433 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8078 0.8276 0.8500 0.8746 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8078 0.8276 0.8500 0.8746 0.9014 0.9301 0.9605 0.9925 1.0259 1.0607 1.0966 1.1336 1.1715 1.2104 1.2500 1.2903 1.3314 1.3730 1.4151 1.3730 1.3314 1.2903 1.2500 1.2104 1.1715 1.1336 1.0966 1.0607 1.0259 0.9925 0.9605 0.9301 0.9014 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 +1.5232 1.4773 1.4318 1.3865 1.3416 1.2971 1.2530 1.2093 1.1662 1.1236 1.0817 1.0404 1.0000 0.9605 0.9220 0.8846 0.8485 0.8139 0.7810 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7810 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8016 0.8062 0.8139 0.8246 0.8382 0.8544 0.8732 0.8944 0.9179 0.9179 0.8944 0.8732 0.8544 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8016 0.8062 0.8139 0.8246 0.8382 0.8544 0.8732 0.8944 0.9179 0.9434 0.9708 1.0000 1.0308 1.0630 1.0966 1.1314 1.1673 1.2042 1.2420 1.2806 1.3200 1.3601 1.4000 1.4000 1.4000 1.3601 1.3200 1.2806 1.2420 1.2042 1.1673 1.1314 1.0966 1.0630 1.0308 1.0000 0.9708 0.9434 0.9179 0.8944 0.8732 0.8544 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 +1.5435 1.4983 1.4534 1.4089 1.3647 1.3210 1.2777 1.2349 1.1927 1.1511 1.1102 1.0700 1.0308 0.9925 0.9552 0.9192 0.8846 0.8515 0.8201 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.8201 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8515 0.8559 0.8631 0.8732 0.8860 0.9014 0.9192 0.9394 0.9618 0.9618 0.9394 0.9192 0.9014 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8515 0.8559 0.8631 0.8732 0.8860 0.9014 0.9192 0.9394 0.9618 0.9862 1.0124 1.0404 1.0700 1.1011 1.1336 1.1673 1.2021 1.2379 1.2748 1.3124 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3124 1.2748 1.2379 1.2021 1.1673 1.1336 1.1011 1.0700 1.0404 1.0124 0.9862 0.9618 0.9394 0.9192 0.9014 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 +1.5652 1.5207 1.4765 1.4327 1.3892 1.3463 1.3038 1.2619 1.2207 1.1800 1.1402 1.1011 1.0630 1.0259 0.9899 0.9552 0.9220 0.8902 0.8602 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8602 0.8902 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9014 0.9055 0.9124 0.9220 0.9341 0.9487 0.9657 0.9849 1.0062 1.0062 0.9849 0.9657 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9014 0.9055 0.9124 0.9220 0.9341 0.9487 0.9657 0.9849 1.0062 1.0296 1.0548 1.0817 1.1102 1.1402 1.1715 1.2042 1.2379 1.2728 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.2728 1.2379 1.2042 1.1715 1.1402 1.1102 1.0817 1.0548 1.0296 1.0062 0.9849 0.9657 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 +1.5882 1.5443 1.5008 1.4577 1.4151 1.3730 1.3314 1.2903 1.2500 1.2104 1.1715 1.1336 1.0966 1.0607 1.0259 0.9925 0.9605 0.9301 0.9014 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8078 0.8276 0.8500 0.8746 0.9014 0.9301 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9513 0.9552 0.9618 0.9708 0.9823 0.9962 1.0124 1.0308 1.0512 1.0512 1.0308 1.0124 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9513 0.9552 0.9618 0.9708 0.9823 0.9962 1.0124 1.0308 1.0512 1.0735 1.0977 1.1236 1.1511 1.1800 1.2104 1.2420 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2420 1.2104 1.1800 1.1511 1.1236 1.0977 1.0735 1.0512 1.0308 1.0124 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 +1.6125 1.5692 1.5264 1.4841 1.4422 1.4009 1.3601 1.3200 1.2806 1.2420 1.2042 1.1673 1.1314 1.0966 1.0630 1.0308 1.0000 0.9708 0.9434 0.9179 0.8944 0.8732 0.8544 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8016 0.8062 0.8139 0.8246 0.8382 0.8544 0.8732 0.8944 0.9179 0.9434 0.9708 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0012 1.0050 1.0112 1.0198 1.0308 1.0440 1.0595 1.0770 1.0966 1.0966 1.0770 1.0595 1.0440 1.0308 1.0198 1.0112 1.0050 1.0012 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0012 1.0050 1.0112 1.0198 1.0308 1.0440 1.0595 1.0770 1.0966 1.1180 1.1413 1.1662 1.1927 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.1927 1.1662 1.1413 1.1180 1.0966 1.0770 1.0595 1.0440 1.0308 1.0198 1.0112 1.0050 1.0012 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 +1.6378 1.5953 1.5532 1.5116 1.4705 1.4300 1.3901 1.3509 1.3124 1.2748 1.2379 1.2021 1.1673 1.1336 1.1011 1.0700 1.0404 1.0124 0.9862 0.9618 0.9394 0.9192 0.9014 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8515 0.8559 0.8631 0.8732 0.8860 0.9014 0.9192 0.9394 0.9618 0.9862 1.0124 1.0404 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0512 1.0548 1.0607 1.0689 1.0794 1.0920 1.1068 1.1236 1.1424 1.1424 1.1236 1.1068 1.0920 1.0794 1.0689 1.0607 1.0548 1.0512 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0512 1.0548 1.0607 1.0689 1.0794 1.0920 1.1068 1.1236 1.1424 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1424 1.1236 1.1068 1.0920 1.0794 1.0689 1.0607 1.0548 1.0512 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 +1.6643 1.6225 1.5811 1.5403 1.5000 1.4603 1.4213 1.3829 1.3454 1.3086 1.2728 1.2379 1.2042 1.1715 1.1402 1.1102 1.0817 1.0548 1.0296 1.0062 0.9849 0.9657 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9014 0.9055 0.9124 0.9220 0.9341 0.9487 0.9657 0.9849 1.0062 1.0296 1.0548 1.0817 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 +1.6919 1.6508 1.6101 1.5700 1.5305 1.4916 1.4534 1.4160 1.3793 1.3435 1.3086 1.2748 1.2420 1.2104 1.1800 1.1511 1.1236 1.0977 1.0735 1.0512 1.0308 1.0124 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9500 0.9500 0.9513 0.9552 0.9618 0.9708 0.9823 0.9962 1.0124 1.0308 1.0512 1.0735 1.0977 1.1236 1.1068 1.0920 1.0794 1.0689 1.0607 1.0548 1.0512 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0512 1.0548 1.0607 1.0689 1.0794 1.0920 1.1068 1.1236 1.1424 1.1424 1.1236 1.1068 1.0920 1.0794 1.0689 1.0607 1.0548 1.0512 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0512 1.0548 1.0607 1.0689 1.0794 1.0920 1.1068 1.1236 1.1424 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1424 1.1236 1.1068 1.0920 1.0794 1.0689 1.0607 1.0548 1.0512 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 +1.6643 1.6225 1.5811 1.5403 1.5000 1.4603 1.4213 1.3829 1.3454 1.3086 1.2728 1.2379 1.2042 1.1715 1.1402 1.1102 1.0817 1.0548 1.0296 1.0062 0.9849 0.9657 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9014 0.9055 0.9124 0.9220 0.9341 0.9487 0.9657 0.9849 1.0062 1.0296 1.0548 1.0770 1.0595 1.0440 1.0308 1.0198 1.0112 1.0050 1.0012 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0012 1.0050 1.0112 1.0198 1.0308 1.0440 1.0595 1.0770 1.0966 1.0966 1.0770 1.0595 1.0440 1.0308 1.0198 1.0112 1.0050 1.0012 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0012 1.0050 1.0112 1.0198 1.0308 1.0440 1.0595 1.0770 1.0966 1.1180 1.1413 1.1662 1.1927 1.2000 1.2000 1.2000 1.1927 1.1662 1.1413 1.1180 1.0966 1.0770 1.0595 1.0440 1.0308 1.0198 1.0112 1.0050 1.0012 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 +1.6378 1.5953 1.5532 1.5116 1.4705 1.4300 1.3901 1.3509 1.3124 1.2748 1.2379 1.2021 1.1673 1.1336 1.1011 1.0700 1.0404 1.0124 0.9862 0.9618 0.9394 0.9192 0.9014 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8515 0.8559 0.8631 0.8732 0.8860 0.9014 0.9192 0.9394 0.9618 0.9862 1.0124 1.0308 1.0124 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9513 0.9552 0.9618 0.9708 0.9823 0.9962 1.0124 1.0308 1.0512 1.0512 1.0308 1.0124 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9513 0.9552 0.9618 0.9708 0.9823 0.9962 1.0124 1.0308 1.0512 1.0735 1.0977 1.1236 1.1511 1.1800 1.2104 1.1800 1.1511 1.1236 1.0977 1.0735 1.0512 1.0308 1.0124 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 +1.6125 1.5692 1.5264 1.4841 1.4422 1.4009 1.3601 1.3200 1.2806 1.2420 1.2042 1.1673 1.1314 1.0966 1.0630 1.0308 1.0000 0.9708 0.9434 0.9179 0.8944 0.8732 0.8544 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8016 0.8062 0.8139 0.8246 0.8382 0.8544 0.8732 0.8944 0.9179 0.9434 0.9708 0.9849 0.9657 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9014 0.9055 0.9124 0.9220 0.9341 0.9487 0.9657 0.9849 1.0062 1.0062 0.9849 0.9657 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9014 0.9055 0.9124 0.9220 0.9341 0.9487 0.9657 0.9849 1.0062 1.0296 1.0548 1.0817 1.1102 1.1402 1.1715 1.1402 1.1102 1.0817 1.0548 1.0296 1.0062 0.9849 0.9657 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 +1.5882 1.5443 1.5008 1.4577 1.4151 1.3730 1.3314 1.2903 1.2500 1.2104 1.1715 1.1336 1.0966 1.0607 1.0259 0.9925 0.9605 0.9301 0.9014 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8078 0.8276 0.8500 0.8746 0.9014 0.9301 0.9394 0.9192 0.9014 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8515 0.8559 0.8631 0.8732 0.8860 0.9014 0.9192 0.9394 0.9618 0.9618 0.9394 0.9192 0.9014 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8515 0.8559 0.8631 0.8732 0.8860 0.9014 0.9192 0.9394 0.9618 0.9862 1.0124 1.0404 1.0700 1.1011 1.1336 1.1011 1.0700 1.0404 1.0124 0.9862 0.9618 0.9394 0.9192 0.9014 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 +1.5652 1.5207 1.4765 1.4327 1.3892 1.3463 1.3038 1.2619 1.2207 1.1800 1.1402 1.1011 1.0630 1.0259 0.9899 0.9552 0.9220 0.8902 0.8602 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8602 0.8902 0.8944 0.8732 0.8544 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8016 0.8062 0.8139 0.8246 0.8382 0.8544 0.8732 0.8944 0.9179 0.9179 0.8944 0.8732 0.8544 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8016 0.8062 0.8139 0.8246 0.8382 0.8544 0.8732 0.8944 0.9179 0.9434 0.9708 1.0000 1.0308 1.0630 1.0966 1.0630 1.0308 1.0000 0.9708 0.9434 0.9179 0.8944 0.8732 0.8544 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 +1.5435 1.4983 1.4534 1.4089 1.3647 1.3210 1.2777 1.2349 1.1927 1.1511 1.1102 1.0700 1.0308 0.9925 0.9552 0.9192 0.8846 0.8515 0.8201 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.8201 0.8515 0.8500 0.8276 0.8078 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8078 0.8276 0.8500 0.8746 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8078 0.8276 0.8500 0.8746 0.9014 0.9301 0.9605 0.9925 1.0259 1.0607 1.0259 0.9925 0.9605 0.9301 0.9014 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 +1.5207 1.4765 1.4318 1.3865 1.3416 1.2971 1.2530 1.2093 1.1662 1.1236 1.0817 1.0404 1.0000 0.9605 0.9220 0.8846 0.8485 0.8139 0.7810 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7810 0.8139 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8602 0.8902 0.9220 0.9552 0.9899 1.0259 0.9899 0.9552 0.9220 0.8902 0.8602 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 +1.4983 1.4534 1.4089 1.3647 1.3200 1.2748 1.2298 1.1853 1.1413 1.0977 1.0548 1.0124 0.9708 0.9301 0.8902 0.8515 0.8139 0.7778 0.7433 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7778 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.8201 0.8515 0.8846 0.9192 0.9552 0.9925 0.9552 0.9192 0.8846 0.8515 0.8201 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 +1.4773 1.4318 1.3865 1.3416 1.2971 1.2530 1.2083 1.1630 1.1180 1.0735 1.0296 0.9862 0.9434 0.9014 0.8602 0.8201 0.7810 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7071 0.7433 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7810 0.8139 0.8485 0.8846 0.9220 0.9605 0.9220 0.8846 0.8485 0.8139 0.7810 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 +1.4577 1.4116 1.3657 1.3200 1.2748 1.2298 1.1853 1.1413 1.0966 1.0512 1.0062 0.9618 0.9179 0.8746 0.8322 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7778 0.8139 0.8515 0.8902 0.9301 0.8902 0.8515 0.8139 0.7778 0.7433 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 +1.4396 1.3928 1.3463 1.3000 1.2540 1.2083 1.1630 1.1180 1.0735 1.0296 0.9849 0.9394 0.8944 0.8500 0.8062 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8602 0.9014 0.8602 0.8201 0.7810 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 +1.4230 1.3757 1.3285 1.2816 1.2349 1.1885 1.1424 1.0966 1.0512 1.0062 0.9618 0.9179 0.8732 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8322 0.8746 0.8322 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 +1.4080 1.3601 1.3124 1.2649 1.2176 1.1705 1.1236 1.0770 1.0308 0.9849 0.9394 0.8944 0.8500 0.8062 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8062 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 +1.3946 1.3463 1.2981 1.2500 1.2021 1.1543 1.1068 1.0595 1.0124 0.9657 0.9192 0.8732 0.8276 0.7826 0.7382 0.6946 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 +1.3829 1.3342 1.2855 1.2369 1.1885 1.1402 1.0920 1.0440 0.9962 0.9487 0.9014 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 +1.3730 1.3238 1.2748 1.2258 1.1769 1.1281 1.0794 1.0308 0.9823 0.9341 0.8860 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4717 0.5148 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 +1.3647 1.3153 1.2659 1.2166 1.1673 1.1180 1.0689 1.0198 0.9708 0.9220 0.8732 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3606 0.4031 0.4472 0.4924 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 +1.3583 1.3086 1.2590 1.2093 1.1597 1.1102 1.0607 1.0112 0.9618 0.9124 0.8631 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 +1.3537 1.3038 1.2540 1.2042 1.1543 1.1045 1.0548 1.0050 0.9552 0.9055 0.8559 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 +1.3509 1.3010 1.2510 1.2010 1.1511 1.1011 1.0512 1.0012 0.9513 0.9014 0.8515 0.8016 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 -0.0500 -0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0707 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1000 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1000 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0707 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0707 -0.0500 -0.0500 -0.0707 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3905 0.4301 0.4717 0.5148 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5408 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6403 0.6801 0.7211 0.7632 0.8062 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7906 0.8322 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5385 0.5220 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7906 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6403 0.6801 0.7211 0.7632 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7566 0.7649 0.7762 0.7906 0.8078 0.8276 0.8500 0.8746 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7500 0.7500 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8139 0.8246 0.8382 0.8544 0.8732 0.8944 0.9179 0.9179 0.8944 0.8732 0.8544 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8000 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8000 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8500 0.8500 0.8500 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8732 0.8860 0.9014 0.9192 0.9394 0.9618 0.9618 0.9394 0.9192 0.9014 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.8201 0.8515 0.8846 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9341 0.9487 0.9657 0.9849 1.0062 1.0062 0.9849 0.9657 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.8860 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.8631 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7810 0.8139 0.8485 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9962 1.0124 1.0308 1.0500 1.0500 1.0308 1.0124 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9487 0.9014 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9055 0.8559 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7778 0.8139 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 0.9657 0.9192 0.8732 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 0.9513 0.9014 0.8515 0.8016 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9513 0.9192 0.8732 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1000 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9014 0.9014 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1000 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8515 0.8559 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1011 1.0512 1.0012 0.9513 0.9014 0.8515 0.8016 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9513 1.0012 1.0512 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8016 0.8062 0.8139 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8000 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.1543 1.1045 1.0548 1.0050 0.9552 0.9055 0.8559 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9552 1.0050 1.0548 1.1045 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7517 0.7566 0.7649 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7500 0.7500 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2093 1.1597 1.1102 1.0607 1.0112 0.9618 0.9124 0.8631 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1118 0.0707 0.0500 0.0500 0.0500 0.0707 0.1118 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9618 1.0112 1.0607 1.1102 1.1597 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.2659 1.2166 1.1673 1.1180 1.0689 1.0198 0.9708 0.9220 0.8732 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9220 0.9708 1.0198 1.0689 1.1180 1.1673 1.2166 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3238 1.2748 1.2258 1.1769 1.1281 1.0794 1.0308 0.9823 0.9341 0.8860 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9341 0.9823 1.0308 1.0794 1.1281 1.1769 1.2258 1.2748 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.3829 1.3342 1.2855 1.2369 1.1885 1.1402 1.0920 1.0440 0.9962 0.9487 0.9014 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9487 0.9962 1.0440 1.0920 1.1402 1.1885 1.2369 1.2855 1.3342 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4431 1.3946 1.3463 1.2981 1.2500 1.2021 1.1543 1.1068 1.0595 1.0124 0.9657 0.9192 0.8732 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8732 0.9192 0.9657 1.0124 1.0595 1.1068 1.1543 1.2021 1.2500 1.2981 1.3463 1.3946 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.4560 1.4080 1.3601 1.3124 1.2649 1.2176 1.1705 1.1236 1.0770 1.0308 0.9849 0.9394 0.8944 0.8500 0.8062 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8062 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8944 0.9394 0.9849 1.0308 1.0770 1.1236 1.1705 1.2176 1.2649 1.3124 1.3601 1.4080 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5182 1.4705 1.4230 1.3757 1.3285 1.2816 1.2349 1.1885 1.1424 1.0966 1.0512 1.0062 0.9618 0.9179 0.8746 0.8322 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8322 0.8746 0.8322 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8322 0.8746 0.9179 0.9618 1.0062 1.0512 1.0966 1.1424 1.1885 1.2349 1.2816 1.3285 1.3757 1.4230 1.4705 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.5977 1.5508 1.5042 1.4577 1.4116 1.3657 1.3200 1.2748 1.2298 1.1853 1.1413 1.0977 1.0548 1.0124 0.9708 0.9301 0.8902 0.8515 0.8139 0.7778 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8602 0.9014 0.8602 0.8201 0.7810 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8602 0.9014 0.9434 0.9862 1.0296 1.0735 1.1180 1.1630 1.2083 1.2540 1.3000 1.3463 1.3928 1.4396 1.4866 1.5338 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6286 1.5811 1.5338 1.4866 1.4396 1.3928 1.3463 1.3000 1.2540 1.2083 1.1630 1.1180 1.0735 1.0296 0.9862 0.9434 0.9014 0.8602 0.8201 0.7810 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5385 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7778 0.8139 0.8515 0.8902 0.9301 0.8902 0.8515 0.8139 0.7778 0.7433 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7778 0.8139 0.8515 0.8902 0.9301 0.9708 1.0124 1.0548 1.0977 1.1413 1.1853 1.2298 1.2748 1.3200 1.3657 1.4116 1.4577 1.5042 1.5508 1.5977 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.5660 1.5182 1.4705 1.4230 1.3757 1.3285 1.2816 1.2349 1.1885 1.1424 1.0966 1.0512 1.0062 0.9618 0.9179 0.8746 0.8322 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7810 0.8139 0.8485 0.8846 0.9220 0.9605 0.9220 0.8846 0.8485 0.8139 0.7810 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7810 0.8139 0.8485 0.8846 0.9220 0.9605 1.0000 1.0404 1.0817 1.1236 1.1662 1.2093 1.2530 1.2971 1.3416 1.3865 1.4318 1.4773 1.5232 1.5692 1.6155 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5042 1.4560 1.4080 1.3601 1.3124 1.2649 1.2176 1.1705 1.1236 1.0770 1.0308 0.9849 0.9394 0.8944 0.8500 0.8062 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8944 0.9394 0.9849 0.9552 0.9192 0.8846 0.8515 0.8201 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.8201 0.8515 0.8846 0.9192 0.9552 0.9925 1.0308 1.0700 1.1102 1.1511 1.1927 1.2349 1.2777 1.3210 1.3647 1.4089 1.4534 1.4983 1.5435 1.5890 1.6348 1.6808 1.7000 1.7000 1.7000 1.7000 1.7000 1.7000 1.7000 1.7000 1.7000 1.7000 1.7000 1.7000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.4916 1.4431 1.3946 1.3463 1.2981 1.2500 1.2021 1.1543 1.1068 1.0595 1.0124 0.9657 0.9192 0.8732 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8732 0.9192 0.9657 0.9899 0.9552 0.9220 0.8902 0.8602 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8602 0.8902 0.9220 0.9552 0.9899 1.0259 1.0630 1.1011 1.1402 1.1800 1.2207 1.2619 1.3038 1.3463 1.3892 1.4327 1.4765 1.5207 1.5652 1.6101 1.6553 1.7007 1.7464 1.7500 1.7500 1.7500 1.7500 1.7500 1.7500 1.7500 1.7500 1.7500 1.7500 1.7500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4318 1.3829 1.3342 1.2855 1.2369 1.1885 1.1402 1.0920 1.0440 0.9962 0.9487 0.9014 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9487 0.9962 0.9925 0.9605 0.9301 0.9014 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8078 0.8276 0.8500 0.8746 0.9014 0.9301 0.9605 0.9925 1.0259 1.0607 1.0966 1.1336 1.1715 1.2104 1.2500 1.2903 1.3314 1.3730 1.4151 1.4577 1.5008 1.5443 1.5882 1.6325 1.6771 1.7219 1.7671 1.8000 1.8000 1.8000 1.8000 1.8000 1.8000 1.8000 1.8000 1.8000 1.8000 1.8000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.3730 1.3238 1.2748 1.2258 1.1769 1.1281 1.0794 1.0308 0.9823 0.9341 0.8860 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9341 0.9823 1.0308 1.0000 0.9708 0.9434 0.9179 0.8944 0.8732 0.8544 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8000 0.8000 0.8000 0.8016 0.8062 0.8139 0.8246 0.8382 0.8544 0.8732 0.8944 0.9179 0.9434 0.9708 1.0000 1.0308 1.0630 1.0966 1.1314 1.1673 1.2042 1.2420 1.2806 1.3200 1.3601 1.4009 1.4422 1.4841 1.5264 1.5692 1.6125 1.6560 1.7000 1.7443 1.7889 1.8337 1.8500 1.8500 1.8500 1.8500 1.8500 1.8500 1.8500 1.8500 1.8500 1.8500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3153 1.2659 1.2166 1.1673 1.1180 1.0689 1.0198 0.9708 0.9220 0.8732 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.1803 0.1581 0.1500 0.1500 0.1500 0.1581 0.1803 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9220 0.9708 1.0198 1.0404 1.0124 0.9862 0.9618 0.9394 0.9192 0.9014 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8500 0.8500 0.8500 0.8515 0.8559 0.8631 0.8732 0.8860 0.9014 0.9192 0.9394 0.9618 0.9862 1.0124 1.0404 1.0700 1.1011 1.1336 1.1673 1.2021 1.2379 1.2748 1.3124 1.3509 1.3901 1.4300 1.4705 1.5116 1.5532 1.5953 1.6378 1.6808 1.7241 1.7678 1.8118 1.8561 1.9000 1.9000 1.9000 1.9000 1.9000 1.9000 1.9000 1.9000 1.9000 1.9000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.2590 1.2093 1.1597 1.1102 1.0607 1.0112 0.9618 0.9124 0.8631 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1414 0.1118 0.1000 0.1000 0.1000 0.1118 0.1414 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9618 1.0112 1.0607 1.0548 1.0296 1.0062 0.9849 0.9657 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9000 0.9000 0.9000 0.9014 0.9055 0.9124 0.9220 0.9341 0.9487 0.9657 0.9849 1.0062 1.0296 1.0548 1.0817 1.1102 1.1402 1.1715 1.2042 1.2379 1.2728 1.3086 1.3454 1.3829 1.4213 1.4603 1.5000 1.5403 1.5811 1.6225 1.6643 1.7066 1.7493 1.7923 1.8358 1.8795 1.9235 1.9500 1.9500 1.9500 1.9500 1.9500 1.9500 1.9500 1.9500 1.9500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1118 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2042 1.1543 1.1045 1.0548 1.0050 0.9552 0.9055 0.8559 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.0707 0.0500 0.0500 0.0500 0.0707 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9552 1.0050 1.0548 1.0977 1.0735 1.0512 1.0308 1.0124 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9500 0.9500 0.9500 0.9500 0.9500 0.9513 0.9552 0.9618 0.9708 0.9823 0.9962 1.0124 1.0308 1.0512 1.0735 1.0977 1.1236 1.1511 1.1800 1.2104 1.2420 1.2748 1.3086 1.3435 1.3793 1.4160 1.4534 1.4916 1.5305 1.5700 1.6101 1.6508 1.6919 1.7335 1.7755 1.8180 1.8608 1.9039 1.9474 1.9912 2.0000 2.0000 2.0000 2.0000 2.0000 2.0000 2.0000 2.0000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.1500 -0.1500 -0.1500 -0.1500 -0.1500 -0.1000 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.1511 1.1011 1.0512 1.0012 0.9513 0.9014 0.8515 0.8016 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9513 1.0012 1.0512 1.1011 1.1180 1.0966 1.0770 1.0595 1.0440 1.0308 1.0198 1.0112 1.0050 1.0012 1.0000 1.0000 1.0000 1.0000 1.0000 1.0012 1.0050 1.0112 1.0198 1.0308 1.0440 1.0595 1.0770 1.0966 1.1180 1.1413 1.1662 1.1927 1.2207 1.2500 1.2806 1.3124 1.3454 1.3793 1.4142 1.4500 1.4866 1.5240 1.5620 1.6008 1.6401 1.6800 1.7205 1.7614 1.8028 1.8446 1.8868 1.9294 1.9723 2.0156 2.0500 2.0500 2.0500 2.0500 2.0500 2.0500 2.0500 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2000 -0.2000 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1000 -0.0707 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.1424 1.1236 1.1068 1.0920 1.0794 1.0689 1.0607 1.0548 1.0512 1.0500 1.0500 1.0500 1.0500 1.0500 1.0512 1.0548 1.0607 1.0689 1.0794 1.0920 1.1068 1.1236 1.1424 1.1630 1.1853 1.2093 1.2349 1.2619 1.2903 1.3200 1.3509 1.3829 1.4160 1.4500 1.4849 1.5207 1.5572 1.5945 1.6325 1.6711 1.7103 1.7500 1.7903 1.8310 1.8722 1.9138 1.9558 1.9981 2.0408 2.0839 2.1000 2.1000 2.1000 2.1000 2.1000 2.1000 2.1000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.1885 1.1705 1.1543 1.1402 1.1281 1.1180 1.1102 1.1045 1.1011 1.1000 1.1000 1.1000 1.1000 1.1000 1.1011 1.1045 1.1102 1.1180 1.1281 1.1402 1.1543 1.1705 1.1885 1.2083 1.2298 1.2530 1.2777 1.3038 1.3314 1.3601 1.3901 1.4213 1.4534 1.4866 1.5207 1.5556 1.5914 1.6279 1.6651 1.7029 1.7414 1.7804 1.8200 1.8601 1.9007 1.9416 1.9831 2.0248 2.0670 2.1095 2.1500 2.1500 2.1500 2.1500 2.1500 2.1500 2.1500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2176 1.2021 1.1885 1.1769 1.1673 1.1597 1.1543 1.1511 1.1500 1.1500 1.1500 1.1500 1.1500 1.1511 1.1543 1.1597 1.1673 1.1769 1.1885 1.2021 1.2176 1.2349 1.2540 1.2748 1.2971 1.3210 1.3463 1.3730 1.4009 1.4300 1.4603 1.4916 1.5240 1.5572 1.5914 1.6263 1.6621 1.6985 1.7357 1.7734 1.8118 1.8507 1.8901 1.9300 1.9704 2.0112 2.0524 2.0940 2.1360 2.1783 2.2000 2.2000 2.2000 2.2000 2.2000 2.2000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9513 1.0012 1.0512 1.1011 1.1511 1.2010 1.2510 1.2500 1.2369 1.2258 1.2166 1.2093 1.2042 1.2010 1.2000 1.2000 1.2000 1.2000 1.2000 1.2010 1.2042 1.2093 1.2166 1.2258 1.2369 1.2500 1.2649 1.2816 1.3000 1.3200 1.3416 1.3647 1.3892 1.4151 1.4422 1.4705 1.5000 1.5305 1.5620 1.5945 1.6279 1.6621 1.6971 1.7328 1.7692 1.8062 1.8439 1.8822 1.9209 1.9602 2.0000 2.0402 2.0809 2.1219 2.1633 2.2051 2.2472 2.2500 2.2500 2.2500 2.2500 2.2500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9552 1.0050 1.0548 1.1045 1.1543 1.2042 1.2540 1.2981 1.2855 1.2748 1.2659 1.2590 1.2540 1.2510 1.2500 1.2500 1.2500 1.2500 1.2500 1.2510 1.2540 1.2590 1.2659 1.2748 1.2855 1.2981 1.3124 1.3285 1.3463 1.3657 1.3865 1.4089 1.4327 1.4577 1.4841 1.5116 1.5403 1.5700 1.6008 1.6325 1.6651 1.6985 1.7328 1.7678 1.8035 1.8398 1.8768 1.9144 1.9526 1.9912 2.0304 2.0700 2.1101 2.1506 2.1915 2.2327 2.2743 2.3000 2.3000 2.3000 2.3000 2.3000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9618 1.0112 1.0607 1.1102 1.1597 1.2093 1.2590 1.3086 1.3342 1.3238 1.3153 1.3086 1.3038 1.3010 1.3000 1.3000 1.3000 1.3000 1.3000 1.3010 1.3038 1.3086 1.3153 1.3238 1.3342 1.3463 1.3601 1.3757 1.3928 1.4116 1.4318 1.4534 1.4765 1.5008 1.5264 1.5532 1.5811 1.6101 1.6401 1.6711 1.7029 1.7357 1.7692 1.8035 1.8385 1.8742 1.9105 1.9474 1.9849 2.0230 2.0616 2.1006 2.1401 2.1800 2.2204 2.2611 2.3022 2.3436 2.3500 2.3500 2.3500 2.3500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9220 0.9708 1.0198 1.0689 1.1180 1.1673 1.2166 1.2659 1.3153 1.3647 1.3730 1.3647 1.3583 1.3537 1.3509 1.3500 1.3500 1.3500 1.3500 1.3500 1.3509 1.3537 1.3583 1.3647 1.3730 1.3829 1.3946 1.4080 1.4230 1.4396 1.4577 1.4773 1.4983 1.5207 1.5443 1.5692 1.5953 1.6225 1.6508 1.6800 1.7103 1.7414 1.7734 1.8062 1.8398 1.8742 1.9092 1.9449 1.9812 2.0180 2.0555 2.0934 2.1319 2.1708 2.2102 2.2500 2.2902 2.3308 2.3717 2.4000 2.4000 2.4000 2.4000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9341 0.9823 1.0308 1.0794 1.1281 1.1769 1.2258 1.2748 1.3238 1.3730 1.4221 1.4142 1.4080 1.4036 1.4009 1.4000 1.4000 1.4000 1.4000 1.4000 1.4009 1.4036 1.4080 1.4142 1.4221 1.4318 1.4431 1.4560 1.4705 1.4866 1.5042 1.5232 1.5435 1.5652 1.5882 1.6125 1.6378 1.6643 1.6919 1.7205 1.7500 1.7804 1.8118 1.8439 1.8768 1.9105 1.9449 1.9799 2.0156 2.0518 2.0887 2.1260 2.1639 2.2023 2.2411 2.2804 2.3200 2.3601 2.4005 2.4413 2.4500 2.4500 2.4500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9341 0.8860 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9487 0.9962 1.0440 1.0920 1.1402 1.1885 1.2369 1.2855 1.3342 1.3829 1.4318 1.4637 1.4577 1.4534 1.4509 1.4500 1.4500 1.4500 1.4500 1.4500 1.4509 1.4534 1.4577 1.4637 1.4714 1.4807 1.4916 1.5042 1.5182 1.5338 1.5508 1.5692 1.5890 1.6101 1.6325 1.6560 1.6808 1.7066 1.7335 1.7614 1.7903 1.8200 1.8507 1.8822 1.9144 1.9474 1.9812 2.0156 2.0506 2.0863 2.1225 2.1593 2.1966 2.2344 2.2727 2.3114 2.3505 2.3901 2.4300 2.4703 2.5000 2.5000 2.5000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 0.9708 0.9220 0.8732 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8732 0.9192 0.9657 1.0124 1.0595 1.1068 1.1543 1.2021 1.2500 1.2981 1.3463 1.3946 1.4431 1.4916 1.5075 1.5033 1.5008 1.5000 1.5000 1.5000 1.5000 1.5000 1.5008 1.5033 1.5075 1.5133 1.5207 1.5297 1.5403 1.5524 1.5660 1.5811 1.5977 1.6155 1.6348 1.6553 1.6771 1.7000 1.7241 1.7493 1.7755 1.8028 1.8310 1.8601 1.8901 1.9209 1.9526 1.9849 2.0180 2.0518 2.0863 2.1213 2.1570 2.1932 2.2299 2.2672 2.3049 2.3431 2.3817 2.4207 2.4602 2.5000 2.5402 2.5500 2.5500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0112 0.9618 0.9124 0.8631 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8944 0.9394 0.9849 1.0308 1.0770 1.1236 1.1705 1.2176 1.2649 1.3124 1.3601 1.4080 1.4560 1.5042 1.5524 1.5532 1.5508 1.5500 1.5500 1.5500 1.5500 1.5500 1.5508 1.5532 1.5572 1.5628 1.5700 1.5788 1.5890 1.6008 1.6140 1.6286 1.6447 1.6621 1.6808 1.7007 1.7219 1.7443 1.7678 1.7923 1.8180 1.8446 1.8722 1.9007 1.9300 1.9602 1.9912 2.0230 2.0555 2.0887 2.1225 2.1570 2.1920 2.2277 2.2638 2.3005 2.3377 2.3754 2.4135 2.4520 2.4910 2.5303 2.5700 2.6000 2.6000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.0548 1.0050 0.9552 0.9055 0.8559 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8322 0.8746 0.9179 0.9618 1.0062 1.0512 1.0966 1.1424 1.1885 1.2349 1.2816 1.3285 1.3757 1.4230 1.4705 1.5182 1.5660 1.6031 1.6008 1.6000 1.6000 1.6000 1.6000 1.6000 1.6008 1.6031 1.6070 1.6125 1.6194 1.6279 1.6378 1.6492 1.6621 1.6763 1.6919 1.7088 1.7270 1.7464 1.7671 1.7889 1.8118 1.8358 1.8608 1.8868 1.9138 1.9416 1.9704 2.0000 2.0304 2.0616 2.0934 2.1260 2.1593 2.1932 2.2277 2.2627 2.2984 2.3345 2.3712 2.4083 2.4459 2.4839 2.5224 2.5612 2.6005 2.6401 2.6500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.1500 1.1500 1.1500 1.1011 1.0512 1.0012 0.9513 0.9014 0.8515 0.8016 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0707 0.1118 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8602 0.9014 0.9434 0.9862 1.0296 1.0735 1.1180 1.1630 1.2083 1.2540 1.3000 1.3463 1.3928 1.4396 1.4866 1.5338 1.5811 1.6286 1.6508 1.6500 1.6500 1.6500 1.6500 1.6500 1.6508 1.6530 1.6568 1.6621 1.6688 1.6771 1.6867 1.6978 1.7103 1.7241 1.7393 1.7557 1.7734 1.7923 1.8125 1.8337 1.8561 1.8795 1.9039 1.9294 1.9558 1.9831 2.0112 2.0402 2.0700 2.1006 2.1319 2.1639 2.1966 2.2299 2.2638 2.2984 2.3335 2.3691 2.4052 2.4418 2.4789 2.5164 2.5544 2.5928 2.6315 2.6707 2.7000 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8078 0.8276 0.8500 0.8746 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7778 0.8139 0.8515 0.8902 0.9301 0.9708 1.0124 1.0548 1.0977 1.1413 1.1853 1.2298 1.2748 1.3200 1.3657 1.4116 1.4577 1.5042 1.5508 1.5977 1.6447 1.6919 1.7000 1.7000 1.7000 1.7000 1.7000 1.7007 1.7029 1.7066 1.7117 1.7183 1.7263 1.7357 1.7464 1.7586 1.7720 1.7868 1.8028 1.8200 1.8385 1.8581 1.8788 1.9007 1.9235 1.9474 1.9723 1.9981 2.0248 2.0524 2.0809 2.1101 2.1401 2.1708 2.2023 2.2344 2.2672 2.3005 2.3345 2.3691 2.4042 2.4398 2.4759 2.5125 2.5495 2.5870 2.6249 2.6632 2.7019 2.7409 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8016 0.8062 0.8139 0.8246 0.8382 0.8544 0.8732 0.8944 0.9179 0.9179 0.8944 0.8732 0.8544 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7810 0.8139 0.8485 0.8846 0.9220 0.9605 1.0000 1.0404 1.0817 1.1236 1.1662 1.2093 1.2530 1.2971 1.3416 1.3865 1.4318 1.4773 1.5232 1.5692 1.6155 1.6621 1.7088 1.7500 1.7500 1.7500 1.7500 1.7500 1.7507 1.7529 1.7564 1.7614 1.7678 1.7755 1.7847 1.7951 1.8069 1.8200 1.8344 1.8500 1.8668 1.8848 1.9039 1.9242 1.9455 1.9679 1.9912 2.0156 2.0408 2.0670 2.0940 2.1219 2.1506 2.1800 2.2102 2.2411 2.2727 2.3049 2.3377 2.3712 2.4052 2.4398 2.4749 2.5105 2.5466 2.5831 2.6201 2.6575 2.6954 2.7336 2.7722 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1413 1.1662 1.1927 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1118 -0.1581 -0.2062 -0.2550 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8515 0.8559 0.8631 0.8732 0.8860 0.9014 0.9192 0.9394 0.9618 0.9618 0.9394 0.9192 0.9014 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6964 0.7159 0.7382 0.7632 0.7906 0.8201 0.8515 0.8846 0.9192 0.9552 0.9925 1.0308 1.0700 1.1102 1.1511 1.1927 1.2349 1.2777 1.3210 1.3647 1.4089 1.4534 1.4983 1.5435 1.5890 1.6348 1.6808 1.7270 1.7734 1.8000 1.8000 1.8000 1.8000 1.8007 1.8028 1.8062 1.8111 1.8173 1.8248 1.8337 1.8439 1.8554 1.8682 1.8822 1.8974 1.9138 1.9313 1.9500 1.9698 1.9906 2.0125 2.0353 2.0591 2.0839 2.1095 2.1360 2.1633 2.1915 2.2204 2.2500 2.2804 2.3114 2.3431 2.3754 2.4083 2.4418 2.4759 2.5105 2.5456 2.5812 2.6173 2.6538 2.6907 2.7281 2.7659 2.8040 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.0735 1.0977 1.1236 1.1511 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1118 -0.1581 -0.2062 -0.2550 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9014 0.9055 0.9124 0.9220 0.9341 0.9487 0.9657 0.9849 1.0062 1.0062 0.9849 0.9657 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7826 0.8062 0.8322 0.8602 0.8902 0.9220 0.9552 0.9899 1.0259 1.0630 1.1011 1.1402 1.1800 1.2207 1.2619 1.3038 1.3463 1.3892 1.4327 1.4765 1.5207 1.5652 1.6101 1.6553 1.7007 1.7464 1.7923 1.8385 1.8500 1.8500 1.8500 1.8507 1.8527 1.8561 1.8608 1.8668 1.8742 1.8828 1.8927 1.9039 1.9164 1.9300 1.9449 1.9609 1.9780 1.9962 2.0156 2.0359 2.0573 2.0797 2.1030 2.1272 2.1523 2.1783 2.2051 2.2327 2.2611 2.2902 2.3200 2.3505 2.3817 2.4135 2.4459 2.4789 2.5125 2.5466 2.5812 2.6163 2.6519 2.6879 2.7244 2.7613 2.7987 2.8364 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9849 1.0062 1.0296 1.0548 1.0817 1.1102 1.1402 1.1011 1.0512 1.0012 0.9513 0.9014 0.8515 0.8016 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9513 0.9552 0.9618 0.9708 0.9823 0.9962 1.0124 1.0124 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8746 0.9014 0.9301 0.9605 0.9925 1.0259 1.0607 1.0966 1.1336 1.1715 1.2104 1.2500 1.2903 1.3314 1.3730 1.4151 1.4577 1.5008 1.5443 1.5882 1.6325 1.6771 1.7219 1.7671 1.8125 1.8581 1.9000 1.9000 1.9000 1.9007 1.9026 1.9059 1.9105 1.9164 1.9235 1.9320 1.9416 1.9526 1.9647 1.9780 1.9925 2.0081 2.0248 2.0427 2.0616 2.0815 2.1024 2.1243 2.1471 2.1708 2.1954 2.2209 2.2472 2.2743 2.3022 2.3308 2.3601 2.3901 2.4207 2.4520 2.4839 2.5164 2.5495 2.5831 2.6173 2.6519 2.6870 2.7226 2.7586 2.7951 2.8320 2.8692 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9192 0.9394 0.9618 0.9862 1.0124 1.0404 1.0700 1.1011 1.1045 1.0548 1.0050 0.9552 0.9055 0.8559 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9014 0.9055 0.9124 0.9220 0.9341 0.9487 0.9657 0.9849 1.0062 1.0296 1.0198 1.0112 1.0050 1.0012 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9434 0.9708 1.0000 1.0308 1.0630 1.0966 1.1314 1.1673 1.2042 1.2420 1.2806 1.3200 1.3601 1.4009 1.4422 1.4841 1.5264 1.5692 1.6125 1.6560 1.7000 1.7443 1.7889 1.8337 1.8788 1.9242 1.9500 1.9500 1.9506 1.9526 1.9558 1.9602 1.9660 1.9729 1.9812 1.9906 2.0012 2.0131 2.0261 2.0402 2.0555 2.0718 2.0893 2.1077 2.1272 2.1477 2.1691 2.1915 2.2147 2.2389 2.2638 2.2897 2.3162 2.3436 2.3717 2.4005 2.4300 2.4602 2.4910 2.5224 2.5544 2.5870 2.6201 2.6538 2.6879 2.7226 2.7577 2.7933 2.8293 2.8657 2.9026 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8382 0.8544 0.8732 0.8944 0.9179 0.9434 0.9708 1.0000 1.0308 1.0630 1.0966 1.0607 1.0112 0.9618 0.9124 0.8631 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8515 0.8559 0.8631 0.8732 0.8860 0.9014 0.9192 0.9394 0.9618 0.9862 1.0124 1.0404 1.0548 1.0512 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0404 1.0700 1.1011 1.1336 1.1673 1.2021 1.2379 1.2748 1.3124 1.3509 1.3901 1.4300 1.4705 1.5116 1.5532 1.5953 1.6378 1.6808 1.7241 1.7678 1.8118 1.8561 1.9007 1.9455 1.9906 2.0000 2.0006 2.0025 2.0056 2.0100 2.0156 2.0224 2.0304 2.0396 2.0500 2.0616 2.0742 2.0881 2.1030 2.1190 2.1360 2.1541 2.1731 2.1932 2.2142 2.2361 2.2589 2.2825 2.3071 2.3324 2.3585 2.3854 2.4130 2.4413 2.4703 2.5000 2.5303 2.5612 2.5928 2.6249 2.6575 2.6907 2.7244 2.7586 2.7933 2.8284 2.8640 2.9000 2.9364 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7762 0.7906 0.8078 0.8276 0.8500 0.8746 0.9014 0.9301 0.9605 0.9925 1.0259 1.0607 1.0689 1.0198 0.9708 0.9220 0.8732 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8016 0.8062 0.8139 0.8246 0.8382 0.8544 0.8732 0.8944 0.9179 0.9434 0.9708 1.0000 1.0308 1.0630 1.0966 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1402 1.1715 1.2042 1.2379 1.2728 1.3086 1.3454 1.3829 1.4213 1.4603 1.5000 1.5403 1.5811 1.6225 1.6643 1.7066 1.7493 1.7923 1.8358 1.8795 1.9235 1.9679 2.0125 2.0500 2.0506 2.0524 2.0555 2.0597 2.0652 2.0718 2.0797 2.0887 2.0988 2.1101 2.1225 2.1360 2.1506 2.1662 2.1829 2.2006 2.2192 2.2389 2.2594 2.2809 2.3033 2.3265 2.3505 2.3754 2.4010 2.4274 2.4546 2.4824 2.5110 2.5402 2.5700 2.6005 2.6315 2.6632 2.6954 2.7281 2.7613 2.7951 2.8293 2.8640 2.8991 2.9347 2.9707 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8602 0.8902 0.9220 0.9552 0.9899 1.0259 1.0630 1.0308 0.9823 0.9341 0.8860 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8078 0.8276 0.8500 0.8746 0.9014 0.9301 0.9605 0.9925 1.0259 1.0607 1.0966 1.1336 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2420 1.2748 1.3086 1.3435 1.3793 1.4160 1.4534 1.4916 1.5305 1.5700 1.6101 1.6508 1.6919 1.7335 1.7755 1.8180 1.8608 1.9039 1.9474 1.9912 2.0353 2.0797 2.1006 2.1024 2.1054 2.1095 2.1148 2.1213 2.1290 2.1378 2.1477 2.1587 2.1708 2.1840 2.1983 2.2136 2.2299 2.2472 2.2655 2.2847 2.3049 2.3259 2.3479 2.3707 2.3943 2.4187 2.4439 2.4698 2.4965 2.5239 2.5520 2.5807 2.6101 2.6401 2.6707 2.7019 2.7336 2.7659 2.7987 2.8320 2.8657 2.9000 2.9347 2.9698 3.0054 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.8201 0.8515 0.8846 0.9192 0.9552 0.9925 1.0308 1.0440 0.9962 0.9487 0.9014 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8602 0.8902 0.9220 0.9552 0.9899 1.0259 1.0630 1.1011 1.1402 1.1800 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3454 1.3793 1.4142 1.4500 1.4866 1.5240 1.5620 1.6008 1.6401 1.6800 1.7205 1.7614 1.8028 1.8446 1.8868 1.9294 1.9723 2.0156 2.0591 2.1030 2.1471 2.1523 2.1552 2.1593 2.1645 2.1708 2.1783 2.1869 2.1966 2.2074 2.2192 2.2322 2.2461 2.2611 2.2771 2.2940 2.3119 2.3308 2.3505 2.3712 2.3927 2.4151 2.4382 2.4622 2.4870 2.5125 2.5387 2.5656 2.5933 2.6215 2.6505 2.6800 2.7102 2.7409 2.7722 2.8040 2.8364 2.8692 2.9026 2.9364 2.9707 3.0054 3.0406 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7810 0.8139 0.8485 0.8846 0.9220 0.9605 1.0000 1.0404 1.0124 0.9657 0.9192 0.8732 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.8201 0.8515 0.8846 0.9192 0.9552 0.9925 1.0308 1.0700 1.1102 1.1511 1.1927 1.2349 1.2500 1.2500 1.2500 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.4849 1.5207 1.5572 1.5945 1.6325 1.6711 1.7103 1.7500 1.7903 1.8310 1.8722 1.9138 1.9558 1.9981 2.0408 2.0839 2.1272 2.1708 2.2023 2.2051 2.2091 2.2142 2.2204 2.2277 2.2361 2.2456 2.2561 2.2677 2.2804 2.2940 2.3087 2.3243 2.3409 2.3585 2.3770 2.3964 2.4166 2.4377 2.4597 2.4824 2.5060 2.5303 2.5554 2.5812 2.6077 2.6349 2.6627 2.6912 2.7203 2.7500 2.7803 2.8111 2.8425 2.8745 2.9069 2.9398 2.9732 3.0071 3.0414 3.0761 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7778 0.8139 0.8515 0.8902 0.9301 0.9708 1.0124 1.0308 0.9849 0.9394 0.8944 0.8500 0.8062 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7810 0.8139 0.8485 0.8846 0.9220 0.9605 1.0000 1.0404 1.0817 1.1236 1.1662 1.2093 1.2530 1.2971 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.5914 1.6279 1.6651 1.7029 1.7414 1.7804 1.8200 1.8601 1.9007 1.9416 1.9831 2.0248 2.0670 2.1095 2.1523 2.1954 2.2389 2.2550 2.2589 2.2638 2.2699 2.2771 2.2853 2.2946 2.3049 2.3162 2.3286 2.3420 2.3564 2.3717 2.3880 2.4052 2.4233 2.4423 2.4622 2.4829 2.5045 2.5269 2.5500 2.5739 2.5986 2.6239 2.6500 2.6768 2.7042 2.7322 2.7609 2.7902 2.8200 2.8504 2.8814 2.9129 2.9449 2.9774 3.0104 3.0438 3.0777 3.1121 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8602 0.9014 0.9434 0.9862 1.0296 1.0062 0.9618 0.9179 0.8746 0.8322 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7778 0.8139 0.8515 0.8902 0.9301 0.9708 1.0124 1.0548 1.0977 1.1413 1.1853 1.2298 1.2748 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.6985 1.7357 1.7734 1.8118 1.8507 1.8901 1.9300 1.9704 2.0112 2.0524 2.0940 2.1360 2.1783 2.2209 2.2638 2.3049 2.3087 2.3135 2.3195 2.3265 2.3345 2.3436 2.3537 2.3648 2.3770 2.3901 2.4042 2.4192 2.4352 2.4520 2.4698 2.4885 2.5080 2.5283 2.5495 2.5715 2.5942 2.6177 2.6420 2.6669 2.6926 2.7189 2.7459 2.7735 2.8018 2.8306 2.8601 2.8901 2.9206 2.9517 2.9833 3.0154 3.0480 3.0810 3.1145 3.1484 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8322 0.8746 0.9179 0.9618 1.0062 1.0296 0.9862 0.9434 0.9014 0.8602 0.8201 0.7810 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8602 0.9014 0.9434 0.9862 1.0296 1.0735 1.1180 1.1630 1.2083 1.2540 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.5914 1.6279 1.6651 1.7029 1.7414 1.7804 1.8200 1.8601 1.9007 1.9416 1.9831 2.0248 2.0670 2.1095 2.1523 2.1954 2.2389 2.2825 2.3265 2.3633 2.3691 2.3759 2.3838 2.3927 2.4026 2.4135 2.4254 2.4382 2.4520 2.4668 2.4824 2.4990 2.5164 2.5348 2.5539 2.5739 2.5947 2.6163 2.6387 2.6618 2.6856 2.7102 2.7354 2.7613 2.7879 2.8151 2.8430 2.8714 2.9004 2.9300 2.9602 2.9908 3.0220 3.0537 3.0859 3.1185 3.1516 3.1851 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8944 0.9394 0.9849 1.0308 1.0124 0.9708 0.9301 0.8902 0.8515 0.8139 0.7778 0.7433 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8322 0.8746 0.9179 0.9618 1.0062 1.0512 1.0966 1.1424 1.1885 1.2349 1.2816 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.4849 1.5207 1.5572 1.5945 1.6325 1.6711 1.7103 1.7500 1.7903 1.8310 1.8722 1.9138 1.9558 1.9981 2.0408 2.0839 2.1272 2.1708 2.2147 2.2589 2.3033 2.3479 2.3927 2.4254 2.4331 2.4418 2.4515 2.4622 2.4739 2.4865 2.5000 2.5145 2.5298 2.5461 2.5632 2.5812 2.6000 2.6196 2.6401 2.6613 2.6833 2.7060 2.7295 2.7536 2.7785 2.8040 2.8302 2.8570 2.8844 2.9125 2.9411 2.9703 3.0000 3.0303 3.0610 3.0923 3.1241 3.1563 3.1890 3.2222 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8732 0.9192 0.9657 1.0124 1.0404 1.0000 0.9605 0.9220 0.8846 0.8485 0.8139 0.7810 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8944 0.9394 0.9849 1.0308 1.0770 1.1236 1.1705 1.2176 1.2619 1.2349 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3454 1.3793 1.4142 1.4500 1.4866 1.5240 1.5620 1.6008 1.6401 1.6800 1.7205 1.7614 1.8028 1.8446 1.8868 1.9294 1.9723 2.0156 2.0591 2.1030 2.1471 2.1915 2.2361 2.2809 2.3259 2.3712 2.4166 2.4622 2.4910 2.5005 2.5110 2.5224 2.5348 2.5480 2.5622 2.5773 2.5933 2.6101 2.6277 2.6462 2.6655 2.6856 2.7065 2.7281 2.7505 2.7735 2.7973 2.8218 2.8469 2.8727 2.8991 2.9262 2.9538 2.9820 3.0108 3.0401 3.0700 3.1004 3.1313 3.1627 3.1945 3.2268 3.2596 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9487 0.9962 1.0440 1.0308 0.9925 0.9552 0.9192 0.8846 0.8515 0.8201 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8732 0.9192 0.9657 1.0124 1.0595 1.1068 1.1543 1.2021 1.2207 1.1927 1.1662 1.1413 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2420 1.2748 1.3086 1.3435 1.3793 1.4160 1.4534 1.4916 1.5305 1.5700 1.6101 1.6508 1.6919 1.7335 1.7755 1.8180 1.8608 1.9039 1.9474 1.9912 2.0353 2.0797 2.1243 2.1691 2.2142 2.2594 2.3049 2.3505 2.3964 2.4423 2.4885 2.5005 2.5110 2.5224 2.5348 2.5480 2.5622 2.5773 2.5933 2.6101 2.6277 2.6462 2.6655 2.6856 2.7065 2.7281 2.7505 2.7731 2.7951 2.8178 2.8412 2.8653 2.8901 2.9155 2.9415 2.9682 2.9954 3.0232 3.0516 3.0806 3.1101 3.1401 3.1706 3.2016 3.2330 +1.3000 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9341 0.9823 1.0308 1.0630 1.0259 0.9899 0.9552 0.9220 0.8902 0.8602 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9487 0.9962 1.0440 1.0920 1.1402 1.1885 1.1800 1.1511 1.1236 1.0977 1.0735 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1402 1.1715 1.2042 1.2379 1.2728 1.3086 1.3454 1.3829 1.4213 1.4603 1.5000 1.5403 1.5811 1.6225 1.6643 1.7066 1.7493 1.7923 1.8358 1.8795 1.9235 1.9679 2.0125 2.0573 2.1024 2.1477 2.1932 2.2389 2.2847 2.3308 2.3770 2.4233 2.4418 2.4515 2.4622 2.4739 2.4865 2.5000 2.5145 2.5298 2.5461 2.5632 2.5812 2.6000 2.6196 2.6401 2.6613 2.6833 2.7060 2.7281 2.7505 2.7735 2.7973 2.8218 2.8469 2.8727 2.8991 2.9262 2.9538 2.9820 3.0108 3.0401 3.0700 3.1004 3.1313 3.1627 3.1945 +1.2500 1.2500 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9220 0.9708 1.0198 1.0689 1.0607 1.0259 0.9925 0.9605 0.9301 0.9014 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9341 0.9823 1.0308 1.0794 1.1281 1.1715 1.1402 1.1102 1.0817 1.0548 1.0296 1.0062 0.9849 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0404 1.0700 1.1011 1.1336 1.1673 1.2021 1.2379 1.2748 1.3124 1.3509 1.3901 1.4300 1.4705 1.5116 1.5532 1.5953 1.6378 1.6808 1.7241 1.7678 1.8118 1.8561 1.9007 1.9455 1.9906 2.0359 2.0815 2.1272 2.1731 2.2192 2.2655 2.3119 2.3585 2.3838 2.3927 2.4026 2.4135 2.4254 2.4382 2.4520 2.4668 2.4824 2.4990 2.5164 2.5348 2.5539 2.5739 2.5947 2.6163 2.6387 2.6613 2.6833 2.7060 2.7295 2.7536 2.7785 2.8040 2.8302 2.8570 2.8844 2.9125 2.9411 2.9703 3.0000 3.0303 3.0610 3.0923 3.1241 3.1563 +1.2000 1.2000 1.2000 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9618 1.0112 1.0607 1.0966 1.0630 1.0308 1.0000 0.9708 0.9434 0.9179 0.8944 0.8732 0.8544 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9220 0.9708 1.0198 1.0689 1.1180 1.1336 1.1011 1.0700 1.0404 1.0124 0.9862 0.9618 0.9394 0.9192 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9434 0.9708 1.0000 1.0308 1.0630 1.0966 1.1314 1.1673 1.2042 1.2420 1.2806 1.3200 1.3601 1.4009 1.4422 1.4841 1.5264 1.5692 1.6125 1.6560 1.7000 1.7443 1.7889 1.8337 1.8788 1.9242 1.9698 2.0156 2.0616 2.1077 2.1541 2.2006 2.2472 2.2940 2.3265 2.3345 2.3436 2.3537 2.3648 2.3770 2.3901 2.4042 2.4192 2.4352 2.4520 2.4698 2.4885 2.5080 2.5283 2.5495 2.5715 2.5942 2.6163 2.6387 2.6618 2.6856 2.7102 2.7354 2.7613 2.7879 2.8151 2.8430 2.8714 2.9004 2.9300 2.9602 2.9908 3.0220 3.0537 3.0859 3.1185 +1.1500 1.1500 1.1500 1.1500 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9552 1.0050 1.0548 1.1045 1.1011 1.0700 1.0404 1.0124 0.9862 0.9618 0.9394 0.9192 0.9014 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9618 1.0112 1.0607 1.1102 1.0966 1.0630 1.0308 1.0000 0.9708 0.9434 0.9179 0.8944 0.8732 0.8544 0.8382 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8746 0.9014 0.9301 0.9605 0.9925 1.0259 1.0607 1.0966 1.1336 1.1715 1.2104 1.2500 1.2903 1.3314 1.3730 1.4151 1.4577 1.5008 1.5443 1.5882 1.6325 1.6771 1.7219 1.7671 1.8125 1.8581 1.9039 1.9500 1.9962 2.0427 2.0893 2.1360 2.1829 2.2299 2.2699 2.2771 2.2853 2.2946 2.3049 2.3162 2.3286 2.3420 2.3564 2.3717 2.3880 2.4052 2.4233 2.4423 2.4622 2.4829 2.5045 2.5269 2.5495 2.5715 2.5942 2.6177 2.6420 2.6669 2.6926 2.7189 2.7459 2.7735 2.8018 2.8306 2.8601 2.8901 2.9206 2.9517 2.9833 3.0154 3.0480 3.0810 +1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9513 1.0012 1.0512 1.1011 1.1402 1.1102 1.0817 1.0548 1.0296 1.0062 0.9849 0.9657 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9552 1.0050 1.0548 1.0966 1.0607 1.0259 0.9925 0.9605 0.9301 0.9014 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7826 0.8062 0.8322 0.8602 0.8902 0.9220 0.9552 0.9899 1.0259 1.0630 1.1011 1.1402 1.1800 1.2207 1.2619 1.3038 1.3463 1.3892 1.4327 1.4765 1.5207 1.5652 1.6101 1.6553 1.7007 1.7464 1.7923 1.8385 1.8848 1.9313 1.9780 2.0248 2.0718 2.1190 2.1662 2.2136 2.2204 2.2277 2.2361 2.2456 2.2561 2.2677 2.2804 2.2940 2.3087 2.3243 2.3409 2.3585 2.3770 2.3964 2.4166 2.4377 2.4597 2.4824 2.5045 2.5269 2.5500 2.5739 2.5986 2.6239 2.6500 2.6768 2.7042 2.7322 2.7609 2.7902 2.8200 2.8504 2.8814 2.9129 2.9449 2.9774 3.0104 3.0438 +1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.1511 1.1236 1.0977 1.0735 1.0512 1.0308 1.0124 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9513 1.0012 1.0512 1.0630 1.0259 0.9899 0.9552 0.9220 0.8902 0.8602 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6964 0.7159 0.7382 0.7632 0.7906 0.8201 0.8515 0.8846 0.9192 0.9552 0.9925 1.0308 1.0700 1.1102 1.1511 1.1927 1.2349 1.2777 1.3210 1.3647 1.4089 1.4534 1.4983 1.5435 1.5890 1.6348 1.6808 1.7270 1.7734 1.8200 1.8668 1.9138 1.9609 2.0081 2.0555 2.1030 2.1506 2.1645 2.1708 2.1783 2.1869 2.1966 2.2074 2.2192 2.2322 2.2461 2.2611 2.2771 2.2940 2.3119 2.3308 2.3505 2.3712 2.3927 2.4151 2.4377 2.4597 2.4824 2.5060 2.5303 2.5554 2.5812 2.6077 2.6349 2.6627 2.6912 2.7203 2.7500 2.7803 2.8111 2.8425 2.8745 2.9069 2.9398 2.9732 3.0071 +1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.1927 1.1662 1.1413 1.1180 1.0966 1.0770 1.0595 1.0440 1.0308 1.0198 1.0112 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2550 -0.2062 -0.1581 -0.1118 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.0308 0.9925 0.9552 0.9192 0.8846 0.8515 0.8201 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7810 0.8139 0.8485 0.8846 0.9220 0.9605 1.0000 1.0404 1.0817 1.1236 1.1662 1.2093 1.2530 1.2971 1.3416 1.3865 1.4318 1.4773 1.5232 1.5692 1.6155 1.6621 1.7088 1.7557 1.8028 1.8500 1.8974 1.9449 1.9925 2.0402 2.0881 2.1095 2.1148 2.1213 2.1290 2.1378 2.1477 2.1587 2.1708 2.1840 2.1983 2.2136 2.2299 2.2472 2.2655 2.2847 2.3049 2.3259 2.3479 2.3707 2.3927 2.4151 2.4382 2.4622 2.4870 2.5125 2.5387 2.5656 2.5933 2.6215 2.6505 2.6800 2.7102 2.7409 2.7722 2.8040 2.8364 2.8692 2.9026 2.9364 2.9707 +0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2042 1.1715 1.1402 1.1102 1.0817 1.0548 1.0296 1.0062 0.9849 0.9657 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0404 1.0000 0.9605 0.9220 0.8846 0.8485 0.8139 0.7810 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7778 0.8139 0.8515 0.8902 0.9301 0.9708 1.0124 1.0548 1.0977 1.1413 1.1853 1.2298 1.2748 1.3200 1.3657 1.4116 1.4577 1.5042 1.5508 1.5977 1.6447 1.6919 1.7393 1.7868 1.8344 1.8822 1.9300 1.9780 2.0261 2.0555 2.0597 2.0652 2.0718 2.0797 2.0887 2.0988 2.1101 2.1225 2.1360 2.1506 2.1662 2.1829 2.2006 2.2192 2.2389 2.2594 2.2809 2.3033 2.3259 2.3479 2.3707 2.3943 2.4187 2.4439 2.4698 2.4965 2.5239 2.5520 2.5807 2.6101 2.6401 2.6707 2.7019 2.7336 2.7659 2.7987 2.8320 2.8657 2.9000 2.9347 +0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.1673 1.1336 1.1011 1.0700 1.0404 1.0124 0.9862 0.9618 0.9394 0.9192 0.9014 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0124 0.9708 0.9301 0.8902 0.8515 0.8139 0.7778 0.7433 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8602 0.9014 0.9434 0.9862 1.0296 1.0735 1.1180 1.1630 1.2083 1.2540 1.3000 1.3463 1.3928 1.4396 1.4866 1.5338 1.5811 1.6286 1.6763 1.7241 1.7720 1.8200 1.8682 1.9164 1.9647 2.0025 2.0056 2.0100 2.0156 2.0224 2.0304 2.0396 2.0500 2.0616 2.0742 2.0881 2.1030 2.1190 2.1360 2.1541 2.1731 2.1932 2.2142 2.2361 2.2589 2.2809 2.3033 2.3265 2.3505 2.3754 2.4010 2.4274 2.4546 2.4824 2.5110 2.5402 2.5700 2.6005 2.6315 2.6632 2.6954 2.7281 2.7613 2.7951 2.8293 2.8640 2.8991 +0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9513 1.0012 1.0512 1.1011 1.1511 1.1673 1.1314 1.0966 1.0630 1.0308 1.0000 0.9708 0.9434 0.9179 0.8944 0.8732 0.8544 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 0.9862 0.9434 0.9014 0.8602 0.8201 0.7810 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8322 0.8746 0.9179 0.9618 1.0062 1.0512 1.0966 1.1424 1.1885 1.2349 1.2816 1.3285 1.3757 1.4230 1.4705 1.5182 1.5660 1.6140 1.6621 1.7103 1.7586 1.8069 1.8554 1.9039 1.9506 1.9526 1.9558 1.9602 1.9660 1.9729 1.9812 1.9906 2.0012 2.0131 2.0261 2.0402 2.0555 2.0718 2.0893 2.1077 2.1272 2.1477 2.1691 2.1915 2.2142 2.2361 2.2589 2.2825 2.3071 2.3324 2.3585 2.3854 2.4130 2.4413 2.4703 2.5000 2.5303 2.5612 2.5928 2.6249 2.6575 2.6907 2.7244 2.7586 2.7933 2.8284 2.8640 +0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9552 1.0050 1.0548 1.1045 1.1543 1.1336 1.0966 1.0607 1.0259 0.9925 0.9605 0.9301 0.9014 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1581 0.1118 0.0707 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9513 1.0012 0.9618 0.9179 0.8746 0.8322 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8944 0.9394 0.9849 1.0308 1.0770 1.1236 1.1705 1.2176 1.2649 1.3124 1.3601 1.4080 1.4560 1.5042 1.5524 1.6008 1.6492 1.6978 1.7464 1.7951 1.8439 1.8927 1.9007 1.9026 1.9059 1.9105 1.9164 1.9235 1.9320 1.9416 1.9526 1.9647 1.9780 1.9925 2.0081 2.0248 2.0427 2.0616 2.0815 2.1024 2.1243 2.1471 2.1691 2.1915 2.2147 2.2389 2.2638 2.2897 2.3162 2.3436 2.3717 2.4005 2.4300 2.4602 2.4910 2.5224 2.5544 2.5870 2.6201 2.6538 2.6879 2.7226 2.7577 2.7933 2.8293 +0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9618 1.0112 1.0607 1.1102 1.1402 1.1011 1.0630 1.0259 0.9899 0.9552 0.9220 0.8902 0.8602 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2236 0.1803 0.1414 0.1118 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9552 0.9849 0.9394 0.8944 0.8500 0.8062 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8732 0.9192 0.9657 1.0124 1.0595 1.1068 1.1543 1.2021 1.2500 1.2981 1.3463 1.3946 1.4431 1.4916 1.5403 1.5890 1.6378 1.6867 1.7357 1.7847 1.8337 1.8500 1.8507 1.8527 1.8561 1.8608 1.8668 1.8742 1.8828 1.8927 1.9039 1.9164 1.9300 1.9449 1.9609 1.9780 1.9962 2.0156 2.0359 2.0573 2.0797 2.1024 2.1243 2.1471 2.1708 2.1954 2.2209 2.2472 2.2743 2.3022 2.3308 2.3601 2.3901 2.4207 2.4520 2.4839 2.5164 2.5495 2.5831 2.6173 2.6519 2.6870 2.7226 2.7586 2.7951 +0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9220 0.9708 1.0198 1.0689 1.1180 1.1102 1.0700 1.0308 0.9925 0.9552 0.9192 0.8846 0.8515 0.8201 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9618 0.9657 0.9192 0.8732 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9487 0.9962 1.0440 1.0920 1.1402 1.1885 1.2369 1.2855 1.3342 1.3829 1.4318 1.4807 1.5297 1.5788 1.6279 1.6771 1.7263 1.7755 1.8000 1.8000 1.8007 1.8028 1.8062 1.8111 1.8173 1.8248 1.8337 1.8439 1.8554 1.8682 1.8822 1.8974 1.9138 1.9313 1.9500 1.9698 1.9906 2.0125 2.0353 2.0573 2.0797 2.1030 2.1272 2.1523 2.1783 2.2051 2.2327 2.2611 2.2902 2.3200 2.3505 2.3817 2.4135 2.4459 2.4789 2.5125 2.5466 2.5812 2.6163 2.6519 2.6879 2.7244 2.7613 +0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9341 0.9823 1.0308 1.0794 1.1236 1.0817 1.0404 1.0000 0.9605 0.9220 0.8846 0.8485 0.8139 0.7810 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9220 0.9708 0.9487 0.9014 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9341 0.9823 1.0308 1.0794 1.1281 1.1769 1.2258 1.2748 1.3238 1.3730 1.4221 1.4714 1.5207 1.5700 1.6194 1.6688 1.7183 1.7507 1.7500 1.7500 1.7507 1.7529 1.7564 1.7614 1.7678 1.7755 1.7847 1.7951 1.8069 1.8200 1.8344 1.8500 1.8668 1.8848 1.9039 1.9242 1.9455 1.9679 1.9906 2.0125 2.0353 2.0591 2.0839 2.1095 2.1360 2.1633 2.1915 2.2204 2.2500 2.2804 2.3114 2.3431 2.3754 2.4083 2.4418 2.4759 2.5105 2.5456 2.5812 2.6173 2.6538 2.6907 2.7281 +0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9487 0.9962 1.0440 1.0920 1.0977 1.0548 1.0124 0.9708 0.9301 0.8902 0.8515 0.8139 0.7778 0.7433 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9341 0.9823 0.9341 0.8860 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9220 0.9708 1.0198 1.0689 1.1180 1.1673 1.2166 1.2659 1.3153 1.3647 1.4142 1.4637 1.5133 1.5628 1.6125 1.6621 1.7029 1.7007 1.7000 1.7000 1.7007 1.7029 1.7066 1.7117 1.7183 1.7263 1.7357 1.7464 1.7586 1.7720 1.7868 1.8028 1.8200 1.8385 1.8581 1.8788 1.9007 1.9235 1.9455 1.9679 1.9912 2.0156 2.0408 2.0670 2.0940 2.1219 2.1506 2.1800 2.2102 2.2411 2.2727 2.3049 2.3377 2.3712 2.4052 2.4398 2.4749 2.5105 2.5466 2.5831 2.6201 2.6575 2.6954 +0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8732 0.9192 0.9657 1.0124 1.0595 1.1068 1.0735 1.0296 0.9862 0.9434 0.9014 0.8602 0.8201 0.7810 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9487 0.9708 0.9220 0.8732 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9618 1.0112 1.0607 1.1102 1.1597 1.2093 1.2590 1.3086 1.3583 1.4080 1.4577 1.5075 1.5572 1.6070 1.6568 1.6530 1.6508 1.6500 1.6500 1.6508 1.6530 1.6568 1.6621 1.6688 1.6771 1.6867 1.6978 1.7103 1.7241 1.7393 1.7557 1.7734 1.7923 1.8125 1.8337 1.8561 1.8788 1.9007 1.9235 1.9474 1.9723 1.9981 2.0248 2.0524 2.0809 2.1101 2.1401 2.1708 2.2023 2.2344 2.2672 2.3005 2.3345 2.3691 2.4042 2.4398 2.4759 2.5125 2.5495 2.5870 2.6249 2.6632 +0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8944 0.9394 0.9849 1.0308 1.0770 1.0966 1.0512 1.0062 0.9618 0.9179 0.8746 0.8322 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9487 0.9618 0.9124 0.8631 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9552 1.0050 1.0548 1.1045 1.1543 1.2042 1.2540 1.3038 1.3537 1.4036 1.4534 1.5033 1.5532 1.6031 1.6070 1.6031 1.6008 1.6000 1.6000 1.6008 1.6031 1.6070 1.6125 1.6194 1.6279 1.6378 1.6492 1.6621 1.6763 1.6919 1.7088 1.7270 1.7464 1.7671 1.7889 1.8118 1.8337 1.8561 1.8795 1.9039 1.9294 1.9558 1.9831 2.0112 2.0402 2.0700 2.1006 2.1319 2.1639 2.1966 2.2299 2.2638 2.2984 2.3335 2.3691 2.4052 2.4418 2.4789 2.5164 2.5544 2.5928 2.6315 +0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8322 0.8746 0.9179 0.9618 1.0062 1.0512 1.0966 1.0770 1.0308 0.9849 0.9394 0.8944 0.8500 0.8062 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9341 0.9552 0.9055 0.8559 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9513 1.0012 1.0512 1.1011 1.1511 1.2010 1.2510 1.3010 1.3509 1.4009 1.4509 1.5008 1.5508 1.5628 1.5572 1.5532 1.5508 1.5500 1.5500 1.5508 1.5532 1.5572 1.5628 1.5700 1.5788 1.5890 1.6008 1.6140 1.6286 1.6447 1.6621 1.6808 1.7007 1.7219 1.7443 1.7671 1.7889 1.8118 1.8358 1.8608 1.8868 1.9138 1.9416 1.9704 2.0000 2.0304 2.0616 2.0934 2.1260 2.1593 2.1932 2.2277 2.2627 2.2984 2.3345 2.3712 2.4083 2.4459 2.4839 2.5224 2.5612 2.6005 +0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8602 0.9014 0.9434 0.9862 1.0296 1.0735 1.1068 1.0595 1.0124 0.9657 0.9192 0.8732 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9220 0.9513 0.9014 0.8515 0.8016 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5207 1.5133 1.5075 1.5033 1.5008 1.5000 1.5000 1.5008 1.5033 1.5075 1.5133 1.5207 1.5297 1.5403 1.5524 1.5660 1.5811 1.5977 1.6155 1.6348 1.6553 1.6771 1.7000 1.7219 1.7443 1.7678 1.7923 1.8180 1.8446 1.8722 1.9007 1.9300 1.9602 1.9912 2.0230 2.0555 2.0887 2.1225 2.1570 2.1920 2.2277 2.2638 2.3005 2.3377 2.3754 2.4135 2.4520 2.4910 2.5303 2.5700 +0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7778 0.8139 0.8515 0.8902 0.9301 0.9708 1.0124 1.0548 1.0977 1.0920 1.0440 0.9962 0.9487 0.9014 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1000 -0.0707 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.4807 1.4714 1.4637 1.4577 1.4534 1.4509 1.4500 1.4500 1.4509 1.4534 1.4577 1.4637 1.4714 1.4807 1.4916 1.5042 1.5182 1.5338 1.5508 1.5692 1.5890 1.6101 1.6325 1.6553 1.6771 1.7000 1.7241 1.7493 1.7755 1.8028 1.8310 1.8601 1.8901 1.9209 1.9526 1.9849 2.0180 2.0518 2.0863 2.1213 2.1570 2.1932 2.2299 2.2672 2.3049 2.3431 2.3817 2.4207 2.4602 2.5000 2.5402 +0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7810 0.8139 0.8485 0.8846 0.9220 0.9605 1.0000 1.0404 1.0817 1.1236 1.0794 1.0308 0.9823 0.9341 0.8860 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.2510 1.2010 1.1511 1.1011 1.0512 1.0012 0.9513 0.9014 0.8515 0.8016 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9513 1.0012 1.0512 1.1011 1.1511 1.2010 1.2510 1.3010 1.3509 1.4009 1.4431 1.4318 1.4221 1.4142 1.4080 1.4036 1.4009 1.4000 1.4000 1.4009 1.4036 1.4080 1.4142 1.4221 1.4318 1.4431 1.4560 1.4705 1.4866 1.5042 1.5232 1.5435 1.5652 1.5882 1.6101 1.6325 1.6560 1.6808 1.7066 1.7335 1.7614 1.7903 1.8200 1.8507 1.8822 1.9144 1.9474 1.9812 2.0156 2.0506 2.0863 2.1225 2.1593 2.1966 2.2344 2.2727 2.3114 2.3505 2.3901 2.4300 2.4703 2.5110 +0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.8201 0.8515 0.8846 0.9192 0.9552 0.9925 1.0308 1.0700 1.1102 1.1180 1.0689 1.0198 0.9708 0.9220 0.8732 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3038 1.2540 1.2042 1.1543 1.1045 1.0548 1.0050 0.9552 0.9055 0.8559 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9552 1.0050 1.0548 1.1045 1.1543 1.2042 1.2540 1.3038 1.3537 1.4036 1.3946 1.3829 1.3730 1.3647 1.3583 1.3537 1.3509 1.3500 1.3500 1.3509 1.3537 1.3583 1.3647 1.3730 1.3829 1.3946 1.4080 1.4230 1.4396 1.4577 1.4773 1.4983 1.5207 1.5435 1.5652 1.5882 1.6125 1.6378 1.6643 1.6919 1.7205 1.7500 1.7804 1.8118 1.8439 1.8768 1.9105 1.9449 1.9799 2.0156 2.0518 2.0887 2.1260 2.1639 2.2023 2.2411 2.2804 2.3200 2.3601 2.4005 2.4413 2.4824 +0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8602 0.8902 0.9220 0.9552 0.9899 1.0259 1.0630 1.1011 1.1402 1.1102 1.0607 1.0112 0.9618 0.9124 0.8631 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9014 0.8515 0.8016 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.3583 1.3086 1.2590 1.2093 1.1597 1.1102 1.0607 1.0112 0.9618 0.9124 0.8631 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1118 0.0707 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9618 1.0112 1.0607 1.1102 1.1597 1.2093 1.2590 1.3086 1.3583 1.3601 1.3463 1.3342 1.3238 1.3153 1.3086 1.3038 1.3010 1.3000 1.3000 1.3010 1.3038 1.3086 1.3153 1.3238 1.3342 1.3463 1.3601 1.3757 1.3928 1.4116 1.4318 1.4534 1.4765 1.4983 1.5207 1.5443 1.5692 1.5953 1.6225 1.6508 1.6800 1.7103 1.7414 1.7734 1.8062 1.8398 1.8742 1.9092 1.9449 1.9812 2.0180 2.0555 2.0934 2.1319 2.1708 2.2102 2.2500 2.2902 2.3308 2.3717 2.4130 2.4546 +0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7762 0.7906 0.8078 0.8276 0.8500 0.8746 0.9014 0.9301 0.9605 0.9925 1.0259 1.0607 1.0966 1.1336 1.1543 1.1045 1.0548 1.0050 0.9552 0.9055 0.8559 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9055 0.8559 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4142 1.3647 1.3153 1.2659 1.2166 1.1673 1.1180 1.0689 1.0198 0.9708 0.9220 0.8732 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9220 0.9708 1.0198 1.0689 1.1180 1.1673 1.2166 1.2659 1.3153 1.3285 1.3124 1.2981 1.2855 1.2748 1.2659 1.2590 1.2540 1.2510 1.2500 1.2500 1.2510 1.2540 1.2590 1.2659 1.2748 1.2855 1.2981 1.3124 1.3285 1.3463 1.3657 1.3865 1.4089 1.4318 1.4534 1.4765 1.5008 1.5264 1.5532 1.5811 1.6101 1.6401 1.6711 1.7029 1.7357 1.7692 1.8035 1.8385 1.8742 1.9105 1.9474 1.9849 2.0230 2.0616 2.1006 2.1401 2.1800 2.2204 2.2611 2.3022 2.3436 2.3854 2.4274 +0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8382 0.8544 0.8732 0.8944 0.9179 0.9434 0.9708 1.0000 1.0308 1.0630 1.0966 1.1314 1.1673 1.1511 1.1011 1.0512 1.0012 0.9513 0.9014 0.8515 0.8016 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9124 0.8631 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.4714 1.4221 1.3730 1.3238 1.2748 1.2258 1.1769 1.1281 1.0794 1.0308 0.9823 0.9341 0.8860 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9341 0.9823 1.0308 1.0794 1.1281 1.1769 1.2258 1.2748 1.3000 1.2816 1.2649 1.2500 1.2369 1.2258 1.2166 1.2093 1.2042 1.2010 1.2000 1.2000 1.2010 1.2042 1.2093 1.2166 1.2258 1.2369 1.2500 1.2649 1.2816 1.3000 1.3200 1.3416 1.3647 1.3865 1.4089 1.4327 1.4577 1.4841 1.5116 1.5403 1.5700 1.6008 1.6325 1.6651 1.6985 1.7328 1.7678 1.8035 1.8398 1.8768 1.9144 1.9526 1.9912 2.0304 2.0700 2.1101 2.1506 2.1915 2.2327 2.2743 2.3162 2.3585 2.4010 +0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9192 0.9394 0.9618 0.9862 1.0124 1.0404 1.0700 1.1011 1.1336 1.1673 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1118 -0.1581 -0.2062 -0.2550 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9220 0.8732 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5297 1.4807 1.4318 1.3829 1.3342 1.2855 1.2369 1.1885 1.1402 1.0920 1.0440 0.9962 0.9487 0.9014 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9487 0.9962 1.0440 1.0920 1.1402 1.1885 1.2369 1.2748 1.2540 1.2349 1.2176 1.2021 1.1885 1.1769 1.1673 1.1597 1.1543 1.1511 1.1500 1.1500 1.1511 1.1543 1.1597 1.1673 1.1769 1.1885 1.2021 1.2176 1.2349 1.2540 1.2748 1.2971 1.3200 1.3416 1.3647 1.3892 1.4151 1.4422 1.4705 1.5000 1.5305 1.5620 1.5945 1.6279 1.6621 1.6971 1.7328 1.7692 1.8062 1.8439 1.8822 1.9209 1.9602 2.0000 2.0402 2.0809 2.1219 2.1633 2.2051 2.2472 2.2897 2.3324 2.3754 +-0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9849 1.0062 1.0296 1.0548 1.0817 1.1102 1.1402 1.1715 1.2042 1.2010 1.1511 1.1011 1.0512 1.0012 0.9513 0.9014 0.8515 0.8016 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9341 0.8860 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.5890 1.5403 1.4916 1.4431 1.3946 1.3463 1.2981 1.2500 1.2021 1.1543 1.1068 1.0595 1.0124 0.9657 0.9192 0.8732 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8732 0.9192 0.9657 1.0124 1.0595 1.1068 1.1543 1.2021 1.2500 1.2298 1.2083 1.1885 1.1705 1.1543 1.1402 1.1281 1.1180 1.1102 1.1045 1.1011 1.1000 1.1000 1.1011 1.1045 1.1102 1.1180 1.1281 1.1402 1.1543 1.1705 1.1885 1.2083 1.2298 1.2530 1.2748 1.2971 1.3210 1.3463 1.3730 1.4009 1.4300 1.4603 1.4916 1.5240 1.5572 1.5914 1.6263 1.6621 1.6985 1.7357 1.7734 1.8118 1.8507 1.8901 1.9300 1.9704 2.0112 2.0524 2.0940 2.1360 2.1783 2.2209 2.2638 2.3071 2.3505 +-0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.0735 1.0977 1.1236 1.1511 1.1800 1.2104 1.2420 1.2042 1.1543 1.1045 1.0548 1.0050 0.9552 0.9055 0.8559 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9487 0.9487 0.9014 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6492 1.6008 1.5524 1.5042 1.4560 1.4080 1.3601 1.3124 1.2649 1.2176 1.1705 1.1236 1.0770 1.0308 0.9849 0.9394 0.8944 0.8500 0.8062 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8944 0.9394 0.9849 1.0308 1.0770 1.1236 1.1705 1.2176 1.2093 1.1853 1.1630 1.1424 1.1236 1.1068 1.0920 1.0794 1.0689 1.0607 1.0548 1.0512 1.0500 1.0500 1.0512 1.0548 1.0607 1.0689 1.0794 1.0920 1.1068 1.1236 1.1424 1.1630 1.1853 1.2083 1.2298 1.2530 1.2777 1.3038 1.3314 1.3601 1.3901 1.4213 1.4534 1.4866 1.5207 1.5556 1.5914 1.6279 1.6651 1.7029 1.7414 1.7804 1.8200 1.8601 1.9007 1.9416 1.9831 2.0248 2.0670 2.1095 2.1523 2.1954 2.2389 2.2825 2.3265 +0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1413 1.1662 1.1927 1.2207 1.2500 1.2590 1.2093 1.1597 1.1102 1.0607 1.0112 0.9618 0.9124 0.8631 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8860 0.9014 0.9192 0.9192 0.8732 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7000 1.7000 1.7000 1.7000 1.6621 1.6140 1.5660 1.5182 1.4705 1.4230 1.3757 1.3285 1.2816 1.2349 1.1885 1.1424 1.0966 1.0512 1.0062 0.9618 0.9179 0.8746 0.8322 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8322 0.8746 0.9179 0.9618 1.0062 1.0512 1.0966 1.1424 1.1885 1.1927 1.1662 1.1413 1.1180 1.0966 1.0770 1.0595 1.0440 1.0308 1.0198 1.0112 1.0050 1.0012 1.0000 1.0000 1.0012 1.0050 1.0112 1.0198 1.0308 1.0440 1.0595 1.0770 1.0966 1.1180 1.1413 1.1630 1.1853 1.2093 1.2349 1.2619 1.2903 1.3200 1.3509 1.3829 1.4160 1.4500 1.4849 1.5207 1.5572 1.5945 1.6325 1.6711 1.7103 1.7500 1.7903 1.8310 1.8722 1.9138 1.9558 1.9981 2.0408 2.0839 2.1272 2.1708 2.2147 2.2589 2.3033 +0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2349 1.2619 1.2903 1.2659 1.2166 1.1673 1.1180 1.0689 1.0198 0.9708 0.9220 0.8732 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8246 0.8382 0.8544 0.8732 0.8944 0.8944 0.8500 0.8062 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7000 1.7000 1.7000 1.7000 1.6763 1.6286 1.5811 1.5338 1.4866 1.4396 1.3928 1.3463 1.3000 1.2540 1.2083 1.1630 1.1180 1.0735 1.0296 0.9862 0.9434 0.9014 0.8602 0.8201 0.7810 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8602 0.9014 0.9434 0.9862 1.0296 1.0735 1.1180 1.1630 1.1800 1.1511 1.1236 1.0977 1.0735 1.0512 1.0308 1.0124 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9500 0.9500 0.9513 0.9552 0.9618 0.9708 0.9823 0.9962 1.0124 1.0308 1.0512 1.0735 1.0966 1.1180 1.1413 1.1662 1.1927 1.2207 1.2500 1.2806 1.3124 1.3454 1.3793 1.4142 1.4500 1.4866 1.5240 1.5620 1.6008 1.6401 1.6800 1.7205 1.7614 1.8028 1.8446 1.8868 1.9294 1.9723 2.0156 2.0591 2.1030 2.1471 2.1915 2.2361 2.2809 +0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3238 1.2748 1.2258 1.1769 1.1281 1.0794 1.0308 0.9823 0.9341 0.8860 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.7649 0.7762 0.7906 0.8078 0.8276 0.8500 0.8746 0.8746 0.8322 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6500 1.6447 1.5977 1.5508 1.5042 1.4577 1.4116 1.3657 1.3200 1.2748 1.2298 1.1853 1.1413 1.0977 1.0548 1.0124 0.9708 0.9301 0.8902 0.8515 0.8139 0.7778 0.7433 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7433 0.7778 0.8139 0.8515 0.8902 0.9301 0.9708 1.0124 1.0548 1.0977 1.1413 1.1715 1.1402 1.1102 1.0817 1.0548 1.0296 1.0062 0.9849 0.9657 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9014 0.9055 0.9124 0.9220 0.9341 0.9487 0.9657 0.9849 1.0062 1.0296 1.0512 1.0735 1.0977 1.1236 1.1511 1.1800 1.2104 1.2420 1.2748 1.3086 1.3435 1.3793 1.4160 1.4534 1.4916 1.5305 1.5700 1.6101 1.6508 1.6919 1.7335 1.7755 1.8180 1.8608 1.9039 1.9474 1.9912 2.0353 2.0797 2.1243 2.1691 2.2142 2.2594 +0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3342 1.2855 1.2369 1.1885 1.1402 1.0920 1.0440 0.9962 0.9487 0.9014 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7018 0.7071 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8602 0.8602 0.8201 0.7810 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.6000 1.5977 1.5508 1.5042 1.4577 1.4116 1.3657 1.3200 1.2748 1.2298 1.1853 1.1413 1.0977 1.0548 1.0124 0.9708 0.9301 0.8902 0.8515 0.8139 0.7778 0.7433 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7433 0.7778 0.8139 0.8515 0.8902 0.9301 0.9708 1.0124 1.0548 1.0977 1.1413 1.1336 1.1011 1.0700 1.0404 1.0124 0.9862 0.9618 0.9394 0.9192 0.9014 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8515 0.8559 0.8631 0.8732 0.8860 0.9014 0.9192 0.9394 0.9618 0.9849 1.0062 1.0296 1.0548 1.0817 1.1102 1.1402 1.1715 1.2042 1.2379 1.2728 1.3086 1.3454 1.3829 1.4213 1.4603 1.5000 1.5403 1.5811 1.6225 1.6643 1.7066 1.7493 1.7923 1.8358 1.8795 1.9235 1.9679 2.0125 2.0573 2.1024 2.1477 2.1932 2.2389 +0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3463 1.2981 1.2500 1.2021 1.1543 1.1068 1.0595 1.0124 0.9657 0.9192 0.8732 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.8201 0.8515 0.8515 0.8139 0.7778 0.7433 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5500 1.5338 1.4866 1.4396 1.3928 1.3463 1.3000 1.2540 1.2083 1.1630 1.1180 1.0735 1.0296 0.9862 0.9434 0.9014 0.8602 0.8201 0.7810 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8602 0.9014 0.9434 0.9862 1.0296 1.0735 1.1180 1.0966 1.0630 1.0308 1.0000 0.9708 0.9434 0.9179 0.8944 0.8732 0.8544 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8016 0.8062 0.8139 0.8246 0.8382 0.8544 0.8732 0.8944 0.9179 0.9394 0.9618 0.9862 1.0124 1.0404 1.0700 1.1011 1.1336 1.1673 1.2021 1.2379 1.2748 1.3124 1.3509 1.3901 1.4300 1.4705 1.5116 1.5532 1.5953 1.6378 1.6808 1.7241 1.7678 1.8118 1.8561 1.9007 1.9455 1.9906 2.0359 2.0815 2.1272 2.1731 2.2192 +0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.3124 1.2649 1.2176 1.1705 1.1236 1.0770 1.0308 0.9849 0.9394 0.8944 0.8500 0.8062 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6021 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7810 0.8139 0.8485 0.8485 0.8139 0.7810 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.5000 1.4705 1.4230 1.3757 1.3285 1.2816 1.2349 1.1885 1.1424 1.0966 1.0512 1.0062 0.9618 0.9179 0.8746 0.8322 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8322 0.8746 0.9179 0.9618 1.0062 1.0512 1.0966 1.0607 1.0259 0.9925 0.9605 0.9301 0.9014 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8078 0.8276 0.8500 0.8732 0.8944 0.9179 0.9434 0.9708 1.0000 1.0308 1.0630 1.0966 1.1314 1.1673 1.2042 1.2420 1.2806 1.3200 1.3601 1.4009 1.4422 1.4841 1.5264 1.5692 1.6125 1.6560 1.7000 1.7443 1.7889 1.8337 1.8788 1.9242 1.9698 2.0156 2.0616 2.1077 2.1541 2.2006 +0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3314 1.3285 1.2816 1.2349 1.1885 1.1424 1.0966 1.0512 1.0062 0.9618 0.9179 0.8746 0.8322 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5701 0.5590 0.5523 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7778 0.8139 0.8515 0.8515 0.8201 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4500 1.4080 1.3601 1.3124 1.2649 1.2176 1.1705 1.1236 1.0770 1.0308 0.9849 0.9394 0.8944 0.8500 0.8062 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8944 0.9394 0.9849 1.0308 1.0630 1.0259 0.9899 0.9552 0.9220 0.8902 0.8602 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8276 0.8500 0.8746 0.9014 0.9301 0.9605 0.9925 1.0259 1.0607 1.0966 1.1336 1.1715 1.2104 1.2500 1.2903 1.3314 1.3730 1.4151 1.4577 1.5008 1.5443 1.5882 1.6325 1.6771 1.7219 1.7671 1.8125 1.8581 1.9039 1.9500 1.9962 2.0427 2.0893 2.1360 2.1829 +0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2349 1.2619 1.2903 1.3200 1.3000 1.2540 1.2083 1.1630 1.1180 1.0735 1.0296 0.9862 0.9434 0.9014 0.8602 0.8201 0.7810 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5385 0.5220 0.5099 0.5025 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8602 0.8602 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.4000 1.3946 1.3463 1.2981 1.2500 1.2021 1.1543 1.1068 1.0595 1.0124 0.9657 0.9192 0.8732 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8732 0.9192 0.9657 1.0124 1.0308 0.9925 0.9552 0.9192 0.8846 0.8515 0.8201 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7616 0.7826 0.8062 0.8322 0.8602 0.8902 0.9220 0.9552 0.9899 1.0259 1.0630 1.1011 1.1402 1.1800 1.2207 1.2619 1.3038 1.3463 1.3892 1.4327 1.4765 1.5207 1.5652 1.6101 1.6553 1.7007 1.7464 1.7923 1.8385 1.8848 1.9313 1.9780 2.0248 2.0718 2.1190 2.1662 +0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1413 1.1662 1.1927 1.2207 1.2500 1.2806 1.3124 1.2748 1.2298 1.1853 1.1413 1.0977 1.0548 1.0124 0.9708 0.9301 0.8902 0.8515 0.8139 0.7778 0.7433 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.4924 0.4743 0.4610 0.4528 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8322 0.8746 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3500 1.3342 1.2855 1.2369 1.1885 1.1402 1.0920 1.0440 0.9962 0.9487 0.9014 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9487 0.9962 1.0000 0.9605 0.9220 0.8846 0.8485 0.8139 0.7810 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7159 0.7382 0.7632 0.7906 0.8201 0.8515 0.8846 0.9192 0.9552 0.9925 1.0308 1.0700 1.1102 1.1511 1.1927 1.2349 1.2777 1.3210 1.3647 1.4089 1.4534 1.4983 1.5435 1.5890 1.6348 1.6808 1.7270 1.7734 1.8200 1.8668 1.9138 1.9609 2.0081 2.0555 2.1030 2.1506 +0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.0735 1.0977 1.1236 1.1511 1.1800 1.2104 1.2420 1.2748 1.2971 1.2530 1.2093 1.1662 1.1236 1.0817 1.0404 1.0000 0.9605 0.9220 0.8846 0.8485 0.8139 0.7810 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4472 0.4272 0.4123 0.4031 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8944 0.8944 0.8732 0.8544 0.8382 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.2748 1.2258 1.1769 1.1281 1.0794 1.0308 0.9823 0.9341 0.8860 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9341 0.9823 0.9708 0.9301 0.8902 0.8515 0.8139 0.7778 0.7433 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6500 0.6708 0.6946 0.7211 0.7500 0.7810 0.8139 0.8485 0.8846 0.9220 0.9605 1.0000 1.0404 1.0817 1.1236 1.1662 1.2093 1.2530 1.2971 1.3416 1.3865 1.4318 1.4773 1.5232 1.5692 1.6155 1.6621 1.7088 1.7557 1.8028 1.8500 1.8974 1.9449 1.9925 2.0402 2.0881 2.1360 +0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9849 1.0062 1.0296 1.0548 1.0817 1.1102 1.1402 1.1715 1.2042 1.2379 1.2728 1.2777 1.2349 1.1927 1.1511 1.1102 1.0700 1.0308 0.9925 0.9552 0.9192 0.8846 0.8515 0.8201 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4031 0.3808 0.3640 0.3536 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8732 0.9192 0.9192 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2166 1.1673 1.1180 1.0689 1.0198 0.9708 0.9220 0.8732 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9220 0.9708 0.9434 0.9014 0.8602 0.8201 0.7810 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7778 0.8139 0.8515 0.8902 0.9301 0.9708 1.0124 1.0548 1.0977 1.1413 1.1853 1.2298 1.2748 1.3200 1.3657 1.4116 1.4577 1.5042 1.5508 1.5977 1.6447 1.6919 1.7393 1.7868 1.8344 1.8822 1.9300 1.9780 2.0261 2.0742 2.1225 +0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9192 0.9394 0.9618 0.9862 1.0124 1.0404 1.0700 1.1011 1.1336 1.1673 1.2021 1.2379 1.2748 1.2619 1.2207 1.1800 1.1402 1.1011 1.0630 1.0259 0.9899 0.9552 0.9220 0.8902 0.8602 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9487 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.1597 1.1102 1.0607 1.0112 0.9618 0.9124 0.8631 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1118 0.0707 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9618 0.9179 0.8746 0.8322 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8602 0.9014 0.9434 0.9862 1.0296 1.0735 1.1180 1.1630 1.2083 1.2540 1.3000 1.3463 1.3928 1.4396 1.4866 1.5338 1.5811 1.6286 1.6763 1.7241 1.7720 1.8200 1.8682 1.9164 1.9647 2.0131 2.0616 2.1101 +0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8382 0.8544 0.8732 0.8944 0.9179 0.9434 0.9708 1.0000 1.0308 1.0630 1.0966 1.1314 1.1673 1.2042 1.2420 1.2806 1.2500 1.2104 1.1715 1.1336 1.0966 1.0607 1.0259 0.9925 0.9605 0.9301 0.9014 0.8746 0.8500 0.8276 0.8078 0.7906 0.7762 0.7649 0.7566 0.7517 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9341 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1045 1.0548 1.0050 0.9552 0.9055 0.8559 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9394 0.8944 0.8500 0.8062 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8322 0.8746 0.9179 0.9618 1.0062 1.0512 1.0966 1.1424 1.1885 1.2349 1.2816 1.3285 1.3757 1.4230 1.4705 1.5182 1.5660 1.6140 1.6621 1.7103 1.7586 1.8069 1.8554 1.9039 1.9526 2.0012 2.0500 2.0988 +0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7762 0.7906 0.8078 0.8276 0.8500 0.8746 0.9014 0.9301 0.9605 0.9925 1.0259 1.0607 1.0966 1.1336 1.1715 1.2104 1.2500 1.2806 1.2420 1.2042 1.1673 1.1314 1.0966 1.0630 1.0308 1.0000 0.9708 0.9434 0.9179 0.8944 0.8732 0.8544 0.8382 0.8246 0.8139 0.8062 0.8016 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9220 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.0512 1.0012 0.9513 0.9014 0.8515 0.8016 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9192 0.8732 0.8276 0.7826 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8944 0.9394 0.9849 1.0308 1.0770 1.1236 1.1705 1.2176 1.2649 1.3124 1.3601 1.4080 1.4560 1.5042 1.5524 1.6008 1.6492 1.6978 1.7464 1.7951 1.8439 1.8927 1.9416 1.9906 2.0396 2.0887 +0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7159 0.7280 0.7433 0.7616 0.7826 0.8062 0.8322 0.8602 0.8902 0.9220 0.9552 0.9899 1.0259 1.0630 1.1011 1.1402 1.1800 1.2207 1.2619 1.2748 1.2379 1.2021 1.1673 1.1336 1.1011 1.0700 1.0404 1.0124 0.9862 0.9618 0.9394 0.9192 0.9014 0.8860 0.8732 0.8631 0.8559 0.8515 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1000 -0.0707 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9014 0.8544 0.8078 0.7616 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8732 0.9192 0.9657 1.0124 1.0595 1.1068 1.1543 1.2021 1.2500 1.2981 1.3463 1.3946 1.4431 1.4916 1.5403 1.5890 1.6378 1.6867 1.7357 1.7847 1.8337 1.8828 1.9320 1.9812 2.0304 2.0797 +0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7632 0.7906 0.8201 0.8515 0.8846 0.9192 0.9552 0.9925 1.0308 1.0700 1.1102 1.1511 1.1927 1.2349 1.2777 1.2728 1.2379 1.2042 1.1715 1.1402 1.1102 1.0817 1.0548 1.0296 1.0062 0.9849 0.9657 0.9487 0.9341 0.9220 0.9124 0.9055 0.9014 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.8860 0.8382 0.7906 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2550 0.2693 0.2915 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9487 0.9962 1.0440 1.0920 1.1402 1.1885 1.2369 1.2855 1.3342 1.3829 1.4318 1.4807 1.5297 1.5788 1.6279 1.6771 1.7263 1.7755 1.8248 1.8742 1.9235 1.9729 2.0224 2.0718 +0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7810 0.8139 0.8485 0.8846 0.9220 0.9605 1.0000 1.0404 1.0817 1.1236 1.1662 1.2093 1.2530 1.2971 1.2748 1.2420 1.2104 1.1800 1.1511 1.1236 1.0977 1.0735 1.0512 1.0308 1.0124 0.9962 0.9823 0.9708 0.9618 0.9552 0.9513 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.8732 0.8246 0.7762 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2062 0.2236 0.2500 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9341 0.9823 1.0308 1.0794 1.1281 1.1769 1.2258 1.2748 1.3238 1.3730 1.4221 1.4714 1.5207 1.5700 1.6194 1.6688 1.7183 1.7678 1.8173 1.8668 1.9164 1.9660 2.0156 2.0652 +0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7778 0.8139 0.8515 0.8902 0.9301 0.9708 1.0124 1.0548 1.0977 1.1413 1.1853 1.2298 1.2748 1.3124 1.2806 1.2500 1.2207 1.1927 1.1662 1.1413 1.1180 1.0966 1.0770 1.0595 1.0440 1.0308 1.0198 1.0112 1.0050 1.0012 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.8631 0.8139 0.7649 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1581 0.1803 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9220 0.9708 1.0198 1.0689 1.1180 1.1673 1.2166 1.2659 1.3153 1.3647 1.4142 1.4637 1.5133 1.5628 1.6125 1.6621 1.7117 1.7614 1.8111 1.8608 1.9105 1.9602 2.0100 2.0597 +0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8602 0.9014 0.9434 0.9862 1.0296 1.0735 1.1180 1.1630 1.2083 1.2540 1.3000 1.3200 1.2903 1.2619 1.2349 1.2093 1.1853 1.1630 1.1424 1.1236 1.1068 1.0920 1.0794 1.0689 1.0607 1.0548 1.0512 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9055 0.8559 0.8062 0.7566 0.7071 0.6576 0.6083 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1118 0.1414 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9618 1.0112 1.0607 1.1102 1.1597 1.2093 1.2590 1.3086 1.3583 1.4080 1.4577 1.5075 1.5572 1.6070 1.6568 1.7066 1.7564 1.8062 1.8561 1.9059 1.9558 2.0056 2.0555 +1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8322 0.8746 0.9179 0.9618 1.0062 1.0512 1.0966 1.1424 1.1885 1.2349 1.2816 1.3285 1.3314 1.3038 1.2777 1.2530 1.2298 1.2083 1.1885 1.1705 1.1543 1.1402 1.1281 1.1180 1.1102 1.1045 1.1011 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7159 0.6671 0.6185 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9014 0.8515 0.8016 0.7517 0.7018 0.6519 0.6021 0.5523 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0707 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9552 1.0050 1.0548 1.1045 1.1543 1.2042 1.2540 1.3038 1.3537 1.4036 1.4534 1.5033 1.5532 1.6031 1.6530 1.7029 1.7529 1.8028 1.8527 1.9026 1.9526 2.0025 2.0524 +1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8944 0.9394 0.9849 1.0308 1.0770 1.1236 1.1705 1.2176 1.2649 1.3124 1.3500 1.3463 1.3210 1.2971 1.2748 1.2540 1.2349 1.2176 1.2021 1.1885 1.1769 1.1673 1.1597 1.1543 1.1511 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7280 0.6801 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9513 1.0012 1.0512 1.1011 1.1511 1.2010 1.2510 1.3010 1.3509 1.4009 1.4509 1.5008 1.5508 1.6008 1.6508 1.7007 1.7507 1.8007 1.8507 1.9007 1.9506 2.0006 2.0506 +1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8732 0.9192 0.9657 1.0124 1.0595 1.1068 1.1543 1.2021 1.2500 1.2981 1.3000 1.3000 1.3000 1.3000 1.3000 1.3000 1.2816 1.2649 1.2500 1.2369 1.2258 1.2166 1.2093 1.2042 1.2010 1.2000 1.2000 1.2000 1.2000 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7433 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.1500 1.1500 1.1500 1.1500 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8078 0.8544 0.9014 0.9487 0.9962 1.0440 1.0920 1.1402 1.1885 1.2369 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7826 0.8276 0.8732 0.9192 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.2000 1.2000 1.2000 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8860 0.9341 0.9823 1.0308 1.0794 1.1281 1.1769 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3536 0.3640 0.3808 0.4031 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7211 0.7632 0.8062 0.8500 0.8944 0.9394 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.2500 1.2500 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9220 0.9708 1.0198 1.0689 1.1180 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7632 0.7211 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4031 0.4123 0.4272 0.4472 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6727 0.7106 0.7500 0.7906 0.8322 0.8746 0.9179 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3000 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9618 1.0112 1.0607 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7906 0.7500 0.7106 0.6727 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4528 0.4610 0.4743 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6727 0.7071 0.7433 0.7810 0.8201 0.8602 0.9014 0.9434 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9552 1.0050 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.7810 0.7433 0.7071 0.6727 0.6403 0.6103 0.5831 0.5590 0.5385 0.5220 0.5099 0.5025 0.5000 0.5025 0.5099 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.7106 0.7433 0.7778 0.8139 0.8515 0.8902 0.9301 0.9708 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7517 0.8016 0.8515 0.9014 0.9513 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8139 0.7778 0.7433 0.7106 0.6801 0.6519 0.6265 0.6042 0.5852 0.5701 0.5590 0.5523 0.5500 0.5523 0.5590 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7071 0.7566 0.8062 0.8559 0.9055 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6325 0.6500 0.6708 0.6946 0.7211 0.7500 0.7810 0.8139 0.8485 0.8846 0.9220 0.9605 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8485 0.8139 0.7810 0.7500 0.7211 0.6946 0.6708 0.6500 0.6325 0.6185 0.6083 0.6021 0.6000 0.6021 0.5701 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6671 0.7159 0.7649 0.8139 0.8631 0.9124 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6964 0.7159 0.7382 0.7632 0.7906 0.8201 0.8515 0.8846 0.9192 0.9552 0.9925 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8515 0.8201 0.7906 0.7632 0.7382 0.7159 0.6964 0.6801 0.6671 0.6576 0.6519 0.6500 0.6325 0.5852 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6325 0.6801 0.7280 0.7762 0.8246 0.8732 0.9124 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7826 0.8062 0.8322 0.8602 0.8902 0.9220 0.9552 0.9899 1.0259 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8500 0.8500 0.8322 0.8062 0.7826 0.7616 0.7433 0.7280 0.7159 0.7071 0.7018 0.6964 0.6500 0.6042 0.5590 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.6042 0.6500 0.6964 0.7433 0.7906 0.8382 0.8559 0.8631 0.8732 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8746 0.9014 0.9301 0.9605 0.9925 1.0259 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7906 0.7762 0.7649 0.7566 0.7517 0.7159 0.6708 0.6265 0.5831 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.6265 0.6708 0.7159 0.7616 0.8000 0.8016 0.8062 0.8139 0.8246 0.8382 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9434 0.9708 1.0000 1.0308 1.0630 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5523 0.6021 0.6519 0.7018 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7382 0.6946 0.6519 0.6103 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6103 0.6519 0.6946 0.7382 0.7500 0.7500 0.7517 0.7566 0.7649 0.7762 0.7906 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0404 1.0700 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5590 0.6083 0.6576 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6801 0.6403 0.6021 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6403 0.6801 0.7000 0.7000 0.7000 0.7000 0.7018 0.7071 0.7159 0.7280 0.7433 0.7616 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5701 0.6185 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6364 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6519 0.6576 0.6671 0.6801 0.6964 0.7159 0.7382 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5852 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6021 0.6083 0.6185 0.6325 0.6500 0.6708 0.6946 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5523 0.5590 0.5701 0.5852 0.6042 0.6265 0.6519 0.6801 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5025 0.5099 0.5220 0.5385 0.5590 0.5831 0.6103 0.6403 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2062 0.1581 0.1118 0.0707 0.0500 0.0707 0.1118 0.1581 0.2062 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2500 -0.2500 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.1000 -0.1500 -0.2000 -0.2236 -0.2062 -0.2000 -0.1500 -0.1000 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1118 -0.1500 -0.1581 -0.1803 -0.1581 -0.1500 -0.1500 -0.1118 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1118 -0.1414 -0.1118 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.1118 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0707 -0.0707 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5025 0.4528 0.4031 0.3536 0.3041 0.2550 0.2062 0.1581 0.1118 0.0707 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 -0.0500 -0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0500 0.0707 0.1118 0.1581 0.2062 0.2550 0.3041 0.3536 0.4031 0.4528 0.5025 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5099 0.4610 0.4123 0.3640 0.3162 0.2693 0.2236 0.1803 0.1414 0.1118 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1000 0.1118 0.1414 0.1803 0.2236 0.2693 0.3162 0.3640 0.4123 0.4610 0.5099 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5220 0.4743 0.4272 0.3808 0.3354 0.2915 0.2500 0.2121 0.1803 0.1581 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1500 0.1581 0.1803 0.2121 0.2500 0.2915 0.3354 0.3808 0.4272 0.4743 0.5220 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5385 0.4924 0.4472 0.4031 0.3606 0.3202 0.2828 0.2500 0.2236 0.2062 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2000 0.2062 0.2236 0.2500 0.2828 0.3202 0.3606 0.4031 0.4472 0.4924 0.5385 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5148 0.4717 0.4301 0.3905 0.3536 0.3202 0.2915 0.2693 0.2550 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2500 0.2550 0.2693 0.2915 0.3202 0.3536 0.3905 0.4301 0.4717 0.5148 0.5590 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5408 0.5000 0.4610 0.4243 0.3905 0.3606 0.3354 0.3162 0.3041 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3000 0.3041 0.3162 0.3354 0.3606 0.3905 0.4243 0.4610 0.5000 0.5408 0.5831 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.5701 0.5315 0.4950 0.4610 0.4301 0.4031 0.3808 0.3640 0.3536 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3500 0.3536 0.3640 0.3808 0.4031 0.4301 0.4610 0.4950 0.5315 0.5701 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.5657 0.5315 0.5000 0.4717 0.4472 0.4272 0.4123 0.4031 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4000 0.4000 0.4000 0.4000 0.4000 0.4031 0.4123 0.4272 0.4472 0.4717 0.5000 0.5315 0.5657 0.6021 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 +1.3500 1.3000 1.2500 1.2000 1.1500 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6021 0.5701 0.5408 0.5148 0.4924 0.4743 0.4610 0.4528 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.4500 0.4500 0.4500 0.4500 0.4528 0.4610 0.4743 0.4924 0.5148 0.5408 0.5701 0.6021 0.6364 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1000 1.0500 1.0000 0.9500 0.9000 0.8500 0.8000 0.7500 0.7000 0.6500 0.6000 0.5500 0.5000 0.4500 0.4000 0.3500 0.3000 0.2500 0.2000 0.1500 0.1000 0.0500 -0.0500 -0.1000 -0.1000 -0.0500 0.0500 0.1000 0.1500 0.2000 0.2500 0.3000 0.3500 0.4000 0.4500 0.5000 0.5500 0.6000 0.6500 0.7000 0.7500 0.8000 0.8500 0.9000 0.9500 1.0000 1.0500 1.1000 1.1500 1.2000 1.2500 1.3000 1.3500 1.4000 1.4500 1.5000 1.5500 1.6000 1.6500 1.7000 1.7500 1.8000 1.8500 1.9000 1.9500 2.0000 2.0500 diff --git a/examples/sphere_basics.cpp b/examples/sphere_basics.cpp index f936c3f..e15d42d 100644 --- a/examples/sphere_basics.cpp +++ b/examples/sphere_basics.cpp @@ -7,13 +7,16 @@ /// - Geodesic distance and interpolation /// - Swapping metrics (ConstantSPDMetric) and retractions (projection retraction) -#include #include -#include + #include #include #include +#include + +#include "geodex/geodex.hpp" + using namespace geodex; int main() { @@ -55,7 +58,7 @@ int main() { std::cout << "\n=== Sphere (anisotropic metric A=diag(4,1,1)) ===\n"; Eigen::Matrix3d A = Eigen::Vector3d(4.0, 1.0, 1.0).asDiagonal(); - Sphere> aniso_sphere{ConstantSPDMetric<3>{A}}; + Sphere<2, ConstantSPDMetric<3>> aniso_sphere{ConstantSPDMetric<3>{A}}; // The anisotropic metric changes norms and distances Eigen::Vector3d u{1.0, 0.0, 0.0}; @@ -71,7 +74,7 @@ int main() { // --- 3. Projection retraction --- std::cout << "\n=== Sphere (round metric, projection retraction) ===\n"; - Sphere proj_sphere; + Sphere<2, SphereRoundMetric, SphereProjectionRetraction> proj_sphere; // Projection retraction: cheaper but approximate Eigen::Vector3d v_proj = proj_sphere.log(p, q); diff --git a/examples/sphere_distance.cpp b/examples/sphere_distance.cpp index cca0ffc..3e5d2cb 100644 --- a/examples/sphere_distance.cpp +++ b/examples/sphere_distance.cpp @@ -7,13 +7,16 @@ /// 2. Anisotropic metric (A=diag(4,1,1)) + exponential map /// 3. Round metric + projection retraction -#include #include -#include + #include #include #include +#include + +#include "geodex/geodex.hpp" + using namespace geodex; static Eigen::Vector3d point_at_theta(double theta) { @@ -52,12 +55,12 @@ int main() { Eigen::Matrix3d A = Eigen::Matrix3d::Identity(); A(0, 0) = 4.0; A(1, 1) = 1.0; - Sphere> aniso_sphere{ConstantSPDMetric<3>{A}}; + Sphere<2, ConstantSPDMetric<3>> aniso_sphere{ConstantSPDMetric<3>{A}}; print_distance_table("Anisotropic metric (A=diag(4,1,1)) + Exponential map", aniso_sphere, north, thetas); // 3. Round metric + projection retraction - Sphere proj_sphere; + Sphere<2, SphereRoundMetric, SphereProjectionRetraction> proj_sphere; print_distance_table("Round metric + Projection retraction", proj_sphere, north, thetas); return 0; diff --git a/examples/sphere_interpolation.cpp b/examples/sphere_interpolation.cpp new file mode 100644 index 0000000..faf412a --- /dev/null +++ b/examples/sphere_interpolation.cpp @@ -0,0 +1,208 @@ +/// @file sphere_interpolation.cpp +/// @brief Demonstrates `discrete_geodesic` on the sphere across several +/// metric / retraction combinations and writes a JSON file for visualisation +/// via `scripts/visualize.py`. +/// +/// Run the example, then visualise: +/// ``` +/// ./build/examples/sphere_interpolation sphere_interpolation.json +/// python scripts/visualize.py sphere_interpolation.json -o sphere.html +/// open sphere.html +/// ``` + +#include +#include + +#include +#include +#include +#include +#include +#include + +#include + +#include "geodex/geodex.hpp" + +using namespace geodex; + +static Eigen::Vector3d point_at_theta(double theta) { + return Eigen::Vector3d(std::sin(theta), 0.0, std::cos(theta)); +} + +/// Point on the unit sphere at polar angle `theta` from the north pole and +/// azimuth `phi` around the z axis (0 → x-axis, π/2 → y-axis). +static Eigen::Vector3d spherical_point(double theta, double phi) { + return Eigen::Vector3d(std::sin(theta) * std::cos(phi), std::sin(theta) * std::sin(phi), + std::cos(theta)); +} + +/// Write a JSON array of 3D points: [[x,y,z], ...] +static void write_points(std::ofstream& out, const std::vector& pts) { + out << "["; + for (size_t i = 0; i < pts.size(); ++i) { + if (i > 0) out << ","; + out << "\n [" << std::setprecision(8) << pts[i][0] << "," << pts[i][1] << "," + << pts[i][2] << "]"; + } + out << "\n ]"; +} + +static void write_vec3(std::ofstream& out, const Eigen::Vector3d& v) { + out << "[" << std::setprecision(8) << v[0] << "," << v[1] << "," << v[2] << "]"; +} + +/// A single path entry for the visualization JSON. +struct PathEntry { + std::string label; + Eigen::Vector3d start; + Eigen::Vector3d target; + std::vector points; +}; + +/// Run `discrete_geodesic` on the given sphere and return a labelled path entry +/// plus a short console summary. +template +static PathEntry run_scenario(const std::string& label, const SphereT& sphere, + const Eigen::Vector3d& start, const Eigen::Vector3d& target, + const InterpolationSettings& settings) { + auto result = discrete_geodesic(sphere, start, target, settings); + + std::printf( + " [%-48s] status=%-17s iters=%4d halvings=%3d initial_d=%.4f final_d=%.2e points=%zu\n", + label.c_str(), to_string(result.status), result.iterations, result.distortion_halvings, + result.initial_distance, result.final_distance, result.path.size()); + + return PathEntry{label, start, target, std::move(result.path)}; +} + +static void write_json(const std::string& output_file, const std::vector& entries) { + std::ofstream out(output_file); + if (!out) { + std::cerr << "Error: cannot open " << output_file << "\n"; + std::exit(1); + } + + out << std::fixed; + out << "{\n"; + out << " \"manifold\": { \"type\": \"S2\" },\n"; + out << " \"paths\": [\n"; + for (size_t i = 0; i < entries.size(); ++i) { + const auto& e = entries[i]; + out << " {\n"; + out << " \"label\": \"" << e.label << "\",\n"; + out << " \"start\": "; + write_vec3(out, e.start); + out << ",\n"; + out << " \"target\": "; + write_vec3(out, e.target); + out << ",\n"; + out << " \"points\": "; + write_points(out, e.points); + out << "\n }" << (i + 1 == entries.size() ? "\n" : ",\n"); + } + out << " ]\n"; + out << "}\n"; + + std::cout << "Wrote " << output_file << "\n"; +} + +int main(int argc, char* argv[]) { + std::string output_file = "sphere_interpolation.json"; + if (argc > 1) output_file = argv[1]; + + // Common start point at the north pole. + const Eigen::Vector3d north(0.0, 0.0, 1.0); + + std::vector entries; + + std::cout << "Running discrete_geodesic scenarios on the sphere:\n"; + + // All anisotropic scenarios use a target with non-zero x AND y components so + // the metric's directional preference is actually visible. A target on the + // y=0 plane makes the problem one-dimensional along the great circle, and + // any metric yields the same (straight great-circle) path. + const double theta = 1.3; // polar angle from north + const double phi = 0.9; // azimuth in x-y plane (~52 deg) + const Eigen::Vector3d shared_target = spherical_point(theta, phi); + + // --------------------------------------------------------------------- + // 1. Round metric + exponential map — the textbook great-circle geodesic. + // `log` is the Riemannian logarithm, `-log` is the natural gradient, + // and the path lies exactly on the great-circle arc. + // --------------------------------------------------------------------- + { + Sphere<> sphere; // default: SphereRoundMetric + SphereExponentialMap + InterpolationSettings s; + s.step_size = 0.1; + entries.push_back( + run_scenario("1. Round metric, true exp/log", sphere, north, shared_target, s)); + } + + // --------------------------------------------------------------------- + // 2. Round metric + projection retraction — the retraction is first-order, + // but the metric is still the round one so the walk still follows the + // great circle. Provides a reference for "projection retraction alone" + // vs "anisotropic metric" effects. + // --------------------------------------------------------------------- + { + Sphere<2, SphereRoundMetric, SphereProjectionRetraction> sphere; + InterpolationSettings s; + s.step_size = 0.1; + entries.push_back( + run_scenario("2. Round metric, projection retraction", sphere, north, shared_target, s)); + } + + // --------------------------------------------------------------------- + // 3. Moderate anisotropic metric — A = diag(4, 1, 1) penalises motion in + // the x direction. The optimal path trades y-motion for less x-motion + // early on, producing a visible bend away from the great circle. + // `has_riemannian_log` is false for ConstantSPDMetric, so + // `discrete_geodesic` always uses the FD natural gradient here. + // --------------------------------------------------------------------- + { + Eigen::Matrix3d A = Eigen::Matrix3d::Identity(); + A(0, 0) = 4.0; + Sphere<2, ConstantSPDMetric<3>> sphere{ConstantSPDMetric<3>{A}}; + InterpolationSettings s; + s.step_size = 0.1; + entries.push_back( + run_scenario("3. Anisotropic metric A=diag(4,1,1)", sphere, north, shared_target, s)); + } + + // --------------------------------------------------------------------- + // 4. Heavy anisotropic metric — A = diag(25, 1, 1). The bend toward + // y-motion should be pronounced. Smaller step_size keeps the walk + // stable under the stretched metric. + // --------------------------------------------------------------------- + { + Eigen::Matrix3d A = Eigen::Matrix3d::Identity(); + A(0, 0) = 25.0; + Sphere<2, ConstantSPDMetric<3>> sphere{ConstantSPDMetric<3>{A}}; + InterpolationSettings s; + s.step_size = 0.05; + s.max_steps = 500; + entries.push_back( + run_scenario("4. Anisotropic metric A=diag(25,1,1)", sphere, north, shared_target, s)); + } + + // --------------------------------------------------------------------- + // 5. Near-antipodal — shows graceful degradation near the cut locus. The + // log is still well-defined (distance < pi), so this should converge. + // --------------------------------------------------------------------- + { + Sphere<> sphere; + InterpolationSettings s; + s.step_size = 0.2; + const Eigen::Vector3d near_antipodal = + spherical_point(std::numbers::pi - 0.1, 0.9); // just inside cut + entries.push_back( + run_scenario("5. Round metric, near-antipodal", sphere, north, near_antipodal, s)); + } + + std::cout << "\n"; + write_json(output_file, entries); + std::cout << "\nVisualise with:\n"; + std::cout << " python scripts/visualize.py " << output_file << " -o sphere.html\n"; + return 0; +} diff --git a/examples/sphere_interpolation.py b/examples/sphere_interpolation.py new file mode 100644 index 0000000..6db81fc --- /dev/null +++ b/examples/sphere_interpolation.py @@ -0,0 +1,103 @@ +#!/usr/bin/env python3 +"""Discrete geodesic interpolation on the sphere across metric/retraction variants. + +Python-API parallel of `examples/sphere_interpolation.cpp`. Runs +`discrete_geodesic` from the north pole to a shared target under five +configurations and prints per-case summary statistics: + + 1. Round metric + exponential map (textbook great-circle). + 2. Round metric + projection retraction. + 3. Anisotropic metric A = diag(4, 1, 1). + 4. Anisotropic metric A = diag(25, 1, 1), smaller step size. + 5. Round metric near-antipodal target (graceful degradation near cut locus). + +For each run we report status, iteration count, initial/final distance, path +length (waypoint count), arc length, and max angular deviation from the +great-circle plane through start and target. Anisotropic runs should show a +non-zero deviation — the path bends to trade expensive x-motion for cheaper +y-motion. +""" + +import math + +import numpy as np + +import geodex + + +def spherical_point(theta: float, phi: float) -> np.ndarray: + """Point on the unit sphere at polar angle theta (from north) and azimuth phi.""" + return np.array( + [math.sin(theta) * math.cos(phi), + math.sin(theta) * math.sin(phi), + math.cos(theta)] + ) + + +def arc_length(points: list[np.ndarray]) -> float: + """Sum of successive angular (great-circle) distances along the polyline.""" + total = 0.0 + for i in range(len(points) - 1): + dot = np.clip(np.dot(points[i], points[i + 1]), -1.0, 1.0) + total += math.acos(dot) + return total + + +def max_plane_deviation(points: list[np.ndarray], start: np.ndarray, + target: np.ndarray) -> float: + """Max angular deviation (radians) of any path point from the great circle + plane spanned by `start` and `target`. Zero for a true great-circle arc.""" + normal = np.cross(start, target) + n = np.linalg.norm(normal) + if n < 1e-12: + return 0.0 # degenerate (antipodal or identical endpoints) + normal /= n + return max(math.asin(min(1.0, abs(float(np.dot(p, normal))))) for p in points) + + +def run(label: str, manifold, start: np.ndarray, target: np.ndarray, + settings: geodex.InterpolationSettings): + result = geodex.discrete_geodesic(manifold, start, target, settings) + pts = [np.asarray(p) for p in result.path] + arc = arc_length(pts) + dev = max_plane_deviation(pts, start, target) + print( + f" [{label:48s}] status={str(result.status):24s} " + f"iters={result.iterations:4d} " + f"d_init={result.initial_distance:.4f} d_final={result.final_distance:.2e} " + f"pts={len(pts):4d} arc={arc:.4f} rad dev={math.degrees(dev):6.2f} deg" + ) + + +# Common start (north pole) and a shared target off the y=0 plane so anisotropy +# can bend the path along y. +north = np.array([0.0, 0.0, 1.0]) +shared = spherical_point(theta=1.3, phi=0.9) # ~52 deg azimuth + +print("Running discrete_geodesic scenarios on the sphere:\n") + +# 1. Round metric + exponential map (default Sphere). +s1 = geodex.InterpolationSettings(step_size=0.1) +run("1. Round metric, true exp/log", geodex.Sphere(), north, shared, s1) + +# 2. Round metric + projection retraction. +s2 = geodex.InterpolationSettings(step_size=0.1) +run("2. Round metric, projection retraction", + geodex.Sphere(retraction="projection"), north, shared, s2) + +# 3. Moderate anisotropic metric via ConfigurationSpace wrapper. +A1 = np.diag([4.0, 1.0, 1.0]) +aniso1 = geodex.ConfigurationSpace(geodex.Sphere(), geodex.ConstantSPDMetric(A1)) +s3 = geodex.InterpolationSettings(step_size=0.1) +run("3. Anisotropic A=diag(4,1,1)", aniso1, north, shared, s3) + +# 4. Heavy anisotropic metric — smaller step_size for stability. +A2 = np.diag([25.0, 1.0, 1.0]) +aniso2 = geodex.ConfigurationSpace(geodex.Sphere(), geodex.ConstantSPDMetric(A2)) +s4 = geodex.InterpolationSettings(step_size=0.05, max_steps=500) +run("4. Anisotropic A=diag(25,1,1)", aniso2, north, shared, s4) + +# 5. Near-antipodal target (just inside the cut locus). +near_antipodal = spherical_point(theta=math.pi - 0.1, phi=0.9) +s5 = geodex.InterpolationSettings(step_size=0.2) +run("5. Round metric, near-antipodal", geodex.Sphere(), north, near_antipodal, s5) diff --git a/include/geodex/algorithm/distance.hpp b/include/geodex/algorithm/distance.hpp index 94a2660..b12df04 100644 --- a/include/geodex/algorithm/distance.hpp +++ b/include/geodex/algorithm/distance.hpp @@ -3,8 +3,8 @@ #pragma once -#include -#include +#include "geodex/core/concepts.hpp" +#include "geodex/core/debug.hpp" namespace geodex { @@ -20,7 +20,7 @@ namespace geodex { /// This method provides a third-order approximation to the exact geodesic distance /// on general Riemannian manifolds. It is computationally cheaper than numerical /// geodesic integration while maintaining high accuracy for moderately curved spaces. -/// For manifolds with with exact exponential and logarithmic maps, this formula yields +/// For manifolds with with exact exponential and logarithmic maps, this formula yields /// the exact geodesic distance. /// /// @note See Kyaw, P. T., & Kelly, J. (2026). Geometry-Aware Sampling-Based Motion diff --git a/include/geodex/algorithm/heuristics.hpp b/include/geodex/algorithm/heuristics.hpp new file mode 100644 index 0000000..5fc584b --- /dev/null +++ b/include/geodex/algorithm/heuristics.hpp @@ -0,0 +1,23 @@ +/// @file heuristics.hpp +/// @brief Admissible heuristics for motion planning on Riemannian manifolds. + +#pragma once + +namespace geodex { + +/// @brief Euclidean (L2) heuristic between coordinate vectors. +/// +/// @details Computes the chord distance \f$ \|a - b\|_2 \f$ between two points. +/// Admissible for any manifold where geodesic distance >= chord distance. +struct EuclideanHeuristic { + /// @brief Compute \f$ \|a - b\|_2 \f$. + /// @param a First point. + /// @param b Second point. + /// @return The Euclidean distance. + template + auto operator()(const PointA& a, const PointB& b) const -> double { + return (a - b).norm(); + } +}; + +} // namespace geodex diff --git a/include/geodex/algorithm/interpolation.hpp b/include/geodex/algorithm/interpolation.hpp new file mode 100644 index 0000000..cdb8175 --- /dev/null +++ b/include/geodex/algorithm/interpolation.hpp @@ -0,0 +1,712 @@ +/// @file interpolation.hpp +/// @brief Discrete geodesic interpolation via Riemannian natural gradient descent. + +#pragma once + +#include + +#include +#include +#include +#include + +#include +#include + +#include "geodex/core/concepts.hpp" +#include "geodex/core/debug.hpp" +#include "geodex/core/metric.hpp" + +namespace geodex { + +// --------------------------------------------------------------------------- +// Status +// --------------------------------------------------------------------------- + +/// @brief Termination status for the discrete geodesic walk. +enum class InterpolationStatus { + Converged, ///< Distance to target fell below convergence tolerance. + MaxStepsReached, ///< Iteration budget exhausted without reaching tolerance. + GradientVanished, ///< Riemannian gradient norm is ~0 at a non-target point. + CutLocus, ///< `log` collapsed to ~0 while start and target are distinct (e.g. antipodal on a + ///< sphere). + StepShrunkToZero, ///< Distortion halving drove step size below `min_step_size`. + DegenerateInput, ///< `start == target` on entry; returned a single-point path immediately. +}; + +/// @brief Return a human-readable name for an `InterpolationStatus`. +inline const char* to_string(InterpolationStatus s) { + switch (s) { + case InterpolationStatus::Converged: + return "Converged"; + case InterpolationStatus::MaxStepsReached: + return "MaxStepsReached"; + case InterpolationStatus::GradientVanished: + return "GradientVanished"; + case InterpolationStatus::CutLocus: + return "CutLocus"; + case InterpolationStatus::StepShrunkToZero: + return "StepShrunkToZero"; + case InterpolationStatus::DegenerateInput: + return "DegenerateInput"; + } + return "Unknown"; +} + +// --------------------------------------------------------------------------- +// Settings +// --------------------------------------------------------------------------- + +/// @brief Settings for the discrete geodesic walk. +/// +/// @details Each iteration takes a Riemannian step of length +/// \f$\min(\texttt{step\_size}, \text{remaining distance})\f$ in the descent direction. +/// Iteration count and returned-path size therefore scale as approximately +/// \f$\text{initial\_distance} / \texttt{step\_size}\f$, so `step_size` also functions +/// as the effective path resolution (the maximum Riemannian distance between +/// consecutive returned points). +/// +/// **Fast path**: the algorithm first tries the Riemannian logarithm as the descent +/// direction, exploiting the identity +/// \f$\nabla_g(\tfrac{1}{2}\, d_g^2(\cdot, q))(x) = -\log_x^g(q)\f$ +/// which holds on any Riemannian manifold when `x` is strictly inside `q`'s +/// injectivity radius and `log` is the Riemannian logarithm of the metric in use. +/// A progress check on each step verifies that the proposed point actually decreased +/// the distance to target. When the check fails (e.g., the retraction is not the +/// true exponential map, or the metric differs from the one implied by the +/// retraction), the algorithm falls back **for that step only** to a central +/// finite-difference natural gradient computed from the manifold's `inner` product. +struct InterpolationSettings { + /// @brief Max Riemannian step per iteration; also the effective path resolution. + double step_size = 0.5; + + /// @brief Absolute stop threshold on \f$|\log(\text{current}, \text{target})|_R\f$. + double convergence_tol = 1e-4; + + /// @brief Relative stop threshold: also stop when distance drops below + /// `convergence_rel * initial_distance`. + double convergence_rel = 1e-3; + + /// @brief Maximum number of successful gradient-descent steps. + int max_steps = 100; + + /// @brief Central finite-difference step for the fallback gradient. Set to 0 + /// to auto-select as `max(1e-8, 1e-5 * max(1, initial_distance))`. + double fd_epsilon = 0.0; + + /// @brief Max ratio \f$|\log(\text{current}, \text{proposed})|_R / \text{step\_used}\f$ + /// before the retraction is considered to have over-shot. If violated, the + /// step cap is halved and the iteration retries. This guards against + /// retractions that blow up under curvature and is usually 1.5 (modest slack + /// over a perfect isometry). + double distortion_ratio = 1.5; + + /// @brief Factor by which the current step cap grows back toward `step_size` + /// after each successful iteration. Set to 1.0 to disable growth. + double growth_factor = 1.5; + + /// @brief Floor below which the step cap triggers a `StepShrunkToZero` failure. + double min_step_size = 1e-12; + + /// @brief Riemannian-norm threshold below which the gradient is considered + /// vanished (triggers `GradientVanished`). + double gradient_eps = 1e-12; + + /// @brief \f$|\log|_R\f$ threshold that, combined with a nonzero ambient gap, + /// flags a cut-locus situation (e.g., antipodal points on the sphere where + /// `log` returns zero). + double cut_locus_eps = 1e-10; + + /// @brief Force the log-based direction even when `is_riemannian_log()` is false. + /// + /// @details When true, the algorithm always uses `log(current, target)` as the + /// descent direction and never falls back to the FD natural gradient. The metric's + /// norm and distance still control step sizing and convergence. This produces + /// smoother paths (no FD oscillation) but the path follows the base retraction's + /// geodesic rather than the true Riemannian geodesic of the configured metric. + bool force_log_direction = false; + + /// @brief Relative-error threshold above which the midpoint distance surrogate + /// used by the FD gradient is deemed unreliable and falls back to + /// `|log(a,b)|_R`. + /// + /// @details `natural_gradient_fd` samples \f$d^2(p \pm h\,e_i, q)\f$ via a + /// third-order-accurate midpoint formula (see `distance_midpoint`). For a true + /// Riemannian midpoint we have \f$\log_m(a) = -\log_m(b)\f$, so the quantity + /// \f$\|v_{ma} + v_{mb}\|_m / \|v_{mb} - v_{ma}\|_m\f$ is zero. When this + /// ratio exceeds `tau`, the midpoint is considered unreliable (non-Riemannian + /// retraction, cut locus, or non-smoothness between the samples) and the FD + /// sample falls back to `|log|_R` for the entire basis direction. The count + /// of fallbacks is reported on `InterpolationResult::fd_midpoint_fallbacks`. + /// Set to 0.0 to force via-log for every sample. Default 0.25. + double fd_midpoint_guard_tau = 0.25; +}; + +// --------------------------------------------------------------------------- +// Local traits +// --------------------------------------------------------------------------- + +namespace detail { + +/// @brief True when the manifold provides a `project(p, v)` method mapping an +/// ambient vector to the tangent space. +template +concept HasProject = requires(const M m, const typename M::Point p, const typename M::Tangent v) { + { m.project(p, v) } -> std::same_as; +}; + +} // namespace detail + +// --------------------------------------------------------------------------- +// Workspace +// --------------------------------------------------------------------------- + +/// @brief Reusable scratch buffers for `discrete_geodesic`. +/// +/// @details Passing a cache to `discrete_geodesic` eliminates per-iteration +/// heap allocations (for fixed-size manifolds) and per-call allocation beyond the +/// first call (for dynamic-size manifolds). Intended for use in hot loops +/// such as steering functions in sampling-based planners: +/// +/// ```cpp +/// geodex::InterpolationCache> cache; +/// for (auto& edge : edges) { +/// auto r = geodex::discrete_geodesic(sphere, edge.a, edge.b, settings, &cache); +/// ... +/// } +/// ``` +/// +/// Users who do not need this optimization can omit the cache argument and +/// a stack-local one will be used automatically. +template +struct InterpolationCache { + using Point = typename M::Point; ///< Manifold point type. + using Tangent = typename M::Tangent; ///< Manifold tangent vector type. + + private: + static constexpr int N = Tangent::SizeAtCompileTime; + static constexpr int MaxN = (N == Eigen::Dynamic) ? Eigen::Dynamic : N; + + public: + /// @brief Scratch FD-path ambient tangent (natural gradient reconstructed in ambient space). + Tangent v_fd; + + /// @brief Basis matrix (FD path): columns are tangent basis vectors at the current point. + Eigen::Matrix basis_mat; + + /// @brief Metric tensor \f$G_{ij} = \langle e_i, e_j\rangle_p\f$ in the current basis. + Eigen::Matrix G; + + /// @brief Coordinate-space gradient of \f$\tfrac{1}{2}\, d^2(\cdot, \text{target})\f$. + Eigen::Matrix grad; + + /// @brief Natural-gradient coefficients \f$\alpha = -G^{-1} g\f$. + Eigen::Matrix alpha; + + /// @brief Resize all buffers for the given ambient and intrinsic dimensions. + /// @param ambient Ambient-space dimension of a tangent vector (typically `Tangent::size()`). + /// @param d Intrinsic manifold dimension (`manifold.dim()`). + void reset(int ambient, int d) { + basis_mat.resize(ambient, d); + G.resize(d, d); + grad.resize(d); + alpha.resize(d); + if constexpr (N == Eigen::Dynamic) { + v_fd.resize(ambient); + } + } +}; + +// --------------------------------------------------------------------------- +// Result +// --------------------------------------------------------------------------- + +/// @brief Output of the discrete geodesic interpolation. +/// +/// @tparam PointT Point type of the manifold (e.g. `Eigen::Vector3d`). +template +struct InterpolationResult { + /// @brief Sequence of iterates from `start` toward `target` (always starts with `start`). + std::vector path; + + /// @brief Termination reason — always check this before using the path for downstream work. + InterpolationStatus status = InterpolationStatus::Converged; + + /// @brief Number of successful gradient steps taken (distortion retries do not count). + int iterations = 0; + + /// @brief Number of times the step cap was halved due to distortion / progress failure. + int distortion_halvings = 0; + + /// @brief Number of FD basis directions whose midpoint distance surrogate was + /// rejected by the runtime guard and replaced with `|log|_R` for that sample. + /// + /// @details Summed across all iterations of the walk. A nonzero value is a + /// strong signal that the manifold/retraction/metric combination is + /// producing a midpoint that is not the Riemannian midpoint (e.g. projection + /// retraction on an anisotropic metric, SE(2) Euler retraction for large Δθ, + /// cut-locus crossings, or a non-smooth metric feature within ~h of the + /// midpoint). + int fd_midpoint_fallbacks = 0; + + /// @brief Riemannian distance from `start` to `target` at entry. + double initial_distance = 0.0; + + /// @brief Riemannian distance from the final iterate to `target` at exit. + double final_distance = 0.0; +}; + +// --------------------------------------------------------------------------- +// Implementation helpers +// --------------------------------------------------------------------------- + +namespace detail { + +/// @brief First-order Riemannian distance via \f$|\log(a, b)|_R\f$. +/// +/// @details For manifolds whose `log` is the actual Riemannian logarithm, this +/// is the exact geodesic distance. For retraction-based logs it is a first-order +/// approximation. Used inside `discrete_geodesic` hot loops in place of +/// `distance_midpoint` because it is very cheap and sufficient for +/// convergence and progress checks. +template +inline auto distance_via_log(const M& m, const typename M::Point& a, const typename M::Point& b) -> + typename M::Scalar { + auto v = m.log(a, b); + return m.norm(a, v); +} + +/// @brief Midpoint distance surrogate with a generic runtime reliability guard. +/// +/// @details Computes the third-order-accurate midpoint distance +/// \f$\|\log_m(b) - \log_m(a)\|_m\f$ where +/// \f$m = \exp_a(\tfrac{1}{2}\log_a(b))\f$, and checks the Riemannian-midpoint +/// identity \f$\log_m(a) = -\log_m(b)\f$ — equivalently +/// \f$\|v_{ma} + v_{mb}\|_m \ll \|v_{mb} - v_{ma}\|_m\f$. When the relative +/// deviation exceeds `tau`, the midpoint is considered unreliable (see the +/// InterpolationSettings doc for scenarios) and the function returns the +/// first-order fallback \f$|\log_a(b)|_R\f$ instead. The boolean out-parameter +/// `tripped` reports which branch was taken so the caller can count fallbacks +/// for diagnostics. +/// +/// Used inside `natural_gradient_fd` where an accurate +/// \f$\nabla(\tfrac{1}{2}\,d^2)\f$ is required — the main-loop progress check +/// continues to use the cheaper `distance_via_log` directly. +template +inline auto distance_midpoint_fd(const M& m, const typename M::Point& a, + const typename M::Point& b, double tau, bool& tripped) -> + typename M::Scalar { + using Scalar = typename M::Scalar; + using Tangent = typename M::Tangent; + + const auto v_ab = m.log(a, b); + // Degenerate: a == b. Midpoint is trivially exact. + if (v_ab.squaredNorm() == Scalar{0}) { + tripped = false; + return Scalar{0}; + } + + const auto mid = m.exp(a, Scalar{0.5} * v_ab); + const auto v_ma = m.log(mid, a); + const auto v_mb = m.log(mid, b); + const Tangent v_diff = v_mb - v_ma; + const Tangent v_sum = v_mb + v_ma; + const Scalar d_mid = m.norm(mid, v_diff); + + // Guard: for a true Riemannian midpoint, v_ma = -v_mb, so ||v_sum|| should be + // tiny compared to ||v_diff||. When it isn't, fall back to |log|_R which is + // more robust though less accurate. + if (d_mid > Scalar{0}) { + const Scalar err = m.norm(mid, v_sum); + if (err > tau * d_mid) { + tripped = true; + return m.norm(a, v_ab); + } + } + tripped = false; + return d_mid; +} + +/// @brief Build an orthonormal tangent basis at `p` into `cache.basis_mat`. +/// +/// @details Seeds columns with ambient unit vectors (projected onto the tangent +/// space if the manifold provides `project`) and orthonormalizes via Euclidean +/// Gram-Schmidt. Returns the number of linearly independent basis vectors found (≤ `d`). +template +int build_tangent_basis(const M& m, const typename M::Point& p, int d, + InterpolationCache& cache) { + using Tangent = typename M::Tangent; + constexpr int N = Tangent::SizeAtCompileTime; + + const int ambient_dim = static_cast(p.size()); + cache.basis_mat.resize(ambient_dim, d); + + int col = 0; + for (int i = 0; i < ambient_dim && col < d; ++i) { + Tangent e_i; + if constexpr (N == Eigen::Dynamic) { + e_i = Tangent::Zero(ambient_dim); + } else { + e_i = Tangent::Zero(); + } + e_i[i] = 1.0; + + if constexpr (HasProject) { + e_i = m.project(p, e_i); + } + + // Euclidean Gram-Schmidt against existing basis columns. + for (int j = 0; j < col; ++j) { + const double dot = e_i.dot(cache.basis_mat.col(j)); + e_i -= dot * cache.basis_mat.col(j); + } + + const double nrm = e_i.norm(); + if (nrm > 1e-12) { + cache.basis_mat.col(col) = e_i / nrm; + ++col; + } + } + + if (col < d) { + cache.basis_mat.conservativeResize(Eigen::NoChange, col); + } + return col; +} + +/// @brief Compute the Riemannian natural gradient of \f$\tfrac{1}{2}\, d^2(\cdot, \text{target})\f$ +/// at `p` via finite differences. Writes the ambient-space gradient into `cache.v_fd`. +/// +/// @details The \f$d^2\f$ samples used for central differences go through +/// `distance_midpoint_fd`, a third-order-accurate midpoint surrogate with a +/// runtime guard that falls back per-sample to `|log|_R` when the Riemannian +/// midpoint identity is violated (see that function for the failure modes). +/// The count of fallbacks this call incurred is added to `*fallbacks_out` when +/// non-null, so the top-level result can report it. +/// +/// @return `true` on success, `false` on Cholesky failure or zero-rank basis. +template +bool natural_gradient_fd(const M& m, const typename M::Point& p, const typename M::Point& target, + double h, double guard_tau, InterpolationCache& cache, + int* fallbacks_out = nullptr) { + using Tangent = typename M::Tangent; + constexpr int N = Tangent::SizeAtCompileTime; + + const int d = build_tangent_basis(m, p, m.dim(), cache); + if (d == 0) { + if constexpr (N == Eigen::Dynamic) { + cache.v_fd = Tangent::Zero(p.size()); + } else { + cache.v_fd = Tangent::Zero(); + } + return false; + } + + cache.grad.resize(d); + cache.G.resize(d, d); + cache.alpha.resize(d); + + // 1) Coordinate gradient via central finite differences. Sample d^2 via the + // midpoint surrogate with guard; when the guard trips for either sample in a + // basis direction we recompute both via-log so the two terms of the central + // difference use the same surrogate (mixing would bias the quotient). + for (int i = 0; i < d; ++i) { + const auto p_plus = m.exp(p, h * cache.basis_mat.col(i)); + const auto p_minus = m.exp(p, -h * cache.basis_mat.col(i)); + bool tripped_plus = false; + bool tripped_minus = false; + double d_plus = distance_midpoint_fd(m, p_plus, target, guard_tau, tripped_plus); + double d_minus = distance_midpoint_fd(m, p_minus, target, guard_tau, tripped_minus); + if (tripped_plus || tripped_minus) { + if (!tripped_plus) d_plus = distance_via_log(m, p_plus, target); + if (!tripped_minus) d_minus = distance_via_log(m, p_minus, target); + if (fallbacks_out) ++(*fallbacks_out); + } + cache.grad(i) = (0.5 * d_plus * d_plus - 0.5 * d_minus * d_minus) / (2.0 * h); + } + GEODEX_LOG(" natural_gradient_fd grad=" << cache.grad.transpose()); + + // 2) Metric tensor G_ij = _p. Use batch path if the manifold + // provides `inner_matrix` (e.g., KineticEnergyMetric: one mass-matrix eval + // instead of d^2 scalar calls). + if constexpr (HasBatchInnerMatrix) { + const Eigen::MatrixXd B = cache.basis_mat.leftCols(d); + const Eigen::MatrixXd G_full = m.inner_matrix(p, B, B); + cache.G = 0.5 * (G_full + G_full.transpose()); // symmetrize against FP noise + } else { + for (int i = 0; i < d; ++i) { + for (int j = i; j < d; ++j) { + cache.G(i, j) = m.inner(p, cache.basis_mat.col(i), cache.basis_mat.col(j)); + cache.G(j, i) = cache.G(i, j); + } + } + } + GEODEX_LOG(" natural_gradient_fd G=\n" << cache.G); + + // 3) Scale-relative Tikhonov regularization + LLT solve. + const double trace = cache.G.diagonal().sum(); + const double reg = 1e-12 * std::max(1.0, trace / static_cast(d)); + cache.G.diagonal().array() += reg; + + auto solver = cache.G.llt(); + if (solver.info() != Eigen::Success) { + GEODEX_LOG(" natural_gradient_fd: LLT failed"); + if constexpr (N == Eigen::Dynamic) { + cache.v_fd = Tangent::Zero(p.size()); + } else { + cache.v_fd = Tangent::Zero(); + } + return false; + } + + cache.alpha = solver.solve(-cache.grad); + GEODEX_LOG(" natural_gradient_fd alpha=" << cache.alpha.transpose()); + + // 4) Reconstruct in ambient space: v_fd = B * alpha. + if constexpr (N == Eigen::Dynamic) { + cache.v_fd = cache.basis_mat.leftCols(d) * cache.alpha; + } else { + cache.v_fd.noalias() = cache.basis_mat.leftCols(d) * cache.alpha; + } + return true; +} + +/// @brief Resolve the initial step cap, optionally bounded by injectivity radius. +template +double initial_step_cap(const M& m, double requested_step_size) { + if constexpr (HasInjectivityRadius) { + const double inj = static_cast(m.injectivity_radius()); + if (std::isfinite(inj) && inj > 0.0) { + return std::min(requested_step_size, 0.5 * inj); + } + } + return requested_step_size; +} + +/// @brief Auto-select the FD central-difference step when the user passed 0. +/// +/// @details The optimal central-FD step for double precision is approximately +/// \f$\varepsilon_{\mathrm{mach}}^{1/3} \approx 6\times 10^{-6}\f$. We scale +/// gently with the initial distance so tiny workspaces don't get an FD step +/// that dwarfs the geometry. +inline double resolve_fd_epsilon(double user_value, double initial_distance) { + if (user_value > 0.0) return user_value; + return std::max(1e-8, 1e-5 * std::max(1.0, initial_distance)); +} + +} // namespace detail + +// --------------------------------------------------------------------------- +// discrete_geodesic +// --------------------------------------------------------------------------- + +/// @brief Walk from `start` toward `target` via Riemannian natural gradient descent. +/// +/// @details The algorithm iteratively descends on +/// \f$\varphi(x) = \tfrac{1}{2}\, d^2(x, \text{target})\f$ with step length capped +/// by `settings.step_size` per iteration. Each iteration tries the Riemannian +/// logarithm direction first (exploiting \f$\nabla\varphi = -\log_x(\text{target})\f$ +/// on any Riemannian manifold away from the cut locus) and verifies via a +/// progress check. When the log direction does not produce enough distance +/// decrease (e.g., because the retraction is a projection, or the metric is +/// custom), the algorithm falls back for that step to a central finite-difference +/// natural gradient computed from the manifold's `inner` product. +/// +/// The returned `InterpolationResult` carries the path, a termination status +/// enum, iteration count, and the initial/final distances — allowing callers to +/// distinguish successful convergence from `MaxStepsReached`, `CutLocus`, +/// `GradientVanished`, `StepShrunkToZero`, and `DegenerateInput`. +/// +/// **Walk semantics**: iteration count and path size both scale as +/// \f$\approx \text{initial\_distance} / \texttt{step\_size}\f$. Reduce +/// `step_size` for higher path resolution. +/// +/// @note See Kyaw, P. T., & Kelly, J. (2026). *Geometry-Aware Sampling-Based +/// Motion Planning on Riemannian Manifolds.* arXiv:2602.00992. The identity +/// \f$\nabla_g(\tfrac{1}{2}\, d_g^2(\cdot, q))(x) = -\log_x^g(q)\f$ is standard; +/// see Sakai, *Riemannian Geometry*, §IV.5 and do Carmo, *Riemannian Geometry*, +/// Ch 13 Prop 3.6. +/// +/// @tparam M A type satisfying `RiemannianManifold`. +/// @param manifold The manifold instance. +/// @param start Starting point. +/// @param target Target point to walk toward. +/// @param settings Algorithm parameters. +/// @param cache Optional reusable cache. If null, a stack-local one is used. +/// @return An `InterpolationResult` carrying the path and termination diagnostics. +template +auto discrete_geodesic(const M& manifold, const typename M::Point& start, + const typename M::Point& target, InterpolationSettings settings = {}, + InterpolationCache* cache = nullptr) + -> InterpolationResult { + using Point = typename M::Point; + using Tangent = typename M::Tangent; + using Result = InterpolationResult; + + Result R; + /// Default reserve cap: avoid over-allocating when max_steps is very large. + static constexpr int kDefaultPathReserve = 128; + R.path.reserve(std::min(settings.max_steps + 1, kDefaultPathReserve)); + R.path.push_back(start); + + // Cache: either the caller-supplied one or a stack-local default. + InterpolationCache stack_cache; + InterpolationCache& C = cache ? *cache : stack_cache; + C.reset(static_cast(start.size()), manifold.dim()); + + GEODEX_LOG("=== discrete_geodesic start ==="); + GEODEX_LOG("start=" << start.transpose() << " target=" << target.transpose()); + + // Initial distance via |log(start, target)|_R — exact for Riemannian-log manifolds, + // first-order approximation otherwise. + Tangent v_log = manifold.log(start, target); + double dist = manifold.norm(start, v_log); + R.initial_distance = dist; + R.final_distance = dist; + + // Early exits: degenerate input, tolerance already met, or cut locus. + { + const double ambient_gap = (target - start).norm(); + if (ambient_gap == 0.0) { + R.status = InterpolationStatus::DegenerateInput; + GEODEX_LOG("=== discrete_geodesic done (DegenerateInput) ==="); + return R; + } + if (dist < settings.cut_locus_eps && ambient_gap > 1e-10) { + R.status = InterpolationStatus::CutLocus; + GEODEX_LOG("=== discrete_geodesic done (CutLocus) ==="); + return R; + } + if (dist <= settings.convergence_tol) { + R.status = InterpolationStatus::Converged; + GEODEX_LOG("=== discrete_geodesic done (already within tol) ==="); + return R; + } + } + + const double fd_eps = detail::resolve_fd_epsilon(settings.fd_epsilon, dist); + double step_cap = detail::initial_step_cap(manifold, settings.step_size); + const double initial_distance = dist; + // Resolved once per call: is the base log the Riemannian log of the metric? + // `is_riemannian_log` collapses the compile-time (`M::has_riemannian_log`) + // and runtime (`m.has_riemannian_log_runtime()`) signals into one bool. + const bool fast_path_enabled = + settings.force_log_direction || geodex::is_riemannian_log(manifold); + + Point current = start; + + for (int i = 0; i < settings.max_steps; ++i) { + GEODEX_LOG("--- step " << i << ": current=" << current.transpose() << " dist=" << dist + << " step_cap=" << step_cap); + + // Convergence on absolute and relative thresholds. + if (dist <= settings.convergence_tol || dist <= settings.convergence_rel * initial_distance) { + R.status = InterpolationStatus::Converged; + break; + } + + // log may vanish at a stationary point that's not the target (cut locus or + // symmetry). Either way, we can't descend further. + if (dist < settings.gradient_eps) { + R.status = InterpolationStatus::CutLocus; + break; + } + + const double step_used = std::min(step_cap, dist); + + Tangent direction; + Point proposed; + Tangent new_v_log; + double new_dist = 0.0; + bool accepted = false; + + // Runtime branch: when `fast_path_enabled` is true the base `log` is the + // Riemannian log of the metric and `-log` is the natural gradient of + // (1/2) d^2. Otherwise we use finite differences to compute the correct + // natural gradient under the (possibly custom) metric. For manifolds with + // compile-time opt-in the branch predictor collapses this into a + // branchless fast path. + if (fast_path_enabled) { + direction = (1.0 / dist) * v_log; + proposed = manifold.exp(current, step_used * direction); + new_v_log = manifold.log(proposed, target); + new_dist = manifold.norm(proposed, new_v_log); + + // Verify: did we actually get closer, and did the retraction deliver a + // step close to the intended length? + const bool progress_ok = (new_dist < dist); + const double actual_step = detail::distance_via_log(manifold, current, proposed); + const bool fidelity_ok = (actual_step <= settings.distortion_ratio * step_used); + accepted = (progress_ok && fidelity_ok); + + if (!accepted) { + GEODEX_LOG(" log step rejected (progress_ok=" << progress_ok << " fidelity_ok=" + << fidelity_ok << "); trying FD"); + } + } + + // --- FD natural gradient. Always used when the manifold does not provide a + // Riemannian log; used as a fallback when the log-step verification fails. --- + if (!accepted) { + if (!detail::natural_gradient_fd(manifold, current, target, fd_eps, + settings.fd_midpoint_guard_tau, C, + &R.fd_midpoint_fallbacks)) { + R.status = InterpolationStatus::GradientVanished; + break; + } + const double fd_norm = manifold.norm(current, C.v_fd); + if (fd_norm < settings.gradient_eps) { + R.status = InterpolationStatus::GradientVanished; + break; + } + direction = (1.0 / fd_norm) * C.v_fd; + proposed = manifold.exp(current, step_used * direction); + new_v_log = manifold.log(proposed, target); + new_dist = manifold.norm(proposed, new_v_log); + + const bool progress_ok = (new_dist < dist); + const double actual_step = detail::distance_via_log(manifold, current, proposed); + const bool fidelity_ok = (actual_step <= settings.distortion_ratio * step_used); + + if (!progress_ok || !fidelity_ok) { + // FD descent at this step cap still over-shoots or makes no progress — + // halve the cap and retry the iteration. + step_cap *= 0.5; + ++R.distortion_halvings; + GEODEX_LOG(" FD rejected; halving step_cap -> " << step_cap); + if (step_cap < settings.min_step_size) { + R.status = InterpolationStatus::StepShrunkToZero; + break; + } + --i; + continue; + } + } + + // Accept the step. + current = proposed; + R.path.push_back(current); + ++R.iterations; + + // Reuse the log computation we already did for the NEXT iteration. + v_log = std::move(new_v_log); + dist = new_dist; + R.final_distance = dist; + + // Regrow step cap after a successful iteration. + step_cap = std::min(settings.step_size, settings.growth_factor * step_cap); + } + + // Post-loop status resolution. If we exhausted max_steps without ever setting + // a terminal status, report MaxStepsReached. + if (R.status == InterpolationStatus::Converged && R.iterations == settings.max_steps && + dist > settings.convergence_tol && dist > settings.convergence_rel * initial_distance) { + R.status = InterpolationStatus::MaxStepsReached; + } + + GEODEX_LOG("=== discrete_geodesic done, " << R.path.size() + << " points, status=" << to_string(R.status) << " ==="); + return R; +} + +} // namespace geodex diff --git a/include/geodex/algorithm/path_smoothing.hpp b/include/geodex/algorithm/path_smoothing.hpp new file mode 100644 index 0000000..f6bbbe9 --- /dev/null +++ b/include/geodex/algorithm/path_smoothing.hpp @@ -0,0 +1,562 @@ +/// @file path_smoothing.hpp +/// @brief Metric-aware path smoothing: shortcutting + L-BFGS energy minimization. +/// +/// @details Two-phase path improvement for planner output: +/// 1. **Shortcutting**: randomly remove redundant vertices while maintaining or +/// reducing metric energy, with collision checking along manifold geodesics. +/// 2. **L-BFGS smoothing**: minimize the discrete path energy with collision +/// constraints in the Armijo line search. + +#pragma once + +#include +#include + +#include +#include +#include + +#include + +#include "geodex/algorithm/interpolation.hpp" +#include "geodex/core/concepts.hpp" +#include "geodex/core/metric.hpp" + +namespace geodex::algorithm { + +// --------------------------------------------------------------------------- +// Settings and result types +// --------------------------------------------------------------------------- + +/// @brief Settings for metric-aware path smoothing. +struct PathSmoothingSettings { + // --- Shortcutting phase --- + int max_shortcut_attempts = 200; ///< Random shortcut attempts. + int edge_collision_samples = 10; ///< Minimum geodesic samples per edge for collision. + double collision_resolution = 0.1; ///< Max spacing (meters) between collision checks. + + // --- L-BFGS energy smoothing phase --- + int lbfgs_target_segments = 64; ///< Upsample resolution for L-BFGS. + int lbfgs_max_iterations = 200; ///< Max L-BFGS iterations. + double grad_tol = 1e-8; ///< Convergence: gradient infinity norm. + double energy_tol = 1e-10; ///< Convergence: relative energy change. + double fd_epsilon = 1e-7; ///< Finite difference step for dM/dq. + int lbfgs_memory = 7; ///< L-BFGS history size. + double armijo_c = 1e-4; ///< Armijo sufficient decrease parameter. + + /// @brief Trust region radius per waypoint (coordinate units). 0 disables. + /// + /// @details Bounds how far each interior waypoint can drift from its initial + /// (upsampled) position during L-BFGS. Disabled by default because the + /// initial upsample uses straight-line midpoints between raw waypoints — on + /// a curved Riemannian geodesic these midpoints are offset from the true + /// geodesic, and clamping them prevents L-BFGS from converging to a smooth + /// curve (it gets stuck with zig-zag between initial and target positions). + /// Set to a positive value if you need a hard cap on per-waypoint drift. + double max_displacement = 0.0; + int armijo_max_backtracks = 30; ///< Max bisection steps in Armijo line search. + + // --- Discrete geodesic densification --- + InterpolationSettings interp; ///< Settings for discrete_geodesic between waypoints. +}; + +/// @brief Result of path smoothing. +template +struct PathSmoothingResult { + std::vector path; ///< Smoothed path (including endpoints). + double energy = 0.0; ///< Discrete energy of the result. + double distance = 0.0; ///< Geodesic distance estimate (sqrt(energy)). + int vertices_removed = 0; ///< Vertices removed in shortcutting phase. + int smooth_iterations = 0; ///< L-BFGS iterations in smoothing phase. + bool collision_free = true; ///< Whether final path passed validation. +}; + +namespace detail { + +// --------------------------------------------------------------------------- +// Mass matrix synthesis from manifold inner product +// --------------------------------------------------------------------------- + +/// @brief Build the Gram matrix (mass matrix) from the manifold's inner product. +/// +/// @details Evaluates \f$ G_{ij} = \langle e_i, e_j \rangle_q \f$ where +/// \f$ e_i \f$ are the standard basis vectors. +template +Eigen::MatrixXd gram_matrix(const M& manifold, const Eigen::VectorXd& q_vec) { + const int d = manifold.dim(); + typename M::Point q; + if constexpr (M::Point::SizeAtCompileTime == Eigen::Dynamic) { + q.resize(d); + } + for (int i = 0; i < d; ++i) q[i] = q_vec[i]; + + if constexpr (HasBatchInnerMatrix) { + const Eigen::MatrixXd I = Eigen::MatrixXd::Identity(d, d); + Eigen::MatrixXd G = manifold.inner_matrix(q, I, I); + return 0.5 * (G + G.transpose()); // symmetrize against FP noise + } else { + Eigen::MatrixXd G(d, d); + for (int i = 0; i < d; ++i) { + typename M::Tangent ei; + if constexpr (M::Tangent::SizeAtCompileTime == Eigen::Dynamic) { + ei = M::Tangent::Zero(d); + } else { + ei = M::Tangent::Zero(); + } + ei[i] = 1.0; + for (int j = i; j < d; ++j) { + typename M::Tangent ej; + if constexpr (M::Tangent::SizeAtCompileTime == Eigen::Dynamic) { + ej = M::Tangent::Zero(d); + } else { + ej = M::Tangent::Zero(); + } + ej[j] = 1.0; + G(i, j) = G(j, i) = manifold.inner(q, ei, ej); + } + } + return G; + } +} + +// --------------------------------------------------------------------------- +// L-BFGS infrastructure +// --------------------------------------------------------------------------- + +/// @brief Compute energy of a single segment using manifold log. +template +double segment_energy(const M& manifold, const Eigen::VectorXd& a, const Eigen::VectorXd& b) { + const int d = manifold.dim(); + typename M::Point pa, pb; + if constexpr (M::Point::SizeAtCompileTime == Eigen::Dynamic) { + pa.resize(d); + pb.resize(d); + } + for (int i = 0; i < d; ++i) { + pa[i] = a[i]; + pb[i] = b[i]; + } + const auto v = manifold.log(pa, pb); + return manifold.inner(pa, v, v); +} + +/// @brief Discrete Dirichlet energy: \f$ N \sum_{k=0}^{N-1} \|\log_{q_k}(q_{k+1})\|^2 \f$. +/// +/// @details Standard finite-difference approximation of the continuous Riemannian +/// energy functional \f$ E[\gamma] = \int_0^1 \|\dot\gamma(t)\|^2\,dt \f$. +/// Minimizers converge to geodesics as \f$ N \to \infty \f$. +template +double dirichlet_energy(const M& manifold, const std::vector& path) { + const int N = static_cast(path.size()) - 1; + double E = 0.0; + for (int k = 0; k < N; ++k) { + E += segment_energy(manifold, path[k], path[k + 1]); + } + return N * E; +} + +/// @brief Compute energy gradient via FD, using manifold log for energy. +template +Eigen::VectorXd compute_gradient(const M& manifold, std::vector& path, + double fd_eps) { + const int N = static_cast(path.size()) - 1; + const int n = static_cast(path[0].size()); + const int n_interior = N - 1; + Eigen::VectorXd grad = Eigen::VectorXd::Zero(n_interior * n); + + for (int i = 1; i < N; ++i) { + for (int j = 0; j < n; ++j) { + // Only segments (i-1,i) and (i,i+1) depend on path[i]. + path[i][j] += fd_eps; + const double E_plus = segment_energy(manifold, path[i - 1], path[i]) + + segment_energy(manifold, path[i], path[i + 1]); + path[i][j] -= 2.0 * fd_eps; + const double E_minus = segment_energy(manifold, path[i - 1], path[i]) + + segment_energy(manifold, path[i], path[i + 1]); + path[i][j] += fd_eps; // restore + + grad[(i - 1) * n + j] = N * (E_plus - E_minus) / (2.0 * fd_eps); + } + } + return grad; +} + +inline Eigen::VectorXd pack_interior(const std::vector& path) { + const int N = static_cast(path.size()) - 1; + const int n = static_cast(path[0].size()); + Eigen::VectorXd x((N - 1) * n); + for (int i = 1; i < N; ++i) { + x.segment((i - 1) * n, n) = path[i]; + } + return x; +} + +inline void unpack_interior(const Eigen::VectorXd& x, std::vector& path) { + const int N = static_cast(path.size()) - 1; + const int n = static_cast(path[0].size()); + for (int i = 1; i < N; ++i) { + path[i] = x.segment((i - 1) * n, n); + } +} + +/// @brief L-BFGS two-loop recursion for search direction. +inline Eigen::VectorXd lbfgs_direction(const Eigen::VectorXd& grad, + const std::vector& s_hist, + const std::vector& y_hist) { + const int m = static_cast(s_hist.size()); + if (m == 0) return -grad; + + Eigen::VectorXd q = grad; + std::vector alpha(m), rho(m); + + for (int i = m - 1; i >= 0; --i) { + rho[i] = 1.0 / y_hist[i].dot(s_hist[i]); + alpha[i] = rho[i] * s_hist[i].dot(q); + q -= alpha[i] * y_hist[i]; + } + + const double gamma = s_hist.back().dot(y_hist.back()) / y_hist.back().dot(y_hist.back()); + Eigen::VectorXd r = gamma * q; + + for (int i = 0; i < m; ++i) { + const double beta = rho[i] * y_hist[i].dot(r); + r += (alpha[i] - beta) * s_hist[i]; + } + return -r; +} + +/// @brief Insert evenly-spaced geodesic points to increase path resolution. +/// +/// @param manifold The manifold instance. +/// @param path Input path. +/// @param subdivisions Intermediate points per edge (1 = double, 2 = triple, etc.). +/// @return Refined path with (N * (subdivisions + 1) + 1) points from original N+1. +/// +/// @note Uses the base manifold's geodesic() for midpoint insertion. For non-identity +/// metrics the midpoints are approximate; the L-BFGS optimizer corrects them. Using +/// discrete_geodesic here would be correct but prohibitively expensive in the inner loop. +template +std::vector upsample(const M& manifold, const std::vector& path, + const int subdivisions = 1) { + const int d = manifold.dim(); + std::vector refined; + refined.reserve(path.size() + (path.size() - 1) * subdivisions); + for (std::size_t i = 0; i < path.size(); ++i) { + refined.push_back(path[i]); + if (i + 1 < path.size()) { + typename M::Point pa, pb; + if constexpr (M::Point::SizeAtCompileTime == Eigen::Dynamic) { + pa.resize(d); + pb.resize(d); + } + for (int j = 0; j < d; ++j) { + pa[j] = path[i][j]; + pb[j] = path[i + 1][j]; + } + for (int s = 1; s <= subdivisions; ++s) { + const double t = static_cast(s) / (subdivisions + 1); + const auto mid = manifold.geodesic(pa, pb, t); + Eigen::VectorXd mid_vec(d); + for (int j = 0; j < d; ++j) mid_vec[j] = mid[j]; + refined.push_back(mid_vec); + } + } + } + return refined; +} + +/// @brief Collision-constrained Armijo line search. +/// +/// @note Uses the base manifold's geodesic() for edge collision checks. For non-identity +/// metrics the intermediate samples are approximate; see upsample() for rationale. +template +double armijo_constrained(const M& manifold, const ValidityFn& validity_fn, + std::vector& path, const Eigen::VectorXd& x, + const Eigen::VectorXd& dir, const Eigen::VectorXd& grad, const double f0, + const PathSmoothingSettings& settings, const Eigen::VectorXd& ref_x) { + double step = 1.0; + const double slope = grad.dot(dir); + if (slope >= 0) return 0.0; + + const int N = static_cast(path.size()) - 1; + const int n = static_cast(path[0].size()); + const int n_interior = N - 1; + + for (int iter = 0; iter < settings.armijo_max_backtracks; ++iter) { + Eigen::VectorXd x_new = x + step * dir; + + // Trust region check. + if (settings.max_displacement > 0.0) { + bool within = true; + for (int k = 0; k < n_interior && within; ++k) { + const double disp = (x_new.segment(k * n, n) - ref_x.segment(k * n, n)).norm(); + if (disp > settings.max_displacement) within = false; + } + if (!within) { + step *= 0.5; + continue; + } + } + + unpack_interior(x_new, path); + + // Point collision check. + bool valid = true; + for (const auto& q : path) { + typename M::Point p; + if constexpr (M::Point::SizeAtCompileTime == Eigen::Dynamic) { + p.resize(n); + } + for (int i = 0; i < n; ++i) p[i] = q[i]; + if (!validity_fn(p)) { + valid = false; + break; + } + } + if (!valid) { + step *= 0.5; + continue; + } + + // Edge collision check via manifold geodesic. + for (int k = 0; k < N && valid; ++k) { + typename M::Point a, b; + if constexpr (M::Point::SizeAtCompileTime == Eigen::Dynamic) { + a.resize(n); + b.resize(n); + } + for (int i = 0; i < n; ++i) { + a[i] = path[k][i]; + b[i] = path[k + 1][i]; + } + for (int s = 1; s <= settings.edge_collision_samples; ++s) { + const double t = static_cast(s) / (settings.edge_collision_samples + 1); + const auto mid = manifold.geodesic(a, b, t); + if (!validity_fn(mid)) { + valid = false; + break; + } + } + } + if (!valid) { + step *= 0.5; + continue; + } + + // Armijo energy decrease. + const double f_new = dirichlet_energy(manifold, path); + if (f_new <= f0 + settings.armijo_c * step * slope) { + return step; + } + step *= 0.5; + } + + unpack_interior(x, path); + return 0.0; +} + +/// @brief Collision-constrained L-BFGS energy minimization. +template +int optimize_constrained(const M& manifold, const ValidityFn& validity_fn, + std::vector& path, const PathSmoothingSettings& settings, + const Eigen::VectorXd& ref_x) { + const int N = static_cast(path.size()) - 1; + const int n = static_cast(path[0].size()); + const int n_vars = (N - 1) * n; + if (n_vars == 0) return 0; + + Eigen::VectorXd x = pack_interior(path); + double f = dirichlet_energy(manifold, path); + Eigen::VectorXd grad = compute_gradient(manifold, path, settings.fd_epsilon); + + std::vector s_hist, y_hist; + int iter = 0; + + for (; iter < settings.lbfgs_max_iterations; ++iter) { + const double grad_norm = grad.cwiseAbs().maxCoeff(); + if (grad_norm < settings.grad_tol) break; + + const Eigen::VectorXd dir = lbfgs_direction(grad, s_hist, y_hist); + + const Eigen::VectorXd x_old = x; + const double f_old = f; + const Eigen::VectorXd grad_old = grad; + + const double step = + armijo_constrained(manifold, validity_fn, path, x, dir, grad, f, settings, ref_x); + if (step == 0.0) break; + + x = x_old + step * dir; + unpack_interior(x, path); + f = dirichlet_energy(manifold, path); + grad = compute_gradient(manifold, path, settings.fd_epsilon); + + if (std::abs(f - f_old) < settings.energy_tol * std::abs(f_old) && f_old > 0) break; + + // Update L-BFGS history. + Eigen::VectorXd s = x - x_old; + Eigen::VectorXd y = grad - grad_old; + const double sy = s.dot(y); + if (sy > 1e-16) { + if (static_cast(s_hist.size()) >= settings.lbfgs_memory) { + s_hist.erase(s_hist.begin()); + y_hist.erase(y_hist.begin()); + } + s_hist.push_back(std::move(s)); + y_hist.push_back(std::move(y)); + } + } + return iter; +} + +// --------------------------------------------------------------------------- +// Shortcutting +// --------------------------------------------------------------------------- + +/// @brief Metric-aware randomized shortcutting with collision checking along geodesics. +template +int shortcut(const M& manifold, const ValidityFn& validity_fn, std::vector& path, + int min_edge_samples, double collision_resolution, int max_attempts) { + int total_removed = 0; + std::mt19937 rng(42); + + for (int attempt = 0; attempt < max_attempts; ++attempt) { + const int n = static_cast(path.size()); + if (n <= 2) break; + + std::uniform_int_distribution dist(0, n - 1); + int i = dist(rng), j = dist(rng); + if (i > j) std::swap(i, j); + if (j - i < 2) continue; + + // Compare arc lengths. Direct connection must be meaningfully shorter than + // the sub-path under the configured metric. A small margin avoids spurious + // shortcuts on already-smooth paths (where d_direct ≈ Σ d_k by triangle + // inequality), which would discard good RRT*/RRT geometry — particularly + // costly for ConfigurationSpace with point-dependent metrics where the + // straight-line direct can hide an expensive region between the endpoints. + double L_sub = 0.0; + for (int k = i; k < j; ++k) { + L_sub += static_cast(manifold.distance(path[k], path[k + 1])); + } + const double L_direct = static_cast(manifold.distance(path[i], path[j])); + if (L_direct >= 0.95 * L_sub) continue; + + // Scale collision checks with edge length to avoid missing obstacles. + // Ambient-coordinate distance (matches `collision_resolution` units). + const double coord_dist = (path[j] - path[i]).norm(); + const int n_checks = + std::max(min_edge_samples, static_cast(std::ceil(coord_dist / collision_resolution))); + + // Collision check along geodesic shortcut. + bool valid = true; + for (int s = 1; s <= n_checks; ++s) { + const double t = static_cast(s) / (n_checks + 1); + const auto mid = manifold.geodesic(path[i], path[j], t); + if (!validity_fn(mid)) { + valid = false; + break; + } + } + if (!valid) continue; + + // Accept: remove intermediate vertices. + const int removed = j - i - 1; + path.erase(path.begin() + i + 1, path.begin() + j); + total_removed += removed; + } + return total_removed; +} + +} // namespace detail + +// --------------------------------------------------------------------------- +// Public API +// --------------------------------------------------------------------------- + +/// @brief Smooth a collision-free path using metric-aware shortcutting and +/// collision-constrained L-BFGS energy minimization. +/// +/// @details Two-phase pipeline: +/// 1. **Shortcutting**: randomly picks non-adjacent vertex pairs and replaces +/// the sub-path with a direct geodesic when the shortcut has lower energy +/// and is collision-free. +/// 2. **L-BFGS smoothing**: upsamples the path and minimizes discrete energy +/// \f$ N \sum_k d_k^\top M(m_k) d_k \f$ with collision constraints in the +/// Armijo line search. +/// +/// @tparam M A type satisfying `RiemannianManifold`. +/// @tparam ValidityFn Callable with signature `bool(const Point&)`. Returns +/// true if the configuration is collision-free. +/// @param manifold The manifold instance. +/// @param validity_fn Collision checker. +/// @param initial_path Collision-free path from planner (>= 2 waypoints). +/// @param settings Smoothing parameters. +/// @return PathSmoothingResult with smoothed path, energy, and diagnostics. +template +PathSmoothingResult smooth_path( + const M& manifold, const ValidityFn& validity_fn, + const std::vector& initial_path, PathSmoothingSettings settings = {}) { + using Point = typename M::Point; + assert(initial_path.size() >= 2); + + PathSmoothingResult result; + + if (initial_path.size() < 3) { + result.path = initial_path; + return result; + } + + const int d = manifold.dim(); + + // Phase 1: Shortcutting — remove redundant vertices along manifold geodesics. + std::vector shortcut_path = initial_path; + result.vertices_removed = + detail::shortcut(manifold, validity_fn, shortcut_path, settings.edge_collision_samples, + settings.collision_resolution, settings.max_shortcut_attempts); + + // Convert to VectorXd. + std::vector vpath(shortcut_path.size()); + for (std::size_t i = 0; i < shortcut_path.size(); ++i) { + vpath[i] = Eigen::VectorXd(d); + for (int j = 0; j < d; ++j) vpath[i][j] = shortcut_path[i][j]; + } + + // Upsample with manifold geodesic midpoints — skip when the raw input is + // already at or above the target resolution. Preserves the raw path shape for + // dense, near-optimal inputs (e.g., minimum-energy planning output). + if (static_cast(vpath.size()) - 1 < settings.lbfgs_target_segments) { + while (static_cast(vpath.size()) - 1 < settings.lbfgs_target_segments) { + vpath = detail::upsample(manifold, vpath); + } + } + + // Save reference for trust region — keeps result close to raw path. + const Eigen::VectorXd ref_x = detail::pack_interior(vpath); + + // L-BFGS energy minimization with collision constraints. + result.smooth_iterations = + detail::optimize_constrained(manifold, validity_fn, vpath, settings, ref_x); + + // Convert back. + std::vector path(vpath.size()); + for (std::size_t i = 0; i < vpath.size(); ++i) { + if constexpr (Point::SizeAtCompileTime == Eigen::Dynamic) { + path[i].resize(d); + } + for (int j = 0; j < d; ++j) path[i][j] = vpath[i][j]; + } + + result.energy = 0.0; + for (std::size_t k = 0; k + 1 < path.size(); ++k) { + const double dd = manifold.distance(path[k], path[k + 1]); + result.energy += dd * dd; + } + result.energy *= static_cast(path.size() - 1); + result.distance = std::sqrt(std::max(result.energy, 0.0)); + result.path = std::move(path); + + return result; +} + +} // namespace geodex::algorithm diff --git a/include/geodex/collision/circle_sdf.hpp b/include/geodex/collision/circle_sdf.hpp new file mode 100644 index 0000000..2aa59c8 --- /dev/null +++ b/include/geodex/collision/circle_sdf.hpp @@ -0,0 +1,112 @@ +/// @file circle_sdf.hpp +/// @brief Signed distance fields for circular obstacles. +/// +/// Provides a single-circle SDF and a log-sum-exp smooth-min combiner for +/// multiple circles. The smooth SDF is suitable for use with SDFConformalMetric +/// to bias planning away from obstacles. + +#pragma once + +#include + +#include +#include + +#include "geodex/utils/math.hpp" + +namespace geodex::collision { + +/// @brief Signed distance to a single circular obstacle. +/// +/// Returns positive values in free space and negative inside the circle: +/// \f$ \mathrm{sdf}(q) = \|q_{xy} - c\| - r \f$ +class CircleSDF { + public: + CircleSDF(const double cx, const double cy, const double radius) + : cx_(cx), cy_(cy), radius_(radius), radius_sq_(radius * radius) {} + + /// @brief Evaluate signed distance from point to circle boundary. + template + double operator()(const Point& q) const { + const double dx = q[0] - cx_, dy = q[1] - cy_; + return std::sqrt(dx * dx + dy * dy) - radius_; + } + + /// @brief X-coordinate of the circle center. + double cx() const { return cx_; } + /// @brief Y-coordinate of the circle center. + double cy() const { return cy_; } + /// @brief Radius of the circle. + double radius() const { return radius_; } + /// @brief Squared radius of the circle. + double radius_sq() const { return radius_sq_; } + + private: + double cx_, cy_, radius_, radius_sq_; +}; + +/// @brief Log-sum-exp smooth-min SDF over a collection of circular obstacles. +/// +/// Produces a smooth approximation to the minimum signed distance across all +/// circles. The smoothing parameter @p beta controls how closely the smooth-min +/// approximates the hard minimum (higher values give a tighter approximation +/// but sharper gradient transitions). +/// +/// The numerically stable computation is: +/// \f[ +/// \mathrm{sdf}(q) = -\frac{1}{\beta}\left(m + \ln\sum_i +/// \exp(-\beta\,d_i - m)\right), \quad m = \max_i(-\beta\,d_i) +/// \f] +class CircleSmoothSDF { + public: + /// @brief Construct from a list of circles and smoothing parameter. + CircleSmoothSDF(std::vector circles, const double beta = 20.0) + : circles_(std::move(circles)), beta_(beta) {} + + /// @brief Evaluate smooth signed distance at point (x, y). + template + double operator()(const Point& q) const { + if (circles_.empty()) return std::numeric_limits::max(); + + const auto n = circles_.size(); + + // Single-pass: compute and cache -beta * d_i, track max for stability. + thread_local std::vector neg_bd; + neg_bd.resize(n); + + double max_neg = std::numeric_limits::lowest(); + for (size_t i = 0; i < n; ++i) { + neg_bd[i] = -beta_ * circles_[i](q); + max_neg = std::max(max_neg, neg_bd[i]); + } + + // Accumulate exp(-beta * d_i - max_neg) from cached values. + double sum = 0.0; + for (size_t i = 0; i < n; ++i) { + sum += utils::fast_exp(neg_bd[i] - max_neg); + } + + return -(max_neg + std::log(sum)) / beta_; + } + + /// @brief Check if a point is outside all circles (binary collision test). + template + bool is_free(const Point& q) const { + for (const auto& c : circles_) { + const double dx = q[0] - c.cx(), dy = q[1] - c.cy(); + if (dx * dx + dy * dy <= c.radius_sq()) return false; + } + return true; + } + + /// @brief Get the underlying circle obstacles. + const std::vector& circles() const { return circles_; } + /// @brief Get the log-sum-exp smoothing parameter. + double beta() const { return beta_; } + + private: + std::vector circles_; + double beta_; +}; + +} // namespace geodex::collision diff --git a/include/geodex/collision/collision.hpp b/include/geodex/collision/collision.hpp new file mode 100644 index 0000000..b6c4f87 --- /dev/null +++ b/include/geodex/collision/collision.hpp @@ -0,0 +1,17 @@ +/// @file collision.hpp +/// @brief Umbrella include for the geodex::collision module. +/// +/// Includes all collision primitives: +/// - CircleSDF, CircleSmoothSDF +/// - RectObstacle, RectSmoothSDF, rects_overlap +/// - DistanceGrid, GridSDF, InflatedSDF +/// - PolygonFootprint +/// - FootprintGridChecker + +#pragma once + +#include "geodex/collision/circle_sdf.hpp" +#include "geodex/collision/distance_grid.hpp" +#include "geodex/collision/footprint_grid_checker.hpp" +#include "geodex/collision/polygon_footprint.hpp" +#include "geodex/collision/rectangle_sdf.hpp" diff --git a/include/geodex/collision/distance_grid.hpp b/include/geodex/collision/distance_grid.hpp new file mode 100644 index 0000000..fd7b682 --- /dev/null +++ b/include/geodex/collision/distance_grid.hpp @@ -0,0 +1,293 @@ +/// @file distance_grid.hpp +/// @brief 2D distance transform grid with bilinear interpolation and batch queries. +/// +/// Provides: +/// - DistanceGrid: occupancy grid distance field (load from file or construct) +/// - GridSDF: callable wrapper for SDFConformalMetric +/// - InflatedSDF: generic SDF inflation wrapper + +#pragma once + +#include + +#include +#include +#include +#include +#include + +#include "geodex/utils/math.hpp" + +#ifdef __ARM_NEON +#include +#elif defined(__SSE2__) +#include +#endif + +namespace geodex::collision { + +// --------------------------------------------------------------------------- +// Distance grid +// --------------------------------------------------------------------------- + +/// @brief A 2D precomputed distance transform with bilinear interpolation. +/// +/// Stores obstacle distances at regular grid points. Queried in world +/// coordinates (meters); returns interpolated distance to nearest obstacle. +/// Positive = free space, zero/negative = obstacle. +class DistanceGrid { + public: + DistanceGrid() = default; + + /// @brief Construct from raw data. + /// @param width Grid width in cells. + /// @param height Grid height in cells. + /// @param resolution Meters per cell. + /// @param data Row-major distance values: data[r * width + c]. + DistanceGrid(const int width, const int height, const double resolution, std::vector data) + : width_(width), height_(height), resolution_(resolution), data_(std::move(data)) {} + + /// @brief Load from the geodex distance transform file format. + /// + /// Format: `width height resolution` on the first line, followed by + /// `height * width` double values in row-major order. + bool load(const std::string& filename) { + std::ifstream in(filename); + if (!in) { + std::cerr << "Error: cannot open " << filename << "\n"; + return false; + } + in >> width_ >> height_ >> resolution_; + data_.resize(static_cast(width_) * height_); + for (int r = 0; r < height_; ++r) { + for (int c = 0; c < width_; ++c) { + in >> data_[static_cast(r) * width_ + c]; + } + } + if (!in) { + std::cerr << "Error: failed to read distance grid data\n"; + return false; + } + return true; + } + + /// @brief Query distance at world coordinates using bilinear interpolation. + double distance_at(const double x_m, const double y_m) const { + const double cx = std::clamp(x_m / resolution_, 0.0, static_cast(width_ - 1)); + const double cy = std::clamp(y_m / resolution_, 0.0, static_cast(height_ - 1)); + + const int c0 = static_cast(std::floor(cx)); + const int r0 = static_cast(std::floor(cy)); + const int c1 = std::min(c0 + 1, width_ - 1); + const int r1 = std::min(r0 + 1, height_ - 1); + + const double fx = cx - c0; + const double fy = cy - r0; + + const double d00 = data_[static_cast(r0) * width_ + c0]; + const double d10 = data_[static_cast(r0) * width_ + c1]; + const double d01 = data_[static_cast(r1) * width_ + c0]; + const double d11 = data_[static_cast(r1) * width_ + c1]; + + return (1.0 - fx) * (1.0 - fy) * d00 + fx * (1.0 - fy) * d10 + (1.0 - fx) * fy * d01 + + fx * fy * d11; + } + + /// @brief Batch query: evaluate distance at N world-coordinate points. + /// + /// On ARM NEON and x86 SSE2, processes 2 points per iteration with + /// vectorized bilinear interpolation math. Grid value gathering remains + /// scalar on both architectures. + void distance_at_batch(const double* x, const double* y, double* out, const int n) const { + const double inv_res = 1.0 / resolution_; + const double max_cx = static_cast(width_ - 1); + const double max_cy = static_cast(height_ - 1); + +#ifdef __ARM_NEON + const float64x2_t vinv = vdupq_n_f64(inv_res); + const float64x2_t vzero = vdupq_n_f64(0.0); + const float64x2_t vmcx = vdupq_n_f64(max_cx); + const float64x2_t vmcy = vdupq_n_f64(max_cy); + const float64x2_t vone = vdupq_n_f64(1.0); + + const int n2 = n & ~1; + for (int i = 0; i < n2; i += 2) { + // Convert to grid coords and clamp. + float64x2_t vcx = vmulq_f64(vld1q_f64(x + i), vinv); + float64x2_t vcy = vmulq_f64(vld1q_f64(y + i), vinv); + vcx = vmaxq_f64(vminq_f64(vcx, vmcx), vzero); + vcy = vmaxq_f64(vminq_f64(vcy, vmcy), vzero); + + // Floor and fraction. + const float64x2_t fc0 = vrndmq_f64(vcx); + const float64x2_t fr0 = vrndmq_f64(vcy); + const float64x2_t vfx = vsubq_f64(vcx, fc0); + const float64x2_t vfy = vsubq_f64(vcy, fr0); + + // Extract integer indices (scalar gather — no ARM NEON gather instruction). + const int c0_a = static_cast(vgetq_lane_f64(fc0, 0)); + const int c0_b = static_cast(vgetq_lane_f64(fc0, 1)); + const int r0_a = static_cast(vgetq_lane_f64(fr0, 0)); + const int r0_b = static_cast(vgetq_lane_f64(fr0, 1)); + const int c1_a = std::min(c0_a + 1, width_ - 1); + const int c1_b = std::min(c0_b + 1, width_ - 1); + const int r1_a = std::min(r0_a + 1, height_ - 1); + const int r1_b = std::min(r0_b + 1, height_ - 1); + + // Gather 4 grid values per point (8 loads total). + const float64x2_t d00 = {data_[static_cast(r0_a) * width_ + c0_a], + data_[static_cast(r0_b) * width_ + c0_b]}; + const float64x2_t d10 = {data_[static_cast(r0_a) * width_ + c1_a], + data_[static_cast(r0_b) * width_ + c1_b]}; + const float64x2_t d01 = {data_[static_cast(r1_a) * width_ + c0_a], + data_[static_cast(r1_b) * width_ + c0_b]}; + const float64x2_t d11 = {data_[static_cast(r1_a) * width_ + c1_a], + data_[static_cast(r1_b) * width_ + c1_b]}; + + // Bilinear interpolation via NEON FMA. + const float64x2_t omfx = vsubq_f64(vone, vfx); + const float64x2_t omfy = vsubq_f64(vone, vfy); + float64x2_t result = vmulq_f64(vmulq_f64(omfx, omfy), d00); + result = vfmaq_f64(result, vmulq_f64(vfx, omfy), d10); + result = vfmaq_f64(result, vmulq_f64(omfx, vfy), d01); + result = vfmaq_f64(result, vmulq_f64(vfx, vfy), d11); + + vst1q_f64(out + i, result); + } + + // Handle odd trailing element. + if (n2 < n) { + out[n2] = distance_at(x[n2], y[n2]); + } +#elif defined(__SSE2__) + const __m128d vinv = _mm_set1_pd(inv_res); + const __m128d vzero = _mm_setzero_pd(); + const __m128d vmcx = _mm_set1_pd(max_cx); + const __m128d vmcy = _mm_set1_pd(max_cy); + const __m128d vone = _mm_set1_pd(1.0); + + const int n2 = n & ~1; + for (int i = 0; i < n2; i += 2) { + // Convert to grid coords and clamp. + __m128d vcx = _mm_mul_pd(_mm_loadu_pd(x + i), vinv); + __m128d vcy = _mm_mul_pd(_mm_loadu_pd(y + i), vinv); + vcx = _mm_max_pd(_mm_min_pd(vcx, vmcx), vzero); + vcy = _mm_max_pd(_mm_min_pd(vcy, vmcy), vzero); + + // Floor and fraction. + const __m128d fc0 = geodex::utils::geodex_floor_pd(vcx); + const __m128d fr0 = geodex::utils::geodex_floor_pd(vcy); + const __m128d vfx = _mm_sub_pd(vcx, fc0); + const __m128d vfy = _mm_sub_pd(vcy, fr0); + + // Extract integer indices (scalar gather). + const int c0_a = static_cast(_mm_cvtsd_f64(fc0)); + const int c0_b = static_cast(_mm_cvtsd_f64(_mm_unpackhi_pd(fc0, fc0))); + const int r0_a = static_cast(_mm_cvtsd_f64(fr0)); + const int r0_b = static_cast(_mm_cvtsd_f64(_mm_unpackhi_pd(fr0, fr0))); + const int c1_a = std::min(c0_a + 1, width_ - 1); + const int c1_b = std::min(c0_b + 1, width_ - 1); + const int r1_a = std::min(r0_a + 1, height_ - 1); + const int r1_b = std::min(r0_b + 1, height_ - 1); + + // Gather 4 grid values per point (8 loads total). + // _mm_set_pd(high, low): lane 0 = low (a), lane 1 = high (b). + const __m128d d00 = _mm_set_pd(data_[static_cast(r0_b) * width_ + c0_b], + data_[static_cast(r0_a) * width_ + c0_a]); + const __m128d d10 = _mm_set_pd(data_[static_cast(r0_b) * width_ + c1_b], + data_[static_cast(r0_a) * width_ + c1_a]); + const __m128d d01 = _mm_set_pd(data_[static_cast(r1_b) * width_ + c0_b], + data_[static_cast(r1_a) * width_ + c0_a]); + const __m128d d11 = _mm_set_pd(data_[static_cast(r1_b) * width_ + c1_b], + data_[static_cast(r1_a) * width_ + c1_a]); + + // Bilinear interpolation via FMA. + const __m128d omfx = _mm_sub_pd(vone, vfx); + const __m128d omfy = _mm_sub_pd(vone, vfy); + __m128d result = _mm_mul_pd(_mm_mul_pd(omfx, omfy), d00); + result = geodex::utils::geodex_fmadd_pd(_mm_mul_pd(vfx, omfy), d10, result); + result = geodex::utils::geodex_fmadd_pd(_mm_mul_pd(omfx, vfy), d01, result); + result = geodex::utils::geodex_fmadd_pd(_mm_mul_pd(vfx, vfy), d11, result); + + _mm_storeu_pd(out + i, result); + } + + // Handle odd trailing element. + if (n2 < n) { + out[n2] = distance_at(x[n2], y[n2]); + } +#else + for (int i = 0; i < n; ++i) { + out[i] = distance_at(x[i], y[i]); + } +#endif + } + + /// @brief Grid width in cells. + int width() const { return width_; } + /// @brief Grid height in cells. + int height() const { return height_; } + /// @brief Cell size in meters. + double resolution() const { return resolution_; } + /// @brief Raw distance data array. + const std::vector& data() const { return data_; } + + private: + int width_ = 0, height_ = 0; + double resolution_ = 0.05; + std::vector data_; +}; + +// --------------------------------------------------------------------------- +// Grid SDF callable +// --------------------------------------------------------------------------- + +/// @brief SDF callable wrapping a DistanceGrid for use with SDFConformalMetric. +/// +/// Extracts (x, y) from the configuration point and queries the grid. +class GridSDF { + public: + /// @brief Construct from a DistanceGrid pointer. + explicit GridSDF(const DistanceGrid* grid) : grid_(grid) {} + + /// @brief Evaluate grid-interpolated signed distance at (x, y). + template + double operator()(const Point& q) const { + return grid_->distance_at(q[0], q[1]); + } + + private: + const DistanceGrid* grid_; +}; + +// --------------------------------------------------------------------------- +// Inflated SDF wrapper +// --------------------------------------------------------------------------- + +/// @brief Wraps any SDF and subtracts a constant inflation radius. +/// +/// Equivalent to Minkowski expansion of all obstacles by @p inflation. +/// Useful for point-robot queries that need to account for robot radius. +template +class InflatedSDF { + public: + /// @brief Construct with a base SDF and inflation radius. + InflatedSDF(SDFType sdf, const double inflation) : sdf_(std::move(sdf)), inflation_(inflation) {} + + /// @brief Evaluate inflated signed distance at (x, y). + template + double operator()(const Point& q) const { + return sdf_(q) - inflation_; + } + + /// @brief Get the inflation radius. + double inflation() const { return inflation_; } + /// @brief Get the underlying base SDF. + const SDFType& base() const { return sdf_; } + + private: + SDFType sdf_; + double inflation_; +}; + +} // namespace geodex::collision diff --git a/include/geodex/collision/footprint_grid_checker.hpp b/include/geodex/collision/footprint_grid_checker.hpp new file mode 100644 index 0000000..31eeee8 --- /dev/null +++ b/include/geodex/collision/footprint_grid_checker.hpp @@ -0,0 +1,143 @@ +/// @file footprint_grid_checker.hpp +/// @brief SIMD-accelerated polygon footprint vs. distance grid collision checker. +/// +/// Checks whether a polygon footprint at a given SE(2) pose collides with +/// obstacles represented by a distance grid. Unlike point-based checking, this +/// evaluates the entire polygon perimeter against the grid. +/// +/// SIMD acceleration pipeline: +/// 1. Bounding sphere early-out at the polygon center +/// 2. One sincos call rotates all body-frame samples to world frame +/// 3. NEON 2-wide batch bilinear interpolation across all samples +/// 4. NEON min-reduce to find minimum clearance + +#pragma once + +#include + +#include +#include +#include + +#include + +#include "geodex/collision/distance_grid.hpp" +#include "geodex/collision/polygon_footprint.hpp" + +#ifdef __ARM_NEON +#include +#elif defined(__SSE2__) +#include +#endif + +namespace geodex::collision { + +/// @brief Polygon-vs-grid collision checker with SIMD acceleration. +/// +/// Precomputes a polygon footprint as body-frame perimeter samples. At query +/// time, transforms all samples to world frame and batch-queries the distance +/// grid. Returns either a binary collision result or a continuous signed +/// distance field (minimum grid distance across all samples minus safety margin). +/// +/// Thread-safe: uses thread_local scratch buffers for OMPL's parallel motion +/// validation. +class FootprintGridChecker { + public: + /// @brief Construct a footprint checker. + /// @param grid Pointer to the distance grid (must outlive this object). + /// @param footprint Polygon footprint with precomputed body-frame samples. + /// @param safety_margin Extra clearance subtracted from distances (default 0). + FootprintGridChecker(const DistanceGrid* grid, PolygonFootprint footprint, + const double safety_margin = 0.0) + : grid_(grid), footprint_(std::move(footprint)), safety_margin_(safety_margin) {} + + /// @brief Binary collision test. Returns true if the footprint is collision-free. + bool is_valid(const Eigen::Vector3d& q) const { return min_distance(q) > 0.0; } + + /// @brief SDF: minimum grid distance across all perimeter samples minus safety margin. + /// + /// Positive = clear, negative = collision. Suitable for use with + /// SDFConformalMetric to bias planning away from obstacles. + template + double operator()(const Point& q) const { + return min_distance_impl(q[0], q[1], q[2]); + } + + /// @brief Get the underlying distance grid. + const DistanceGrid* grid() const { return grid_; } + /// @brief Get the polygon footprint. + const PolygonFootprint& footprint() const { return footprint_; } + /// @brief Get the safety margin. + double safety_margin() const { return safety_margin_; } + + private: + const DistanceGrid* grid_; + PolygonFootprint footprint_; + double safety_margin_; + + double min_distance(const Eigen::Vector3d& q) const { + return min_distance_impl(q[0], q[1], q[2]); + } + + double min_distance_impl(const double x, const double y, const double theta) const { + // Early-out: if center distance exceeds bounding radius + margin, + // the entire footprint is clear. + const double center_dist = grid_->distance_at(x, y); + if (center_dist > footprint_.bounding_radius() + safety_margin_) { + return center_dist - footprint_.bounding_radius() - safety_margin_; + } + // If center is deep inside an obstacle, skip the full check. + if (center_dist < -(footprint_.bounding_radius() + safety_margin_)) { + return center_dist + footprint_.bounding_radius() - safety_margin_; + } + + const int np = footprint_.sample_count(); + const int nr = footprint_.sample_count_raw(); + + // Thread-local scratch buffers for OMPL thread safety. + thread_local std::vector wx, wy, dist; + if (static_cast(wx.size()) < np) { + wx.resize(np); + wy.resize(np); + dist.resize(np); + } + + // Transform body-frame samples to world frame (1 sincos + NEON rotation). + footprint_.transform(x, y, theta, wx.data(), wy.data()); + + // Batch grid lookup with NEON bilinear interpolation. + grid_->distance_at_batch(wx.data(), wy.data(), dist.data(), nr); + + // Find minimum distance across all samples. +#ifdef __ARM_NEON + float64x2_t vmin = vdupq_n_f64(std::numeric_limits::max()); + const int n2 = nr & ~1; + for (int i = 0; i < n2; i += 2) { + vmin = vminq_f64(vmin, vld1q_f64(dist.data() + i)); + } + double min_d = std::min(vgetq_lane_f64(vmin, 0), vgetq_lane_f64(vmin, 1)); + if (n2 < nr) { + min_d = std::min(min_d, dist[n2]); + } +#elif defined(__SSE2__) + __m128d vmin = _mm_set1_pd(std::numeric_limits::max()); + const int n2 = nr & ~1; + for (int i = 0; i < n2; i += 2) { + vmin = _mm_min_pd(vmin, _mm_loadu_pd(dist.data() + i)); + } + double min_d = std::min(_mm_cvtsd_f64(vmin), _mm_cvtsd_f64(_mm_unpackhi_pd(vmin, vmin))); + if (n2 < nr) { + min_d = std::min(min_d, dist[n2]); + } +#else + double min_d = std::numeric_limits::max(); + for (int i = 0; i < nr; ++i) { + min_d = std::min(min_d, dist[i]); + } +#endif + + return min_d - safety_margin_; + } +}; + +} // namespace geodex::collision diff --git a/include/geodex/collision/polygon_footprint.hpp b/include/geodex/collision/polygon_footprint.hpp new file mode 100644 index 0000000..415e01f --- /dev/null +++ b/include/geodex/collision/polygon_footprint.hpp @@ -0,0 +1,172 @@ +/// @file polygon_footprint.hpp +/// @brief Convex polygon footprint with precomputed body-frame perimeter samples. +/// +/// The polygon perimeter is discretized into uniformly-spaced sample points at +/// construction time, stored in SoA layout for SIMD-friendly access. At query +/// time, a single sincos call rotates all samples to world frame — amortizing +/// the expensive trig across the entire polygon. + +#pragma once + +#include + +#include + +#include + +#include "geodex/utils/math.hpp" + +#ifdef __ARM_NEON +#include +#elif defined(__SSE2__) +#include +#endif + +namespace geodex::collision { + +/// @brief A convex polygon footprint represented as body-frame perimeter samples. +/// +/// Samples are stored in SoA layout (separate x[] and y[] arrays) padded to +/// an even count for NEON 2-wide processing. The transform() method rotates +/// and translates all samples to world frame using a single sincos call and +/// NEON vectorized rotation. +/// +/// @note Only convex polygons are supported. For non-convex shapes, interior +/// sampling would be needed (future work). +class PolygonFootprint { + public: + /// @brief Construct from polygon vertices with a specified number of samples per edge. + /// + /// Vertices define a convex polygon in the body frame, centered at the origin. + /// Samples are placed uniformly along each edge, including the start vertex + /// but excluding the end vertex (to avoid duplicates at corners). + PolygonFootprint(const std::vector& vertices, const int samples_per_edge) + : samples_per_edge_(samples_per_edge) { + const int n_edges = static_cast(vertices.size()); + n_ = n_edges * samples_per_edge; + n_padded_ = (n_ + 1) & ~1; + + body_x_.resize(n_padded_, 0.0); + body_y_.resize(n_padded_, 0.0); + + int idx = 0; + for (int e = 0; e < n_edges; ++e) { + const auto& v0 = vertices[e]; + const auto& v1 = vertices[(e + 1) % n_edges]; + for (int s = 0; s < samples_per_edge; ++s) { + const double t = static_cast(s) / samples_per_edge; + body_x_[idx] = (1.0 - t) * v0[0] + t * v1[0]; + body_y_[idx] = (1.0 - t) * v0[1] + t * v1[1]; + ++idx; + } + } + + // Bounding radius: max distance from origin across all samples. + // Track max(r²) then sqrt once — avoids n-1 unnecessary sqrt calls. + double max_r2 = 0.0; + for (int i = 0; i < n_; ++i) { + const double r2 = body_x_[i] * body_x_[i] + body_y_[i] * body_y_[i]; + max_r2 = std::max(max_r2, r2); + } + bounding_radius_ = std::sqrt(max_r2); + } + + /// @brief Convenience factory for a rectangular footprint. + /// @param half_length Half-extent along the local x-axis. + /// @param half_width Half-extent along the local y-axis. + /// @param samples_per_edge Number of sample points per edge. + static PolygonFootprint rectangle(const double half_length, const double half_width, + const int samples_per_edge) { + std::vector vertices = { + {-half_length, -half_width}, + {half_length, -half_width}, + {half_length, half_width}, + {-half_length, half_width}, + }; + return PolygonFootprint(vertices, samples_per_edge); + } + + /// @brief Total number of perimeter samples (padded to even for NEON). + int sample_count() const { return n_padded_; } + + /// @brief Actual (unpadded) number of perimeter samples. + int sample_count_raw() const { return n_; } + + /// @brief Body-frame x-coordinates (SoA, padded). + const double* body_x() const { return body_x_.data(); } + + /// @brief Body-frame y-coordinates (SoA, padded). + const double* body_y() const { return body_y_.data(); } + + /// @brief Bounding radius from origin (for early-out tests). + double bounding_radius() const { return bounding_radius_; } + + /// @brief Transform body-frame samples to world frame at pose (x, y, theta). + /// + /// SIMD strategy: + /// - One sincos(theta) call shared across all samples + /// - NEON 2-wide: rotate + translate 2 points per iteration + /// - For a rectangle with samples_per_edge=4: 16 samples → 8 iterations + /// + /// @param x World x-coordinate of the polygon center. + /// @param y World y-coordinate of the polygon center. + /// @param theta Rotation angle (radians). + /// @param[out] wx World-frame x-coordinates (must have capacity >= sample_count()). + /// @param[out] wy World-frame y-coordinates (must have capacity >= sample_count()). + void transform(const double x, const double y, const double theta, double* wx, double* wy) const { + double ct, st; + utils::sincos(theta, &st, &ct); + +#ifdef __ARM_NEON + const float64x2_t vct = vdupq_n_f64(ct); + const float64x2_t vst = vdupq_n_f64(st); + const float64x2_t vtx = vdupq_n_f64(x); + const float64x2_t vty = vdupq_n_f64(y); + + for (int i = 0; i < n_padded_; i += 2) { + const float64x2_t bx = vld1q_f64(body_x_.data() + i); + const float64x2_t by = vld1q_f64(body_y_.data() + i); + + // Rotate: rx = ct*bx - st*by, ry = st*bx + ct*by. + float64x2_t rx = vfmsq_f64(vmulq_f64(vct, bx), vst, by); + float64x2_t ry = vfmaq_f64(vmulq_f64(vct, by), vst, bx); + + // Translate. + vst1q_f64(wx + i, vaddq_f64(rx, vtx)); + vst1q_f64(wy + i, vaddq_f64(ry, vty)); + } +#elif defined(__SSE2__) + const __m128d vct = _mm_set1_pd(ct); + const __m128d vst = _mm_set1_pd(st); + const __m128d vtx = _mm_set1_pd(x); + const __m128d vty = _mm_set1_pd(y); + + for (int i = 0; i < n_padded_; i += 2) { + const __m128d bx = _mm_loadu_pd(body_x_.data() + i); + const __m128d by = _mm_loadu_pd(body_y_.data() + i); + + // Rotate: rx = ct*bx - st*by, ry = st*bx + ct*by. + __m128d rx = geodex::utils::geodex_fnmadd_pd(vst, by, _mm_mul_pd(vct, bx)); + __m128d ry = geodex::utils::geodex_fmadd_pd(vst, bx, _mm_mul_pd(vct, by)); + + // Translate. + _mm_storeu_pd(wx + i, _mm_add_pd(rx, vtx)); + _mm_storeu_pd(wy + i, _mm_add_pd(ry, vty)); + } +#else + for (int i = 0; i < n_padded_; ++i) { + const double bx = body_x_[i], by = body_y_[i]; + wx[i] = ct * bx - st * by + x; + wy[i] = st * bx + ct * by + y; + } +#endif + } + + private: + std::vector body_x_, body_y_; + int n_ = 0, n_padded_ = 0; + int samples_per_edge_ = 0; + double bounding_radius_ = 0.0; +}; + +} // namespace geodex::collision diff --git a/include/geodex/collision/rectangle_sdf.hpp b/include/geodex/collision/rectangle_sdf.hpp new file mode 100644 index 0000000..67fed54 --- /dev/null +++ b/include/geodex/collision/rectangle_sdf.hpp @@ -0,0 +1,428 @@ +/// @file rectangle_sdf.hpp +/// @brief Oriented rectangle obstacles: SDF, SAT collision, and SIMD acceleration. +/// +/// Provides: +/// - RectObstacle: oriented rectangle descriptor +/// - rect_corners / rects_overlap: SAT-based overlap test +/// - RectObstacleSoA: NEON-friendly Structure-of-Arrays layout +/// - RectSmoothSDF: SIMD-accelerated smooth-min SDF with bounding-sphere +/// early-out, branchless signed distance, and fast_exp log-sum-exp + +#pragma once + +#include + +#include +#include +#include + +#include + +#include "geodex/utils/math.hpp" + +#ifdef __ARM_NEON +#include +#elif defined(__SSE2__) +#include +#endif + +namespace geodex::collision { + +// --------------------------------------------------------------------------- +// Oriented rectangle obstacle +// --------------------------------------------------------------------------- + +/// @brief An oriented rectangle obstacle defined by center, rotation, and half-extents. +struct RectObstacle { + double cx, cy, theta; + double half_length, half_width; +}; + +/// @brief Compute the 4 corners of an oriented rectangle. +inline std::array rect_corners(const RectObstacle& r) { + const double ct = std::cos(r.theta), st = std::sin(r.theta); + const double hl = r.half_length, hw = r.half_width; + return {{ + {r.cx + ct * (-hl) - st * (-hw), r.cy + st * (-hl) + ct * (-hw)}, + {r.cx + ct * (hl)-st * (-hw), r.cy + st * (hl) + ct * (-hw)}, + {r.cx + ct * (hl)-st * (hw), r.cy + st * (hl) + ct * (hw)}, + {r.cx + ct * (-hl) - st * (hw), r.cy + st * (-hl) + ct * (hw)}, + }}; +} + +/// @brief Separating Axis Theorem (SAT) overlap test for two oriented rectangles. +/// @return true if the rectangles overlap (collide). +inline bool rects_overlap(const RectObstacle& a, const RectObstacle& b) { + auto corners_a = rect_corners(a); + auto corners_b = rect_corners(b); + + auto test_axes = [&](const RectObstacle& r) -> bool { + const double ct = std::cos(r.theta), st = std::sin(r.theta); + Eigen::Vector2d axes[2] = {{ct, st}, {-st, ct}}; + for (const auto& axis : axes) { + double min_a = std::numeric_limits::max(); + double max_a = std::numeric_limits::lowest(); + double min_b = std::numeric_limits::max(); + double max_b = std::numeric_limits::lowest(); + for (const auto& c : corners_a) { + const double proj = axis.dot(c); + min_a = std::min(min_a, proj); + max_a = std::max(max_a, proj); + } + for (const auto& c : corners_b) { + const double proj = axis.dot(c); + min_b = std::min(min_b, proj); + max_b = std::max(max_b, proj); + } + if (max_a < min_b || max_b < min_a) return true; // separated + } + return false; + }; + + return !test_axes(a) && !test_axes(b); +} + +// --------------------------------------------------------------------------- +// SoA layout for NEON-friendly rectangle data +// --------------------------------------------------------------------------- + +/// @brief Structure-of-Arrays layout for oriented rectangle obstacles. +/// +/// Precomputes sin/cos of each obstacle's orientation and bounding sphere +/// radius. Arrays are padded to a multiple of 2 for NEON 2-wide processing. +class RectObstacleSoA { + public: + /// @brief Build SoA arrays from a vector of obstacles with skip distance. + void build(const std::vector& obstacles, const double skip_dist) { + n_ = static_cast(obstacles.size()); + n_padded_ = (n_ + 1) & ~1; + auto alloc = [&](std::vector& v, const double fill) { v.resize(n_padded_, fill); }; + alloc(cx_, 0.0); + alloc(cy_, 0.0); + alloc(ct_, 1.0); + alloc(st_, 0.0); + alloc(half_length_, 0.0); + alloc(half_width_, 0.0); + alloc(bounding_r2_, 0.0); + for (int i = 0; i < n_; ++i) { + const auto& o = obstacles[i]; + ct_[i] = std::cos(o.theta); + st_[i] = std::sin(o.theta); + cx_[i] = o.cx; + cy_[i] = o.cy; + half_length_[i] = o.half_length; + half_width_[i] = o.half_width; + const double diag = std::sqrt(o.half_length * o.half_length + o.half_width * o.half_width); + const double br = diag + skip_dist; + bounding_r2_[i] = br * br; + } + } + + /// @brief Number of actual obstacles. + int count() const { return n_; } + /// @brief Number of obstacles including SIMD padding. + int padded_count() const { return n_padded_; } + /// @brief Obstacle center x-coordinates. + const double* cx() const { return cx_.data(); } + /// @brief Obstacle center y-coordinates. + const double* cy() const { return cy_.data(); } + /// @brief Precomputed cos(theta) for each obstacle. + const double* ct() const { return ct_.data(); } + /// @brief Precomputed sin(theta) for each obstacle. + const double* st() const { return st_.data(); } + /// @brief Half-length of each obstacle. + const double* half_length() const { return half_length_.data(); } + /// @brief Half-width of each obstacle. + const double* half_width() const { return half_width_.data(); } + /// @brief Squared bounding sphere radius for early-out. + const double* bounding_r2() const { return bounding_r2_.data(); } + + private: + std::vector cx_, cy_, ct_, st_; + std::vector half_length_, half_width_, bounding_r2_; + int n_ = 0, n_padded_ = 0; +}; + +// --------------------------------------------------------------------------- +// SIMD-accelerated smooth-min SDF for oriented rectangles +// --------------------------------------------------------------------------- + +/// @brief Fused SDF + log-sum-exp for oriented rectangles with SIMD acceleration. +/// +/// SIMD strategy (ARM NEON, 2-wide float64): +/// - SoA layout: cache-line-friendly, NEON-loadable +/// - 2-wide processing: 2 obstacles per iteration, branchless via vbslq +/// - Bounding sphere early-out: skip obstacles where center distance exceeds +/// diagonal + skip_dist (where exp(-beta*d) ~ 0) +/// - Inflation applied inside the SIMD loop (no separate wrapper needed) +/// - fast_exp_neon for the log-sum-exp accumulation +/// +/// Scalar fallback provided for platforms without SIMD. +/// x86 SSE2 path uses 2-wide float64 processing with optional SSE4.1/FMA. +class RectSmoothSDF { + public: + /// @brief Construct from obstacles with smoothing and optional inflation. + RectSmoothSDF(std::vector obstacles, const double beta = 20.0, + const double inflation = 0.0) + : obstacles_(std::move(obstacles)), + beta_(beta), + skip_dist_(20.0 / beta), + inflation_(inflation) { + soa_.build(obstacles_, skip_dist_); + simd_buf_.resize(soa_.padded_count()); + } + + /// @brief Evaluate smooth signed distance at point (x, y). + template + double operator()(const Point& q) const { + const double px = q[0], py = q[1]; + const int np = soa_.padded_count(); + +#ifdef __ARM_NEON + return eval_neon(px, py, np); +#elif defined(__SSE2__) + return eval_sse2(px, py, np); +#else + return eval_scalar(px, py, np); +#endif + } + + /// @brief Get the rectangle obstacles. + const std::vector& obstacles() const { return obstacles_; } + /// @brief Get the log-sum-exp smoothing parameter. + double beta() const { return beta_; } + /// @brief Get the inflation radius. + double inflation() const { return inflation_; } + + private: + std::vector obstacles_; + RectObstacleSoA soa_; + double beta_; + double skip_dist_; + double inflation_; + mutable std::vector simd_buf_; ///< Pre-allocated SIMD scratch buffer. + +#ifdef __ARM_NEON + double eval_neon(const double px, const double py, const int np) const { + const float64x2_t vpx = vdupq_n_f64(px); + const float64x2_t vpy = vdupq_n_f64(py); + const float64x2_t vzero = vdupq_n_f64(0.0); + const float64x2_t vbeta = vdupq_n_f64(beta_); + const float64x2_t vskip = vdupq_n_f64(skip_dist_); + const float64x2_t vinfl = vdupq_n_f64(inflation_); + const uint64x2_t abs_mask = vdupq_n_u64(0x7FFFFFFFFFFFFFFFULL); + + double* neg_beta_d = simd_buf_.data(); + int total = 0; + + for (int i = 0; i < np; i += 2) { + const float64x2_t vcx = vld1q_f64(soa_.cx() + i); + const float64x2_t vcy = vld1q_f64(soa_.cy() + i); + + // Bounding sphere early-out. + const float64x2_t dx = vsubq_f64(vpx, vcx); + const float64x2_t dy = vsubq_f64(vpy, vcy); + const float64x2_t dist2 = vaddq_f64(vmulq_f64(dx, dx), vmulq_f64(dy, dy)); + const float64x2_t vbr2 = vld1q_f64(soa_.bounding_r2() + i); + const uint64x2_t in_range = vcltq_f64(dist2, vbr2); + if (vgetq_lane_u64(in_range, 0) == 0 && vgetq_lane_u64(in_range, 1) == 0) continue; + + // Local coordinates via rotation. + const float64x2_t vct = vld1q_f64(soa_.ct() + i); + const float64x2_t vst = vld1q_f64(soa_.st() + i); + const float64x2_t lx = vaddq_f64(vmulq_f64(vct, dx), vmulq_f64(vst, dy)); + const float64x2_t ly = vsubq_f64(vmulq_f64(vct, dy), vmulq_f64(vst, dx)); + + const float64x2_t alx = vreinterpretq_f64_u64(vandq_u64(vreinterpretq_u64_f64(lx), abs_mask)); + const float64x2_t aly = vreinterpretq_f64_u64(vandq_u64(vreinterpretq_u64_f64(ly), abs_mask)); + + const float64x2_t vhl = vld1q_f64(soa_.half_length() + i); + const float64x2_t vhw = vld1q_f64(soa_.half_width() + i); + + // Exterior distance: max(|l| - half, 0). + const float64x2_t ex = vmaxq_f64(vsubq_f64(alx, vhl), vzero); + const float64x2_t ey = vmaxq_f64(vsubq_f64(aly, vhw), vzero); + const float64x2_t ext2 = vaddq_f64(vmulq_f64(ex, ex), vmulq_f64(ey, ey)); + const float64x2_t ext_d = vsqrtq_f64(ext2); + + // Interior distance: -min(hl - |lx|, hw - |ly|). + const float64x2_t ix = vsubq_f64(vhl, alx); + const float64x2_t iy = vsubq_f64(vhw, aly); + const float64x2_t int_d = vnegq_f64(vminq_f64(ix, iy)); + + // Branchless select: ext2 > 0 → exterior, else interior. + const uint64x2_t is_outside = vcgtq_f64(ext2, vzero); + float64x2_t d = vbslq_f64(is_outside, ext_d, int_d); + + // Inflation: subtract so clearance triggers at robot edge. + d = vsubq_f64(d, vinfl); + + // Mask out-of-range obstacles to skip_dist. + d = vbslq_f64(in_range, d, vskip); + + const float64x2_t nbd = vnegq_f64(vmulq_f64(vbeta, d)); + vst1q_f64(&neg_beta_d[total], nbd); + total += 2; + } + + if (total == 0) return skip_dist_; + + // Find global max for numerical stability. + double global_max = std::numeric_limits::lowest(); + for (int j = 0; j < total; j += 2) { + const float64x2_t v = vld1q_f64(&neg_beta_d[j]); + global_max = std::max(global_max, std::max(vgetq_lane_f64(v, 0), vgetq_lane_f64(v, 1))); + } + + // Sum exp(nbd - max) using NEON fast_exp. + const float64x2_t vgmax = vdupq_n_f64(global_max); + float64x2_t vsum = vdupq_n_f64(0.0); + for (int j = 0; j < total; j += 2) { + const float64x2_t shifted = vsubq_f64(vld1q_f64(&neg_beta_d[j]), vgmax); + vsum = vaddq_f64(vsum, utils::fast_exp(shifted)); + } + const double sum = vgetq_lane_f64(vsum, 0) + vgetq_lane_f64(vsum, 1); + + return -(global_max + std::log(sum)) / beta_; + } +#endif // __ARM_NEON + +#ifdef __SSE2__ + double eval_sse2(const double px, const double py, const int np) const { + const __m128d vpx = _mm_set1_pd(px); + const __m128d vpy = _mm_set1_pd(py); + const __m128d vzero = _mm_setzero_pd(); + const __m128d vbeta = _mm_set1_pd(beta_); + const __m128d vskip = _mm_set1_pd(skip_dist_); + const __m128d vinfl = _mm_set1_pd(inflation_); + const __m128d abs_mask = _mm_castsi128_pd(_mm_set1_epi64x(0x7FFFFFFFFFFFFFFFLL)); + const __m128d sign_mask = + _mm_castsi128_pd(_mm_set1_epi64x(static_cast(0x8000000000000000ULL))); + + double* neg_beta_d = simd_buf_.data(); + int total = 0; + + for (int i = 0; i < np; i += 2) { + const __m128d vcx = _mm_loadu_pd(soa_.cx() + i); + const __m128d vcy = _mm_loadu_pd(soa_.cy() + i); + + // Bounding sphere early-out. + const __m128d dx = _mm_sub_pd(vpx, vcx); + const __m128d dy = _mm_sub_pd(vpy, vcy); + const __m128d dist2 = _mm_add_pd(_mm_mul_pd(dx, dx), _mm_mul_pd(dy, dy)); + const __m128d vbr2 = _mm_loadu_pd(soa_.bounding_r2() + i); + const __m128d in_range = _mm_cmplt_pd(dist2, vbr2); + if (_mm_movemask_pd(in_range) == 0) continue; + + // Local coordinates via rotation. + const __m128d vct = _mm_loadu_pd(soa_.ct() + i); + const __m128d vst = _mm_loadu_pd(soa_.st() + i); + const __m128d lx = _mm_add_pd(_mm_mul_pd(vct, dx), _mm_mul_pd(vst, dy)); + const __m128d ly = _mm_sub_pd(_mm_mul_pd(vct, dy), _mm_mul_pd(vst, dx)); + + const __m128d alx = _mm_and_pd(lx, abs_mask); + const __m128d aly = _mm_and_pd(ly, abs_mask); + + const __m128d vhl = _mm_loadu_pd(soa_.half_length() + i); + const __m128d vhw = _mm_loadu_pd(soa_.half_width() + i); + + // Exterior distance: max(|l| - half, 0). + const __m128d ex = _mm_max_pd(_mm_sub_pd(alx, vhl), vzero); + const __m128d ey = _mm_max_pd(_mm_sub_pd(aly, vhw), vzero); + const __m128d ext2 = _mm_add_pd(_mm_mul_pd(ex, ex), _mm_mul_pd(ey, ey)); + const __m128d ext_d = _mm_sqrt_pd(ext2); + + // Interior distance: -min(hl - |lx|, hw - |ly|). + const __m128d ix = _mm_sub_pd(vhl, alx); + const __m128d iy = _mm_sub_pd(vhw, aly); + const __m128d int_d = _mm_xor_pd(_mm_min_pd(ix, iy), sign_mask); + + // Branchless select: ext2 > 0 → exterior, else interior. + const __m128d is_outside = _mm_cmpgt_pd(ext2, vzero); + __m128d d = geodex::utils::geodex_blendv_pd(int_d, ext_d, is_outside); + + // Inflation: subtract so clearance triggers at robot edge. + d = _mm_sub_pd(d, vinfl); + + // Mask out-of-range obstacles to skip_dist. + d = geodex::utils::geodex_blendv_pd(vskip, d, in_range); + + const __m128d nbd = _mm_xor_pd(_mm_mul_pd(vbeta, d), sign_mask); + _mm_storeu_pd(&neg_beta_d[total], nbd); + total += 2; + } + + if (total == 0) return skip_dist_; + + // Find global max for numerical stability. + double global_max = std::numeric_limits::lowest(); + for (int j = 0; j < total; j += 2) { + const __m128d v = _mm_loadu_pd(&neg_beta_d[j]); + const double l0 = _mm_cvtsd_f64(v); + const double l1 = _mm_cvtsd_f64(_mm_unpackhi_pd(v, v)); + global_max = std::max(global_max, std::max(l0, l1)); + } + + // Sum exp(nbd - max) using SSE2 fast_exp. + const __m128d vgmax = _mm_set1_pd(global_max); + __m128d vsum = _mm_setzero_pd(); + for (int j = 0; j < total; j += 2) { + const __m128d shifted = _mm_sub_pd(_mm_loadu_pd(&neg_beta_d[j]), vgmax); + vsum = _mm_add_pd(vsum, utils::fast_exp(shifted)); + } + const double sum = _mm_cvtsd_f64(vsum) + _mm_cvtsd_f64(_mm_unpackhi_pd(vsum, vsum)); + + return -(global_max + std::log(sum)) / beta_; + } +#endif // __SSE2__ + + double eval_scalar(const double px, const double py, const int np) const { + thread_local std::vector neg_beta_d; + neg_beta_d.clear(); + neg_beta_d.reserve(np); + + for (int i = 0; i < soa_.count(); ++i) { + const double dx = px - soa_.cx()[i]; + const double dy = py - soa_.cy()[i]; + const double dist2 = dx * dx + dy * dy; + + // Bounding sphere early-out. + if (dist2 >= soa_.bounding_r2()[i]) continue; + + // Local coordinates. + const double lx = soa_.ct()[i] * dx + soa_.st()[i] * dy; + const double ly = soa_.ct()[i] * dy - soa_.st()[i] * dx; + const double alx = std::abs(lx); + const double aly = std::abs(ly); + + const double hl = soa_.half_length()[i]; + const double hw = soa_.half_width()[i]; + + // Signed distance. + const double ex = std::max(alx - hl, 0.0); + const double ey = std::max(aly - hw, 0.0); + const double ext2 = ex * ex + ey * ey; + double d; + if (ext2 > 0.0) { + d = std::sqrt(ext2); // exterior + } else { + d = -std::min(hl - alx, hw - aly); // interior + } + + d -= inflation_; + neg_beta_d.push_back(-beta_ * d); + } + + if (neg_beta_d.empty()) return skip_dist_; + + double global_max = std::numeric_limits::lowest(); + for (const double v : neg_beta_d) global_max = std::max(global_max, v); + + double sum = 0.0; + for (const double v : neg_beta_d) sum += utils::fast_exp(v - global_max); + + return -(global_max + std::log(sum)) / beta_; + } +}; + +} // namespace geodex::collision diff --git a/include/geodex/core/debug.hpp b/include/geodex/core/debug.hpp index 28569a2..0b27b4d 100644 --- a/include/geodex/core/debug.hpp +++ b/include/geodex/core/debug.hpp @@ -1,9 +1,37 @@ #pragma once #include +#include +#include #ifdef GEODEX_DEBUG #define GEODEX_LOG(msg) std::cerr << "[geodex] " << msg << "\n" #else #define GEODEX_LOG(msg) ((void)0) #endif + +namespace geodex::detail { + +/// @brief Extract a clean type name from compiler intrinsics. +/// +/// @details Used by `GEODEX_LOG` sites that want to print template parameter +/// names in a human-readable form (e.g. "SphereRoundMetric" instead of a +/// mangled name). Only active when GEODEX_DEBUG is enabled at the call site. +template +constexpr std::string_view type_name() { +#if defined(__clang__) || defined(__GNUC__) + // __PRETTY_FUNCTION__ looks like: + // "std::string_view geodex::detail::type_name() [T = SphereRoundMetric]" + std::string_view fn = __PRETTY_FUNCTION__; + auto start = fn.find("T = "); + if (start == std::string_view::npos) return fn; + start += 4; + auto end = fn.rfind(']'); + if (end == std::string_view::npos) return fn.substr(start); + return fn.substr(start, end - start); +#else + return typeid(T).name(); +#endif +} + +} // namespace geodex::detail diff --git a/include/geodex/core/metric.hpp b/include/geodex/core/metric.hpp index 78c356f..a4500bf 100644 --- a/include/geodex/core/metric.hpp +++ b/include/geodex/core/metric.hpp @@ -1,14 +1,73 @@ /// @file metric.hpp -/// @brief HasMetric concept for manifolds with a Riemannian inner product. +/// @brief HasMetric concept and batched variant for manifolds with a Riemannian inner product. #pragma once +#include + #include +#include + #include "concepts.hpp" namespace geodex { +/// @brief Default Riemannian norm formula \f$ \|v\|_p = \sqrt{\langle v, v \rangle_p} \f$. +/// +/// @details Shared helper that every metric/manifold with the canonical induced +/// norm can forward to, removing the duplicated `return std::sqrt(inner(p, v, v));` +/// body from each implementation. +template +inline double riemannian_norm(const HasInner& h, const Point& p, const Tangent& v) { + return std::sqrt(h.inner(p, v, v)); +} + +namespace detail { + +template +concept HasCompileTimeRiemannianLog = requires { requires M::has_riemannian_log; }; + +template +concept HasRuntimeRiemannianLog = requires(const M& m) { + { m.has_riemannian_log_runtime() } -> std::convertible_to; +}; + +} // namespace detail + +/// @brief Concept: manifold exposes a compile-time or runtime signal that +/// `log` is the Riemannian logarithm of its currently configured metric. +/// +/// @details Algorithms should not branch on this concept directly — use +/// `is_riemannian_log(m)` below, which collapses the two signals into a +/// single boolean. +template +concept HasRiemannianLogSignal = + detail::HasCompileTimeRiemannianLog || detail::HasRuntimeRiemannianLog; + +/// @brief Decide whether `log` coincides with the Riemannian logarithm of `m`'s +/// metric, combining compile-time (`M::has_riemannian_log`) and runtime +/// (`m.has_riemannian_log_runtime()`) signals. +/// +/// @details On a Riemannian manifold \f$(M, g)\f$ the identity +/// \f$\nabla_g(\tfrac{1}{2}\, d_g^2(\cdot, q))(x) = -\log_x^g(q)\f$ +/// holds exactly only when `log` is the Riemannian log of `g`. Algorithms +/// such as `discrete_geodesic` use this resolver to switch between the fast +/// log-based natural gradient and a finite-difference fallback. +/// +/// Compile-time signal beats runtime signal. Manifolds with neither return +/// `false` (the FD fallback is always safe). +template +constexpr bool is_riemannian_log(const M& m) { + if constexpr (detail::HasCompileTimeRiemannianLog) { + return M::has_riemannian_log; + } else if constexpr (detail::HasRuntimeRiemannianLog) { + return m.has_riemannian_log_runtime(); + } else { + return false; + } +} + /// @brief A manifold that provides a Riemannian inner product and norm. /// /// @details Requires: @@ -22,4 +81,33 @@ concept HasMetric = { m.norm(p, v) } -> std::convertible_to; }; +/// @brief A manifold that exposes a batched inner-product, computing +/// \f$U^\top M(p) V\f$ in one call. +/// +/// @details This is an optional optimization hook for point-dependent metrics +/// where the expensive part is evaluating the metric tensor \f$M(p)\f$ +/// (e.g., forward kinematics for a kinetic-energy metric). Providing +/// `inner_matrix` allows algorithms that compute a \f$d \times d\f$ metric tensor +/// in a tangent basis (`natural_gradient_fd` is the canonical consumer) to +/// evaluate \f$M(p)\f$ **once** instead of \f$d^2\f$ times. +/// +/// Algorithms that only need pointwise evaluation use the scalar `inner` path +/// and do not require metrics to provide `inner_matrix`. +template +concept HasBatchInnerMatrix = + Manifold && requires(const M m, const typename M::Point p, const Eigen::MatrixXd U, + const Eigen::MatrixXd V) { + { m.inner_matrix(p, U, V) } -> std::convertible_to; + }; + +/// @brief Check if a metric type provides a batched `inner_matrix` method. +/// +/// @details Used by manifold classes to conditionally expose `inner_matrix` +/// without referencing a specific member variable in a requires-clause. +template +concept MetricHasInnerMatrix = + requires(const MetricT m, const Point p, const Eigen::MatrixXd U, const Eigen::MatrixXd V) { + { m.inner_matrix(p, U, V) } -> std::convertible_to; + }; + } // namespace geodex diff --git a/include/geodex/core/retraction.hpp b/include/geodex/core/retraction.hpp index b81c2ab..d1724c5 100644 --- a/include/geodex/core/retraction.hpp +++ b/include/geodex/core/retraction.hpp @@ -18,7 +18,8 @@ namespace geodex { /// @tparam Tangent The tangent vector type. template concept Retraction = requires(const R r, const Point& p, const Point& q, const Tangent& v) { - /// `retract(p, v)` — map tangent vector \f$ v \in T_p\mathcal{M} \f$ to a point on \f$ \mathcal{M} \f$. + /// `retract(p, v)` — map tangent vector \f$ v \in T_p\mathcal{M} \f$ to a point on \f$ + /// \mathcal{M} \f$. { r.retract(p, v) } -> std::same_as; /// `inverse_retract(p, q)` — map point \f$ q \f$ to a tangent vector at \f$ p \f$. { r.inverse_retract(p, q) } -> std::same_as; diff --git a/include/geodex/core/sampler.hpp b/include/geodex/core/sampler.hpp new file mode 100644 index 0000000..80dcbe8 --- /dev/null +++ b/include/geodex/core/sampler.hpp @@ -0,0 +1,135 @@ +/// @file sampler.hpp +/// @brief Sampler concepts and implementations for uniform sampling in \f$[0,1]^d\f$. +/// +/// @details Manifolds compose a sampler with a `box_to_point` map to produce +/// points on the manifold. This split lets the same sampler back any manifold +/// while keeping Halton (deterministic low-discrepancy) sampling meaningful: +/// Halton is only well-defined on a fixed-cardinality coordinate space, so +/// the manifold owns the mapping from the box to its native representation. + +#pragma once + +#include +#include + +#include +#include +#include + +#include + +namespace geodex { + +namespace detail { + +/// @brief First 30 primes — upper bound on Halton sampling dimensions. +inline constexpr std::array halton_primes = {2, 3, 5, 7, 11, 13, 17, 19, 23, 29, + 31, 37, 41, 43, 47, 53, 59, 61, 67, 71, + 73, 79, 83, 89, 97, 101, 103, 107, 109, 113}; + +/// @brief Van der Corput sequence — the 1-D building block of Halton sampling. +/// @param index 1-based index into the sequence. +/// @param base Prime base for the digit expansion. +/// @return The value of the van der Corput sequence at `index` in base `base`. +inline double van_der_corput(const std::uint64_t index, const int base) { + double result = 0.0; + double f = 1.0 / static_cast(base); + std::uint64_t i = index; + const std::uint64_t b = static_cast(base); + while (i > 0) { + result += static_cast(i % b) * f; + i /= b; + f /= static_cast(base); + } + return result; +} + +} // namespace detail + +/// @brief Concept: a type that fills a length-`d` vector with uniform samples in \f$[0, 1)\f$. +template +concept Sampler = requires(S& s, const int d, Eigen::Ref out) { + { s.sample_box(d, out) } -> std::same_as; +}; + +/// @brief Concept: a `Sampler` that also supports explicit reseeding. +template +concept SeedableSampler = Sampler && requires(S& s, std::uint64_t seed) { + { s.seed(seed) } -> std::same_as; +}; + +/// @brief Pseudo-random sampler wrapping `std::mt19937`. +/// +/// @details Default construction uses a shared `thread_local` Mersenne-Twister +/// generator, preserving the pre-refactor per-manifold random_point() semantics +/// and zero-cost instantiation. Passing an explicit seed creates an owned +/// generator with a reproducible sequence — useful for tests and benchmarks. +class StochasticSampler { + public: + /// @brief Default: share a thread-local generator. + StochasticSampler() = default; + + /// @brief Seeded: own a generator for reproducible sequences. + explicit StochasticSampler(std::uint64_t seed) : gen_(seed), owned_(true) {} + + /// @brief Reseed the sampler; transitions to an owned generator. + void seed(std::uint64_t s) { + gen_.seed(s); + owned_ = true; + } + + /// @brief Fill `out[0..d-1]` with uniform values in \f$[0, 1)\f$. + void sample_box(const int d, Eigen::Ref out) { + std::uniform_real_distribution dist(0.0, 1.0); + auto& g = owned_ ? gen_ : thread_local_gen(); + for (int i = 0; i < d; ++i) { + out[i] = dist(g); + } + } + + private: + static std::mt19937& thread_local_gen() { + thread_local std::mt19937 g{std::random_device{}()}; + return g; + } + + std::mt19937 gen_{}; + bool owned_ = false; +}; + +/// @brief Halton low-discrepancy sampler (deterministic quasi-random). +/// +/// @details Produces a fully reproducible quasi-random sequence by advancing +/// an internal 1-based index. Coordinates are computed per dimension via +/// `detail::van_der_corput` with the first `d` primes. Maximum supported +/// dimension is `detail::halton_primes.size()` (30). +class HaltonSampler { + public: + /// @brief Default: start the sequence at index 1. + HaltonSampler() = default; + + /// @brief Start the sequence at an explicit index. + explicit HaltonSampler(std::uint64_t start_index) : index_(start_index) {} + + /// @brief Reset the sequence index. + void seed(std::uint64_t s) { index_ = s; } + + /// @brief Fill `out[0..d-1]` with the next Halton sample. + void sample_box(const int d, Eigen::Ref out) { + ++index_; // 1-based + for (int i = 0; i < d; ++i) { + out[i] = detail::van_der_corput(index_, detail::halton_primes[static_cast(i)]); + } + } + + private: + std::uint64_t index_ = 0; +}; + +// Self-verification: our concrete samplers model the concepts. +static_assert(Sampler); +static_assert(Sampler); +static_assert(SeedableSampler); +static_assert(SeedableSampler); + +} // namespace geodex diff --git a/include/geodex/geodex.hpp b/include/geodex/geodex.hpp index 4587dde..cfa5313 100644 --- a/include/geodex/geodex.hpp +++ b/include/geodex/geodex.hpp @@ -1,21 +1,27 @@ /// @file geodex.hpp /// @brief Umbrella header for the geodex library. +/// /// @details Includes all core concepts, manifold implementations, and algorithms. +/// For OMPL integration, include `geodex/integration/ompl/geodex_state_space.hpp` separately. #pragma once #include "algorithm/distance.hpp" +#include "algorithm/heuristics.hpp" +#include "algorithm/interpolation.hpp" #include "core/concepts.hpp" #include "core/distance.hpp" #include "core/interpolation.hpp" #include "core/metric.hpp" #include "core/retraction.hpp" +#include "core/sampler.hpp" #include "manifold/configuration_space.hpp" #include "manifold/euclidean.hpp" #include "manifold/se2.hpp" #include "manifold/sphere.hpp" #include "manifold/torus.hpp" #include "metrics/constant_spd.hpp" +#include "metrics/identity.hpp" #include "metrics/jacobi.hpp" #include "metrics/kinetic_energy.hpp" #include "metrics/pullback.hpp" diff --git a/include/geodex/integration/ompl/geodex_informed_sampler.hpp b/include/geodex/integration/ompl/geodex_informed_sampler.hpp new file mode 100644 index 0000000..d3dd1a0 --- /dev/null +++ b/include/geodex/integration/ompl/geodex_informed_sampler.hpp @@ -0,0 +1,179 @@ +/// @file geodex_informed_sampler.hpp +/// @brief Direct informed sampler for GeodexStateSpace with PHS specialization. + +#pragma once + +#include + +#include +#include +#include + +#include +#include +#include +#include + +#include "geodex/algorithm/heuristics.hpp" +#include "geodex/integration/ompl/geodex_state_space.hpp" + +namespace geodex::integration::ompl { + +using geodex::EuclideanHeuristic; + +namespace ob = ::ompl::base; + +/// @brief Direct informed sampler for GeodexStateSpace. +/// +/// @details For `EuclideanHeuristic`, samples directly from a prolate +/// hyperspheroid (PHS) centered on the start-goal line. For other heuristics, +/// falls back to heuristic-guided rejection sampling. +/// +/// @tparam HeuristicT Callable with signature `double(Point, Point)`. +template +class GeodexDirectInfSampler : public ob::InformedSampler { + public: + /// @brief Construct the informed sampler. + /// @param probDefn Problem definition (provides start/goal states). + /// @param maxNumberCalls Maximum sampling attempts per call. + /// @param heuristic Admissible heuristic functor. + GeodexDirectInfSampler(const ob::ProblemDefinitionPtr& probDefn, unsigned int maxNumberCalls, + HeuristicT heuristic = HeuristicT{}) + : ob::InformedSampler(probDefn, maxNumberCalls), heuristic_(std::move(heuristic)) { + // Extract start and goal coordinates + const auto* startState = probDefn_->getStartState(0); + // Sample a goal state (GoalSampleableRegion doesn't expose getState directly) + auto* goalState = space_->allocState(); + probDefn_->getGoal()->as()->sampleGoal(goalState); + + unsigned int dim = space_->getDimension(); + start_coords_.resize(dim); + goal_coords_.resize(dim); + space_->copyToReals(start_coords_, startState); + space_->copyToReals(goal_coords_, goalState); + space_->freeState(goalState); + + // Create a base sampler for uniform fallback + baseSampler_ = space_->allocStateSampler(); + + if constexpr (std::is_same_v) { + // Build the prolate hyperspheroid from the two foci + phs_ = std::make_shared<::ompl::ProlateHyperspheroid>(dim, start_coords_.data(), + goal_coords_.data()); + } + } + + /// @brief Sample a state uniformly from the informed region {x : h(s,x) + h(x,g) <= maxCost}. + bool sampleUniform(ob::State* statePtr, const ob::Cost& maxCost) override { + if constexpr (std::is_same_v) { + return samplePHS(statePtr, maxCost); + } else { + return sampleRejection(statePtr, maxCost); + } + } + + /// @brief Sample from the annular informed region (minCost < cost <= maxCost). + bool sampleUniform(ob::State* statePtr, const ob::Cost& minCost, + const ob::Cost& maxCost) override { + // Sample from outer PHS/region and reject if inside inner region + for (unsigned int i = 0; i < numIters_; ++i) { + if (sampleUniform(statePtr, maxCost)) { + double cost = heuristicCost(statePtr); + if (cost > minCost.value()) { + return true; + } + } + } + return false; + } + + /// @brief Whether this sampler has an analytic measure of the informed region. + bool hasInformedMeasure() const override { + return std::is_same_v; + } + + /// @brief Measure (volume) of the informed region at the given cost. + double getInformedMeasure(const ob::Cost& currentCost) const override { + if constexpr (std::is_same_v) { + if (std::isinf(currentCost.value())) { + return space_->getMeasure(); + } + if (currentCost.value() < phs_->getMinTransverseDiameter()) { + return 0.0; + } + return phs_->getPhsMeasure(currentCost.value()); + } else { + return space_->getMeasure(); + } + } + + /// @brief Heuristic cost of a solution path through the given state. + ob::Cost heuristicSolnCost(const ob::State* statePtr) const override { + return ob::Cost(heuristicCost(statePtr)); + } + + private: + /// @brief Compute h(start, state) + h(state, goal) using the heuristic. + double heuristicCost(const ob::State* statePtr) const { + std::vector coords(space_->getDimension()); + space_->copyToReals(coords, statePtr); + + if constexpr (std::is_same_v) { + // Use PHS path length (L2 distance through foci) directly + return phs_->getPathLength(coords.data()); + } else { + // Map to Eigen for the heuristic callable + Eigen::Map s(start_coords_.data(), start_coords_.size()); + Eigen::Map g(goal_coords_.data(), goal_coords_.size()); + Eigen::Map x(coords.data(), coords.size()); + return heuristic_(s, x) + heuristic_(x, g); + } + } + + /// @brief Direct PHS sampling (EuclideanHeuristic only). + bool samplePHS(ob::State* statePtr, const ob::Cost& maxCost) { + // Before a solution is found, maxCost is infinity — fall back to uniform sampling + if (std::isinf(maxCost.value())) { + baseSampler_->sampleUniform(statePtr); + return true; + } + if (maxCost.value() < phs_->getMinTransverseDiameter()) { + return false; + } + phs_->setTransverseDiameter(maxCost.value()); + + unsigned int dim = space_->getDimension(); + std::vector coords(dim); + + for (unsigned int i = 0; i < numIters_; ++i) { + rng_.uniformProlateHyperspheroid(phs_, coords.data()); + space_->copyFromReals(statePtr, coords); + if (space_->satisfiesBounds(statePtr)) { + return true; + } + } + return false; + } + + /// @brief Rejection sampling for generic heuristics. + bool sampleRejection(ob::State* statePtr, const ob::Cost& maxCost) { + for (unsigned int i = 0; i < numIters_; ++i) { + baseSampler_->sampleUniform(statePtr); + if (heuristicCost(statePtr) <= maxCost.value()) { + return true; + } + } + return false; + } + + HeuristicT heuristic_; + std::vector start_coords_; + std::vector goal_coords_; + ob::StateSamplerPtr baseSampler_; + ::ompl::RNG rng_; + + // Only used for EuclideanHeuristic + std::shared_ptr<::ompl::ProlateHyperspheroid> phs_; +}; + +} // namespace geodex::integration::ompl diff --git a/include/geodex/integration/ompl/geodex_optimization_objective.hpp b/include/geodex/integration/ompl/geodex_optimization_objective.hpp new file mode 100644 index 0000000..5e5b221 --- /dev/null +++ b/include/geodex/integration/ompl/geodex_optimization_objective.hpp @@ -0,0 +1,125 @@ +/// @file geodex_optimization_objective.hpp +/// @brief OMPL optimization objective using geodesic cost and admissible heuristic. + +#pragma once + +#include + +#include +#include + +#include "geodex/algorithm/heuristics.hpp" +#include "geodex/integration/ompl/geodex_informed_sampler.hpp" +#include "geodex/integration/ompl/geodex_state_space.hpp" + +namespace geodex::integration::ompl { + +using geodex::EuclideanHeuristic; +using geodex::RiemannianManifold; + +namespace ob = ::ompl::base; + +/// @brief OMPL optimization objective for geodex manifolds. +/// +/// @details Uses geodesic distance for motion cost (via `si->distance()`) and an +/// admissible heuristic (default: Euclidean chord distance) for `motionCostHeuristic` +/// and `costToGo`. This enables informed planners (InformedRRT*, BIT*) to focus +/// sampling in promising regions. +/// +/// When `setIntegratedArcCost(true)` is enabled, `motionCost` returns the sum +/// of per-segment Riemannian distances along the cached discrete-geodesic arc +/// instead of the endpoint-only `si->distance()`. This makes the planner's +/// parent-selection and rewiring reflect the actual curved arc the local +/// planner will traverse under the custom metric, rather than a scalar +/// midpoint approximation of its endpoints. Falls back to endpoint distance +/// when the cache cannot hold a valid path for the pair. +/// +/// @tparam ManifoldT A type satisfying `geodex::RiemannianManifold`. +/// @tparam HeuristicT Callable with signature `double(Point, Point)`. Defaults to +/// `EuclideanHeuristic` which computes \f$ \|a - b\|_2 \f$. +template +class GeodexOptimizationObjective : public ob::OptimizationObjective { + public: + using Point = typename ManifoldT::Point; ///< Manifold point type. + using StateType = GeodexState; ///< OMPL state type. + + /// @brief Construct the objective. + /// @param si OMPL space information (distance uses geodesic metric). + /// @param goal_coords Goal point coordinates for costToGo evaluation. + /// @param heuristic Admissible heuristic functor. + GeodexOptimizationObjective(const ob::SpaceInformationPtr& si, const Point& goal_coords, + HeuristicT heuristic = HeuristicT{}) + : ob::OptimizationObjective(si), goal_coords_(goal_coords), heuristic_(std::move(heuristic)) { + description_ = "Geodex geodesic distance with admissible heuristic"; + setCostToGoHeuristic( + [this](const ob::State* s, const ob::Goal*) { return this->costToGoHeuristic(s); }); + } + + /// @brief Opt into integrated-arc motion cost. + /// + /// @details When enabled, `motionCost(s1, s2)` computes the arc cost by + /// summing per-segment Riemannian distances along the cached discrete + /// geodesic from `s1` to `s2`, triggering a compute when the cache doesn't + /// hold the pair. When disabled (default), `motionCost` uses + /// `si->distance()`. + void setIntegratedArcCost(bool enabled) { integrated_arc_cost_ = enabled; } + + /// @brief Whether integrated-arc cost is enabled. + bool usesIntegratedArcCost() const { return integrated_arc_cost_; } + + /// @brief State cost (zero for path-length objectives). + ob::Cost stateCost(const ob::State* /*s*/) const override { return ob::Cost(0.0); } + + /// @brief Motion cost: endpoint distance by default, arc cost when enabled. + ob::Cost motionCost(const ob::State* s1, const ob::State* s2) const override { + if (integrated_arc_cost_) { + if (auto cost = tryArcCost(s1, s2); cost.has_value()) { + return ob::Cost(*cost); + } + } + return ob::Cost(si_->distance(s1, s2)); + } + + /// @brief Admissible heuristic for motion cost between two states. + ob::Cost motionCostHeuristic(const ob::State* s1, const ob::State* s2) const override { + const auto* a = s1->as(); + const auto* b = s2->as(); + return ob::Cost(heuristic_(a->asEigen(), b->asEigen())); + } + + /// @brief Allocate a direct informed sampler for this objective. + ob::InformedSamplerPtr allocInformedStateSampler(const ob::ProblemDefinitionPtr& probDefn, + unsigned int maxNumberCalls) const override { + return std::make_shared>(probDefn, maxNumberCalls, + heuristic_); + } + + private: + /// @brief Admissible cost-to-go: heuristic distance from state to goal. + ob::Cost costToGoHeuristic(const ob::State* state) const { + const auto* s = state->as(); + return ob::Cost(heuristic_(s->asEigen(), goal_coords_)); + } + + /// @brief Compute the integrated arc cost if the state space is a + /// `GeodexStateSpace`; otherwise returns nullopt so the caller + /// falls back to endpoint distance. Populates the cache when needed. + std::optional tryArcCost(const ob::State* s1, const ob::State* s2) const { + const auto* space = dynamic_cast*>(si_->getStateSpace().get()); + if (!space) return std::nullopt; + const auto* a = s1->as(); + const auto* b = s2->as(); + Point pa = a->asEigen(); + Point pb = b->asEigen(); + space->ensureGeodesicCached(pa, pb); + const auto& cache = space->getGeodesicCache(); + if (!cache.valid()) return std::nullopt; + return cache.total_arc_cost(); + } + + Point goal_coords_; + HeuristicT heuristic_; + bool integrated_arc_cost_ = false; +}; + +} // namespace geodex::integration::ompl diff --git a/include/geodex/integration/ompl/geodex_state_space.hpp b/include/geodex/integration/ompl/geodex_state_space.hpp new file mode 100644 index 0000000..8702669 --- /dev/null +++ b/include/geodex/integration/ompl/geodex_state_space.hpp @@ -0,0 +1,628 @@ +/// @file geodex_state_space.hpp +/// @brief OMPL integration: adapts geodex manifolds to ompl::base::StateSpace. + +#pragma once + +#include +#include +#include + +#include +#include +#include + +#include +#include +#include +#include + +#include "geodex/algorithm/interpolation.hpp" +#include "geodex/core/concepts.hpp" +#include "geodex/core/metric.hpp" + +namespace geodex::integration::ompl { + +using geodex::discrete_geodesic; +using geodex::InterpolationCache; +using geodex::InterpolationSettings; +using geodex::InterpolationStatus; +using geodex::is_riemannian_log; +using geodex::RiemannianManifold; + +namespace ob = ::ompl::base; + +/// @brief Interpolation strategy for GeodexStateSpace::interpolate(). +enum class InterpolationMode { + Auto, ///< Identity metric -> base geodesic, custom metric -> discrete geodesic. + BaseGeodesic, ///< Always use closed-form manifold.geodesic(p, q, t). + RiemannianGeodesic, ///< Always use iterative discrete geodesic with FD natural gradient. +}; + +// --------------------------------------------------------------------------- +// GeodesicPathCache — amortizes discrete_geodesic across same-endpoint queries +// --------------------------------------------------------------------------- + +/// @brief Caches a discrete geodesic path between two points for efficient +/// arc-length-parameterized lookups. +/// +/// @details OMPL's `DiscreteMotionValidator` calls `interpolate(s1, s2, j/n)` +/// for `j = 1..n-1` with the same `(s1, s2)` pair. This cache computes the +/// full discrete geodesic once and serves subsequent lookups via binary search +/// on cumulative arc lengths — O(log K) per query instead of recomputing the +/// geodesic each time. +/// +/// @note Not thread-safe: the owning `GeodexStateSpace` stores this cache as a +/// `mutable` member and mutates it from the `const` `interpolate()` method. +/// OMPL's standard planners run a single `interpolate()` call per state-space +/// instance at a time, so the single-entry cache is safe in that context. +/// Concurrent planners must either synchronize externally or use a separate +/// state-space instance per thread. +/// +/// @tparam M A type satisfying `RiemannianManifold`. +template +class GeodesicPathCache { + public: + using Point = typename M::Point; + using Scalar = typename M::Scalar; + + /// @brief Check whether the cache holds a valid path for the given endpoints. + /// @param f Start point. + /// @param t Target point. + /// @param dim Ambient dimension (number of doubles to compare). + /// @return True if the cache matches and is valid. + bool matches(const Point& f, const Point& t, unsigned int dim) const { + if (!valid_) return false; + return std::memcmp(from_.data(), f.data(), dim * sizeof(double)) == 0 && + std::memcmp(to_.data(), t.data(), dim * sizeof(double)) == 0; + } + + /// @brief Compute the discrete geodesic from \p f to \p t and cache the result. + /// @param manifold The manifold instance. + /// @param f Start point. + /// @param t Target point. + /// @param settings Interpolation settings (step_size controls path resolution). + void compute(const M& manifold, const Point& f, const Point& t, + const InterpolationSettings& settings) { + from_ = f; + to_ = t; + valid_ = false; + + auto result = discrete_geodesic(manifold, f, t, settings, &interp_cache_); + + // Accept Converged, MaxStepsReached, and DegenerateInput. + // Reject CutLocus, GradientVanished, StepShrunkToZero — caller falls back. + if (result.status == InterpolationStatus::CutLocus || + result.status == InterpolationStatus::GradientVanished || + result.status == InterpolationStatus::StepShrunkToZero) { + return; + } + + waypoints_ = std::move(result.path); + + // Ensure the target is the final waypoint for exact t=1 lookup. + if (waypoints_.empty()) { + waypoints_.push_back(f); + waypoints_.push_back(t); + } else if ((waypoints_.back() - t).norm() > 1e-12) { + waypoints_.push_back(t); + } + + // Build cumulative arc-length table. + const auto n = waypoints_.size(); + cum_arc_.resize(n); + cum_arc_[0] = 0.0; + for (std::size_t i = 1; i < n; ++i) { + cum_arc_[i] = cum_arc_[i - 1] + + static_cast(manifold.distance(waypoints_[i - 1], waypoints_[i])); + } + total_arc_ = cum_arc_.back(); + + valid_ = true; + } + + /// @brief Look up the point at arc-length fraction \p t along the cached path. + /// @param manifold The manifold instance (for local geodesic interpolation). + /// @param t Parameter in [0, 1] (0 = start, 1 = target). + /// @return The interpolated point on the cached geodesic path. + Point at(const M& manifold, double t) const { + if (t <= 0.0) return waypoints_.front(); + if (t >= 1.0) return waypoints_.back(); + + if (waypoints_.size() <= 1 || total_arc_ <= 0.0) { + return waypoints_.front(); + } + + const double target_s = t * total_arc_; + + // Binary search: find first element > target_s. + const auto it = std::upper_bound(cum_arc_.begin(), cum_arc_.end(), target_s); + auto idx = static_cast(it - cum_arc_.begin()) - 1; + idx = std::max(0, std::min(idx, static_cast(waypoints_.size()) - 2)); + + const double seg_len = cum_arc_[idx + 1] - cum_arc_[idx]; + const double t_local = (seg_len > 1e-15) ? (target_s - cum_arc_[idx]) / seg_len : 0.0; + + // Local geodesic between adjacent waypoints — close enough for retraction accuracy. + return manifold.geodesic(waypoints_[idx], waypoints_[idx + 1], t_local); + } + + /// @brief Whether the cache holds a valid path. + bool valid() const { return valid_; } + + /// @brief Total Riemannian arc length along the cached discrete geodesic. + /// + /// @details Sum of per-segment `manifold.distance(waypoints[i], waypoints[i+1])` + /// values computed when the path was cached. For a valid cache this is the + /// natural cost of the arc under the configured metric; for an invalid cache + /// (no successful compute) returns 0.0. + double total_arc_cost() const { return total_arc_; } + + private: + Point from_; + Point to_; + std::vector waypoints_; + std::vector cum_arc_; + double total_arc_ = 0.0; + bool valid_ = false; + InterpolationCache interp_cache_; +}; + +// --------------------------------------------------------------------------- +// GeodexStateSpace — adapts a geodex RiemannianManifold to ompl::base::StateSpace +// --------------------------------------------------------------------------- + +template + requires geodex::RiemannianManifold +class GeodexStateSpace; + +// --------------------------------------------------------------------------- +// GeodexState — state type storing ambient-space coordinates +// --------------------------------------------------------------------------- + +/// @brief State type for GeodexStateSpace, storing ambient-space coordinates. +/// +/// @details Wraps a raw `double*` array with Eigen map accessors for +/// convenient conversion between OMPL states and geodex manifold points. +/// +/// @tparam ManifoldT The geodex manifold type. +template +class GeodexState : public ob::State { + public: + double* values = nullptr; ///< Raw coordinate array (owned by the state space). + + /// @brief Read-only Eigen map of the state coordinates. + auto asEigen() const { + using Point = typename ManifoldT::Point; + constexpr int Dim = Point::SizeAtCompileTime; + return Eigen::Map>(values); + } + + /// @brief Mutable Eigen map of the state coordinates. + auto asEigen() { + using Point = typename ManifoldT::Point; + constexpr int Dim = Point::SizeAtCompileTime; + return Eigen::Map>(values); + } +}; + +// --------------------------------------------------------------------------- +// GeodexStateSampler +// --------------------------------------------------------------------------- + +/// @brief State sampler for GeodexStateSpace. +/// +/// @details Provides uniform, near-uniform, and Gaussian sampling on the +/// manifold by sampling tangent vectors and applying the exponential map. +/// +/// @tparam ManifoldT The geodex manifold type. +template +class GeodexStateSampler : public ob::StateSampler { + using StateSpace = GeodexStateSpace; + using StateType = GeodexState; + + public: + /// @brief Construct a sampler for the given state space. + /// @param space The GeodexStateSpace to sample from. + explicit GeodexStateSampler(const ob::StateSpace* space) : ob::StateSampler(space) {} + + /// @brief Sample a state uniformly within the bounds. + void sampleUniform(ob::State* state) override { + auto* s = state->as(); + const auto* space = static_cast(space_); + const auto& bounds = space->getBounds(); + const unsigned int dim = space->getDimension(); + for (unsigned int i = 0; i < dim; ++i) { + s->values[i] = rng_.uniformReal(bounds.low[i], bounds.high[i]); + } + } + + /// @brief Sample a state uniformly near another state at a given distance. + /// @param state Output state. + /// @param near Reference state to sample around. + /// @param distance Desired geodesic distance from \p near. + void sampleUniformNear(ob::State* state, const ob::State* near, double distance) override { + auto* s = state->as(); + const auto* n = near->as(); + const auto* space = static_cast(space_); + const auto& manifold = space->getManifold(); + const auto& bounds = space->getBounds(); + const unsigned int dim = space->getDimension(); + + // Sample a random tangent vector at 'near', scale to desired distance + using Point = typename ManifoldT::Point; + using Tangent = typename ManifoldT::Tangent; + Point p_near = n->asEigen(); + + Tangent v; + if constexpr (Point::SizeAtCompileTime == Eigen::Dynamic) { + v.resize(dim); + } + for (unsigned int i = 0; i < dim; ++i) { + v[i] = rng_.gaussian01(); + } + double v_norm = manifold.norm(p_near, v); + if (v_norm > 1e-12) { + v *= distance / v_norm; + } + + Point result = manifold.exp(p_near, v); + + // Clamp to bounds + for (unsigned int i = 0; i < dim; ++i) { + s->values[i] = std::clamp(result[i], bounds.low[i], bounds.high[i]); + } + } + + /// @brief Sample a state from a Gaussian distribution centered at \p mean. + /// @param state Output state. + /// @param mean Center of the Gaussian. + /// @param stdDev Standard deviation in the tangent space. + void sampleGaussian(ob::State* state, const ob::State* mean, double stdDev) override { + auto* s = state->as(); + const auto* m = mean->as(); + const auto* space = static_cast(space_); + const auto& manifold = space->getManifold(); + const auto& bounds = space->getBounds(); + const unsigned int dim = space->getDimension(); + + using Point = typename ManifoldT::Point; + using Tangent = typename ManifoldT::Tangent; + Point p_mean = m->asEigen(); + + Tangent v; + if constexpr (Point::SizeAtCompileTime == Eigen::Dynamic) { + v.resize(dim); + } + for (unsigned int i = 0; i < dim; ++i) { + v[i] = rng_.gaussian(0.0, stdDev); + } + + Point result = manifold.exp(p_mean, v); + + for (unsigned int i = 0; i < dim; ++i) { + s->values[i] = std::clamp(result[i], bounds.low[i], bounds.high[i]); + } + } +}; + +// --------------------------------------------------------------------------- +// GeodexStateSpace +// --------------------------------------------------------------------------- + +/// @brief OMPL state space adapter for geodex Riemannian manifolds. +/// +/// @details Wraps a geodex `RiemannianManifold` as an `ompl::base::StateSpace`, +/// delegating distance, interpolation, and sampling to the manifold's operations. +/// States store ambient-space coordinates as raw `double*` arrays. +/// +/// @tparam ManifoldT A type satisfying `geodex::RiemannianManifold`. +template + requires geodex::RiemannianManifold +class GeodexStateSpace : public ob::StateSpace { + public: + using Point = typename ManifoldT::Point; ///< Manifold point type. + using Tangent = typename ManifoldT::Tangent; ///< Manifold tangent type. + using StateType = GeodexState; ///< OMPL state type. + + /// @brief Construct a state space from a manifold and bounds. + /// @param manifold The geodex manifold instance. + /// @param bounds Axis-aligned bounds for the ambient coordinates. + GeodexStateSpace(ManifoldT manifold, ob::RealVectorBounds bounds) + : manifold_(std::move(manifold)), bounds_(std::move(bounds)) { + setName("GeodexStateSpace"); + type_ = ob::STATE_SPACE_UNKNOWN; + + if constexpr (Point::SizeAtCompileTime != Eigen::Dynamic) { + ambient_dim_ = static_cast(Point::SizeAtCompileTime); + } else { + ambient_dim_ = static_cast(manifold_.dim()); + } + + assert(bounds_.low.size() == ambient_dim_); + assert(bounds_.high.size() == ambient_dim_); + } + + /// @brief Access the underlying geodex manifold. + const ManifoldT& getManifold() const { return manifold_; } + + /// @brief Access the coordinate bounds. + const ob::RealVectorBounds& getBounds() const { return bounds_; } + + /// @brief Set the minimum collision checking resolution in coordinate distance. + /// + /// @details When set to a positive value, `validSegmentCount()` ensures at + /// least `ceil(coord_distance / resolution)` checks along each edge, + /// independent of OMPL's `longestValidSegmentFraction`. This prevents thin + /// walls from being missed when `getMaximumExtent()` is large. + /// + /// @param resolution Minimum distance (meters) between collision checks. + /// Use 0.0 to disable (OMPL default only). + void setCollisionResolution(double resolution) { collision_resolution_ = resolution; } + + /// @brief Get the collision checking resolution. + double getCollisionResolution() const { return collision_resolution_; } + + /// @brief Set the interpolation strategy. + /// @param mode The desired interpolation mode. + void setInterpolationMode(const InterpolationMode mode) { interpolation_mode_ = mode; } + + /// @brief Get the current interpolation mode. + InterpolationMode getInterpolationMode() const { return interpolation_mode_; } + + /// @brief Set the interpolation settings for discrete geodesic computation. + /// @param settings The settings (step_size, convergence_tol, max_steps, etc.). + void setInterpolationSettings(const InterpolationSettings& settings) { + interpolation_settings_ = settings; + } + + /// @brief Get the current interpolation settings. + const InterpolationSettings& getInterpolationSettings() const { return interpolation_settings_; } + + /// @brief Convenience: set the step size for discrete geodesic interpolation. + /// + /// @details Controls the maximum Riemannian distance between consecutive + /// waypoints in the cached geodesic path. Smaller values increase resolution + /// (and computation cost). Default is 0.5. + /// + /// @param step_size Maximum step size per iteration. + void setGeodesicStepSize(const double step_size) { + interpolation_settings_.step_size = step_size; + } + + // -- StateSpace interface -- + + /// @brief Return the ambient dimension of the state space. + unsigned int getDimension() const override { return ambient_dim_; } + + /// @brief Return the maximum extent of the state space. + /// + /// @todo Validate this fix properly. Current approach (max of coordinate + /// diagonal and Riemannian corner-to-corner distance) fixes the connect-loop + /// hang with anisotropic metrics, but the corner-to-corner Riemannian + /// distance may not be the true maximum extent (angle wrapping, non-diagonal + /// pairs, configuration-dependent metrics). Needs formal analysis and tests + /// across different manifold types. + double getMaximumExtent() const override { + // Coordinate diagonal (baseline for isotropic metrics) + double diag2 = 0.0; + for (unsigned int i = 0; i < ambient_dim_; ++i) { + double d = bounds_.high[i] - bounds_.low[i]; + diag2 += d * d; + } + double coord_extent = std::sqrt(diag2); + + // Riemannian distance between bounding box corners + Point lo, hi; + if constexpr (Point::SizeAtCompileTime == Eigen::Dynamic) { + lo.resize(ambient_dim_); + hi.resize(ambient_dim_); + } + for (unsigned int i = 0; i < ambient_dim_; ++i) { + lo[i] = bounds_.low[i]; + hi[i] = bounds_.high[i]; + } + double riem_extent = manifold_.distance(lo, hi); + + return std::max(coord_extent, riem_extent); + } + + /// @brief Return the volume of the bounding box. + double getMeasure() const override { + double vol = 1.0; + for (unsigned int i = 0; i < ambient_dim_; ++i) { + vol *= bounds_.high[i] - bounds_.low[i]; + } + return vol; + } + + /// @brief Clamp state coordinates to the bounds. + void enforceBounds(ob::State* state) const override { + auto* s = state->as(); + for (unsigned int i = 0; i < ambient_dim_; ++i) { + s->values[i] = std::clamp(s->values[i], bounds_.low[i], bounds_.high[i]); + } + } + + /// @brief Check whether all coordinates satisfy the bounds. + bool satisfiesBounds(const ob::State* state) const override { + const auto* s = state->as(); + for (unsigned int i = 0; i < ambient_dim_; ++i) { + if (s->values[i] < bounds_.low[i] - std::numeric_limits::epsilon() || + s->values[i] > bounds_.high[i] + std::numeric_limits::epsilon()) { + return false; + } + } + return true; + } + + /// @brief Copy state coordinates. + void copyState(ob::State* destination, const ob::State* source) const override { + auto* dst = destination->as(); + const auto* src = source->as(); + std::memcpy(dst->values, src->values, ambient_dim_ * sizeof(double)); + } + + /// @brief Compute the geodesic distance between two states. + double distance(const ob::State* state1, const ob::State* state2) const override { + const auto* s1 = state1->as(); + const auto* s2 = state2->as(); + return manifold_.distance(s1->asEigen(), s2->asEigen()); + } + + /// @brief Check whether two states are equal (within tolerance). + bool equalStates(const ob::State* state1, const ob::State* state2) const override { + const auto* s1 = state1->as(); + const auto* s2 = state2->as(); + for (unsigned int i = 0; i < ambient_dim_; ++i) { + if (std::abs(s1->values[i] - s2->values[i]) > 1e-12) return false; + } + return true; + } + + /// @brief Geodesic interpolation between two states. + /// + /// @details For manifolds where `is_riemannian_log()` returns true (identity + /// metric with matching retraction), uses the direct `geodesic(p, q, t)` — + /// zero overhead. For non-flat metrics, computes a discrete geodesic via + /// Riemannian natural gradient descent, caches the path, and serves + /// subsequent lookups via arc-length parameterization. The cache is keyed on + /// the (from, to) state pair; sequential calls with the same pair (as in + /// `DiscreteMotionValidator::checkMotion`) amortize the computation. + /// + /// @param from Start state. + /// @param to End state. + /// @param t Interpolation parameter in [0, 1]. + /// @param state Output state. + void interpolate(const ob::State* from, const ob::State* to, double t, + ob::State* state) const override { + const auto* f = from->as(); + const auto* tgt = to->as(); + auto* s = state->as(); + + const bool use_base_geodesic = + (interpolation_mode_ == InterpolationMode::BaseGeodesic) || + (interpolation_mode_ == InterpolationMode::Auto && is_riemannian_log(manifold_)); + if (use_base_geodesic) { + Point result = manifold_.geodesic(f->asEigen(), tgt->asEigen(), t); + for (unsigned int i = 0; i < ambient_dim_; ++i) s->values[i] = result[i]; + return; + } + + // Boundary: avoid cache computation for endpoints. + if (t <= 0.0) { + copyState(state, from); + return; + } + if (t >= 1.0) { + copyState(state, to); + return; + } + + // Check cache; compute if miss. + Point p_from = f->asEigen(); + Point p_to = tgt->asEigen(); + if (!geodesic_cache_.matches(p_from, p_to, ambient_dim_)) { + geodesic_cache_.compute(manifold_, p_from, p_to, interpolation_settings_); + } + + // Fallback on convergence failure (cut locus, gradient vanished, etc.). + if (!geodesic_cache_.valid()) { + Point result = manifold_.geodesic(p_from, p_to, t); + for (unsigned int i = 0; i < ambient_dim_; ++i) s->values[i] = result[i]; + return; + } + + // Arc-length lookup from cache. + Point result = geodesic_cache_.at(manifold_, t); + for (unsigned int i = 0; i < ambient_dim_; ++i) s->values[i] = result[i]; + } + + /// @brief Allocate the default state sampler. + ob::StateSamplerPtr allocDefaultStateSampler() const override { + return std::make_shared>(this); + } + + /// @brief Allocate a new state. + ob::State* allocState() const override { + auto* s = new StateType(); + s->values = new double[ambient_dim_]; + return s; + } + + /// @brief Free a state. + void freeState(ob::State* state) const override { + auto* s = state->as(); + delete[] s->values; + delete s; + } + + /// @brief Get a pointer to the coordinate at the given index. + double* getValueAddressAtIndex(ob::State* state, unsigned int index) const override { + if (index >= ambient_dim_) return nullptr; + return state->as()->values + index; + } + + /// @brief Copy state coordinates to a vector of doubles. + void copyToReals(std::vector& reals, const ob::State* source) const override { + const auto* s = source->as(); + reals.resize(ambient_dim_); + for (unsigned int i = 0; i < ambient_dim_; ++i) reals[i] = s->values[i]; + } + + /// @brief Set state coordinates from a vector of doubles. + void copyFromReals(ob::State* destination, const std::vector& reals) const override { + auto* d = destination->as(); + for (unsigned int i = 0; i < ambient_dim_; ++i) d->values[i] = reals[i]; + } + + /// @brief Read-only access to the internal cached discrete-geodesic path. + /// + /// @details Exposed so `GeodexOptimizationObjective` can compute the + /// integrated arc cost for the last `interpolate()` pair without recomputing. + /// The cache holds at most one (s1, s2) pair at a time; callers must check + /// `matches()` before using it. + const GeodesicPathCache& getGeodesicCache() const { return geodesic_cache_; } + + /// @brief Populate the cache for the given endpoint pair (or no-op on hit). + /// + /// @details Used by the optimization objective when it needs the arc cost + /// for a pair that is not yet cached. + /// Uses the state space's configured `InterpolationSettings`. + void ensureGeodesicCached(const Point& from, const Point& to) const { + if (!geodesic_cache_.matches(from, to, ambient_dim_)) { + geodesic_cache_.compute(manifold_, from, to, interpolation_settings_); + } + } + + /// @brief Number of collision checks for a motion between two states. + /// + /// @details Returns the maximum of OMPL's default segment count and a + /// coordinate-distance-based count derived from `collision_resolution_`. + unsigned int validSegmentCount(const ob::State* s1, const ob::State* s2) const override { + unsigned int n = ob::StateSpace::validSegmentCount(s1, s2); + if (collision_resolution_ > 0.0) { + const auto* a = s1->as(); + const auto* b = s2->as(); + double dist2 = 0.0; + for (unsigned int i = 0; i < ambient_dim_; ++i) { + double d = a->values[i] - b->values[i]; + dist2 += d * d; + } + unsigned int n_coord = + static_cast(std::ceil(std::sqrt(dist2) / collision_resolution_)); + n = std::max(n, n_coord); + } + return std::max(n, 1u); + } + + private: + ManifoldT manifold_; + ob::RealVectorBounds bounds_; + unsigned int ambient_dim_; + double collision_resolution_ = 0.0; + InterpolationMode interpolation_mode_ = InterpolationMode::Auto; + InterpolationSettings interpolation_settings_; + mutable GeodesicPathCache geodesic_cache_; +}; + +} // namespace geodex::integration::ompl diff --git a/include/geodex/integration/ompl/validity_checker.hpp b/include/geodex/integration/ompl/validity_checker.hpp new file mode 100644 index 0000000..19e5a81 --- /dev/null +++ b/include/geodex/integration/ompl/validity_checker.hpp @@ -0,0 +1,45 @@ +/// @file validity_checker.hpp +/// @brief Generic OMPL StateValidityChecker adapter for any callable. + +#pragma once + +#include + +#include + +#include "geodex/integration/ompl/geodex_state_space.hpp" + +namespace geodex::integration::ompl { + +/// @brief Generic OMPL StateValidityChecker from any bool(Point) callable. +/// +/// Usage: +/// @code +/// auto validity = [&](const auto& q) { return checker.is_valid(q); }; +/// ss.setStateValidityChecker( +/// make_validity_checker(si, validity)); +/// @endcode +template +class ValidityChecker : public ::ompl::base::StateValidityChecker { + public: + /// @brief Construct with space information and validity callable. + ValidityChecker(const ::ompl::base::SpaceInformationPtr& si, ValidityFn fn) + : ::ompl::base::StateValidityChecker(si), fn_(std::move(fn)) {} + + /// @brief Check if the given state is collision-free. + bool isValid(const ::ompl::base::State* state) const override { + const auto* s = state->as>(); + return fn_(s->asEigen()); + } + + private: + ValidityFn fn_; +}; + +/// @brief Convenience factory (deduces ValidityFn from the argument). +template +auto make_validity_checker(const ::ompl::base::SpaceInformationPtr& si, ValidityFn fn) { + return std::make_shared>(si, std::move(fn)); +} + +} // namespace geodex::integration::ompl diff --git a/include/geodex/manifold/configuration_space.hpp b/include/geodex/manifold/configuration_space.hpp index c76d27e..3ac9ca6 100644 --- a/include/geodex/manifold/configuration_space.hpp +++ b/include/geodex/manifold/configuration_space.hpp @@ -3,8 +3,9 @@ #pragma once -#include -#include +#include "geodex/algorithm/distance.hpp" +#include "geodex/core/concepts.hpp" +#include "geodex/core/metric.hpp" namespace geodex { @@ -20,13 +21,24 @@ namespace geodex { /// @tparam MetricT The metric policy type (must provide `inner` and `norm`). template class ConfigurationSpace { - BaseManifoldT base_; - MetricT metric_; - public: - using Scalar = typename BaseManifoldT::Scalar; ///< Scalar type from the base manifold. - using Point = typename BaseManifoldT::Point; ///< Point type from the base manifold. - using Tangent = typename BaseManifoldT::Tangent; ///< Tangent vector type from the base manifold. + using Scalar = typename BaseManifoldT::Scalar; ///< Scalar type from the base manifold. + using Point = typename BaseManifoldT::Point; ///< Point type from the base manifold. + using Tangent = typename BaseManifoldT::Tangent; ///< Tangent vector type from the base manifold. + + /// @brief Runtime query: is `log` the Riemannian logarithm of the custom metric? + /// + /// @details Always returns `false`. The whole purpose of `ConfigurationSpace` + /// is to overlay a custom metric on a base manifold — the base's `log` is the + /// Riemannian log of the base's native metric, not of the custom metric. + /// This forces `discrete_geodesic` to use the finite-difference natural + /// gradient, which correctly follows the energy-minimizing curve under the + /// custom metric. + /// @warning Setting `InterpolationSettings::force_log_direction = true` on a + /// ConfigurationSpace bypasses this and uses the base manifold's log for direction. + /// The resulting path follows the base metric's geodesic, not the custom metric's. + /// Only use when the base log is a reasonable approximation. + bool has_riemannian_log_runtime() const { return false; } /// @brief Construct with a base manifold and a metric. /// @param base The base manifold instance. @@ -73,27 +85,40 @@ class ConfigurationSpace { /// @brief Riemannian norm from the custom metric. Scalar norm(const Point& p, const Tangent& v) const { return metric_.norm(p, v); } + /// @brief Batched inner product \f$U^\top M(p)\, V\f$ when the custom metric provides it. + /// + /// @details Forwards to the metric's `inner_matrix`. This is the main + /// performance hook for kinetic-energy configuration spaces, where the + /// expensive mass matrix evaluation is amortized over all \f$d^2\f$ entries + /// of the tangent-metric tensor in a single call. + Eigen::MatrixXd inner_matrix(const Point& p, const Eigen::MatrixXd& U, + const Eigen::MatrixXd& V) const + requires requires(const MetricT& m, const Point& q, const Eigen::MatrixXd& A) { + { m.inner_matrix(q, A, A) } -> std::convertible_to; + } + { + return metric_.inner_matrix(p, U, V); + } + /// @} /// @name Derived operations /// @{ /// @brief Geodesic distance via the midpoint approximation. - Scalar distance(const Point& p, const Point& q) const { - return distance_midpoint(*this, p, q); - } + Scalar distance(const Point& p, const Point& q) const { return distance_midpoint(*this, p, q); } /// @brief Injectivity radius — forwarded from the metric if available. Scalar injectivity_radius() const - requires requires { metric_.injectivity_radius(); } + requires requires(const MetricT& m) { + { m.injectivity_radius() }; + } { return metric_.injectivity_radius(); } /// @brief Geodesic interpolation between two points. - Point geodesic(const Point& p, const Point& q, Scalar t) const { - return exp(p, t * log(p, q)); - } + Point geodesic(const Point& p, const Point& q, Scalar t) const { return exp(p, t * log(p, q)); } /// @} @@ -102,6 +127,10 @@ class ConfigurationSpace { /// @brief Access the metric. const MetricT& metric() const { return metric_; } + + private: + BaseManifoldT base_; + MetricT metric_; }; } // namespace geodex diff --git a/include/geodex/manifold/euclidean.hpp b/include/geodex/manifold/euclidean.hpp index e8807fe..fc4888d 100644 --- a/include/geodex/manifold/euclidean.hpp +++ b/include/geodex/manifold/euclidean.hpp @@ -3,50 +3,31 @@ #pragma once -#include #include -#include -#include + #include -#include +#include -#include +#include + +#include "geodex/algorithm/distance.hpp" +#include "geodex/core/concepts.hpp" +#include "geodex/core/sampler.hpp" +#include "geodex/metrics/constant_spd.hpp" +#include "geodex/metrics/identity.hpp" namespace geodex { // --------------------------------------------------------------------------- -// Metric +// Metric alias // --------------------------------------------------------------------------- -/// @brief Standard flat (Euclidean) metric on \f$ \mathbb{R}^n \f$. +/// @brief The standard Euclidean metric on \f$ \mathbb{R}^n \f$. /// /// @details The inner product is the standard dot product: -/// \f$ \langle u, v \rangle = u \cdot v \f$. -/// The injectivity radius is \f$ \infty \f$. -/// -/// @tparam Dim Compile-time dimension, or `Eigen::Dynamic` for runtime sizing. +/// \f$ \langle u, v \rangle = u \cdot v \f$. Zero-storage stateless metric. template -struct EuclideanStandardMetric { - /// @brief Compute the inner product \f$ \langle u, v \rangle = u \cdot v \f$. - /// @param u First tangent vector. - /// @param v Second tangent vector. - /// @return The inner product value. - double inner(const Eigen::Vector& /*p*/, const Eigen::Vector& u, - const Eigen::Vector& v) const { - return u.dot(v); - } - - /// @brief Compute the Euclidean norm \f$ \|v\| = \sqrt{v \cdot v} \f$. - /// @param p Base point. - /// @param v Tangent vector. - /// @return The norm value. - double norm(const Eigen::Vector& p, const Eigen::Vector& v) const { - return std::sqrt(inner(p, v, v)); - } - - /// @brief Return the injectivity radius \f$ \infty \f$. - double injectivity_radius() const { return std::numeric_limits::infinity(); } -}; +using EuclideanStandardMetric = IdentityMetric; // --------------------------------------------------------------------------- // Euclidean manifold @@ -60,54 +41,97 @@ struct EuclideanStandardMetric { /// /// @tparam Dim Compile-time dimension, or `Eigen::Dynamic`. /// @tparam MetricT Metric policy (default: EuclideanStandardMetric). -template > +/// @tparam SamplerT Sampler policy for `random_point()` (default: `StochasticSampler`). +template , + typename SamplerT = StochasticSampler> class Euclidean { - MetricT metric_; - int dim_; - public: using Scalar = double; ///< Scalar type. using Point = Eigen::Vector; ///< Point type. using Tangent = Eigen::Vector; ///< Tangent vector type. - /// @brief Fixed-dimension constructor. + /// @brief Runtime query: is `log` the Riemannian logarithm of the metric? + /// + /// @details True only when the metric is the identity `ConstantSPDMetric` + /// (the standard Euclidean dot product). Non-identity SPDs live under a + /// different inner product, so `discrete_geodesic` falls back to finite + /// differences for those cases. + bool has_riemannian_log_runtime() const { + if constexpr (std::is_same_v>) { + return true; + } else if constexpr (std::is_same_v>) { + return metric_.weight_matrix().isApprox( + Eigen::Matrix::Identity(dim_, dim_)); + } else { + return false; + } + } + + /// @brief Fixed-dimension constructor with default bounds \f$[-1, 1]^n\f$. Euclidean() requires(Dim != Eigen::Dynamic) - : dim_(Dim) {} + : dim_(Dim), + lo_(Eigen::VectorXd::Constant(Dim, -1.0)), + hi_(Eigen::VectorXd::Constant(Dim, 1.0)), + sample_buf_(Dim) {} /// @brief Fixed-dimension constructor with custom metric. /// @param metric The metric policy instance. explicit Euclidean(MetricT metric) requires(Dim != Eigen::Dynamic) - : metric_(std::move(metric)), dim_(Dim) {} + : metric_(std::move(metric)), + dim_(Dim), + lo_(Eigen::VectorXd::Constant(Dim, -1.0)), + hi_(Eigen::VectorXd::Constant(Dim, 1.0)), + sample_buf_(Dim) {} /// @brief Dynamic-dimension constructor. /// @param n The dimension of the space. explicit Euclidean(int n) requires(Dim == Eigen::Dynamic) - : dim_(n) {} + : metric_(make_default_metric(n)), + dim_(n), + lo_(Eigen::VectorXd::Constant(n, -1.0)), + hi_(Eigen::VectorXd::Constant(n, 1.0)), + sample_buf_(n) {} /// @brief Dynamic-dimension constructor with custom metric. /// @param n The dimension of the space. /// @param metric The metric policy instance. Euclidean(int n, MetricT metric) requires(Dim == Eigen::Dynamic) - : metric_(std::move(metric)), dim_(n) {} + : metric_(std::move(metric)), + dim_(n), + lo_(Eigen::VectorXd::Constant(n, -1.0)), + hi_(Eigen::VectorXd::Constant(n, 1.0)), + sample_buf_(n) {} + + /// @brief Set the sampling bounds. Values outside these bounds are never + /// returned by `random_point()`, but `exp`/`log`/metric operations remain + /// unchanged (bounds are a sampler concern, not a topological one). + void set_sampling_bounds(const Eigen::VectorXd& lo, const Eigen::VectorXd& hi) { + lo_ = lo; + hi_ = hi; + } /// @brief Return the dimension of the space. int dim() const { return dim_; } - /// @brief Sample a random point from a standard normal distribution. - /// @return A point in \f$ \mathbb{R}^n \f$. + /// @brief Sample a point uniformly in \f$[\mathrm{lo}, \mathrm{hi}]^n\f$ (default \f$[-1, + /// 1]^n\f$). + /// + /// @details Uses the configured `SamplerT` (default: `StochasticSampler`) + /// to draw uniform box samples and linearly rescales to the sampling + /// bounds. Pass `HaltonSampler` via the template parameter for + /// deterministic low-discrepancy sampling. Point random_point() const { - thread_local std::mt19937 gen{std::random_device{}()}; - std::normal_distribution dist(0.0, 1.0); + sampler_.sample_box(dim_, sample_buf_); Point p; if constexpr (Dim == Eigen::Dynamic) { p.resize(dim_); } for (int i = 0; i < dim_; ++i) { - p[i] = dist(gen); + p[i] = lo_[i] + sample_buf_[i] * (hi_[i] - lo_[i]); } return p; } @@ -129,6 +153,14 @@ class Euclidean { /// @brief Riemannian norm at \f$ p \f$. Scalar norm(const Point& p, const Tangent& v) const { return metric_.norm(p, v); } + /// @brief Batched inner product \f$U^\top M(p)\, V\f$ when the metric provides it. + Eigen::MatrixXd inner_matrix(const Point& p, const Eigen::MatrixXd& U, + const Eigen::MatrixXd& V) const + requires MetricHasInnerMatrix + { + return metric_.inner_matrix(p, U, V); + } + /// @} /// @name Exp / Log @@ -157,12 +189,13 @@ class Euclidean { /// @return The distance \f$ d(p, q) \f$. Scalar distance(const Point& p, const Point& q) const { return distance_midpoint(*this, p, q); } - /// @brief Injectivity radius — only available when the metric provides it. - Scalar injectivity_radius() const - requires requires { metric_.injectivity_radius(); } - { - return metric_.injectivity_radius(); - } + /// @brief Injectivity radius of \f$ \mathbb{R}^n \f$: \f$ \infty \f$. + /// + /// @details Euclidean space is flat, so the injectivity radius is infinite + /// regardless of the metric. Anisotropic custom metrics change geodesic + /// directions but not the fact that the space is simply connected and + /// geodesically complete. + Scalar injectivity_radius() const { return std::numeric_limits::infinity(); } /// @brief Geodesic interpolation: \f$ (1 - t) p + t q \f$. /// @param p Start point. @@ -172,6 +205,24 @@ class Euclidean { Point geodesic(const Point& p, const Point& q, Scalar t) const { return (1.0 - t) * p + t * q; } /// @} + + private: + /// @brief Build the default metric for dynamic Euclidean: `ConstantSPDMetric(n)` + /// when applicable, otherwise a default-constructed metric. + static MetricT make_default_metric(int n) { + if constexpr (std::is_constructible_v) { + return MetricT(n); + } else { + return MetricT{}; + } + } + + MetricT metric_; + int dim_; + Eigen::VectorXd lo_; ///< Lower sampling bounds (default: -1^n). + Eigen::VectorXd hi_; ///< Upper sampling bounds (default: 1^n). + mutable SamplerT sampler_; ///< Sampler used by `random_point`. + mutable Eigen::VectorXd sample_buf_; ///< Preallocated buffer for sampler output. }; // Verify the default type satisfies RiemannianManifold. diff --git a/include/geodex/manifold/se2.hpp b/include/geodex/manifold/se2.hpp index 36ddcc1..dfc8825 100644 --- a/include/geodex/manifold/se2.hpp +++ b/include/geodex/manifold/se2.hpp @@ -3,16 +3,20 @@ #pragma once -#include #include -#include -#include -#include -#include + #include -#include +#include -#include +#include + +#include "geodex/algorithm/distance.hpp" +#include "geodex/core/concepts.hpp" +#include "geodex/core/retraction.hpp" +#include "geodex/core/sampler.hpp" +#include "geodex/metrics/se2_left_invariant.hpp" +#include "geodex/utils/angle.hpp" +#include "geodex/utils/math.hpp" namespace geodex { @@ -51,7 +55,7 @@ struct SE2ExponentialMap { const double dx = ct * tx - st * ty; const double dy = st * tx + ct * ty; - return Eigen::Vector3d(p[0] + dx, p[1] + dy, wrap_to_pi(p[2] + omega)); + return Eigen::Vector3d(p[0] + dx, p[1] + dy, utils::wrap_to_pi(p[2] + omega)); } /// @brief Logarithmic map \f$ \log_p(q) \f$ on SE(2). @@ -64,7 +68,7 @@ struct SE2ExponentialMap { const double dxw = q[0] - p[0], dyw = q[1] - p[1]; const double dx = ct * dxw + st * dyw; const double dy = -st * dxw + ct * dyw; - const double dtheta = wrap_to_pi(q[2] - p[2]); + const double dtheta = utils::wrap_to_pi(q[2] - p[2]); double vx, vy; if (std::abs(dtheta) < 1e-8) { @@ -82,18 +86,20 @@ struct SE2ExponentialMap { } }; -/// @brief First-order Euler retraction on SE(2) (cheapest, treats as \f$ \mathbb{R}^2 \times S^1 \f$). +/// @brief First-order Euler retraction on SE(2) (cheapest, treats as \f$ \mathbb{R}^2 \times S^1 +/// \f$). /// /// @details Simply adds the tangent vector component-wise with angle wrapping. /// This is a valid first-order retraction but does not capture the group structure. struct SE2EulerRetraction { - /// @brief Euler retraction: \f$ R_p(v) = (p_x + v_x, p_y + v_y, \mathrm{wrap}(p_\theta + v_\theta)) \f$. + /// @brief Euler retraction: \f$ R_p(v) = (p_x + v_x, p_y + v_y, \mathrm{wrap}(p_\theta + + /// v_\theta)) \f$. /// @param p Base pose. /// @param v Tangent vector. /// @return The retracted pose. EIGEN_STRONG_INLINE Eigen::Vector3d retract(const Eigen::Vector3d p, const Eigen::Vector3d v) const { - return Eigen::Vector3d(p[0] + v[0], p[1] + v[1], wrap_to_pi(p[2] + v[2])); + return Eigen::Vector3d(p[0] + v[0], p[1] + v[1], utils::wrap_to_pi(p[2] + v[2])); } /// @brief Inverse Euler retraction. @@ -102,7 +108,7 @@ struct SE2EulerRetraction { /// @return Tangent vector at \f$ p \f$. EIGEN_STRONG_INLINE Eigen::Vector3d inverse_retract(const Eigen::Vector3d p, const Eigen::Vector3d q) const { - return Eigen::Vector3d(q[0] - p[0], q[1] - p[1], wrap_to_pi(q[2] - p[2])); + return Eigen::Vector3d(q[0] - p[0], q[1] - p[1], utils::wrap_to_pi(q[2] - p[2])); } }; @@ -122,51 +128,84 @@ static_assert(Retraction); /// /// @tparam MetricT Metric policy (default: SE2LeftInvariantMetric). /// @tparam RetractionT Retraction policy (default: SE2ExponentialMap). -template +/// @tparam SamplerT Sampler policy for `random_point()` (default: `StochasticSampler`). +template class SE2 { - MetricT metric_; - RetractionT retraction_; - double x_lo_, x_hi_, y_lo_, y_hi_; - public: - using Scalar = double; ///< Scalar type. - using Point = Eigen::Vector3d; ///< Pose \f$ (x, y, \theta) \f$. - using Tangent = Eigen::Vector3d; ///< Tangent vector \f$ (v_x, v_y, \omega) \f$. + using Scalar = double; ///< Scalar type. + using Point = Eigen::Vector3d; ///< Pose \f$ (x, y, \theta) \f$. + using Tangent = Eigen::Vector3d; ///< Tangent vector \f$ (v_x, v_y, \omega) \f$. - /// @brief Default constructor with workspace bounds \f$ [0, 10]^2 \f$. - SE2() : x_lo_(0.0), x_hi_(10.0), y_lo_(0.0), y_hi_(10.0) {} + /// @brief Runtime query: is the currently-configured metric the bi-invariant + /// Lie group metric (unit weights on `SE2LeftInvariantMetric` paired with the + /// true `SE2ExponentialMap`)? + /// + /// @details Only in this case is the Lie-group `log` the Riemannian logarithm + /// of the metric, so `discrete_geodesic` can safely take the log direction + /// as the natural gradient. `discrete_geodesic` calls this method to + /// activate the fast path on a per-call basis — anisotropic SE2 metrics + /// fall through to finite differences. + /// + /// Because `SE2LeftInvariantMetric::weights_` is a runtime value, this check + /// cannot be made at compile time. + bool has_riemannian_log_runtime() const { + if constexpr (std::is_same_v && + std::is_same_v) { + return metric_.weights().isApprox(Eigen::Vector3d(1.0, 1.0, 1.0)); + } else { + return false; + } + } + + /// @brief Default constructor. Users must call `set_sampling_bounds()` before + /// using `random_point()` if the default \f$[0,10]^2 \times [-\pi,\pi)\f$ is unsuitable. + SE2() = default; /// @brief Construct with explicit metric. /// @param metric The metric policy instance. - explicit SE2(MetricT metric) : metric_(std::move(metric)), x_lo_(0.0), x_hi_(10.0), y_lo_(0.0), y_hi_(10.0) {} + explicit SE2(MetricT metric) : metric_(std::move(metric)) {} - /// @brief Construct with explicit metric, retraction, and workspace bounds. + /// @brief Construct with sampling bounds. + /// @param lo Lower sampling bounds \f$(x_\min, y_\min, \theta_\min)\f$. + /// @param hi Upper sampling bounds \f$(x_\max, y_\max, \theta_\max)\f$. + SE2(const Eigen::Vector3d& lo, const Eigen::Vector3d& hi) : lo_(lo), hi_(hi), sample_buf_(3) {} + + /// @brief Construct with explicit metric and sampling bounds. + /// @param metric The metric policy instance. + /// @param lo Lower sampling bounds \f$(x_\min, y_\min, \theta_\min)\f$. + /// @param hi Upper sampling bounds \f$(x_\max, y_\max, \theta_\max)\f$. + SE2(MetricT metric, const Eigen::Vector3d& lo, const Eigen::Vector3d& hi) + : metric_(std::move(metric)), lo_(lo), hi_(hi), sample_buf_(3) {} + + /// @brief Construct with explicit metric, retraction, and sampling bounds. /// @param metric The metric policy instance. /// @param retraction The retraction policy instance. - /// @param x_lo Lower x bound for random sampling. - /// @param x_hi Upper x bound for random sampling. - /// @param y_lo Lower y bound for random sampling. - /// @param y_hi Upper y bound for random sampling. - SE2(MetricT metric, RetractionT retraction, double x_lo = 0.0, double x_hi = 10.0, - double y_lo = 0.0, double y_hi = 10.0) + /// @param lo Lower sampling bounds \f$(x_\min, y_\min, \theta_\min)\f$. + /// @param hi Upper sampling bounds \f$(x_\max, y_\max, \theta_\max)\f$. + SE2(MetricT metric, RetractionT retraction, const Eigen::Vector3d& lo, const Eigen::Vector3d& hi) : metric_(std::move(metric)), retraction_(std::move(retraction)), - x_lo_(x_lo), - x_hi_(x_hi), - y_lo_(y_lo), - y_hi_(y_hi) {} + lo_(lo), + hi_(hi), + sample_buf_(3) {} + + /// @brief Set the sampling bounds. + void set_sampling_bounds(const Eigen::Vector3d& lo, const Eigen::Vector3d& hi) { + lo_ = lo; + hi_ = hi; + } /// @brief Return the intrinsic dimension (always 3). int dim() const { return 3; } - /// @brief Sample a random pose uniformly in the workspace bounds. + /// @brief Sample a random pose uniformly in the sampling bounds. /// @return A random pose \f$ (x, y, \theta) \f$. Point random_point() const { - thread_local std::mt19937 gen{std::random_device{}()}; - std::uniform_real_distribution dist_x(x_lo_, x_hi_); - std::uniform_real_distribution dist_y(y_lo_, y_hi_); - std::uniform_real_distribution dist_theta(-std::numbers::pi, std::numbers::pi); - return Point(dist_x(gen), dist_y(gen), dist_theta(gen)); + sampler_.sample_box(3, sample_buf_); + return Point(lo_[0] + sample_buf_[0] * (hi_[0] - lo_[0]), + lo_[1] + sample_buf_[1] * (hi_[1] - lo_[1]), + lo_[2] + sample_buf_[2] * (hi_[2] - lo_[2])); } /// @brief Project an ambient vector onto the tangent space at \f$ p \f$. @@ -186,6 +225,14 @@ class SE2 { /// @brief Riemannian norm at \f$ p \f$. Scalar norm(const Point& p, const Tangent& v) const { return metric_.norm(p, v); } + /// @brief Batched inner product \f$U^\top M(p)\, V\f$ when the metric provides it. + Eigen::MatrixXd inner_matrix(const Point& p, const Eigen::MatrixXd& U, + const Eigen::MatrixXd& V) const + requires MetricHasInnerMatrix + { + return metric_.inner_matrix(p, U, V); + } + /// @} /// @name Retraction delegates @@ -209,9 +256,6 @@ class SE2 { /// @{ /// @brief Geodesic distance \f$ d(p, q) \f$ via the midpoint approximation. - /// @param p First pose. - /// @param q Second pose. - /// @return The approximate geodesic distance. Scalar distance(const Point& p, const Point& q) const { return distance_midpoint(*this, p, q); } /// @brief Geodesic interpolation between \f$ p \f$ and \f$ q \f$ at parameter \f$ t \f$. @@ -222,10 +266,206 @@ class SE2 { Point geodesic(const Point& p, const Point& q, Scalar t) const { return exp(p, t * log(p, q)); } /// @} + + private: + MetricT metric_; + RetractionT retraction_; + Eigen::Vector3d lo_{0.0, 0.0, -std::numbers::pi}; ///< Lower sampling bounds (x, y, theta). + Eigen::Vector3d hi_{10.0, 10.0, std::numbers::pi}; ///< Upper sampling bounds (x, y, theta). + mutable SamplerT sampler_; + mutable Eigen::VectorXd sample_buf_{3}; ///< Preallocated buffer for sampler output. }; +// Forward declaration for ConfigurationSpace overload below. +template +class ConfigurationSpace; + // Verify the composed types satisfy RiemannianManifold. static_assert(RiemannianManifold>); static_assert(RiemannianManifold>); +// --------------------------------------------------------------------------- +// distance_midpoint overloads for SE(2) +// --------------------------------------------------------------------------- +// +// The implementation shares trig across the log→exp→log→log chain: +// - 2 utils::sincos calls +// - sincos(mid.θ) derived via angle-addition (no trig) +// - tan(dθ/4) derived via half-angle formula (no trig) +// - fma() for single-cycle FMADD on ARM +// - NEON 2-wide for log(m,a) and log(m,b) in parallel +// Only norm() is called from the manifold — preserves metric evaluation. + +#ifdef __ARM_NEON +#include +#elif defined(__SSE2__) +#include +#endif + +namespace detail { + +/// @brief SE(2) fused midpoint retraction: computes midpoint + v_diff with +/// minimal trig, then delegates norm to the manifold. +template +auto distance_midpoint_se2_impl(const M& m, const Eigen::Vector3d& a, const Eigen::Vector3d& b) -> + typename M::Scalar { + const double dxw = b[0] - a[0], dyw = b[1] - a[1]; + const double dtheta = utils::wrap_to_pi(b[2] - a[2]); + const double half_dt = 0.5 * dtheta; + const double quarter_dt = 0.25 * dtheta; + const double abs_hdt = std::abs(half_dt); + + // === sincos #1: a.θ === + double sa, ca; + utils::sincos(a[2], &sa, &ca); + + const double dx = std::fma(ca, dxw, sa * dyw); + const double dy = std::fma(-sa, dxw, ca * dyw); + + // === sincos #2: dθ/2 === + double sh, ch; + utils::sincos(half_dt, &sh, &ch); + + // --- log(a, b): V⁻¹(dθ) = [[(dθ/2) cot(dθ/2), dθ/2], [-dθ/2, (dθ/2) cot(dθ/2)]] --- + const bool hgeneral = abs_hdt > 1e-10; + const double half_cot_h = hgeneral ? (half_dt * ch / sh) : 1.0; + + const double vx_ab = std::fma(half_cot_h, dx, half_dt * dy); + const double vy_ab = std::fma(half_cot_h, dy, -half_dt * dx); + + // --- exp(a, 0.5·v_ab): V(dθ/2) --- + const double hvx = 0.5 * vx_ab, hvy = 0.5 * vy_ab; + const double inv_hdt = hgeneral ? (1.0 / half_dt) : 1.0; + const double sho = hgeneral ? (sh * inv_hdt) : 1.0; + const double chm1o = hgeneral ? ((1.0 - ch) * inv_hdt) : 0.0; + + const double tx = std::fma(sho, hvx, -chm1o * hvy); + const double ty = std::fma(sho, hvy, chm1o * hvx); + const double mx = std::fma(ca, tx, std::fma(-sa, ty, a[0])); + const double my = std::fma(sa, tx, std::fma(ca, ty, a[1])); + + // --- sincos(mid.θ) via angle-addition (no trig) --- + const double cm = std::fma(ca, ch, -(sa * sh)); + const double sm = std::fma(sa, ch, ca * sh); + + // --- log(m,a) and log(m,b) --- + const double dxw_ma = a[0] - mx, dyw_ma = a[1] - my; + const double dxw_mb = b[0] - mx, dyw_mb = b[1] - my; + +#ifdef __ARM_NEON + const float64x2_t vcm = vdupq_n_f64(cm); + const float64x2_t vsm = vdupq_n_f64(sm); + float64x2_t dxw_pair = {dxw_ma, dxw_mb}; + float64x2_t dyw_pair = {dyw_ma, dyw_mb}; + + float64x2_t dx_pair = vfmaq_f64(vmulq_f64(vcm, dxw_pair), vsm, dyw_pair); + float64x2_t dy_pair = vfmsq_f64(vmulq_f64(vcm, dyw_pair), vsm, dxw_pair); + + double vx_ma, vy_ma, vx_mb, vy_mb; + if (hgeneral) { + const double tan_q = sh / (1.0 + ch); + const double cot_q = quarter_dt / tan_q; + const float64x2_t vc = vdupq_n_f64(cot_q); + const float64x2_t vq = {-quarter_dt, quarter_dt}; + const float64x2_t vnq = vnegq_f64(vq); + float64x2_t vx_pair = vfmaq_f64(vmulq_f64(vc, dx_pair), vq, dy_pair); + float64x2_t vy_pair = vfmaq_f64(vmulq_f64(vc, dy_pair), vnq, dx_pair); + vx_ma = vgetq_lane_f64(vx_pair, 0); + vy_ma = vgetq_lane_f64(vy_pair, 0); + vx_mb = vgetq_lane_f64(vx_pair, 1); + vy_mb = vgetq_lane_f64(vy_pair, 1); + } else { + const float64x2_t vq = {quarter_dt, -quarter_dt}; + const float64x2_t vnq = {-quarter_dt, quarter_dt}; + float64x2_t vx_pair = vfmaq_f64(dx_pair, vq, dy_pair); + float64x2_t vy_pair = vfmaq_f64(dy_pair, vnq, dx_pair); + vx_ma = vgetq_lane_f64(vx_pair, 0); + vy_ma = vgetq_lane_f64(vy_pair, 0); + vx_mb = vgetq_lane_f64(vx_pair, 1); + vy_mb = vgetq_lane_f64(vy_pair, 1); + } +#elif defined(__SSE2__) + const __m128d vcm = _mm_set1_pd(cm); + const __m128d vsm = _mm_set1_pd(sm); + // _mm_set_pd(high, low): lane 0 = ma, lane 1 = mb + __m128d dxw_pair = _mm_set_pd(dxw_mb, dxw_ma); + __m128d dyw_pair = _mm_set_pd(dyw_mb, dyw_ma); + + // dx_pair = cm*dxw + sm*dyw, dy_pair = cm*dyw - sm*dxw + __m128d dx_pair = utils::geodex_fmadd_pd(vsm, dyw_pair, _mm_mul_pd(vcm, dxw_pair)); + __m128d dy_pair = utils::geodex_fnmadd_pd(vsm, dxw_pair, _mm_mul_pd(vcm, dyw_pair)); + + double vx_ma, vy_ma, vx_mb, vy_mb; + if (hgeneral) { + const double tan_q = sh / (1.0 + ch); + const double cot_q = quarter_dt / tan_q; + const __m128d vc = _mm_set1_pd(cot_q); + // vq: lane 0 = -quarter_dt (for ma), lane 1 = quarter_dt (for mb) + const __m128d vq = _mm_set_pd(quarter_dt, -quarter_dt); + const __m128d vnq = _mm_sub_pd(_mm_setzero_pd(), vq); + __m128d vx_pair = utils::geodex_fmadd_pd(vq, dy_pair, _mm_mul_pd(vc, dx_pair)); + __m128d vy_pair = utils::geodex_fmadd_pd(vnq, dx_pair, _mm_mul_pd(vc, dy_pair)); + vx_ma = _mm_cvtsd_f64(vx_pair); + vy_ma = _mm_cvtsd_f64(vy_pair); + vx_mb = _mm_cvtsd_f64(_mm_unpackhi_pd(vx_pair, vx_pair)); + vy_mb = _mm_cvtsd_f64(_mm_unpackhi_pd(vy_pair, vy_pair)); + } else { + // vq: lane 0 = quarter_dt (for ma), lane 1 = -quarter_dt (for mb) + const __m128d vq = _mm_set_pd(-quarter_dt, quarter_dt); + const __m128d vnq = _mm_set_pd(quarter_dt, -quarter_dt); + __m128d vx_pair = utils::geodex_fmadd_pd(vq, dy_pair, dx_pair); + __m128d vy_pair = utils::geodex_fmadd_pd(vnq, dx_pair, dy_pair); + vx_ma = _mm_cvtsd_f64(vx_pair); + vy_ma = _mm_cvtsd_f64(vy_pair); + vx_mb = _mm_cvtsd_f64(_mm_unpackhi_pd(vx_pair, vx_pair)); + vy_mb = _mm_cvtsd_f64(_mm_unpackhi_pd(vy_pair, vy_pair)); + } +#else + const double dx_ma = cm * dxw_ma + sm * dyw_ma; + const double dy_ma = -sm * dxw_ma + cm * dyw_ma; + const double dx_mb = cm * dxw_mb + sm * dyw_mb; + const double dy_mb = -sm * dxw_mb + cm * dyw_mb; + + double vx_ma, vy_ma, vx_mb, vy_mb; + if (hgeneral) { + const double tan_q = sh / (1.0 + ch); + const double cot_q = quarter_dt / tan_q; + vx_ma = cot_q * dx_ma - quarter_dt * dy_ma; + vy_ma = quarter_dt * dx_ma + cot_q * dy_ma; + vx_mb = cot_q * dx_mb + quarter_dt * dy_mb; + vy_mb = -quarter_dt * dx_mb + cot_q * dy_mb; + } else { + vx_ma = dx_ma + quarter_dt * dy_ma; + vy_ma = -quarter_dt * dx_ma + dy_ma; + vx_mb = dx_mb - quarter_dt * dy_mb; + vy_mb = quarter_dt * dx_mb + dy_mb; + } +#endif + + Eigen::Vector3d midpoint(mx, my, utils::wrap_to_pi(a[2] + half_dt)); + Eigen::Vector3d v_diff(vx_mb - vx_ma, vy_mb - vy_ma, dtheta); + return m.norm(midpoint, v_diff); +} + +} // namespace detail + +/// @brief Fused distance_midpoint overload for SE2. +template +auto distance_midpoint(const SE2& m, const Eigen::Vector3d& a, + const Eigen::Vector3d& b) -> double { + return detail::distance_midpoint_se2_impl(m, a, b); +} + +/// @brief Fused distance_midpoint overload for ConfigurationSpace wrapping an SE(2) base. +/// +/// @note ConfigurationSpace is forward-declared here; the full definition is in +/// configuration_space.hpp. This overload is instantiated only when both +/// headers are included, which is the normal usage pattern. +template + requires std::is_same_v +auto distance_midpoint(const ConfigurationSpace& m, const Eigen::Vector3d& a, + const Eigen::Vector3d& b) -> double { + return detail::distance_midpoint_se2_impl(m, a, b); +} + } // namespace geodex diff --git a/include/geodex/manifold/sphere.hpp b/include/geodex/manifold/sphere.hpp index 6348f85..e540280 100644 --- a/include/geodex/manifold/sphere.hpp +++ b/include/geodex/manifold/sphere.hpp @@ -1,92 +1,69 @@ /// @file sphere.hpp -/// @brief Sphere manifold \f$ S^2 \f$ with interchangeable metric and retraction policies. +/// @brief Sphere manifold \f$ S^n \f$ with interchangeable metric and retraction policies. #pragma once -#include #include -#include -#include -#include -#include + #include -#include -#include +#include + +#include -#include +#include "geodex/algorithm/distance.hpp" +#include "geodex/core/concepts.hpp" +#include "geodex/core/debug.hpp" +#include "geodex/core/metric.hpp" +#include "geodex/core/retraction.hpp" +#include "geodex/core/sampler.hpp" +#include "geodex/metrics/constant_spd.hpp" +#include "geodex/metrics/identity.hpp" namespace geodex { namespace detail { -/// Extract a clean type name from compiler intrinsics. -template -constexpr std::string_view type_name() { -#if defined(__clang__) || defined(__GNUC__) - // __PRETTY_FUNCTION__ looks like: - // "std::string_view geodex::detail::type_name() [T = SphereRoundMetric]" - std::string_view fn = __PRETTY_FUNCTION__; - auto start = fn.find("T = "); - if (start == std::string_view::npos) return fn; - start += 4; - auto end = fn.rfind(']'); - if (end == std::string_view::npos) return fn.substr(start); - return fn.substr(start, end - start); -#else - return typeid(T).name(); -#endif -} +/// @brief Ambient dimension of \f$ S^n \f$ as a compile-time constant. +/// +/// @details \f$ S^n \f$ lives in \f$ \mathbb{R}^{n+1} \f$, so the ambient dim +/// is Dim+1. For the dynamic case, ambient stays dynamic. +template +inline constexpr int sphere_ambient_v = Dim + 1; +template <> +inline constexpr int sphere_ambient_v = Eigen::Dynamic; } // namespace detail // --------------------------------------------------------------------------- -// Metric policies +// Metric alias // --------------------------------------------------------------------------- -/// @brief Standard round (bi-invariant) metric on \f$ S^2 \f$. +/// @brief The standard round (bi-invariant) metric on \f$ S^2 \f$. /// /// @details The inner product is the ambient Euclidean dot product restricted /// to tangent vectors: \f$ \langle u, v \rangle_p = u \cdot v \f$. -/// The injectivity radius is \f$ \pi \f$. -struct SphereRoundMetric { - /// @brief Compute the inner product \f$ \langle u, v \rangle_p = u \cdot v \f$. - /// @param u First tangent vector. - /// @param v Second tangent vector. - /// @return The inner product value. - double inner(const Eigen::Vector3d& /*p*/, const Eigen::Vector3d& u, - const Eigen::Vector3d& v) const { - return u.dot(v); - } - - /// @brief Compute the norm \f$ \|v\|_p = \sqrt{\langle v, v \rangle_p} \f$. - /// @param p Base point. - /// @param v Tangent vector. - /// @return The norm value. - double norm(const Eigen::Vector3d& p, const Eigen::Vector3d& v) const { - return std::sqrt(inner(p, v, v)); - } - - /// @brief Return the injectivity radius \f$ \pi \f$. - double injectivity_radius() const { return std::numbers::pi; } -}; - +/// Zero-storage stateless metric. +using SphereRoundMetric = IdentityMetric<3>; // --------------------------------------------------------------------------- // Retraction policies // --------------------------------------------------------------------------- -/// @brief True exponential and logarithmic maps on \f$ S^2 \f$ (round geometry). +/// @brief True exponential and logarithmic maps on \f$ S^n \f$ (round geometry). /// /// @details /// - `retract(p, v)` computes \f$ \exp_p(v) = \cos(\|v\|)\, p + \sin(\|v\|)\, v / \|v\| \f$ /// - `inverse_retract(p, q)` computes \f$ \log_p(q) \f$ via the arc-length formula +/// +/// Both methods are polymorphic in the point type, so the same retraction +/// struct serves every \f$ S^n \f$. struct SphereExponentialMap { - /// @brief Exponential map \f$ \exp_p(v) \f$ on \f$ S^2 \f$. + /// @brief Exponential map \f$ \exp_p(v) \f$ on \f$ S^n \f$. /// @param p Base point on the sphere. /// @param v Tangent vector at \f$ p \f$. /// @return The resulting point on the sphere. - EIGEN_STRONG_INLINE - Eigen::Vector3d retract(const Eigen::Vector3d p, const Eigen::Vector3d v) const { + template + EIGEN_STRONG_INLINE Point retract(const Point& p, const Point& v) const { const double theta = v.norm(); if (theta < 1e-10) { return p; @@ -95,41 +72,41 @@ struct SphereExponentialMap { return std::cos(theta) * p + (std::sin(theta) * inv_theta) * v; } - /// @brief Logarithmic map \f$ \log_p(q) \f$ on \f$ S^2 \f$. + /// @brief Logarithmic map \f$ \log_p(q) \f$ on \f$ S^n \f$. /// @param p Base point on the sphere. /// @param q Target point on the sphere. /// @return Tangent vector at \f$ p \f$ such that \f$ \exp_p(v) = q \f$. - EIGEN_STRONG_INLINE - Eigen::Vector3d inverse_retract(const Eigen::Vector3d p, const Eigen::Vector3d q) const { + template + EIGEN_STRONG_INLINE Point inverse_retract(const Point& p, const Point& q) const { const double cos_theta = p.dot(q); - const Eigen::Vector3d v = q - cos_theta * p; + const Point v = q - cos_theta * p; const double sin_theta = v.norm(); if (sin_theta < 1e-10) { if (cos_theta < 0.0) { // TODO: handle cut locus properly — direction is non-unique for antipodal points. - // Options: random tangent direction, user-provided fallback, or error. - GEODEX_LOG("SphereExponentialMap: log called at cut locus " - "(antipodal points). Returning zero vector."); + GEODEX_LOG( + "SphereExponentialMap: log called at cut locus " + "(antipodal points). Returning zero vector."); } - return Eigen::Vector3d::Zero(); + return Point::Zero(p.size()); } const double theta = std::atan2(sin_theta, cos_theta); return (theta / sin_theta) * v; } }; -/// @brief First-order projection retraction on \f$ S^2 \f$. +/// @brief First-order projection retraction on \f$ S^n \f$. /// /// @details /// - `retract(p, v)` computes \f$ R_p(v) = (p + v) / \|p + v\| \f$ -/// - `inverse_retract(p, q)` projects \f$ q - p \f$ onto \f$ T_p S^2 \f$ +/// - `inverse_retract(p, q)` projects \f$ q - p \f$ onto \f$ T_p S^n \f$ struct SphereProjectionRetraction { /// @brief Projection retraction: normalize \f$ p + v \f$. /// @param p Base point on the sphere. /// @param v Tangent vector at \f$ p \f$. /// @return The retracted point on the sphere. - EIGEN_STRONG_INLINE - Eigen::Vector3d retract(const Eigen::Vector3d p, const Eigen::Vector3d v) const { + template + EIGEN_STRONG_INLINE Point retract(const Point& p, const Point& v) const { return (p + v).normalized(); } @@ -137,21 +114,22 @@ struct SphereProjectionRetraction { /// @param p Base point on the sphere. /// @param q Target point on the sphere. /// @return Tangent vector at \f$ p \f$ approximating \f$ \log_p(q) \f$. - EIGEN_STRONG_INLINE - Eigen::Vector3d inverse_retract(const Eigen::Vector3d p, const Eigen::Vector3d q) const { - const Eigen::Vector3d d = q - p; - const Eigen::Vector3d v = d - d.dot(p) * p; + template + EIGEN_STRONG_INLINE Point inverse_retract(const Point& p, const Point& q) const { + const Point d = q - p; + const Point v = d - d.dot(p) * p; if (v.norm() < 1e-10 && p.dot(q) < 0.0) { - // TODO: handle cut locus properly — direction is non-unique for antipodal points. - GEODEX_LOG("SphereProjectionRetraction: inverse_retract called at cut locus " - "(antipodal points). Returning zero vector."); - return Eigen::Vector3d::Zero(); + // TODO: handle cut locus properly. + GEODEX_LOG( + "SphereProjectionRetraction: inverse_retract called at cut locus " + "(antipodal points). Returning zero vector."); + return Point::Zero(p.size()); } return v; } }; -// Verify retraction concepts. +// Verify retraction concepts at the canonical S^2 signature. static_assert(Retraction); static_assert(Retraction); @@ -159,46 +137,112 @@ static_assert(Retraction +/// @tparam Dim Intrinsic dimension (e.g. `2` for \f$ S^2 \f$), or `Eigen::Dynamic` +/// for runtime sizing. Defaults to `2` (the classical round 2-sphere). +/// @tparam MetricT Metric policy (default: `ConstantSPDMetric` identity). +/// @tparam RetractionT Retraction policy (default: `SphereExponentialMap`). +template >, + typename RetractionT = SphereExponentialMap, typename SamplerT = StochasticSampler> class Sphere { - MetricT metric_; - RetractionT retraction_; - public: - using Scalar = double; ///< Scalar type. - using Point = Eigen::Vector3d; ///< Point type (unit vector in \f$ \mathbb{R}^3 \f$). - using Tangent = Eigen::Vector3d; ///< Tangent vector type. + /// @brief Ambient dimension (`Dim + 1` for static, `Eigen::Dynamic` otherwise). + static constexpr int Ambient = detail::sphere_ambient_v; + + using Scalar = double; ///< Scalar type. + using Point = + Eigen::Vector; ///< Point type (unit vector in \f$ \mathbb{R}^{n+1} \f$). + using Tangent = Eigen::Vector; ///< Tangent vector type. + + /// @brief Runtime query: is `log` the Riemannian logarithm of the metric? + /// + /// @details Only when the metric is the identity `ConstantSPDMetric` + /// AND the retraction is the true exponential map does + /// `grad((1/2) d^2)(x) = -log_x(q)` hold exactly. Other metrics and any + /// projection retraction fall back to finite-difference natural gradient. + bool has_riemannian_log_runtime() const { + if constexpr (std::is_same_v) { + if constexpr (std::is_same_v>) { + return true; + } else if constexpr (std::is_same_v>) { + return metric_.weight_matrix().isApprox( + Eigen::Matrix::Identity(dim_ + 1, dim_ + 1)); + } else { + return false; + } + } else { + return false; + } + } - /// @brief Default constructor (requires default-constructible policies). - Sphere() { log_construction(); } + /// @brief Static-dim default constructor: default-construct metric/retraction. + Sphere() + requires(Dim != Eigen::Dynamic) + : dim_(Dim) { + log_construction(); + } - /// @brief Construct with explicit metric and retraction policies. - /// @param metric The metric policy instance. - /// @param retraction The retraction policy instance (default-constructed if omitted). + /// @brief Static-dim constructor with explicit metric and retraction policies. explicit Sphere(MetricT metric, RetractionT retraction = {}) - : metric_(std::move(metric)), retraction_(std::move(retraction)) { + requires(Dim != Eigen::Dynamic) + : metric_(std::move(metric)), retraction_(std::move(retraction)), dim_(Dim) { log_construction(); } - /// @brief Return the intrinsic dimension (always 2). - int dim() const { return 2; } + /// @brief Dynamic-dim constructor: takes the intrinsic dimension \f$ n \f$ of \f$ S^n \f$. + explicit Sphere(int n) + requires(Dim == Eigen::Dynamic) + : metric_(make_default_metric(n + 1)), dim_(n) { + log_construction(); + } - /// @brief Sample a uniformly random point on \f$ S^2 \f$. - /// @return A unit vector in \f$ \mathbb{R}^3 \f$. + /// @brief Dynamic-dim constructor with explicit metric and retraction. + Sphere(int n, MetricT metric, RetractionT retraction = {}) + requires(Dim == Eigen::Dynamic) + : metric_(std::move(metric)), retraction_(std::move(retraction)), dim_(n) { + log_construction(); + } + + /// @brief Return the intrinsic dimension \f$ n \f$ of \f$ S^n \f$. + int dim() const { return dim_; } + + /// @brief Sample a uniformly random point on \f$ S^n \f$. + /// + /// @details Draws `n+1` uniform samples from the sampler via `sample_box`, + /// applies the Box-Muller transform to produce standard normal variates, and + /// normalizes the resulting vector to project onto the sphere. This is + /// mathematically equivalent to Marsaglia's method but uses the configurable + /// sampler policy instead of a thread-local RNG. + /// @return A unit vector in \f$ \mathbb{R}^{n+1} \f$. Point random_point() const { - // Uniform sampling on S^2 via standard normal. - thread_local std::mt19937 gen{std::random_device{}()}; - std::normal_distribution dist(0.0, 1.0); - Point p(dist(gen), dist(gen), dist(gen)); + const int n = dim_ + 1; + // We need `n` normals. Box-Muller produces pairs, so draw ceil(n/2)*2 + // uniforms. + const int n_pairs = (n + 1) / 2; + const int n_uniform = n_pairs * 2; + sample_buf_.conservativeResize(n_uniform); + sampler_.sample_box(n_uniform, sample_buf_); + + Point p; + if constexpr (Ambient == Eigen::Dynamic) { + p.resize(n); + } + // Box-Muller: pairs of U(0,1) → pairs of N(0,1). + for (int i = 0; i < n_pairs; ++i) { + const double u1 = std::max(sample_buf_[2 * i], 1e-300); // avoid log(0) + const double u2 = sample_buf_[2 * i + 1]; + const double r = std::sqrt(-2.0 * std::log(u1)); + const double theta = 2.0 * std::numbers::pi * u2; + const int j = 2 * i; + if (j < n) p[j] = r * std::cos(theta); + if (j + 1 < n) p[j + 1] = r * std::sin(theta); + } return p.normalized(); } @@ -212,35 +256,36 @@ class Sphere { /// @{ /// @brief Riemannian inner product at \f$ p \f$. - /// @param p Base point. - /// @param u First tangent vector. - /// @param v Second tangent vector. - /// @return \f$ \langle u, v \rangle_p \f$ Scalar inner(const Point& p, const Tangent& u, const Tangent& v) const { return metric_.inner(p, u, v); } /// @brief Riemannian norm at \f$ p \f$. - /// @param p Base point. - /// @param v Tangent vector. - /// @return \f$ \|v\|_p \f$ Scalar norm(const Point& p, const Tangent& v) const { return metric_.norm(p, v); } + /// @brief Batched inner product \f$U^\top M(p)\, V\f$ when the metric provides it. + Eigen::MatrixXd inner_matrix(const Point& p, const Eigen::MatrixXd& U, + const Eigen::MatrixXd& V) const + requires MetricHasInnerMatrix + { + return metric_.inner_matrix(p, U, V); + } + /// @} /// @name Retraction delegates /// @{ /// @brief Exponential map (or retraction) \f$ \exp_p(v) \f$. - /// @param p Base point. - /// @param v Tangent vector. - /// @return Resulting point on the manifold. + /// @param p Base point on the sphere. + /// @param v Tangent vector at \f$ p \f$. + /// @return The resulting point on the sphere. Point exp(const Point& p, const Tangent& v) const { return retraction_.retract(p, v); } /// @brief Logarithmic map (or inverse retraction) \f$ \log_p(q) \f$. - /// @param p Base point. - /// @param q Target point. - /// @return Tangent vector at \f$ p \f$ pointing toward \f$ q \f$. + /// @param p Base point on the sphere. + /// @param q Target point on the sphere. + /// @return Tangent vector at \f$ p \f$ such that \f$ \exp_p(v) \approx q \f$. Tangent log(const Point& p, const Point& q) const { return retraction_.inverse_retract(p, q); } /// @} @@ -249,47 +294,63 @@ class Sphere { /// @{ /// @brief Geodesic distance \f$ d(p, q) \f$ via the midpoint approximation. - /// @param p First point. - /// @param q Second point. - /// @return The approximate geodesic distance. + /// @param p First point on the sphere. + /// @param q Second point on the sphere. + /// @return The geodesic distance. Scalar distance(const Point& p, const Point& q) const { double dot = p.dot(q); if (dot < -1.0 + 1e-10) { - // Antipodal: geodesic distance = π for round metric. - // For non-round metrics, this is still the best we can do - // since log is undefined at the cut locus. return std::numbers::pi; } return distance_midpoint(*this, p, q); } - /// @brief Injectivity radius — only available when the metric provides it. - /// @return The injectivity radius of the manifold. - Scalar injectivity_radius() const - requires requires { metric_.injectivity_radius(); } - { - return metric_.injectivity_radius(); - } + /// @brief Injectivity radius of the round n-sphere: \f$ \pi \f$. + /// + /// @details Returns the topological injectivity radius for the default round + /// (identity) metric. For anisotropic custom metrics the effective radius is + /// smaller: \f$ \pi / \sqrt{\lambda_{\max}(A)} \f$ where \f$ \lambda_{\max} \f$ + /// is the largest eigenvalue of the weight matrix. This value is an upper + /// bound; `discrete_geodesic` uses it for step capping and may take extra + /// retries if the true radius is smaller. + Scalar injectivity_radius() const { return std::numbers::pi; } /// @brief Geodesic interpolation between \f$ p \f$ and \f$ q \f$ at parameter \f$ t \f$. /// @param p Start point. /// @param q End point. /// @param t Interpolation parameter in \f$ [0, 1] \f$. - /// @return The interpolated point. + /// @return The interpolated point on the sphere. Point geodesic(const Point& p, const Point& q, Scalar t) const { return exp(p, t * log(p, q)); } /// @} private: + /// @brief Build the default metric for dynamic Sphere (identity of ambient size). + static MetricT make_default_metric(int ambient_size) { + if constexpr (std::is_constructible_v) { + return MetricT(ambient_size); + } else { + return MetricT{}; + } + } + void log_construction() const { - GEODEX_LOG("Sphere<" << detail::type_name() << ", " + GEODEX_LOG("Sphere<" << Dim << ", " << detail::type_name() << ", " << detail::type_name() << "> created (dim=" << dim() << ")"); } + + MetricT metric_; + RetractionT retraction_; + int dim_; ///< Intrinsic dimension (Dim for static, runtime for dynamic). + mutable SamplerT sampler_; ///< Sampler used by `random_point`. + mutable Eigen::VectorXd sample_buf_; ///< Preallocated buffer for Box-Muller uniform samples. }; // Verify the composed types satisfy RiemannianManifold. static_assert(RiemannianManifold>); -static_assert(RiemannianManifold>>); -static_assert(RiemannianManifold>); +static_assert(RiemannianManifold>>); +static_assert(RiemannianManifold>); +static_assert(RiemannianManifold>); +static_assert(RiemannianManifold>); } // namespace geodex diff --git a/include/geodex/manifold/torus.hpp b/include/geodex/manifold/torus.hpp index a7aec24..4039813 100644 --- a/include/geodex/manifold/torus.hpp +++ b/include/geodex/manifold/torus.hpp @@ -3,49 +3,32 @@ #pragma once -#include #include -#include -#include -#include + #include -#include +#include + +#include + +#include "geodex/algorithm/distance.hpp" +#include "geodex/core/concepts.hpp" +#include "geodex/core/sampler.hpp" +#include "geodex/metrics/constant_spd.hpp" +#include "geodex/metrics/identity.hpp" +#include "geodex/utils/angle.hpp" namespace geodex { // --------------------------------------------------------------------------- -// Metric +// Metric alias // --------------------------------------------------------------------------- /// @brief Standard flat metric on \f$ T^n \f$. /// /// @details The inner product is the standard dot product: -/// \f$ \langle u, v \rangle = u \cdot v \f$. -/// The injectivity radius is \f$ \pi \f$ (half the period). -/// -/// @tparam Dim Compile-time dimension, or `Eigen::Dynamic`. +/// \f$ \langle u, v \rangle = u \cdot v \f$. Zero-storage stateless metric. template -struct TorusFlatMetric { - /// @brief Compute the inner product \f$ \langle u, v \rangle = u \cdot v \f$. - /// @param u First tangent vector. - /// @param v Second tangent vector. - /// @return The inner product value. - double inner(const Eigen::Vector& /*p*/, const Eigen::Vector& u, - const Eigen::Vector& v) const { - return u.dot(v); - } - - /// @brief Compute the flat norm \f$ \|v\| = \sqrt{v \cdot v} \f$. - /// @param p Base point. - /// @param v Tangent vector. - /// @return The norm value. - double norm(const Eigen::Vector& p, const Eigen::Vector& v) const { - return std::sqrt(inner(p, v, v)); - } - - /// @brief Return the injectivity radius \f$ \pi \f$. - double injectivity_radius() const { return std::numbers::pi; } -}; +using TorusFlatMetric = IdentityMetric; // --------------------------------------------------------------------------- // Torus manifold @@ -59,39 +42,56 @@ struct TorusFlatMetric { /// /// @tparam Dim Compile-time dimension, or `Eigen::Dynamic`. /// @tparam MetricT Metric policy (default: TorusFlatMetric). -template > +/// @tparam SamplerT Sampler policy for `random_point()` (default: `StochasticSampler`). +template , + typename SamplerT = StochasticSampler> class Torus { - MetricT metric_; - int dim_; - public: using Scalar = double; ///< Scalar type. using Point = Eigen::Vector; ///< Point type (angles in \f$ [0, 2\pi)^n \f$). using Tangent = Eigen::Vector; ///< Tangent vector type. + /// @brief Runtime query: is `log` the Riemannian logarithm of the metric? + /// + /// @details Torus topology has trivial exp/log (addition/wrapping), which is + /// the Riemannian log exactly when the metric is the identity (standard flat + /// metric). Anisotropic SPDs are still flat in the mathematical sense but + /// their geodesics are reparameterized, so we mark them as not log-compatible + /// and `discrete_geodesic` uses finite differences. + bool has_riemannian_log_runtime() const { + if constexpr (std::is_same_v>) { + return true; + } else if constexpr (std::is_same_v>) { + return metric_.weight_matrix().isApprox( + Eigen::Matrix::Identity(dim_, dim_)); + } else { + return false; + } + } + /// @brief Fixed-dimension constructor. Torus() requires(Dim != Eigen::Dynamic) - : dim_(Dim) {} + : dim_(Dim), sample_buf_(Dim) {} /// @brief Fixed-dimension constructor with custom metric. /// @param metric The metric policy instance. explicit Torus(MetricT metric) requires(Dim != Eigen::Dynamic) - : metric_(std::move(metric)), dim_(Dim) {} + : metric_(std::move(metric)), dim_(Dim), sample_buf_(Dim) {} /// @brief Dynamic-dimension constructor. /// @param n The dimension of the torus. explicit Torus(int n) requires(Dim == Eigen::Dynamic) - : dim_(n) {} + : metric_(make_default_metric(n)), dim_(n), sample_buf_(n) {} /// @brief Dynamic-dimension constructor with custom metric. /// @param n The dimension of the torus. /// @param metric The metric policy instance. Torus(int n, MetricT metric) requires(Dim == Eigen::Dynamic) - : metric_(std::move(metric)), dim_(n) {} + : metric_(std::move(metric)), dim_(n), sample_buf_(n) {} /// @brief Return the dimension of the torus. int dim() const { return dim_; } @@ -99,14 +99,13 @@ class Torus { /// @brief Sample a uniformly random point in \f$ [0, 2\pi)^n \f$. /// @return A random point on the torus. Point random_point() const { - thread_local std::mt19937 gen{std::random_device{}()}; - std::uniform_real_distribution dist(0.0, 2.0 * std::numbers::pi); + sampler_.sample_box(dim_, sample_buf_); Point p; if constexpr (Dim == Eigen::Dynamic) { p.resize(dim_); } for (int i = 0; i < dim_; ++i) { - p[i] = dist(gen); + p[i] = sample_buf_[i] * 2.0 * std::numbers::pi; } return p; } @@ -128,6 +127,14 @@ class Torus { /// @brief Riemannian norm at \f$ p \f$. Scalar norm(const Point& p, const Tangent& v) const { return metric_.norm(p, v); } + /// @brief Batched inner product \f$U^\top M(p)\, V\f$ when the metric provides it. + Eigen::MatrixXd inner_matrix(const Point& p, const Eigen::MatrixXd& U, + const Eigen::MatrixXd& V) const + requires MetricHasInnerMatrix + { + return metric_.inner_matrix(p, U, V); + } + /// @} /// @name Exp / Log @@ -137,13 +144,13 @@ class Torus { /// @param p Base point. /// @param v Tangent vector. /// @return The resulting point, wrapped to \f$ [0, 2\pi)^n \f$. - Point exp(const Point& p, const Tangent& v) const { return wrap_point(p + v); } + Point exp(const Point& p, const Tangent& v) const { return utils::wrap_point(p + v); } /// @brief Logarithmic map: shortest-path tangent vector from \f$ p \f$ to \f$ q \f$. /// @param p Base point. /// @param q Target point. /// @return The wrapped difference in \f$ [-\pi, \pi)^n \f$. - Tangent log(const Point& p, const Point& q) const { return wrap_delta(q - p); } + Tangent log(const Point& p, const Point& q) const { return utils::wrap_delta(q - p); } /// @} @@ -156,12 +163,13 @@ class Torus { /// @return The distance \f$ d(p, q) \f$. Scalar distance(const Point& p, const Point& q) const { return distance_midpoint(*this, p, q); } - /// @brief Injectivity radius — only available when the metric provides it. - Scalar injectivity_radius() const - requires requires { metric_.injectivity_radius(); } - { - return metric_.injectivity_radius(); - } + /// @brief Injectivity radius of \f$ T^n \f$: \f$ \pi \f$ (half the period). + /// + /// @details Returns the topological value for the default identity metric and + /// period \f$ 2\pi \f$. For anisotropic custom metrics the effective radius is + /// \f$ \pi / \sqrt{\lambda_{\max}(A)} \f$. This value is an upper bound; + /// `discrete_geodesic` may take extra retries if the true radius is smaller. + Scalar injectivity_radius() const { return std::numbers::pi; } /// @brief Geodesic interpolation between \f$ p \f$ and \f$ q \f$ at parameter \f$ t \f$. /// @param p Start point. @@ -171,6 +179,21 @@ class Torus { Point geodesic(const Point& p, const Point& q, Scalar t) const { return exp(p, t * log(p, q)); } /// @} + + private: + /// @brief Build the default metric for dynamic Torus. + static MetricT make_default_metric(int n) { + if constexpr (std::is_constructible_v) { + return MetricT(n); + } else { + return MetricT{}; + } + } + + MetricT metric_; + int dim_; + mutable SamplerT sampler_; + mutable Eigen::VectorXd sample_buf_; ///< Preallocated buffer for sampler output. }; // Verify the default types satisfy RiemannianManifold. diff --git a/include/geodex/metrics/clearance.hpp b/include/geodex/metrics/clearance.hpp new file mode 100644 index 0000000..de3ee14 --- /dev/null +++ b/include/geodex/metrics/clearance.hpp @@ -0,0 +1,99 @@ +/// @file clearance.hpp +/// @brief SDF-based conformal metric for obstacle clearance biasing. + +#pragma once + +#include + +#include + +#include + +#include "geodex/core/metric.hpp" + +namespace geodex { + +/// @brief Conformal metric that scales a base metric by an obstacle proximity field. +/// +/// @details The inner product is: +/// \f$ \langle u, v \rangle_q = c(q) \cdot \langle u, v \rangle^{\mathrm{base}}_q \f$ +/// +/// where the conformal factor is: +/// \f$ c(q) = 1 + \kappa \exp(-\beta \cdot \mathrm{sdf}(q)) \f$ +/// +/// This makes the metric expensive near obstacles (low SDF) and unmodified far +/// away (high SDF), causing geodesics to naturally maintain clearance. With +/// multiple obstacles, geodesics follow channels equidistant from obstacle +/// surfaces. +/// +/// The SDF callable should return a smooth signed distance field where positive +/// values indicate free space. For circular obstacles, use log-sum-exp +/// smooth-min to avoid gradient discontinuities at Voronoi boundaries. For +/// grid-based distance transforms, use bilinear interpolation. +/// +/// @tparam BaseMetricT The base metric type (e.g., `SE2LeftInvariantMetric`). +/// @tparam SDFFn Callable with signature `double(const Point&)` returning the +/// signed distance to the nearest obstacle surface. +template +class SDFConformalMetric { + public: + /// @brief Construct an SDF-based conformal metric. + /// @param base The base metric to scale. + /// @param sdf Callable returning signed distance (positive = free space). + /// @param kappa Strength of obstacle repulsion (higher = more clearance). + /// @param beta Falloff rate (higher = tighter to obstacle surfaces). + SDFConformalMetric(BaseMetricT base, SDFFn sdf, double kappa = 5.0, double beta = 3.0) + : base_(std::move(base)), sdf_(std::move(sdf)), kappa_(kappa), beta_(beta) {} + + /// @brief Compute the scaled inner product \f$ c(q) \langle u, v \rangle^{\mathrm{base}}_q \f$. + template + double inner(const Point& q, const Tangent& u, const Tangent& v) const { + return conformal_factor(q) * base_.inner(q, u, v); + } + + /// @brief Compute the scaled norm \f$ \|v\|_q = \sqrt{c(q)} \|v\|^{\mathrm{base}}_q \f$. + template + double norm(const Point& q, const Tangent& v) const { + return riemannian_norm(*this, q, v); + } + + /// @brief Batched inner product scaled by the conformal factor. + template + Eigen::MatrixXd inner_matrix(const Point& q, const Eigen::MatrixXd& U, + const Eigen::MatrixXd& V) const + requires requires(const BaseMetricT& m, const Point& p, const Eigen::MatrixXd& A) { + { m.inner_matrix(p, A, A) } -> std::convertible_to; + } + { + return conformal_factor(q) * base_.inner_matrix(q, U, V); + } + + /// @brief Access the base metric. + const BaseMetricT& base() const { return base_; } + + /// @brief Access the SDF callable. + const SDFFn& sdf() const { return sdf_; } + + /// @brief Get the strength parameter. + double kappa() const { return kappa_; } + + /// @brief Get the falloff rate parameter. + double beta() const { return beta_; } + + /// @brief Evaluate the conformal factor at a configuration. + /// @param q Configuration point. + /// @return \f$ c(q) = 1 + \kappa \exp(-\beta \cdot \mathrm{sdf}(q)) \f$. + template + double conformal_factor(const Point& q) const { + const double d = sdf_(q); + return 1.0 + kappa_ * std::exp(-beta_ * d); + } + + private: + BaseMetricT base_; + SDFFn sdf_; + double kappa_; + double beta_; +}; + +} // namespace geodex diff --git a/include/geodex/metrics/constant_spd.hpp b/include/geodex/metrics/constant_spd.hpp index 4794242..c094825 100644 --- a/include/geodex/metrics/constant_spd.hpp +++ b/include/geodex/metrics/constant_spd.hpp @@ -4,7 +4,8 @@ #pragma once #include -#include + +#include "geodex/core/metric.hpp" namespace geodex { @@ -20,8 +21,23 @@ namespace geodex { /// /// @tparam Dim Compile-time dimension, or `Eigen::Dynamic`. template -struct ConstantSPDMetric { - Eigen::Matrix A_; ///< The SPD weight matrix. +class ConstantSPDMetric { + public: + /// @brief Default: identity weight matrix (only for static Dim). + /// + /// @details The default metric is the standard ambient inner product, which + /// is the "natural" choice for every built-in manifold (Sphere/Euclidean/Torus). + /// For `Dim == Eigen::Dynamic` the size is unknown at compile time, so use the + /// `int n` constructor below instead. + ConstantSPDMetric() + requires(Dim != Eigen::Dynamic) + : A_(Eigen::Matrix::Identity()) {} + + /// @brief Dynamic-size identity factory (size n×n). + /// @param n Dimension of the SPD matrix. + explicit ConstantSPDMetric(int n) + requires(Dim == Eigen::Dynamic) + : A_(Eigen::MatrixXd::Identity(n, n)) {} /// @brief Construct with a given SPD weight matrix. /// @param A Symmetric positive-definite matrix defining the metric. @@ -41,8 +57,27 @@ struct ConstantSPDMetric { /// @param v Tangent vector. /// @return The norm value. double norm(const Eigen::Vector& p, const Eigen::Vector& v) const { - return std::sqrt(inner(p, v, v)); + return riemannian_norm(*this, p, v); + } + + /// @brief Batched inner product: \f$U^\top A\, V\f$ in a single matrix multiply. + /// + /// @details Provides the `HasBatchInnerMatrix` fast path for algorithms that + /// evaluate a tangent-metric tensor in a basis (e.g., `natural_gradient_fd`). + /// For `ConstantSPDMetric` this is a simple linear-algebra shortcut; the + /// bigger win is for point-dependent metrics like `KineticEnergyMetric` + /// where the expensive mass matrix is evaluated once instead of \f$d^2\f$ + /// times. + Eigen::MatrixXd inner_matrix(const Eigen::Vector& /*p*/, const Eigen::MatrixXd& U, + const Eigen::MatrixXd& V) const { + return U.transpose() * A_ * V; } + + /// @brief Access the weight matrix. + const Eigen::Matrix& weight_matrix() const { return A_; } + + private: + Eigen::Matrix A_; ///< The SPD weight matrix. }; } // namespace geodex diff --git a/include/geodex/metrics/identity.hpp b/include/geodex/metrics/identity.hpp new file mode 100644 index 0000000..3da1892 --- /dev/null +++ b/include/geodex/metrics/identity.hpp @@ -0,0 +1,61 @@ +/// @file identity.hpp +/// @brief Zero-storage identity Riemannian metric. + +#pragma once + +#include + +#include "geodex/core/metric.hpp" + +namespace geodex { + +/// @brief Stateless identity metric: \f$ \langle u, v \rangle_p = u \cdot v \f$. +/// +/// @details A zero-storage alternative to `ConstantSPDMetric` with the +/// identity weight matrix. Uses O(1) memory instead of O(n^2) for the +/// identity-metric case. All manifold default-metric aliases +/// (`SphereRoundMetric`, `TorusFlatMetric`, `EuclideanStandardMetric`) point here. +/// +/// @tparam Dim Compile-time vector dimension, or `Eigen::Dynamic`. +template +class IdentityMetric { + public: + /// @brief Compute the inner product \f$ \langle u, v \rangle = u \cdot v \f$. + /// @param u First tangent vector. + /// @param v Second tangent vector. + /// @return The inner product value. + double inner(const Eigen::Vector& /*p*/, const Eigen::Vector& u, + const Eigen::Vector& v) const { + return u.dot(v); + } + + /// @brief Compute the norm \f$ \|v\| = \sqrt{v \cdot v} \f$. + /// @param p Base point (unused). + /// @param v Tangent vector. + /// @return The norm value. + double norm(const Eigen::Vector& p, const Eigen::Vector& v) const { + return riemannian_norm(*this, p, v); + } + + /// @brief Batched inner product: \f$ U^\top V \f$. + Eigen::MatrixXd inner_matrix(const Eigen::Vector& /*p*/, const Eigen::MatrixXd& U, + const Eigen::MatrixXd& V) const { + return U.transpose() * V; + } + + /// @brief Identity weight matrix (runtime-sized identity, for API compatibility). + /// @details Returns a dynamically-sized identity matrix of the given dimension. + /// Provided so that `has_riemannian_log_runtime()` can call `weight_matrix()` + /// uniformly on any metric. Unlike `ConstantSPDMetric`, this allocates only + /// when called — which should be rare. + Eigen::MatrixXd weight_matrix() const { + if constexpr (Dim != Eigen::Dynamic) { + return Eigen::MatrixXd::Identity(Dim, Dim); + } else { + // Dynamic case: callers must not rely on this for hot paths. + return Eigen::MatrixXd::Identity(1, 1); + } + } +}; + +} // namespace geodex diff --git a/include/geodex/metrics/jacobi.hpp b/include/geodex/metrics/jacobi.hpp index ac30790..266ddb8 100644 --- a/include/geodex/metrics/jacobi.hpp +++ b/include/geodex/metrics/jacobi.hpp @@ -1,39 +1,80 @@ /// @file jacobi.hpp -/// @brief Jacobi metric for minimum-time geodesics under a potential field. +/// @brief Jacobi metric — a configuration-dependent scaling of the kinetic energy metric. #pragma once +#include + #include -#include + +#include "geodex/core/metric.hpp" +#include "geodex/metrics/kinetic_energy.hpp" +#include "geodex/metrics/weighted.hpp" namespace geodex { -/// @brief Jacobi metric conformally scaling a kinetic energy metric by -/// the available kinetic energy \f$ H - P(q) \f$. +namespace detail { + +/// @brief Functor capturing the Jacobi scaling \f$\alpha(q) = 2(H - P(q))\f$. +/// +/// @details Used as the `AlphaT` parameter of `WeightedMetric` to turn a +/// kinetic-energy metric into a Jacobi metric. We use a named functor struct +/// (rather than a lambda) so that `JacobiMetric` has a nameable type. +template +class JacobiAlphaFunctor { + public: + JacobiAlphaFunctor(PotentialFn pot_fn, double H) + : potential_fn_(std::move(pot_fn)), total_energy_(H) {} + + template + double operator()(const Point& q) const { + return 2.0 * (total_energy_ - potential_fn_(q)); + } + + /// @brief Access the total energy. + double total_energy() const { return total_energy_; } + + private: + PotentialFn potential_fn_; + double total_energy_; +}; + +} // namespace detail + +/// @brief Jacobi metric conformally scaling a kinetic energy metric by the +/// available kinetic energy \f$ H - P(q) \f$. /// /// @details The inner product at configuration \f$ q \f$ is: /// \f$ \langle u, v \rangle_q = 2\,(H - P(q))\, u^\top M(q) \, v \f$ -/// where \f$ H \f$ is the total energy (conserved), \f$ P(q) \f$ is the -/// potential energy, and \f$ M(q) \f$ is the mass matrix. Geodesics of -/// this metric are natural motions of the mechanical system (Maupertuis' -/// principle). +/// where \f$ H \f$ is the total energy, \f$ P(q) \f$ is the potential, and +/// \f$ M(q) \f$ is the mass matrix. Geodesics of this metric are the natural +/// motions of the mechanical system (Maupertuis' principle). +/// +/// Implementation: this is a thin composition of `KineticEnergyMetric` (the +/// mass matrix) and `WeightedMetric` (the configuration-dependent scaling). +/// The `inner`, `inner_matrix`, and `norm` methods forward to the composed +/// metric — no duplicated mass-matrix or potential-evaluation logic. /// /// @tparam MassMatrixFn Callable returning the SPD mass matrix at \f$ q \f$. /// @tparam PotentialFn Callable returning the scalar potential \f$ P(q) \f$. template -struct JacobiMetric { - MassMatrixFn mass_matrix_fn_; ///< Callable returning M(q). - PotentialFn potential_fn_; ///< Callable returning P(q). - double total_energy_; ///< Total energy \f$ H \f$. +class JacobiMetric { + public: + using KEMetric = KineticEnergyMetric; + using AlphaFn = detail::JacobiAlphaFunctor; + using InnerMetric = WeightedMetric; /// @brief Construct a Jacobi metric. /// @param mass_fn Callable returning the SPD mass matrix. /// @param pot_fn Callable returning the potential energy. /// @param H Total energy (must satisfy \f$ H > P(q) \f$ everywhere on the path). JacobiMetric(MassMatrixFn mass_fn, PotentialFn pot_fn, double H) - : mass_matrix_fn_(std::move(mass_fn)), - potential_fn_(std::move(pot_fn)), - total_energy_(H) {} + : inner_metric_(KEMetric{std::move(mass_fn)}, AlphaFn(std::move(pot_fn), H)) { + static_assert(std::is_invocable_v, + "MassMatrixFn must be callable with (const VectorXd&)"); + static_assert(std::is_invocable_v, + "PotentialFn must be callable with (const VectorXd&)"); + } /// @brief Compute the inner product \f$ 2(H - P(q))\, u^\top M(q) \, v \f$. /// @param q Configuration point. @@ -42,18 +83,40 @@ struct JacobiMetric { /// @return The inner product value. template double inner(const Point& q, const Tangent& u, const Tangent& v) const { - double kinetic_factor = 2.0 * (total_energy_ - potential_fn_(q)); - return kinetic_factor * u.dot(mass_matrix_fn_(q) * v); + return inner_metric_.inner(q, u, v); } - /// @brief Compute the norm \f$ \|v\|_q \f$. + /// @brief Compute the norm \f$ \|v\|_q = \sqrt{2(H - P(q))\, v^\top M(q) \, v} \f$. /// @param q Configuration point. /// @param v Tangent vector. /// @return The norm value. template double norm(const Point& q, const Tangent& v) const { - return std::sqrt(inner(q, v, v)); + return riemannian_norm(*this, q, v); + } + + /// @brief Batched inner product: \f$U^\top \bigl(2(H - P(q)) M(q)\bigr) V\f$ + /// computed with a single evaluation of \f$M(q)\f$ and \f$P(q)\f$ through + /// the wrapped `WeightedMetric`. + template + Eigen::MatrixXd inner_matrix(const Point& q, const Eigen::MatrixXd& U, + const Eigen::MatrixXd& V) const { + return inner_metric_.inner_matrix(q, U, V); } + + /// @brief Return the total energy \f$ H \f$ set at construction. + double total_energy() const { return inner_metric_.alpha().total_energy(); } + + private: + InnerMetric inner_metric_; }; +/// @brief Factory function for `JacobiMetric` — convenience wrapper that lets +/// users write `make_jacobi_metric(mass_fn, pot_fn, H)` without naming the +/// template parameters. +template +auto make_jacobi_metric(MassMatrixFn mass_fn, PotentialFn pot_fn, double H) { + return JacobiMetric{std::move(mass_fn), std::move(pot_fn), H}; +} + } // namespace geodex diff --git a/include/geodex/metrics/kinetic_energy.hpp b/include/geodex/metrics/kinetic_energy.hpp index 92e6e10..4a59225 100644 --- a/include/geodex/metrics/kinetic_energy.hpp +++ b/include/geodex/metrics/kinetic_energy.hpp @@ -3,10 +3,12 @@ #pragma once -#include -#include #include +#include + +#include "geodex/core/metric.hpp" + namespace geodex { /// @brief Kinetic energy metric where the inner product is defined by a @@ -20,9 +22,8 @@ namespace geodex { /// @tparam MassMatrixFn A callable type with signature /// `auto operator()(const Point& q) -> Eigen::MatrixXd` (or fixed-size matrix). template -struct KineticEnergyMetric { - MassMatrixFn mass_matrix_fn_; ///< Callable returning M(q). - +class KineticEnergyMetric { + public: /// @brief Construct with a mass matrix function. /// @param fn Callable returning the SPD mass matrix at a given configuration. explicit KineticEnergyMetric(MassMatrixFn fn) : mass_matrix_fn_(std::move(fn)) {} @@ -43,11 +44,28 @@ struct KineticEnergyMetric { /// @return The norm value. template double norm(const Point& q, const Tangent& v) const { - return std::sqrt(inner(q, v, v)); + return riemannian_norm(*this, q, v); + } + + /// @brief Batched inner product: \f$U^\top M(q)\, V\f$ computed with a single + /// call to the mass-matrix function. + /// + /// @details This is the performance-critical path for `natural_gradient_fd` + /// when the mass matrix is expensive to compute (e.g., forward kinematics for + /// a manipulator): instead of calling `mass_matrix_fn_(q)` for every scalar + /// \f$G_{ij} = \langle e_i, e_j\rangle_q\f$, we call it once and form the + /// entire \f$d\times d\f$ tensor in a single matmul. + template + Eigen::MatrixXd inner_matrix(const Point& q, const Eigen::MatrixXd& U, + const Eigen::MatrixXd& V) const { + return U.transpose() * mass_matrix_fn_(q) * V; } /// @brief Return the injectivity radius \f$ \infty \f$ (assumes flat topology). double injectivity_radius() const { return std::numeric_limits::infinity(); } + + private: + MassMatrixFn mass_matrix_fn_; ///< Callable returning M(q). }; } // namespace geodex diff --git a/include/geodex/metrics/pullback.hpp b/include/geodex/metrics/pullback.hpp index e2bcae0..d69b3be 100644 --- a/include/geodex/metrics/pullback.hpp +++ b/include/geodex/metrics/pullback.hpp @@ -4,7 +4,8 @@ #pragma once #include -#include + +#include "geodex/core/metric.hpp" namespace geodex { @@ -20,19 +21,14 @@ namespace geodex { /// @tparam JacobianFn Callable returning the Jacobian matrix at \f$ q \f$. /// @tparam TaskMetricFn Callable returning the task-space SPD metric at \f$ q \f$. template -struct PullbackMetric { - JacobianFn jacobian_fn_; ///< Callable returning J(q). - TaskMetricFn task_metric_fn_; ///< Callable returning G_X(q). - double lambda_; ///< Regularization parameter. - +class PullbackMetric { + public: /// @brief Construct a pullback metric. /// @param jac_fn Callable returning the Jacobian. /// @param task_fn Callable returning the task-space metric. /// @param lambda Regularization (default 0). PullbackMetric(JacobianFn jac_fn, TaskMetricFn task_fn, double lambda = 0.0) - : jacobian_fn_(std::move(jac_fn)), - task_metric_fn_(std::move(task_fn)), - lambda_(lambda) {} + : jacobian_fn_(std::move(jac_fn)), task_metric_fn_(std::move(task_fn)), lambda_(lambda) {} /// @brief Compute the inner product. /// @param q Configuration point. @@ -41,8 +37,8 @@ struct PullbackMetric { /// @return The inner product value. template double inner(const Point& q, const Tangent& u, const Tangent& v) const { - auto J = jacobian_fn_(q); - auto G = task_metric_fn_(q); + const auto J = jacobian_fn_(q); + const auto G = task_metric_fn_(q); double val = u.dot(J.transpose() * G * J * v); if (lambda_ > 0.0) { val += lambda_ * u.dot(v); @@ -56,25 +52,30 @@ struct PullbackMetric { /// @return The norm value. template double norm(const Point& q, const Tangent& v) const { - return std::sqrt(inner(q, v, v)); + return riemannian_norm(*this, q, v); } -}; - -/// @brief Task-space metric that always returns the identity matrix. -/// -/// @details Used as the default task metric for `make_pullback_euclidean_metric`. -struct IdentityTaskMetric { - int task_dim_; ///< Dimension of the task space. - /// @brief Construct with the task-space dimension. - /// @param task_dim Dimension of the task space. - explicit IdentityTaskMetric(int task_dim) : task_dim_(task_dim) {} - - /// @brief Return the identity matrix. + /// @brief Batched inner product: \f$U^\top (J^\top G J + \lambda I)\, V\f$ with + /// a single pair of Jacobian / task-metric evaluations. template - Eigen::MatrixXd operator()(const Point& /*q*/) const { - return Eigen::MatrixXd::Identity(task_dim_, task_dim_); + Eigen::MatrixXd inner_matrix(const Point& q, const Eigen::MatrixXd& U, + const Eigen::MatrixXd& V) const { + const auto J = jacobian_fn_(q); + const auto G = task_metric_fn_(q); + Eigen::MatrixXd result = (J * U).transpose() * G * (J * V); + if (lambda_ > 0.0) { + result.noalias() += lambda_ * (U.transpose() * V); + } + return result; } + + /// @brief Access the regularization parameter. + double lambda() const { return lambda_; } + + private: + JacobianFn jacobian_fn_; ///< Callable returning J(q). + TaskMetricFn task_metric_fn_; ///< Callable returning G_X(q). + double lambda_; ///< Regularization parameter. }; /// @brief Create a pullback metric with Euclidean task-space metric (\f$ G_X = I \f$). @@ -88,8 +89,11 @@ struct IdentityTaskMetric { /// @return A PullbackMetric with identity task-space metric. template auto make_pullback_euclidean_metric(JacobianFn jac_fn, int task_dim, double lambda = 0.0) { - return PullbackMetric{ - std::move(jac_fn), IdentityTaskMetric{task_dim}, lambda}; + auto identity_task_metric = [task_dim](const auto& /*q*/) { + return Eigen::MatrixXd::Identity(task_dim, task_dim); + }; + return PullbackMetric{ + std::move(jac_fn), std::move(identity_task_metric), lambda}; } } // namespace geodex diff --git a/include/geodex/metrics/se2_left_invariant.hpp b/include/geodex/metrics/se2_left_invariant.hpp index 4bac774..d49a22b 100644 --- a/include/geodex/metrics/se2_left_invariant.hpp +++ b/include/geodex/metrics/se2_left_invariant.hpp @@ -1,10 +1,12 @@ /// @file se2_left_invariant.hpp -/// @brief Left-invariant metric on SE(2). +/// @brief Left-invariant metric on SE(2) — thin wrapper over ConstantSPDMetric<3>. #pragma once #include -#include + +#include "geodex/core/metric.hpp" +#include "geodex/metrics/constant_spd.hpp" namespace geodex { @@ -14,25 +16,63 @@ namespace geodex { /// \f$ \langle u, v \rangle = w_x u_x v_x + w_y u_y v_y + w_\theta u_\theta v_\theta \f$. /// The weights \f$ (w_x, w_y, w_\theta) \f$ allow anisotropic cost, e.g. penalizing /// lateral motion for car-like robots. -struct SE2LeftInvariantMetric { - Eigen::Vector3d weights_; ///< Diagonal weight vector \f$ (w_x, w_y, w_\theta) \f$. - +/// +/// Implementation: this is `ConstantSPDMetric<3>` with `A = diag(w_x, w_y, w_\theta)`. +/// The `weights_` field is preserved alongside the base metric so that +/// `SE2::has_riemannian_log_runtime()` can quickly check unit weights without +/// inspecting the full SPD matrix. +class SE2LeftInvariantMetric { + public: /// @brief Construct with unit weights (isotropic). - SE2LeftInvariantMetric() : weights_(1.0, 1.0, 1.0) {} + SE2LeftInvariantMetric() : SE2LeftInvariantMetric(1.0, 1.0, 1.0) {} + + /// @brief Create a car-like metric with a specified effective turning radius. + /// + /// @details The metric \f$ g = \mathrm{diag}(w_x, w_y, w_\theta) \f$ with high + /// \f$ w_y \f$ suppresses lateral motion. The effective minimum turning radius + /// of the resulting geodesic is approximately + /// \f$ r_{\mathrm{eff}} \approx \sqrt{w_\theta / w_x} \f$. + /// + /// @param turning_radius Desired effective turning radius. + /// @param lateral_penalty Weight for lateral (y) motion — higher values more + /// strongly suppress sideslip (default 100.0). + /// @return An SE2LeftInvariantMetric configured for car-like behavior. + /// @note Soft constraint only: the metric penalizes but does not forbid motions + /// violating the turning radius. Near start/goal the planner may produce in-place + /// rotations. + static SE2LeftInvariantMetric car_like(const double turning_radius, + const double lateral_penalty = 100.0) { + return SE2LeftInvariantMetric(1.0, lateral_penalty, turning_radius * turning_radius); + } /// @brief Construct with explicit weights. /// @param wx Translational weight in x. /// @param wy Translational weight in y. /// @param wtheta Rotational weight. - SE2LeftInvariantMetric(double wx, double wy, double wtheta) : weights_(wx, wy, wtheta) {} + SE2LeftInvariantMetric(double wx, double wy, double wtheta) + : weights_(wx, wy, wtheta), + base_(Eigen::Vector3d(wx, wy, wtheta).asDiagonal().toDenseMatrix()) {} - /// @brief Compute the inner product \f$ \langle u, v \rangle = \sum_i w_i u_i v_i \f$. + /// @brief Access the diagonal weight vector \f$ (w_x, w_y, w_\theta) \f$. + const Eigen::Vector3d& weights() const { return weights_; } + + /// @brief Compute the inner product via the wrapped ConstantSPDMetric. + /// @param p Base point (unused for a constant metric). /// @param u First tangent vector. /// @param v Second tangent vector. /// @return The inner product value. - double inner(const Eigen::Vector3d& /*p*/, const Eigen::Vector3d& u, - const Eigen::Vector3d& v) const { - return weights_[0] * u[0] * v[0] + weights_[1] * u[1] * v[1] + weights_[2] * u[2] * v[2]; + double inner(const Eigen::Vector3d& p, const Eigen::Vector3d& u, const Eigen::Vector3d& v) const { + return base_.inner(p, u, v); + } + + /// @brief Batched inner product via the wrapped ConstantSPDMetric. + /// @param p Base point. + /// @param U Matrix whose columns are tangent vectors. + /// @param V Matrix whose columns are tangent vectors. + /// @return \f$ U^\top A \, V \f$. + Eigen::MatrixXd inner_matrix(const Eigen::Vector3d& p, const Eigen::MatrixXd& U, + const Eigen::MatrixXd& V) const { + return base_.inner_matrix(p, U, V); } /// @brief Compute the norm \f$ \|v\| = \sqrt{\langle v, v \rangle} \f$. @@ -40,8 +80,12 @@ struct SE2LeftInvariantMetric { /// @param v Tangent vector. /// @return The norm value. double norm(const Eigen::Vector3d& p, const Eigen::Vector3d& v) const { - return std::sqrt(inner(p, v, v)); + return riemannian_norm(*this, p, v); } + + private: + Eigen::Vector3d weights_; ///< Diagonal weight vector \f$ (w_x, w_y, w_\theta) \f$. + ConstantSPDMetric<3> base_; ///< Wrapped SPD metric with `A = diag(weights_)`. }; } // namespace geodex diff --git a/include/geodex/metrics/weighted.hpp b/include/geodex/metrics/weighted.hpp index 56e149a..9909753 100644 --- a/include/geodex/metrics/weighted.hpp +++ b/include/geodex/metrics/weighted.hpp @@ -1,53 +1,102 @@ /// @file weighted.hpp -/// @brief Uniformly scaled metric wrapper. +/// @brief Scaled metric wrapper with constant or configuration-dependent alpha. #pragma once -#include +#include + +#include + +#include "geodex/core/metric.hpp" namespace geodex { -/// @brief Metric wrapper that uniformly scales another metric by a constant factor. +/// @brief Metric wrapper that scales another metric by a constant or +/// configuration-dependent factor \f$\alpha\f$. /// /// @details The inner product is: -/// \f$ \langle u, v \rangle_q = \alpha \cdot \langle u, v \rangle^{\mathrm{base}}_q \f$ +/// \f$ \langle u, v \rangle_q = \alpha(q) \cdot \langle u, v \rangle^{\mathrm{base}}_q \f$ +/// +/// The alpha parameter can be either: +/// - a constant `double` (e.g. `WeightedMetric{base, 3.0}`) +/// - a callable `Fn(q) -> double` for configuration-dependent scaling +/// (used by `JacobiMetric`, region-avoiding metrics, etc.). /// /// @tparam MetricT The base metric type. -template -struct WeightedMetric { - MetricT base_; ///< The base metric. - double alpha_; ///< The scaling factor. - +/// @tparam AlphaT Scaling factor type — either `double` or a callable. +template +class WeightedMetric { + public: /// @brief Construct a weighted metric. - /// @param base The base metric instance. - /// @param alpha The scaling factor (must be positive). - WeightedMetric(MetricT base, double alpha) : base_(std::move(base)), alpha_(alpha) {} + /// @param base The base metric to scale. + /// @param alpha Scaling factor — constant `double` or callable `Fn(q) -> double`. + WeightedMetric(MetricT base, AlphaT alpha) : base_(std::move(base)), alpha_(std::move(alpha)) {} - /// @brief Compute the scaled inner product. + /// @brief Compute the scaled inner product \f$\alpha(q) \langle u, v + /// \rangle^{\mathrm{base}}_q\f$. /// @param q Configuration point. /// @param u First tangent vector. /// @param v Second tangent vector. /// @return The scaled inner product value. template double inner(const Point& q, const Tangent& u, const Tangent& v) const { - return alpha_ * base_.inner(q, u, v); + return evaluate_alpha(q) * base_.inner(q, u, v); } - /// @brief Compute the scaled norm. + /// @brief Compute the scaled norm \f$\|v\|_q = \sqrt{\alpha(q) \langle v, v + /// \rangle^{\mathrm{base}}_q}\f$. /// @param q Configuration point. /// @param v Tangent vector. /// @return The scaled norm value. template double norm(const Point& q, const Tangent& v) const { - return std::sqrt(inner(q, v, v)); + return riemannian_norm(*this, q, v); + } + + /// @brief Batched inner product: forwards to the base metric's `inner_matrix` + /// when available and scales the result by \f$\alpha(q)\f$. + template + Eigen::MatrixXd inner_matrix(const Point& q, const Eigen::MatrixXd& U, + const Eigen::MatrixXd& V) const + requires requires(const MetricT& m, const Point& p, const Eigen::MatrixXd& A) { + { m.inner_matrix(p, A, A) } -> std::convertible_to; + } + { + return evaluate_alpha(q) * base_.inner_matrix(q, U, V); } - /// @brief Forward injectivity radius from the base metric if available. + /// @brief Forward injectivity radius from the base metric — only valid for + /// constant-scalar \f$\alpha\f$ (a config-dependent alpha breaks the + /// uniform-scaling guarantee). double injectivity_radius() const - requires requires { base_.injectivity_radius(); } + requires(std::is_arithmetic_v && + requires(const MetricT& m) { + { m.injectivity_radius() }; + }) { return base_.injectivity_radius(); } + + /// @brief Access the base metric. + const MetricT& base() const { return base_; } + + /// @brief Access the scaling factor. + const AlphaT& alpha() const { return alpha_; } + + private: + /// @brief Evaluate \f$\alpha(q)\f$ — selects between constant scalar and + /// callable at compile time. + template + double evaluate_alpha(const Point& q) const { + if constexpr (std::is_invocable_r_v) { + return alpha_(q); + } else { + return static_cast(alpha_); + } + } + + MetricT base_; ///< The base metric. + AlphaT alpha_; ///< The scaling factor (constant or callable). }; } // namespace geodex diff --git a/include/geodex/core/angle.hpp b/include/geodex/utils/angle.hpp similarity index 96% rename from include/geodex/core/angle.hpp rename to include/geodex/utils/angle.hpp index f3e3c28..6e7bfc9 100644 --- a/include/geodex/core/angle.hpp +++ b/include/geodex/utils/angle.hpp @@ -3,10 +3,11 @@ #pragma once -#include #include -namespace geodex { +#include + +namespace geodex::utils { /// @brief Wrap angle to \f$ [-\pi, \pi) \f$. /// @@ -41,4 +42,4 @@ Eigen::Vector wrap_delta(const Eigen::Vector& d) { return d.unaryExpr([](double x) { return wrap_to_pi(x); }); } -} // namespace geodex +} // namespace geodex::utils diff --git a/include/geodex/utils/math.hpp b/include/geodex/utils/math.hpp new file mode 100644 index 0000000..9298bd5 --- /dev/null +++ b/include/geodex/utils/math.hpp @@ -0,0 +1,213 @@ +/// @file math.hpp +/// @brief Portable fast-math and SIMD utility functions. +/// +/// Provides: +/// - Portable sincos() wrapper (macOS __sincos, POSIX ::sincos) +/// - Schraudolph fast_exp() approximation (~5x faster, ~4% max relative error) +/// - ARM NEON 2-wide helpers and x86 SSE2 2-wide helpers with scalar fallbacks +/// +/// SIMD portability: The x86 path requires only SSE2 (baseline x86_64). When +/// SSE4.1 or FMA are available (detected via __SSE4_1__ / __FMA__), faster +/// intrinsics are used automatically. Compile with -march=native for best +/// performance on your machine. +/// +/// Used by geodex::collision (SDF evaluation), geodex::SE2 (distance), +/// and anywhere fast transcendental approximations are acceptable. + +#pragma once + +#include +#include + +#include +#include + +#ifdef __ARM_NEON +#include +#elif defined(__SSE2__) +#include +#endif + +namespace geodex::utils { + +// --------------------------------------------------------------------------- +// Portable sincos +// --------------------------------------------------------------------------- + +/// @brief Compute sin and cos of @p angle in a single call. +/// +/// On macOS/Apple, maps to `__sincos`. On POSIX/Linux, maps to `::sincos`. +/// Falls back to separate `std::sin`/`std::cos` on other platforms. +inline void sincos(const double angle, double* s, double* c) { +#if defined(__APPLE__) + __sincos(angle, s, c); +#elif defined(_GNU_SOURCE) || defined(__linux__) + ::sincos(angle, s, c); +#else + *s = std::sin(angle); + *c = std::cos(angle); +#endif +} + +// --------------------------------------------------------------------------- +// Schraudolph fast exp() approximation +// --------------------------------------------------------------------------- + +/// @brief Fast exp() approximation via Schraudolph's IEEE 754 bit trick. +/// +/// Maps `x` to `2^(x/ln2)` by writing directly into the exponent bits of a +/// double. ~5x faster than std::exp on ARM. Max relative error ~4% (3.9%). +/// +/// Schraudolph's paper writes to the upper 32-bit int of a double using +/// `a = 2^20/ln(2)`, `b = 1023*2^20`, `c = 60801`. The 64-bit adaptation +/// shifts all constants by 2^32 (the upper int occupies bits 32-63 of the +/// int64). The correction c=60801 balances over/under-estimates of the linear +/// chord approximation to 2^f on each unit interval. +/// +/// @par Reference +/// Schraudolph, N. N. (1999). A fast, compact approximation of the +/// exponential function. Neural Computation, 11(4), 853-862. +inline double fast_exp(const double x) { + const double clamped = std::max(x, -700.0); + // a = 2^52 / ln(2) (= 2^20/ln(2) * 2^32) + // b - c = (1023 * 2^20 - 60801) * 2^32 = 4606921280493453312 + const auto i = static_cast(6497320848556798.0 * clamped + 4606921280493453312.0); + return std::bit_cast(i); +} + +// --------------------------------------------------------------------------- +// ARM NEON 2-wide helpers +// --------------------------------------------------------------------------- + +#ifdef __ARM_NEON + +/// @brief NEON 2-wide fast_exp: process two doubles simultaneously. +/// +/// Same Schraudolph approximation as the scalar version with the 2^32-scaled +/// bias correction. Uses vcvtq_s64_f64 (truncation toward zero), matching +/// the scalar static_cast behavior. +inline float64x2_t fast_exp(float64x2_t x) { + const float64x2_t vmin = vdupq_n_f64(-700.0); + x = vmaxq_f64(x, vmin); + const float64x2_t scale = vdupq_n_f64(6497320848556798.0); + const float64x2_t bias = vdupq_n_f64(4606921280493453312.0); + const float64x2_t val = vaddq_f64(vmulq_f64(scale, x), bias); + const int64x2_t ival = vcvtq_s64_f64(val); + return vreinterpretq_f64_s64(ival); +} + +/// @brief Forward rotation: rotate 2 points by angle θ (body → world). +/// +/// Standard 2D rotation matrix applied to 2-wide coordinate pairs: +/// rx = ct * dx - st * dy +/// ry = st * dx + ct * dy +/// +/// where (ct, st) = (cos θ, sin θ) are broadcast values and (dx, dy) are +/// 2-wide coordinate pairs (e.g., body-frame polygon samples). +inline void rotate_2wide(const float64x2_t ct, const float64x2_t st, const float64x2_t dx, + const float64x2_t dy, float64x2_t& rx, float64x2_t& ry) { + rx = vfmsq_f64(vmulq_f64(ct, dx), st, dy); // ct*dx - st*dy + ry = vfmaq_f64(vmulq_f64(ct, dy), st, dx); // st*dx + ct*dy +} + +/// @brief Inverse rotation: rotate 2 points by -θ (world → local). +/// +/// Transpose of the rotation matrix (R^T = R^{-1}): +/// lx = ct * dx + st * dy +/// ly = ct * dy - st * dx +/// +/// Used by SDF code to transform query points into obstacle-local frames. +inline void inverse_rotate_2wide(const float64x2_t ct, const float64x2_t st, const float64x2_t dx, + const float64x2_t dy, float64x2_t& lx, float64x2_t& ly) { + lx = vfmaq_f64(vmulq_f64(ct, dx), st, dy); // ct*dx + st*dy + ly = vfmsq_f64(vmulq_f64(ct, dy), st, dx); // ct*dy - st*dx +} + +#endif // __ARM_NEON + +// --------------------------------------------------------------------------- +// x86 SSE2 2-wide helpers (with optional SSE4.1 and FMA acceleration) +// --------------------------------------------------------------------------- + +#ifdef __SSE2__ + +// --- Portable wrappers: dispatch to best available ISA at compile time --- + +/// @brief Branchless blend: select trueVal where mask is all-1s, falseVal otherwise. +/// Uses SSE4.1 _mm_blendv_pd when available, SSE2 bitwise fallback otherwise. +inline __m128d geodex_blendv_pd(const __m128d falseVal, const __m128d trueVal, const __m128d mask) { +#ifdef __SSE4_1__ + return _mm_blendv_pd(falseVal, trueVal, mask); +#else + return _mm_or_pd(_mm_and_pd(mask, trueVal), _mm_andnot_pd(mask, falseVal)); +#endif +} + +/// @brief Floor (round toward -infinity). Uses SSE4.1 when available. +inline __m128d geodex_floor_pd(const __m128d x) { +#ifdef __SSE4_1__ + return _mm_floor_pd(x); +#else + const __m128d truncated = _mm_cvtepi32_pd(_mm_cvttpd_epi32(x)); + const __m128d needs_correction = _mm_cmpgt_pd(truncated, x); + return _mm_sub_pd(truncated, _mm_and_pd(needs_correction, _mm_set1_pd(1.0))); +#endif +} + +/// @brief Fused multiply-add: a*b + c. Uses FMA3 when available. +inline __m128d geodex_fmadd_pd(const __m128d a, const __m128d b, const __m128d c) { +#ifdef __FMA__ + return _mm_fmadd_pd(a, b, c); +#else + return _mm_add_pd(_mm_mul_pd(a, b), c); +#endif +} + +/// @brief Negated fused multiply-add: -(a*b) + c = c - a*b. Uses FMA3 when available. +inline __m128d geodex_fnmadd_pd(const __m128d a, const __m128d b, const __m128d c) { +#ifdef __FMA__ + return _mm_fnmadd_pd(a, b, c); +#else + return _mm_sub_pd(c, _mm_mul_pd(a, b)); +#endif +} + +/// @brief SSE2 2-wide fast_exp: process two doubles simultaneously. +/// +/// Same Schraudolph approximation as the scalar version. SSE2 has no packed +/// double-to-int64 conversion, so lanes are extracted to scalar for the +/// static_cast step. +inline __m128d fast_exp(__m128d x) { + const __m128d vmin = _mm_set1_pd(-700.0); + x = _mm_max_pd(x, vmin); + const __m128d scale = _mm_set1_pd(6497320848556798.0); + const __m128d bias = _mm_set1_pd(4606921280493453312.0); + const __m128d val = _mm_add_pd(_mm_mul_pd(scale, x), bias); + // SSE2 has no _mm_cvttpd_epi64: extract lanes, cast scalar, reload. + alignas(16) double dv[2]; + _mm_store_pd(dv, val); + alignas(16) int64_t iv[2] = {static_cast(dv[0]), static_cast(dv[1])}; + return _mm_castsi128_pd(_mm_load_si128(reinterpret_cast(iv))); +} + +/// @brief Forward rotation: rotate 2 points by angle θ (body → world). +/// rx = ct * dx - st * dy +/// ry = st * dx + ct * dy +inline void rotate_2wide(const __m128d ct, const __m128d st, const __m128d dx, const __m128d dy, + __m128d& rx, __m128d& ry) { + rx = geodex_fnmadd_pd(st, dy, _mm_mul_pd(ct, dx)); // ct*dx - st*dy + ry = geodex_fmadd_pd(st, dx, _mm_mul_pd(ct, dy)); // st*dx + ct*dy +} + +/// @brief Inverse rotation: rotate 2 points by -θ (world → local). +/// lx = ct * dx + st * dy +/// ly = ct * dy - st * dx +inline void inverse_rotate_2wide(const __m128d ct, const __m128d st, const __m128d dx, + const __m128d dy, __m128d& lx, __m128d& ly) { + lx = geodex_fmadd_pd(st, dy, _mm_mul_pd(ct, dx)); // ct*dx + st*dy + ly = geodex_fnmadd_pd(st, dx, _mm_mul_pd(ct, dy)); // ct*dy - st*dx +} + +#endif // __SSE2__ + +} // namespace geodex::utils diff --git a/pyproject.toml b/pyproject.toml index d637c9e..9d55f7d 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -4,7 +4,7 @@ build-backend = "scikit_build_core.build" [project] name = "geodex" -version = "0.1.0" +version = "0.1.1" description = "A general-purpose framework for planning on Riemannian manifolds" readme = "README.md" license = "Apache-2.0" diff --git a/python/CMakeLists.txt b/python/CMakeLists.txt index 2e33f36..204a731 100644 --- a/python/CMakeLists.txt +++ b/python/CMakeLists.txt @@ -22,6 +22,7 @@ nanobind_add_module(_geodex_core src/bind_metrics.cpp src/bind_config_space.cpp src/bind_algorithms.cpp + src/bind_collision.cpp ) target_link_libraries(_geodex_core PRIVATE geodex) diff --git a/python/geodex/__init__.py b/python/geodex/__init__.py index 0f90335..f1b3804 100644 --- a/python/geodex/__init__.py +++ b/python/geodex/__init__.py @@ -2,4 +2,4 @@ from geodex._geodex_core import * # noqa: F401, F403 -__version__ = "0.1.0" +__version__ = "0.1.1" diff --git a/python/geodex/_geodex_core.pyi b/python/geodex/_geodex_core.pyi index 0e311e5..10f9f53 100644 --- a/python/geodex/_geodex_core.pyi +++ b/python/geodex/_geodex_core.pyi @@ -1,5 +1,6 @@ """Type stubs for geodex._geodex_core.""" +import enum from typing import Callable import numpy as np @@ -425,6 +426,146 @@ class WeightedMetric: # Algorithms # --------------------------------------------------------------------------- +class InterpolationStatus(enum.Enum): + """Termination status for the discrete geodesic walk.""" + + Converged = 0 + """Distance to target fell below convergence tolerance.""" + MaxStepsReached = 1 + """Iteration budget exhausted without reaching tolerance.""" + GradientVanished = 2 + """Riemannian gradient norm is ~0 at a non-target point.""" + CutLocus = 3 + """``log`` collapsed to ~0 while start and target are distinct (e.g. antipodal).""" + StepShrunkToZero = 4 + """Distortion halving drove the step size below ``min_step_size``.""" + DegenerateInput = 5 + """``start == target`` on entry; returned a single-point path.""" + + +class InterpolationSettings: + """Settings for the discrete geodesic walk. + + Walk semantics: each iteration takes a Riemannian step of length + ``min(step_size, remaining_distance)`` in the descent direction. Iteration + count and returned-path size therefore scale as + ``~initial_distance / step_size``, so ``step_size`` also serves as the + effective path resolution (max Riemannian distance between consecutive + returned points). + """ + + step_size: float + """Max Riemannian step per iteration; also the effective path resolution.""" + convergence_tol: float + """Absolute stop threshold on ``|log(current, target)|_R``.""" + convergence_rel: float + """Relative stop threshold (``distance < rel * initial_distance``).""" + max_steps: int + """Maximum number of successful gradient-descent steps.""" + fd_epsilon: float + """Central FD step for the fallback gradient; 0 means auto-select.""" + distortion_ratio: float + """Progress-check tolerance; 1.5 requires ≥50% of intended-step progress.""" + growth_factor: float + """Factor by which the step cap grows back after each successful iteration.""" + min_step_size: float + """Failure threshold after repeated distortion halvings.""" + gradient_eps: float + """Gradient Riemannian-norm threshold for ``GradientVanished``.""" + cut_locus_eps: float + """``|log|_R`` threshold flagging ``CutLocus``.""" + force_log_direction: bool + """If True, always use ``-log(current, target)`` as the descent direction and skip + the FD fallback. Produces smoother paths at the cost of following the base + retraction's geodesic rather than the true Riemannian geodesic of the configured + metric.""" + fd_midpoint_guard_tau: float + """Relative-error threshold above which the midpoint distance surrogate used inside + the FD gradient is rejected and the sample falls back to ``|log|_R`` for that basis + direction.""" + + def __init__( + self, + step_size: float = 0.5, + convergence_tol: float = 1e-4, + convergence_rel: float = 1e-3, + max_steps: int = 100, + fd_epsilon: float = 0.0, + distortion_ratio: float = 1.5, + growth_factor: float = 1.5, + min_step_size: float = 1e-12, + gradient_eps: float = 1e-12, + cut_locus_eps: float = 1e-10, + force_log_direction: bool = False, + fd_midpoint_guard_tau: float = 0.25, + ) -> None: + """Create interpolation settings. + + Args: + step_size: Max Riemannian step per iteration (also effective path resolution). + convergence_tol: Absolute stop threshold on ``|log(current, target)|_R``. + convergence_rel: Relative stop threshold (``distance < rel * initial_distance``). + max_steps: Maximum number of successful gradient-descent steps. + fd_epsilon: Central FD step for the fallback gradient; 0 means auto-select. + distortion_ratio: Progress-check tolerance (1.5 requires ≥50% progress). + growth_factor: Factor by which the step cap grows after a successful step. + min_step_size: Failure threshold after repeated distortion halvings. + gradient_eps: Gradient norm threshold for ``GradientVanished``. + cut_locus_eps: ``|log|_R`` threshold flagging ``CutLocus``. + force_log_direction: If True, always use ``-log`` as the descent direction and + skip the FD fallback. + fd_midpoint_guard_tau: Relative-error threshold for the FD midpoint surrogate + (set to 0 to force via-log sampling every time). + """ + ... + + +class InterpolationResult: + """Output of :func:`discrete_geodesic`. + + Carries the discretised path, a termination :class:`InterpolationStatus`, + iteration count, and the initial/final Riemannian distances to target. + """ + + @property + def path(self) -> list[_Point]: + """Sequence of points traced from start toward target (always starts with ``start``).""" + ... + + @property + def status(self) -> InterpolationStatus: + """Termination reason — always check before using ``path``.""" + ... + + @property + def iterations(self) -> int: + """Number of successful gradient steps taken (distortion retries do not count).""" + ... + + @property + def distortion_halvings(self) -> int: + """Number of times the step cap was halved due to progress failure.""" + ... + + @property + def fd_midpoint_fallbacks(self) -> int: + """Number of FD basis samples whose midpoint distance surrogate was rejected + by the runtime guard and replaced with ``|log|_R``. A nonzero value flags a + non-Riemannian retraction, a cut-locus crossing, or a non-smooth metric + feature within the FD neighbourhood.""" + ... + + @property + def initial_distance(self) -> float: + """Riemannian distance from ``start`` to ``target`` at entry.""" + ... + + @property + def final_distance(self) -> float: + """Riemannian distance from the final iterate to ``target`` at exit.""" + ... + + def distance_midpoint( manifold: "Sphere | Euclidean | Torus | SE2 | ConfigurationSpace", a: _Point, @@ -446,3 +587,51 @@ def distance_midpoint( ... +def discrete_geodesic( + manifold: "Sphere | Euclidean | Torus | SE2 | ConfigurationSpace", + start: _Point, + goal: _Point, + settings: InterpolationSettings = ..., +) -> InterpolationResult: + """Walk from *start* toward *goal* via Riemannian natural gradient descent. + + Each iteration first tries the Riemannian logarithm direction (exploiting + the identity ``grad((1/2) d²) = -log`` at points inside the injectivity + radius) and verifies via a progress check. When the check fails (e.g., the + retraction is not a true exponential map or the metric does not match the + retraction), the algorithm falls back **for that step only** to a central + finite-difference natural gradient computed from the manifold's ``inner`` + product. + + Walk semantics: iteration count and path size both scale as + ``~initial_distance / settings.step_size``; reduce ``step_size`` for + higher path resolution. + + Args: + manifold: Any geodex manifold (Sphere, Euclidean, Torus, SE2, ConfigurationSpace). + start: Starting point. + goal: Target point. + settings: Algorithm settings (uses defaults if omitted). + + Returns: + InterpolationResult with fields ``path``, ``status``, ``iterations``, + ``distortion_halvings``, ``fd_midpoint_fallbacks``, ``initial_distance``, + ``final_distance``. + """ + ... + + +class EuclideanHeuristic: + """Euclidean (L2) heuristic between coordinate vectors. + + Computes the chord distance ‖a − b‖₂. Admissible for any manifold + where geodesic distance ≥ chord distance. + """ + + def __init__(self) -> None: + """Create a Euclidean heuristic.""" + ... + + def __call__(self, a: _Point, b: _Point) -> float: + """Compute ‖a − b‖₂.""" + ... diff --git a/python/src/bind_algorithms.cpp b/python/src/bind_algorithms.cpp index e7ca8a4..32c5419 100644 --- a/python/src/bind_algorithms.cpp +++ b/python/src/bind_algorithms.cpp @@ -1,11 +1,18 @@ /// @file bind_algorithms.cpp -/// @brief Python bindings for geodex algorithms: distance_midpoint. +/// @brief Python bindings for geodex algorithms: InterpolationSettings, +/// InterpolationStatus, InterpolationResult, distance_midpoint, discrete_geodesic, +/// EuclideanHeuristic. -#include #include +#include +#include #include +#include -#include +#include "geodex/algorithm/distance.hpp" +#include "geodex/algorithm/heuristics.hpp" +#include "geodex/algorithm/interpolation.hpp" +#include "geodex/algorithm/path_smoothing.hpp" #include "wrappers/dynamic_manifold.hpp" #include "wrappers/py_config_space.hpp" @@ -20,16 +27,12 @@ using namespace geodex::python; namespace { /// Extract a DynamicManifold from any known Python manifold type. -/// All returned DynamicManifolds have project() set (identity for flat manifolds). DynamicManifold extract_algo_manifold(nb::object obj) { - if (nb::isinstance(obj)) - return nb::cast(obj).to_dynamic_manifold(); + if (nb::isinstance(obj)) return nb::cast(obj).to_dynamic_manifold(); if (nb::isinstance(obj)) return nb::cast(obj).to_dynamic_manifold(); - if (nb::isinstance(obj)) - return nb::cast(obj).to_dynamic_manifold(); - if (nb::isinstance(obj)) - return nb::cast(obj).to_dynamic_manifold(); + if (nb::isinstance(obj)) return nb::cast(obj).to_dynamic_manifold(); + if (nb::isinstance(obj)) return nb::cast(obj).to_dynamic_manifold(); if (nb::isinstance(obj)) return nb::cast(obj).to_dynamic_manifold(); throw std::invalid_argument( @@ -39,6 +42,147 @@ DynamicManifold extract_algo_manifold(nb::object obj) { } // namespace void bind_algorithms(nb::module_& m) { + using geodex::InterpolationResult; + using geodex::InterpolationSettings; + using geodex::InterpolationStatus; + + // --- InterpolationStatus --- + nb::enum_(m, "InterpolationStatus", + "Termination status for the discrete geodesic walk.") + .value("Converged", InterpolationStatus::Converged, + "Distance to target fell below convergence tolerance.") + .value("MaxStepsReached", InterpolationStatus::MaxStepsReached, + "Iteration budget exhausted without reaching tolerance.") + .value("GradientVanished", InterpolationStatus::GradientVanished, + "Riemannian gradient norm is ~0 at a non-target point.") + .value("CutLocus", InterpolationStatus::CutLocus, + "log collapsed to ~0 while start and target are distinct (e.g. antipodal).") + .value("StepShrunkToZero", InterpolationStatus::StepShrunkToZero, + "Distortion halving drove the step size below min_step_size.") + .value("DegenerateInput", InterpolationStatus::DegenerateInput, + "start == target on entry; returned a single-point path."); + + // --- InterpolationSettings --- + nb::class_( + m, "InterpolationSettings", + "Settings for the discrete geodesic walk.\n\n" + "Walk semantics: each iteration takes a Riemannian step of length\n" + "min(step_size, remaining_distance) in the descent direction. Iteration\n" + "count and returned-path size scale as ~initial_distance / step_size,\n" + "so step_size also serves as the effective path resolution.") + .def( + "__init__", + [](InterpolationSettings* s, double step_size, double convergence_tol, + double convergence_rel, int max_steps, double fd_epsilon, double distortion_ratio, + double growth_factor, double min_step_size, double gradient_eps, double cut_locus_eps, + bool force_log_direction, double fd_midpoint_guard_tau) { + new (s) InterpolationSettings{step_size, + convergence_tol, + convergence_rel, + max_steps, + fd_epsilon, + distortion_ratio, + growth_factor, + min_step_size, + gradient_eps, + cut_locus_eps, + force_log_direction, + fd_midpoint_guard_tau}; + }, + nb::arg("step_size") = 0.5, nb::arg("convergence_tol") = 1e-4, + nb::arg("convergence_rel") = 1e-3, nb::arg("max_steps") = 100, + nb::arg("fd_epsilon") = 0.0, nb::arg("distortion_ratio") = 1.5, + nb::arg("growth_factor") = 1.5, nb::arg("min_step_size") = 1e-12, + nb::arg("gradient_eps") = 1e-12, nb::arg("cut_locus_eps") = 1e-10, + nb::arg("force_log_direction") = false, nb::arg("fd_midpoint_guard_tau") = 0.25, + "Create interpolation settings.\n\n" + "Args:\n" + " step_size: Max Riemannian step per iteration (also effective path resolution).\n" + " convergence_tol: Absolute stop threshold on |log(current, target)|_R.\n" + " convergence_rel: Relative stop threshold (distance < rel * initial_distance).\n" + " max_steps: Maximum number of successful gradient-descent steps.\n" + " fd_epsilon: Central FD step for the fallback gradient; 0 means auto-select.\n" + " distortion_ratio: Progress-check tolerance; 1.5 requires at least 50% of the\n" + " intended step length in distance decrease before accepting a step.\n" + " growth_factor: After a successful step, regrow the step cap by this factor.\n" + " min_step_size: Failure threshold after repeated distortion halvings.\n" + " gradient_eps: Gradient norm threshold for GradientVanished status.\n" + " cut_locus_eps: |log|_R threshold that flags a cut-locus situation.\n" + " force_log_direction: If True, always use -log(current, target) as the descent\n" + " direction and skip the FD fallback. Produces smoother paths at the cost\n" + " of following the base retraction's geodesic instead of the true\n" + " Riemannian geodesic of the configured metric.\n" + " fd_midpoint_guard_tau: Relative-error threshold above which the midpoint\n" + " distance surrogate used inside the FD gradient is rejected and the sample\n" + " falls back to |log|_R for that basis direction. Set to 0 to force\n" + " via-log sampling every time.") + .def_rw("step_size", &InterpolationSettings::step_size, + "Max Riemannian step per iteration; also the effective path resolution.") + .def_rw("convergence_tol", &InterpolationSettings::convergence_tol, + "Absolute stop threshold on |log(current, target)|_R.") + .def_rw("convergence_rel", &InterpolationSettings::convergence_rel, + "Relative stop threshold (distance < rel * initial_distance).") + .def_rw("max_steps", &InterpolationSettings::max_steps, + "Maximum number of successful gradient-descent steps.") + .def_rw("fd_epsilon", &InterpolationSettings::fd_epsilon, + "Central FD step for the fallback gradient; 0 means auto-select.") + .def_rw("distortion_ratio", &InterpolationSettings::distortion_ratio, + "Progress-check tolerance.") + .def_rw("growth_factor", &InterpolationSettings::growth_factor, + "Factor by which the step cap grows back after a successful iteration.") + .def_rw("min_step_size", &InterpolationSettings::min_step_size, + "Failure threshold after repeated distortion halvings.") + .def_rw("gradient_eps", &InterpolationSettings::gradient_eps, + "Gradient Riemannian-norm threshold for GradientVanished status.") + .def_rw("cut_locus_eps", &InterpolationSettings::cut_locus_eps, + "|log|_R threshold that flags CutLocus.") + .def_rw("force_log_direction", &InterpolationSettings::force_log_direction, + "If True, always use -log(current, target) as the descent direction and skip " + "the FD fallback. Produces smoother paths at the cost of following the base " + "retraction's geodesic rather than the true Riemannian geodesic of the " + "configured metric.") + .def_rw("fd_midpoint_guard_tau", &InterpolationSettings::fd_midpoint_guard_tau, + "Relative-error threshold above which the midpoint distance surrogate used " + "inside the FD gradient is rejected and the sample falls back to |log|_R for " + "that basis direction.") + .def("__repr__", [](const InterpolationSettings& s) { + return "InterpolationSettings(step_size=" + std::to_string(s.step_size) + + ", convergence_tol=" + std::to_string(s.convergence_tol) + + ", max_steps=" + std::to_string(s.max_steps) + ")"; + }); + + // --- InterpolationResult --- + using PyResult = InterpolationResult; + nb::class_(m, "InterpolationResult", + "Output of discrete_geodesic.\n\n" + "Carries the discretised path, a termination status, iteration count,\n" + "and the initial/final Riemannian distances to target.") + .def_ro( + "path", &PyResult::path, + "list[np.ndarray] — points traced from start toward target (always starts with start).") + .def_ro("status", &PyResult::status, + "InterpolationStatus — termination reason. Always check before using `path`.") + .def_ro("iterations", &PyResult::iterations, + "Number of successful gradient steps taken (distortion retries do not count).") + .def_ro("distortion_halvings", &PyResult::distortion_halvings, + "Number of times the step cap was halved due to progress failure.") + .def_ro("fd_midpoint_fallbacks", &PyResult::fd_midpoint_fallbacks, + "Number of FD basis samples whose midpoint distance surrogate was rejected " + "by the runtime guard and replaced with |log|_R. A nonzero value flags a " + "non-Riemannian retraction, a cut-locus crossing, or a non-smooth metric " + "feature within the FD neighbourhood.") + .def_ro("initial_distance", &PyResult::initial_distance, + "Riemannian distance from start to target at entry.") + .def_ro("final_distance", &PyResult::final_distance, + "Riemannian distance from the final iterate to target at exit.") + .def("__repr__", [](const PyResult& r) { + return "InterpolationResult(status=" + std::string(geodex::to_string(r.status)) + + ", iterations=" + std::to_string(r.iterations) + + ", path_size=" + std::to_string(r.path.size()) + + ", initial_distance=" + std::to_string(r.initial_distance) + + ", final_distance=" + std::to_string(r.final_distance) + ")"; + }); + // --- distance_midpoint --- m.def( "distance_midpoint", @@ -56,4 +200,89 @@ void bind_algorithms(nb::module_& m) { " b: Second point on the manifold.\n" "Returns:\n" " Approximate geodesic distance (float)."); + + // --- discrete_geodesic --- + m.def( + "discrete_geodesic", + [](nb::object manifold, const Eigen::VectorXd& start, const Eigen::VectorXd& goal, + const InterpolationSettings& settings) -> PyResult { + auto dm = extract_algo_manifold(manifold); + return geodex::discrete_geodesic(dm, start, goal, settings); + }, + nb::arg("manifold"), nb::arg("start"), nb::arg("goal"), + nb::arg("settings") = InterpolationSettings{}, + "Walk from start toward goal via Riemannian natural gradient descent.\n\n" + "Each iteration first tries the Riemannian logarithm direction (exploiting\n" + "the identity grad((1/2) d^2) = -log at points inside the injectivity radius)\n" + "and verifies via a progress check. When the check fails (non-Riemannian\n" + "retraction or metric mismatch), the algorithm falls back for that step only\n" + "to a central finite-difference natural gradient computed from the manifold's\n" + "inner product.\n\n" + "Walk semantics: iteration count and path size both scale as\n" + "~initial_distance / settings.step_size; reduce step_size for higher resolution.\n\n" + "Args:\n" + " manifold: Any geodex manifold (Sphere, Euclidean, Torus, SE2, ConfigurationSpace).\n" + " start: Starting point (np.ndarray).\n" + " goal: Target point (np.ndarray).\n" + " settings: InterpolationSettings (optional, uses defaults if omitted).\n" + "Returns:\n" + " InterpolationResult with fields path, status, iterations, distortion_halvings,\n" + " fd_midpoint_fallbacks, initial_distance, final_distance."); + + // --- EuclideanHeuristic --- + nb::class_( + m, "EuclideanHeuristic", + "Euclidean (L2) heuristic between coordinate vectors.\n\n" + "Computes the chord distance ||a - b||_2. Admissible for any manifold where\n" + "geodesic distance >= chord distance (e.g., convex subsets of Euclidean space).") + .def(nb::init<>(), "Create a Euclidean heuristic.") + .def( + "__call__", + [](const geodex::EuclideanHeuristic& h, const Eigen::VectorXd& a, + const Eigen::VectorXd& b) { return h(a, b); }, + nb::arg("a"), nb::arg("b"), "Compute ||a - b||_2."); + + // --- PathSmoothingSettings --- + using PSS = geodex::algorithm::PathSmoothingSettings; + nb::class_(m, "PathSmoothingSettings", "Settings for metric-aware path smoothing.") + .def(nb::init<>(), "Create default path smoothing settings.") + .def_rw("max_shortcut_attempts", &PSS::max_shortcut_attempts) + .def_rw("edge_collision_samples", &PSS::edge_collision_samples) + .def_rw("collision_resolution", &PSS::collision_resolution) + .def_rw("lbfgs_target_segments", &PSS::lbfgs_target_segments) + .def_rw("lbfgs_max_iterations", &PSS::lbfgs_max_iterations) + .def_rw("grad_tol", &PSS::grad_tol) + .def_rw("energy_tol", &PSS::energy_tol) + .def_rw("fd_epsilon", &PSS::fd_epsilon) + .def_rw("lbfgs_memory", &PSS::lbfgs_memory) + .def_rw("armijo_c", &PSS::armijo_c) + .def_rw("max_displacement", &PSS::max_displacement) + .def_rw("armijo_max_backtracks", &PSS::armijo_max_backtracks); + + // --- PathSmoothingResult --- + using PSR = geodex::algorithm::PathSmoothingResult; + nb::class_(m, "PathSmoothingResult", "Result of path smoothing.") + .def_ro("path", &PSR::path, "Smoothed path (list of arrays).") + .def_ro("energy", &PSR::energy, "Discrete energy of the result.") + .def_ro("distance", &PSR::distance, "Geodesic distance estimate.") + .def_ro("vertices_removed", &PSR::vertices_removed, "Vertices removed in shortcutting.") + .def_ro("smooth_iterations", &PSR::smooth_iterations, "L-BFGS iterations used.") + .def_ro("collision_free", &PSR::collision_free, "Whether final path is collision-free."); + + // --- smooth_path --- + using ValidityFn = std::function; + m.def( + "smooth_path", + [](nb::object manifold_obj, ValidityFn validity_fn, const std::vector& path, + PSS settings) { + const DynamicManifold manifold = extract_algo_manifold(manifold_obj); + return geodex::algorithm::smooth_path(manifold, validity_fn, path, settings); + }, + nb::arg("manifold"), nb::arg("validity_fn"), nb::arg("path"), nb::arg("settings") = PSS{}, + "Smooth a path using metric-aware shortcutting and L-BFGS energy minimization.\n\n" + "Args:\n" + " manifold: Any geodex manifold.\n" + " validity_fn: Callable(q) -> bool, returns True if collision-free.\n" + " path: List of waypoints (numpy arrays).\n" + " settings: PathSmoothingSettings (optional)."); } diff --git a/python/src/bind_collision.cpp b/python/src/bind_collision.cpp new file mode 100644 index 0000000..99b2b7e --- /dev/null +++ b/python/src/bind_collision.cpp @@ -0,0 +1,90 @@ +/// @file bind_collision.cpp +/// @brief Python bindings for geodex collision detection primitives. + +#include +#include +#include +#include + +#include "geodex/collision/collision.hpp" + +namespace nb = nanobind; +using namespace geodex::collision; + +void bind_collision(nb::module_& m) { + auto col = m.def_submodule("collision", "Collision detection primitives."); + + // --- CircleSDF --- + nb::class_(col, "CircleSDF", "Signed distance function for a circle obstacle.") + .def(nb::init(), nb::arg("cx"), nb::arg("cy"), nb::arg("radius"), + "Create a circle SDF.\n\n" + "Args:\n" + " cx, cy: Center coordinates.\n" + " radius: Circle radius.") + .def( + "__call__", + [](const CircleSDF& self, const double x, const double y) { + const Eigen::Vector2d q(x, y); + return self(q); + }, + nb::arg("x"), nb::arg("y"), "Evaluate signed distance at (x, y).") + .def_prop_ro("cx", &CircleSDF::cx, "X-coordinate of the circle center.") + .def_prop_ro("cy", &CircleSDF::cy, "Y-coordinate of the circle center.") + .def_prop_ro("radius", &CircleSDF::radius, "Radius of the circle."); + + // --- CircleSmoothSDF --- + nb::class_(col, "CircleSmoothSDF", + "Smooth-min SDF over multiple circle obstacles.") + .def(nb::init, double>(), nb::arg("circles"), nb::arg("beta") = 20.0, + "Create from circles with smoothing parameter beta.") + .def( + "__call__", + [](const CircleSmoothSDF& self, const double x, const double y) { + const Eigen::Vector2d q(x, y); + return self(q); + }, + nb::arg("x"), nb::arg("y"), "Evaluate smooth signed distance at (x, y).") + .def( + "is_free", + [](const CircleSmoothSDF& self, const double x, const double y) { + const Eigen::Vector2d q(x, y); + return self.is_free(q); + }, + nb::arg("x"), nb::arg("y"), "Check if (x, y) is outside all circles.") + .def_prop_ro("beta", &CircleSmoothSDF::beta, "Log-sum-exp smoothing parameter."); + + // --- RectObstacle --- + nb::class_(col, "RectObstacle", "An oriented rectangle obstacle.") + .def(nb::init<>()) + .def_rw("cx", &RectObstacle::cx, "Center x-coordinate.") + .def_rw("cy", &RectObstacle::cy, "Center y-coordinate.") + .def_rw("theta", &RectObstacle::theta, "Orientation angle (radians).") + .def_rw("half_length", &RectObstacle::half_length, "Half-extent along local x-axis.") + .def_rw("half_width", &RectObstacle::half_width, "Half-extent along local y-axis."); + + // --- RectSmoothSDF --- + nb::class_(col, "RectSmoothSDF", + "Smooth-min SDF over oriented rectangle obstacles.") + .def(nb::init, double, double>(), nb::arg("obstacles"), + nb::arg("beta") = 20.0, nb::arg("inflation") = 0.0, + "Create from rectangle obstacles with smoothing and optional inflation.") + .def( + "__call__", + [](const RectSmoothSDF& self, const double x, const double y) { + const Eigen::Vector2d q(x, y); + return self(q); + }, + nb::arg("x"), nb::arg("y"), "Evaluate smooth signed distance at (x, y).") + .def_prop_ro("beta", &RectSmoothSDF::beta, "Log-sum-exp smoothing parameter.") + .def_prop_ro("inflation", &RectSmoothSDF::inflation, "Inflation radius."); + + // --- PolygonFootprint --- + nb::class_(col, "PolygonFootprint", + "Polygon footprint for swept-volume collision checking.") + .def_static("rectangle", &PolygonFootprint::rectangle, nb::arg("half_length"), + nb::arg("half_width"), nb::arg("samples_per_edge") = 8, + "Create a rectangular footprint.") + .def("sample_count", &PolygonFootprint::sample_count, "Number of perimeter samples.") + .def("bounding_radius", &PolygonFootprint::bounding_radius, + "Max distance from origin to any sample."); +} diff --git a/python/src/bind_config_space.cpp b/python/src/bind_config_space.cpp index 766878b..3d87d47 100644 --- a/python/src/bind_config_space.cpp +++ b/python/src/bind_config_space.cpp @@ -1,5 +1,5 @@ -#include #include +#include #include #include "wrappers/dynamic_manifold.hpp" @@ -17,14 +17,11 @@ namespace { /// Extract a DynamicManifold from any known Python manifold type. DynamicManifold extract_dynamic_manifold(nb::object obj) { - if (nb::isinstance(obj)) - return nb::cast(obj).to_dynamic_manifold(); + if (nb::isinstance(obj)) return nb::cast(obj).to_dynamic_manifold(); if (nb::isinstance(obj)) return nb::cast(obj).to_dynamic_manifold(); - if (nb::isinstance(obj)) - return nb::cast(obj).to_dynamic_manifold(); - if (nb::isinstance(obj)) - return nb::cast(obj).to_dynamic_manifold(); + if (nb::isinstance(obj)) return nb::cast(obj).to_dynamic_manifold(); + if (nb::isinstance(obj)) return nb::cast(obj).to_dynamic_manifold(); if (nb::isinstance(obj)) return nb::cast(obj).to_dynamic_manifold(); throw std::invalid_argument( @@ -51,24 +48,26 @@ DynamicMetric extract_dynamic_metric(nb::object obj) { } // namespace void bind_config_space(nb::module_& m) { - nb::class_(m, "ConfigurationSpace", + nb::class_( + m, "ConfigurationSpace", "A configuration space combining a base manifold's topology with a custom metric.\n\n" "Topology operations (exp, log, dim, random_point) come from the base manifold.\n" "Geometry operations (inner, norm, distance) come from the custom metric.") - .def("__init__", - [](PyConfigurationSpace* self, nb::object base, nb::object metric) { - auto dm = extract_dynamic_manifold(base); - auto dmet = extract_dynamic_metric(metric); - std::string base_name = nb::repr(base).c_str(); - std::string metric_name = nb::repr(metric).c_str(); - new (self) PyConfigurationSpace(std::move(dm), std::move(dmet), - std::move(base_name), std::move(metric_name)); - }, - nb::arg("base_manifold"), nb::arg("metric"), - "Create a configuration space.\n\n" - "Args:\n" - " base_manifold: Base manifold (Sphere, Euclidean, Torus, SE2, etc.).\n" - " metric: Custom metric (KineticEnergyMetric, ConstantSPDMetric, etc.).") + .def( + "__init__", + [](PyConfigurationSpace* self, nb::object base, nb::object metric) { + auto dm = extract_dynamic_manifold(base); + auto dmet = extract_dynamic_metric(metric); + std::string base_name = nb::repr(base).c_str(); + std::string metric_name = nb::repr(metric).c_str(); + new (self) PyConfigurationSpace(std::move(dm), std::move(dmet), std::move(base_name), + std::move(metric_name)); + }, + nb::arg("base_manifold"), nb::arg("metric"), + "Create a configuration space.\n\n" + "Args:\n" + " base_manifold: Base manifold (Sphere, Euclidean, Torus, SE2, etc.).\n" + " metric: Custom metric (KineticEnergyMetric, ConstantSPDMetric, etc.).") .def("dim", &PyConfigurationSpace::dim, "Return the intrinsic dimension.") .def("random_point", &PyConfigurationSpace::random_point, "Sample a random point from the base manifold.") @@ -82,8 +81,7 @@ void bind_config_space(nb::module_& m) { "Logarithmic map from the base manifold.") .def("distance", &PyConfigurationSpace::distance, nb::arg("p"), nb::arg("q"), "Geodesic distance using the midpoint approximation with the custom metric.") - .def("geodesic", &PyConfigurationSpace::geodesic, - nb::arg("p"), nb::arg("q"), nb::arg("t"), + .def("geodesic", &PyConfigurationSpace::geodesic, nb::arg("p"), nb::arg("q"), nb::arg("t"), "Geodesic interpolation at parameter t in [0, 1].") .def("__repr__", &PyConfigurationSpace::repr); } diff --git a/python/src/bind_euclidean.cpp b/python/src/bind_euclidean.cpp index ad401e3..c9ff9dc 100644 --- a/python/src/bind_euclidean.cpp +++ b/python/src/bind_euclidean.cpp @@ -1,5 +1,5 @@ -#include #include +#include #include #include "wrappers/py_euclidean.hpp" @@ -9,21 +9,17 @@ using namespace geodex::python; void bind_euclidean(nb::module_& m) { nb::class_(m, "Euclidean", - "Euclidean manifold R^n with the standard flat metric.\n\n" - "Exp/log are trivial (addition/subtraction).") - .def(nb::init(), nb::arg("dim"), - "Create a Euclidean space of the given dimension.") + "Euclidean manifold R^n with the standard flat metric.\n\n" + "Exp/log are trivial (addition/subtraction).") + .def(nb::init(), nb::arg("dim"), "Create a Euclidean space of the given dimension.") .def("dim", &PyEuclidean::dim, "Return the dimension.") .def("random_point", &PyEuclidean::random_point, "Sample a random point from a standard normal distribution.") .def("inner", &PyEuclidean::inner, nb::arg("p"), nb::arg("u"), nb::arg("v"), "Inner product = u . v.") - .def("norm", &PyEuclidean::norm, nb::arg("p"), nb::arg("v"), - "Euclidean norm ||v||.") - .def("exp", &PyEuclidean::exp, nb::arg("p"), nb::arg("v"), - "Exponential map: p + v.") - .def("log", &PyEuclidean::log, nb::arg("p"), nb::arg("q"), - "Logarithmic map: q - p.") + .def("norm", &PyEuclidean::norm, nb::arg("p"), nb::arg("v"), "Euclidean norm ||v||.") + .def("exp", &PyEuclidean::exp, nb::arg("p"), nb::arg("v"), "Exponential map: p + v.") + .def("log", &PyEuclidean::log, nb::arg("p"), nb::arg("q"), "Logarithmic map: q - p.") .def("distance", &PyEuclidean::distance, nb::arg("p"), nb::arg("q"), "Euclidean distance ||p - q||.") .def("geodesic", &PyEuclidean::geodesic, nb::arg("p"), nb::arg("q"), nb::arg("t"), diff --git a/python/src/bind_metrics.cpp b/python/src/bind_metrics.cpp index de6d08e..105bb66 100644 --- a/python/src/bind_metrics.cpp +++ b/python/src/bind_metrics.cpp @@ -1,5 +1,5 @@ -#include #include +#include #include #include @@ -22,16 +22,19 @@ DynamicMetric extract_dynamic_metric(nb::object obj) { return nb::cast(obj).to_dynamic_metric(); if (nb::isinstance(obj)) return nb::cast(obj).to_dynamic_metric(); + if (nb::isinstance(obj)) + return nb::cast(obj).to_dynamic_metric(); throw std::invalid_argument( "Unknown metric type. Expected KineticEnergyMetric, JacobiMetric, " - "PullbackMetric, ConstantSPDMetric, or WeightedMetric."); + "PullbackMetric, ConstantSPDMetric, WeightedMetric, or ClearanceMetric."); } } // namespace void bind_metrics(nb::module_& m) { // --- KineticEnergyMetric --- - nb::class_(m, "KineticEnergyMetric", + nb::class_( + m, "KineticEnergyMetric", "Kinetic energy metric g(q) = M(q).\n\n" "The inner product at q is _q = u^T M(q) v where M(q) is a\n" "symmetric positive-definite mass matrix returned by the callable.") @@ -47,11 +50,11 @@ void bind_metrics(nb::module_& m) { // --- JacobiMetric --- nb::class_(m, "JacobiMetric", - "Jacobi metric for minimum-time geodesics under a potential field.\n\n" - "The inner product at q is _q = 2(H - P(q)) u^T M(q) v\n" - "where H is the total energy and P(q) is the potential energy.") - .def(nb::init(), - nb::arg("mass_matrix_fn"), nb::arg("potential_fn"), nb::arg("total_energy"), + "Jacobi metric for minimum-time geodesics under a potential field.\n\n" + "The inner product at q is _q = 2(H - P(q)) u^T M(q) v\n" + "where H is the total energy and P(q) is the potential energy.") + .def(nb::init(), nb::arg("mass_matrix_fn"), + nb::arg("potential_fn"), nb::arg("total_energy"), "Create a Jacobi metric.\n\n" "Args:\n" " mass_matrix_fn: Callable(q) -> np.ndarray returning the SPD mass matrix.\n" @@ -59,16 +62,16 @@ void bind_metrics(nb::module_& m) { " total_energy: Total energy H (must satisfy H > P(q) everywhere).") .def("inner", &PyJacobiMetric::inner, nb::arg("p"), nb::arg("u"), nb::arg("v"), "Riemannian inner product 2(H - P(p)) u^T M(p) v.") - .def("norm", &PyJacobiMetric::norm, nb::arg("p"), nb::arg("v"), - "Riemannian norm.") + .def("norm", &PyJacobiMetric::norm, nb::arg("p"), nb::arg("v"), "Riemannian norm.") .def("__repr__", &PyJacobiMetric::repr); // --- PullbackMetric --- - nb::class_(m, "PullbackMetric", + nb::class_( + m, "PullbackMetric", "Pullback metric from task space to configuration space via the Jacobian.\n\n" "The inner product at q is _q = u^T J(q)^T G(q) J(q) v + lambda * u^T v.") - .def(nb::init(), - nb::arg("jacobian_fn"), nb::arg("task_metric_fn"), nb::arg("regularization") = 0.0, + .def(nb::init(), nb::arg("jacobian_fn"), + nb::arg("task_metric_fn"), nb::arg("regularization") = 0.0, "Create a pullback metric.\n\n" "Args:\n" " jacobian_fn: Callable(q) -> np.ndarray returning the Jacobian matrix.\n" @@ -76,12 +79,12 @@ void bind_metrics(nb::module_& m) { " regularization: Regularization parameter lambda (default 0).") .def("inner", &PyPullbackMetric::inner, nb::arg("p"), nb::arg("u"), nb::arg("v"), "Riemannian inner product u^T J^T G J v + lambda * u^T v.") - .def("norm", &PyPullbackMetric::norm, nb::arg("p"), nb::arg("v"), - "Riemannian norm.") + .def("norm", &PyPullbackMetric::norm, nb::arg("p"), nb::arg("v"), "Riemannian norm.") .def("__repr__", &PyPullbackMetric::repr); // --- ConstantSPDMetric --- - nb::class_(m, "ConstantSPDMetric", + nb::class_( + m, "ConstantSPDMetric", "Point-independent Riemannian metric defined by a constant SPD matrix.\n\n" "The inner product is = u^T A v where A is a constant SPD matrix.") .def(nb::init(), nb::arg("matrix"), @@ -96,21 +99,47 @@ void bind_metrics(nb::module_& m) { // --- WeightedMetric --- nb::class_(m, "WeightedMetric", - "Uniformly scaled metric wrapper.\n\n" - "The inner product is _q = alpha * ^base_q.") - .def("__init__", - [](PyWeightedMetric* self, nb::object base_metric, double alpha) { - new (self) PyWeightedMetric(extract_dynamic_metric(base_metric), alpha); - }, - nb::arg("base_metric"), nb::arg("alpha"), - "Create a weighted metric.\n\n" - "Args:\n" - " base_metric: Any geodex metric to scale.\n" - " alpha: Scaling factor (must be positive).") + "Uniformly scaled metric wrapper.\n\n" + "The inner product is _q = alpha * ^base_q.") + .def( + "__init__", + [](PyWeightedMetric* self, nb::object base_metric, double alpha) { + new (self) PyWeightedMetric(extract_dynamic_metric(base_metric), alpha); + }, + nb::arg("base_metric"), nb::arg("alpha"), + "Create a weighted metric.\n\n" + "Args:\n" + " base_metric: Any geodex metric to scale.\n" + " alpha: Scaling factor (must be positive).") .def("inner", &PyWeightedMetric::inner, nb::arg("p"), nb::arg("u"), nb::arg("v"), "Scaled Riemannian inner product alpha * ^base_p.") - .def("norm", &PyWeightedMetric::norm, nb::arg("p"), nb::arg("v"), - "Scaled Riemannian norm.") + .def("norm", &PyWeightedMetric::norm, nb::arg("p"), nb::arg("v"), "Scaled Riemannian norm.") .def_prop_ro("alpha", &PyWeightedMetric::alpha, "The scaling factor.") .def("__repr__", &PyWeightedMetric::repr); + + // --- ClearanceMetric --- + nb::class_( + m, "ClearanceMetric", + "SDF-based conformal metric that scales a base metric by obstacle proximity.\n\n" + "Inner product: _q = (1 + kappa * exp(-beta * sdf(q))) * ^base_q.") + .def( + "__init__", + [](PyClearanceMetric* self, nb::object base_metric, SDFFn sdf, double kappa, + double beta) { + new (self) + PyClearanceMetric(extract_dynamic_metric(base_metric), std::move(sdf), kappa, beta); + }, + nb::arg("base_metric"), nb::arg("sdf"), nb::arg("kappa") = 5.0, nb::arg("beta") = 3.0, + "Create an SDF-based conformal metric.\n\n" + "Args:\n" + " base_metric: Any geodex metric to scale.\n" + " sdf: Callable(q) -> float returning signed distance (positive = free).\n" + " kappa: Strength of obstacle repulsion (default 5.0).\n" + " beta: Falloff rate (default 3.0).") + .def("inner", &PyClearanceMetric::inner, nb::arg("p"), nb::arg("u"), nb::arg("v"), + "Conformally scaled inner product.") + .def("norm", &PyClearanceMetric::norm, nb::arg("p"), nb::arg("v"), "Conformally scaled norm.") + .def_prop_ro("kappa", &PyClearanceMetric::kappa, "Obstacle repulsion strength.") + .def_prop_ro("beta", &PyClearanceMetric::beta, "Falloff rate.") + .def("__repr__", &PyClearanceMetric::repr); } diff --git a/python/src/bind_se2.cpp b/python/src/bind_se2.cpp index f715243..621b00d 100644 --- a/python/src/bind_se2.cpp +++ b/python/src/bind_se2.cpp @@ -1,5 +1,5 @@ -#include #include +#include #include #include "wrappers/py_se2.hpp" @@ -9,14 +9,12 @@ using namespace geodex::python; void bind_se2(nb::module_& m) { nb::class_(m, "SE2", - "The special Euclidean group SE(2) = R^2 x SO(2).\n\n" - "Poses are (x, y, theta) with theta in [-pi, pi).\n" - "Uses a left-invariant metric with configurable weights.") - .def(nb::init(), + "The special Euclidean group SE(2) = R^2 x SO(2).\n\n" + "Poses are (x, y, theta) with theta in [-pi, pi).\n" + "Uses a left-invariant metric with configurable weights.") + .def(nb::init(), nb::arg("wx") = 1.0, nb::arg("wy") = 1.0, nb::arg("wtheta") = 1.0, - nb::arg("retraction") = "exponential", - nb::arg("x_lo") = 0.0, nb::arg("x_hi") = 10.0, + nb::arg("retraction") = "exponential", nb::arg("x_lo") = 0.0, nb::arg("x_hi") = 10.0, nb::arg("y_lo") = 0.0, nb::arg("y_hi") = 10.0, "Create an SE(2) manifold.\n\n" "Args:\n" @@ -24,19 +22,26 @@ void bind_se2(nb::module_& m) { " retraction: 'exponential' or 'euler'.\n" " x_lo, x_hi, y_lo, y_hi: Workspace bounds for random sampling.") .def("dim", &PySE2::dim, "Return the intrinsic dimension (always 3).") - .def("random_point", &PySE2::random_point, - "Sample a random pose in the workspace bounds.") + .def("random_point", &PySE2::random_point, "Sample a random pose in the workspace bounds.") .def("inner", &PySE2::inner, nb::arg("p"), nb::arg("u"), nb::arg("v"), "Left-invariant inner product _p.") - .def("norm", &PySE2::norm, nb::arg("p"), nb::arg("v"), - "Left-invariant norm ||v||_p.") + .def("norm", &PySE2::norm, nb::arg("p"), nb::arg("v"), "Left-invariant norm ||v||_p.") .def("exp", &PySE2::exp, nb::arg("p"), nb::arg("v"), "Exponential map (or retraction) exp_p(v).") .def("log", &PySE2::log, nb::arg("p"), nb::arg("q"), "Logarithmic map (or inverse retraction) log_p(q).") - .def("distance", &PySE2::distance, nb::arg("p"), nb::arg("q"), - "Geodesic distance d(p, q).") + .def("distance", &PySE2::distance, nb::arg("p"), nb::arg("q"), "Geodesic distance d(p, q).") .def("geodesic", &PySE2::geodesic, nb::arg("p"), nb::arg("q"), nb::arg("t"), "Geodesic interpolation at parameter t in [0, 1].") - .def("__repr__", &PySE2::repr); + .def("__repr__", &PySE2::repr) + .def_static("car_like", &PySE2::car_like, nb::arg("turning_radius"), + nb::arg("lateral_penalty") = 100.0, nb::arg("retraction") = "exponential", + nb::arg("x_lo") = 0.0, nb::arg("x_hi") = 10.0, nb::arg("y_lo") = 0.0, + nb::arg("y_hi") = 10.0, + "Create a car-like SE(2) manifold.\n\n" + "Args:\n" + " turning_radius: Effective minimum turning radius.\n" + " lateral_penalty: Weight suppressing sideslip (default 100).\n" + " retraction: 'exponential' or 'euler'.\n" + " x_lo, x_hi, y_lo, y_hi: Workspace bounds for random sampling."); } diff --git a/python/src/bind_sphere.cpp b/python/src/bind_sphere.cpp index f48785c..c4ce841 100644 --- a/python/src/bind_sphere.cpp +++ b/python/src/bind_sphere.cpp @@ -1,31 +1,29 @@ -#include #include +#include #include #include "wrappers/py_sphere.hpp" +#include "wrappers/py_sphere_n.hpp" namespace nb = nanobind; using namespace geodex::python; void bind_sphere(nb::module_& m) { nb::class_(m, "Sphere", - "The 2-sphere S^2 with interchangeable retraction policy.\n\n" - "Points are unit vectors in R^3. Tangent vectors lie in the\n" - "orthogonal complement of the base point.") - .def(nb::init(), - nb::arg("retraction") = "exponential", + "The 2-sphere S^2 with interchangeable retraction policy.\n\n" + "Points are unit vectors in R^3. Tangent vectors lie in the\n" + "orthogonal complement of the base point.") + .def(nb::init(), nb::arg("retraction") = "exponential", "Create a Sphere with the round metric.\n\n" "Args:\n" " retraction: 'exponential' (true exp/log) or 'projection' (first-order).") .def("dim", &PySphere::dim, "Return the intrinsic dimension (always 2).") - .def("random_point", &PySphere::random_point, - "Sample a uniformly random point on S^2.") + .def("random_point", &PySphere::random_point, "Sample a uniformly random point on S^2.") .def("project", &PySphere::project, nb::arg("p"), nb::arg("v"), "Project an ambient vector onto the tangent space at p.") .def("inner", &PySphere::inner, nb::arg("p"), nb::arg("u"), nb::arg("v"), "Riemannian inner product _p.") - .def("norm", &PySphere::norm, nb::arg("p"), nb::arg("v"), - "Riemannian norm ||v||_p.") + .def("norm", &PySphere::norm, nb::arg("p"), nb::arg("v"), "Riemannian norm ||v||_p.") .def("exp", &PySphere::exp, nb::arg("p"), nb::arg("v"), "Exponential map (or retraction) exp_p(v).") .def("log", &PySphere::log, nb::arg("p"), nb::arg("q"), @@ -35,4 +33,31 @@ void bind_sphere(nb::module_& m) { .def("geodesic", &PySphere::geodesic, nb::arg("p"), nb::arg("q"), nb::arg("t"), "Geodesic interpolation at parameter t in [0, 1].") .def("__repr__", &PySphere::repr); + + nb::class_(m, "SphereN", + "The n-sphere S^n with interchangeable retraction policy.\n\n" + "Points are unit vectors in R^(n+1). The dimension n is set\n" + "at construction time.") + .def(nb::init(), nb::arg("dim"), + nb::arg("retraction") = "exponential", + "Create an n-sphere with the round metric.\n\n" + "Args:\n" + " dim: Intrinsic dimension n of S^n.\n" + " retraction: 'exponential' (true exp/log) or 'projection' (first-order).") + .def("dim", &PySphereN::dim, "Return the intrinsic dimension n.") + .def("random_point", &PySphereN::random_point, "Sample a uniformly random point on S^n.") + .def("project", &PySphereN::project, nb::arg("p"), nb::arg("v"), + "Project an ambient vector onto the tangent space at p.") + .def("inner", &PySphereN::inner, nb::arg("p"), nb::arg("u"), nb::arg("v"), + "Riemannian inner product _p.") + .def("norm", &PySphereN::norm, nb::arg("p"), nb::arg("v"), "Riemannian norm ||v||_p.") + .def("exp", &PySphereN::exp, nb::arg("p"), nb::arg("v"), + "Exponential map (or retraction) exp_p(v).") + .def("log", &PySphereN::log, nb::arg("p"), nb::arg("q"), + "Logarithmic map (or inverse retraction) log_p(q).") + .def("distance", &PySphereN::distance, nb::arg("p"), nb::arg("q"), + "Geodesic distance d(p, q).") + .def("geodesic", &PySphereN::geodesic, nb::arg("p"), nb::arg("q"), nb::arg("t"), + "Geodesic interpolation at parameter t in [0, 1].") + .def("__repr__", &PySphereN::repr); } diff --git a/python/src/bind_torus.cpp b/python/src/bind_torus.cpp index 955d102..6b21fd8 100644 --- a/python/src/bind_torus.cpp +++ b/python/src/bind_torus.cpp @@ -1,5 +1,5 @@ -#include #include +#include #include #include "wrappers/py_torus.hpp" @@ -9,17 +9,15 @@ using namespace geodex::python; void bind_torus(nb::module_& m) { nb::class_(m, "Torus", - "Flat torus T^n with periodic angle coordinates in [0, 2*pi)^n.\n\n" - "Exp wraps to [0, 2*pi), log wraps differences to [-pi, pi).") - .def(nb::init(), nb::arg("dim"), - "Create a flat torus of the given dimension.") + "Flat torus T^n with periodic angle coordinates in [0, 2*pi)^n.\n\n" + "Exp wraps to [0, 2*pi), log wraps differences to [-pi, pi).") + .def(nb::init(), nb::arg("dim"), "Create a flat torus of the given dimension.") .def("dim", &PyTorus::dim, "Return the dimension.") .def("random_point", &PyTorus::random_point, "Sample a uniformly random point in [0, 2*pi)^n.") .def("inner", &PyTorus::inner, nb::arg("p"), nb::arg("u"), nb::arg("v"), "Flat inner product = u . v.") - .def("norm", &PyTorus::norm, nb::arg("p"), nb::arg("v"), - "Flat norm ||v||.") + .def("norm", &PyTorus::norm, nb::arg("p"), nb::arg("v"), "Flat norm ||v||.") .def("exp", &PyTorus::exp, nb::arg("p"), nb::arg("v"), "Exponential map: wrap(p + v) to [0, 2*pi)^n.") .def("log", &PyTorus::log, nb::arg("p"), nb::arg("q"), diff --git a/python/src/geodex_python.cpp b/python/src/geodex_python.cpp index 311a272..62ae685 100644 --- a/python/src/geodex_python.cpp +++ b/python/src/geodex_python.cpp @@ -9,6 +9,7 @@ void bind_se2(nb::module_& m); void bind_metrics(nb::module_& m); void bind_config_space(nb::module_& m); void bind_algorithms(nb::module_& m); +void bind_collision(nb::module_& m); NB_MODULE(_geodex_core, m) { m.doc() = "geodex: planning on Riemannian manifolds"; @@ -20,4 +21,5 @@ NB_MODULE(_geodex_core, m) { bind_metrics(m); bind_config_space(m); bind_algorithms(m); + bind_collision(m); } diff --git a/python/src/wrappers/dynamic_manifold.hpp b/python/src/wrappers/dynamic_manifold.hpp index 6b271e7..8f53d7c 100644 --- a/python/src/wrappers/dynamic_manifold.hpp +++ b/python/src/wrappers/dynamic_manifold.hpp @@ -3,12 +3,14 @@ #pragma once -#include #include -#include -#include #include +#include + +#include "geodex/algorithm/distance.hpp" +#include "geodex/core/concepts.hpp" + namespace geodex::python { /// @brief Type-erased metric storing inner/norm as std::function. @@ -22,14 +24,11 @@ struct DynamicMetric { InnerFn inner_fn; NormFn norm_fn; - double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) const { + double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) const { return inner_fn(p, u, v); } - double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { - return norm_fn(p, v); - } + double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { return norm_fn(p, v); } double injectivity_radius() const { return std::numeric_limits::infinity(); } }; @@ -75,13 +74,9 @@ class DynamicManifold { Scalar norm(const Point& p, const Tangent& v) const { return norm_fn_(p, v); } - Scalar distance(const Point& p, const Point& q) const { - return distance_midpoint(*this, p, q); - } + Scalar distance(const Point& p, const Point& q) const { return distance_midpoint(*this, p, q); } - Point geodesic(const Point& p, const Point& q, Scalar t) const { - return exp(p, t * log(p, q)); - } + Point geodesic(const Point& p, const Point& q, Scalar t) const { return exp(p, t * log(p, q)); } Tangent project(const Point& p, const Tangent& v) const { if (project_fn_) return project_fn_(p, v); diff --git a/python/src/wrappers/py_config_space.hpp b/python/src/wrappers/py_config_space.hpp index 4af9367..67102ba 100644 --- a/python/src/wrappers/py_config_space.hpp +++ b/python/src/wrappers/py_config_space.hpp @@ -25,27 +25,25 @@ class PyConfigurationSpace { [dm]() { return dm.random_point(); }, [dm](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { return dm.exp(p, v); }, [dm](const Eigen::VectorXd& p, const Eigen::VectorXd& q) { return dm.log(p, q); }, - [dmet](const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) { return dmet.inner(p, u, v); }, + [dmet](const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) { + return dmet.inner(p, u, v); + }, [dmet](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { return dmet.norm(p, v); }, - dm.has_project() ? DynamicManifold::ProjectFn{[dm](const Eigen::VectorXd& p, - const Eigen::VectorXd& v) { - return dm.project(p, v); - }} - : nullptr}; + dm.has_project() + ? DynamicManifold::ProjectFn{[dm](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { + return dm.project(p, v); + }} + : nullptr}; } int dim() const { return impl_.dim(); } Eigen::VectorXd random_point() const { return impl_.random_point(); } - double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) const { + double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) const { return impl_.inner(p, u, v); } - double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { - return impl_.norm(p, v); - } + double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { return impl_.norm(p, v); } Eigen::VectorXd exp(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { return impl_.exp(p, v); @@ -59,8 +57,7 @@ class PyConfigurationSpace { return impl_.distance(p, q); } - Eigen::VectorXd geodesic(const Eigen::VectorXd& p, const Eigen::VectorXd& q, - double t) const { + Eigen::VectorXd geodesic(const Eigen::VectorXd& p, const Eigen::VectorXd& q, double t) const { return impl_.geodesic(p, q, t); } diff --git a/python/src/wrappers/py_euclidean.hpp b/python/src/wrappers/py_euclidean.hpp index 06f9fdf..784dfd7 100644 --- a/python/src/wrappers/py_euclidean.hpp +++ b/python/src/wrappers/py_euclidean.hpp @@ -3,11 +3,13 @@ #pragma once -#include -#include #include #include +#include + +#include "geodex/manifold/euclidean.hpp" + #include "dynamic_manifold.hpp" namespace geodex::python { @@ -22,14 +24,11 @@ class PyEuclidean { Eigen::VectorXd random_point() const { return impl_.random_point(); } - double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) const { + double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) const { return impl_.inner(p, u, v); } - double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { - return impl_.norm(p, v); - } + double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { return impl_.norm(p, v); } Eigen::VectorXd exp(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { return impl_.exp(p, v); @@ -43,8 +42,7 @@ class PyEuclidean { return impl_.distance(p, q); } - Eigen::VectorXd geodesic(const Eigen::VectorXd& p, const Eigen::VectorXd& q, - double t) const { + Eigen::VectorXd geodesic(const Eigen::VectorXd& p, const Eigen::VectorXd& q, double t) const { return impl_.geodesic(p, q, t); } @@ -59,18 +57,15 @@ class PyEuclidean { [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& q) -> Eigen::VectorXd { return shared->log(p, q); }, - [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) { return shared->inner(p, u, v); }, - [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { - return shared->norm(p, v); + [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) { + return shared->inner(p, u, v); }, + [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { return shared->norm(p, v); }, // Euclidean tangent space = ambient space; projection is the identity. [](const Eigen::VectorXd& /*p*/, const Eigen::VectorXd& v) { return v; }}; } - std::string repr() const { - return "Euclidean(dim=" + std::to_string(impl_.dim()) + ")"; - } + std::string repr() const { return "Euclidean(dim=" + std::to_string(impl_.dim()) + ")"; } private: Impl impl_; diff --git a/python/src/wrappers/py_metrics.hpp b/python/src/wrappers/py_metrics.hpp index 1ffadef..ac64b4e 100644 --- a/python/src/wrappers/py_metrics.hpp +++ b/python/src/wrappers/py_metrics.hpp @@ -3,17 +3,21 @@ #pragma once -#include #include + #include -#include -#include -#include -#include -#include #include #include +#include + +#include "geodex/metrics/clearance.hpp" +#include "geodex/metrics/constant_spd.hpp" +#include "geodex/metrics/jacobi.hpp" +#include "geodex/metrics/kinetic_energy.hpp" +#include "geodex/metrics/pullback.hpp" +#include "geodex/metrics/weighted.hpp" + #include "dynamic_manifold.hpp" namespace geodex::python { @@ -32,23 +36,19 @@ class PyKineticEnergyMetric { explicit PyKineticEnergyMetric(MassMatrixFn fn) : impl_(std::move(fn)) {} - double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) const { + double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) const { return impl_.inner(p, u, v); } - double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { - return impl_.norm(p, v); - } + double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { return impl_.norm(p, v); } DynamicMetric to_dynamic_metric() const { auto shared = std::make_shared(impl_); - return DynamicMetric{ - [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) { return shared->inner(p, u, v); }, - [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { - return shared->norm(p, v); - }}; + return DynamicMetric{[shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, + const Eigen::VectorXd& v) { return shared->inner(p, u, v); }, + [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { + return shared->norm(p, v); + }}; } std::string repr() const { return "KineticEnergyMetric()"; } @@ -66,26 +66,24 @@ class PyJacobiMetric { PyJacobiMetric(MassMatrixFn mass_fn, PotentialFn pot_fn, double H) : impl_(std::move(mass_fn), std::move(pot_fn), H) {} - double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) const { + double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) const { return impl_.inner(p, u, v); } - double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { - return impl_.norm(p, v); - } + double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { return impl_.norm(p, v); } DynamicMetric to_dynamic_metric() const { auto shared = std::make_shared(impl_); - return DynamicMetric{ - [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) { return shared->inner(p, u, v); }, - [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { - return shared->norm(p, v); - }}; + return DynamicMetric{[shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, + const Eigen::VectorXd& v) { return shared->inner(p, u, v); }, + [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { + return shared->norm(p, v); + }}; } - std::string repr() const { return "JacobiMetric(H=" + std::to_string(impl_.total_energy_) + ")"; } + std::string repr() const { + return "JacobiMetric(H=" + std::to_string(impl_.total_energy()) + ")"; + } private: Impl impl_; @@ -100,27 +98,23 @@ class PyPullbackMetric { PyPullbackMetric(JacobianFn jac_fn, TaskMetricFn task_fn, double lambda = 0.0) : impl_(std::move(jac_fn), std::move(task_fn), lambda) {} - double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) const { + double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) const { return impl_.inner(p, u, v); } - double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { - return impl_.norm(p, v); - } + double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { return impl_.norm(p, v); } DynamicMetric to_dynamic_metric() const { auto shared = std::make_shared(impl_); - return DynamicMetric{ - [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) { return shared->inner(p, u, v); }, - [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { - return shared->norm(p, v); - }}; + return DynamicMetric{[shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, + const Eigen::VectorXd& v) { return shared->inner(p, u, v); }, + [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { + return shared->norm(p, v); + }}; } std::string repr() const { - return "PullbackMetric(lambda=" + std::to_string(impl_.lambda_) + ")"; + return "PullbackMetric(lambda=" + std::to_string(impl_.lambda()) + ")"; } private: @@ -135,27 +129,23 @@ class PyConstantSPDMetric { explicit PyConstantSPDMetric(const Eigen::MatrixXd& A) : impl_(A) {} - double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) const { + double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) const { return impl_.inner(p, u, v); } - double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { - return impl_.norm(p, v); - } + double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { return impl_.norm(p, v); } DynamicMetric to_dynamic_metric() const { auto shared = std::make_shared(impl_); - return DynamicMetric{ - [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) { return shared->inner(p, u, v); }, - [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { - return shared->norm(p, v); - }}; + return DynamicMetric{[shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, + const Eigen::VectorXd& v) { return shared->inner(p, u, v); }, + [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { + return shared->norm(p, v); + }}; } std::string repr() const { - return "ConstantSPDMetric(dim=" + std::to_string(impl_.A_.rows()) + ")"; + return "ConstantSPDMetric(dim=" + std::to_string(impl_.weight_matrix().rows()) + ")"; } private: @@ -167,11 +157,9 @@ class PyConstantSPDMetric { /// WeightedMetric wraps a type-erased DynamicMetric and uniformly scales it. class PyWeightedMetric { public: - PyWeightedMetric(DynamicMetric base, double alpha) - : base_(std::move(base)), alpha_(alpha) {} + PyWeightedMetric(DynamicMetric base, double alpha) : base_(std::move(base)), alpha_(alpha) {} - double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) const { + double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) const { return alpha_ * base_.inner(p, u, v); } @@ -184,9 +172,7 @@ class PyWeightedMetric { double a = alpha_; return DynamicMetric{ [shared_base, a](const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) { - return a * shared_base->inner(p, u, v); - }, + const Eigen::VectorXd& v) { return a * shared_base->inner(p, u, v); }, [shared_base, a](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { return std::sqrt(a * shared_base->inner(p, v, v)); }}; @@ -201,4 +187,44 @@ class PyWeightedMetric { double alpha_; }; +// --- ClearanceMetric --- + +using SDFFn = std::function; + +/// ClearanceMetric wraps SDFConformalMetric with DynamicMetric base and callable SDF. +class PyClearanceMetric { + public: + using Impl = SDFConformalMetric; + + PyClearanceMetric(DynamicMetric base, SDFFn sdf, const double kappa = 5.0, + const double beta = 3.0) + : impl_(std::move(base), std::move(sdf), kappa, beta) {} + + double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) const { + return impl_.inner(p, u, v); + } + + double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { return impl_.norm(p, v); } + + double kappa() const { return impl_.kappa(); } + double beta() const { return impl_.beta(); } + + DynamicMetric to_dynamic_metric() const { + auto shared = std::make_shared(impl_); + return DynamicMetric{[shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, + const Eigen::VectorXd& v) { return shared->inner(p, u, v); }, + [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { + return shared->norm(p, v); + }}; + } + + std::string repr() const { + return "ClearanceMetric(kappa=" + std::to_string(impl_.kappa()) + + ", beta=" + std::to_string(impl_.beta()) + ")"; + } + + private: + Impl impl_; +}; + } // namespace geodex::python diff --git a/python/src/wrappers/py_se2.hpp b/python/src/wrappers/py_se2.hpp index 1129b56..86f0c4b 100644 --- a/python/src/wrappers/py_se2.hpp +++ b/python/src/wrappers/py_se2.hpp @@ -3,13 +3,15 @@ #pragma once -#include -#include #include #include #include #include +#include + +#include "geodex/manifold/se2.hpp" + #include "dynamic_manifold.hpp" namespace geodex::python { @@ -20,21 +22,21 @@ class PySE2 { SE2>; PySE2(double wx = 1.0, double wy = 1.0, double wtheta = 1.0, - const std::string& retraction = "exponential", - double x_lo = 0.0, double x_hi = 10.0, + const std::string& retraction = "exponential", double x_lo = 0.0, double x_hi = 10.0, double y_lo = 0.0, double y_hi = 10.0) : retraction_name_(retraction) { SE2LeftInvariantMetric metric(wx, wy, wtheta); + const Eigen::Vector3d lo(x_lo, y_lo, -std::numbers::pi); + const Eigen::Vector3d hi(x_hi, y_hi, std::numbers::pi); if (retraction == "exponential") { - impl_.emplace>( - metric, SE2ExponentialMap{}, x_lo, x_hi, y_lo, y_hi); + impl_.emplace>(metric, SE2ExponentialMap{}, lo, + hi); } else if (retraction == "euler") { - impl_.emplace>( - metric, SE2EulerRetraction{}, x_lo, x_hi, y_lo, y_hi); + impl_.emplace>(metric, SE2EulerRetraction{}, + lo, hi); } else { - throw std::invalid_argument( - "Unknown retraction: '" + retraction + - "'. Options: 'exponential', 'euler'"); + throw std::invalid_argument("Unknown retraction: '" + retraction + + "'. Options: 'exponential', 'euler'"); } } @@ -46,8 +48,7 @@ class PySE2 { return std::visit([](const auto& m) { return m.random_point(); }, impl_); } - double inner(const Eigen::Vector3d& p, const Eigen::Vector3d& u, - const Eigen::Vector3d& v) const { + double inner(const Eigen::Vector3d& p, const Eigen::Vector3d& u, const Eigen::Vector3d& v) const { return std::visit([&](const auto& m) { return m.inner(p, u, v); }, impl_); } @@ -67,8 +68,7 @@ class PySE2 { return std::visit([&](const auto& m) { return m.distance(p, q); }, impl_); } - Eigen::Vector3d geodesic(const Eigen::Vector3d& p, const Eigen::Vector3d& q, - double t) const { + Eigen::Vector3d geodesic(const Eigen::Vector3d& p, const Eigen::Vector3d& q, double t) const { return std::visit([&](const auto& m) { return m.geodesic(p, q, t); }, impl_); } @@ -82,13 +82,13 @@ class PySE2 { }, [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) -> Eigen::VectorXd { Eigen::Vector3d p3(p), v3(v); - return std::visit( - [&](const auto& m) -> Eigen::VectorXd { return m.exp(p3, v3); }, *shared); + return std::visit([&](const auto& m) -> Eigen::VectorXd { return m.exp(p3, v3); }, + *shared); }, [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& q) -> Eigen::VectorXd { Eigen::Vector3d p3(p), q3(q); - return std::visit( - [&](const auto& m) -> Eigen::VectorXd { return m.log(p3, q3); }, *shared); + return std::visit([&](const auto& m) -> Eigen::VectorXd { return m.log(p3, q3); }, + *shared); }, [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) -> double { @@ -103,10 +103,18 @@ class PySE2 { [](const Eigen::VectorXd& /*p*/, const Eigen::VectorXd& v) { return v; }}; } - std::string repr() const { - return "SE2(retraction='" + retraction_name_ + "')"; + /// @brief Factory for car-like SE2 with turning radius constraint. + static PySE2 car_like(const double turning_radius, const double lateral_penalty = 100.0, + const std::string& retraction = "exponential", const double x_lo = 0.0, + const double x_hi = 10.0, const double y_lo = 0.0, + const double y_hi = 10.0) { + const auto metric = SE2LeftInvariantMetric::car_like(turning_radius, lateral_penalty); + return PySE2(metric.weights()[0], metric.weights()[1], metric.weights()[2], retraction, x_lo, + x_hi, y_lo, y_hi); } + std::string repr() const { return "SE2(retraction='" + retraction_name_ + "')"; } + private: V impl_; std::string retraction_name_; diff --git a/python/src/wrappers/py_sphere.hpp b/python/src/wrappers/py_sphere.hpp index f34d361..15ba9f5 100644 --- a/python/src/wrappers/py_sphere.hpp +++ b/python/src/wrappers/py_sphere.hpp @@ -3,28 +3,29 @@ #pragma once -#include -#include #include #include #include #include +#include + +#include "geodex/manifold/sphere.hpp" + #include "dynamic_manifold.hpp" namespace geodex::python { class PySphere { public: - using V = std::variant, - Sphere>; + using V = std::variant, + Sphere<2, SphereRoundMetric, SphereProjectionRetraction>>; - PySphere(const std::string& retraction = "exponential") - : retraction_name_(retraction) { + PySphere(const std::string& retraction = "exponential") : retraction_name_(retraction) { if (retraction == "exponential") { - impl_.emplace>(); + impl_.emplace>(); } else if (retraction == "projection") { - impl_.emplace>(); + impl_.emplace>(); } else { throw std::invalid_argument("Unknown retraction: '" + retraction + "'. Options: 'exponential', 'projection'"); @@ -43,8 +44,7 @@ class PySphere { return std::visit([&](const auto& m) { return m.project(p, v); }, impl_); } - double inner(const Eigen::Vector3d& p, const Eigen::Vector3d& u, - const Eigen::Vector3d& v) const { + double inner(const Eigen::Vector3d& p, const Eigen::Vector3d& u, const Eigen::Vector3d& v) const { return std::visit([&](const auto& m) { return m.inner(p, u, v); }, impl_); } @@ -64,8 +64,7 @@ class PySphere { return std::visit([&](const auto& m) { return m.distance(p, q); }, impl_); } - Eigen::Vector3d geodesic(const Eigen::Vector3d& p, const Eigen::Vector3d& q, - double t) const { + Eigen::Vector3d geodesic(const Eigen::Vector3d& p, const Eigen::Vector3d& q, double t) const { return std::visit([&](const auto& m) { return m.geodesic(p, q, t); }, impl_); } @@ -79,13 +78,13 @@ class PySphere { }, [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) -> Eigen::VectorXd { Eigen::Vector3d p3(p), v3(v); - return std::visit( - [&](const auto& m) -> Eigen::VectorXd { return m.exp(p3, v3); }, *shared); + return std::visit([&](const auto& m) -> Eigen::VectorXd { return m.exp(p3, v3); }, + *shared); }, [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& q) -> Eigen::VectorXd { Eigen::Vector3d p3(p), q3(q); - return std::visit( - [&](const auto& m) -> Eigen::VectorXd { return m.log(p3, q3); }, *shared); + return std::visit([&](const auto& m) -> Eigen::VectorXd { return m.log(p3, q3); }, + *shared); }, [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) -> double { @@ -98,14 +97,12 @@ class PySphere { }, [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) -> Eigen::VectorXd { Eigen::Vector3d p3(p), v3(v); - return std::visit( - [&](const auto& m) -> Eigen::VectorXd { return m.project(p3, v3); }, *shared); + return std::visit([&](const auto& m) -> Eigen::VectorXd { return m.project(p3, v3); }, + *shared); }}; } - std::string repr() const { - return "Sphere(retraction='" + retraction_name_ + "')"; - } + std::string repr() const { return "Sphere(retraction='" + retraction_name_ + "')"; } private: V impl_; diff --git a/python/src/wrappers/py_sphere_n.hpp b/python/src/wrappers/py_sphere_n.hpp new file mode 100644 index 0000000..c85da5d --- /dev/null +++ b/python/src/wrappers/py_sphere_n.hpp @@ -0,0 +1,118 @@ +/// @file py_sphere_n.hpp +/// @brief Python wrapper for geodex::Sphere (n-dimensional sphere). + +#pragma once + +#include +#include +#include +#include + +#include + +#include "geodex/manifold/sphere.hpp" + +#include "dynamic_manifold.hpp" + +namespace geodex::python { + +/// @brief Python wrapper for the n-dimensional sphere \f$ S^n \f$. +/// +/// @details Wraps `Sphere` — points are `VectorXd` of size +/// `n+1`. The dimension `n` is set at construction time. +class PySphereN { + public: + using SphereExp = Sphere, SphereExponentialMap>; + using SphereProj = + Sphere, SphereProjectionRetraction>; + using V = std::variant; + + PySphereN(int n, const std::string& retraction = "exponential") + : impl_(SphereExp(n)), dim_(n), retraction_name_(retraction) { + if (n < 1) { + throw std::invalid_argument("Sphere dimension must be >= 1, got " + std::to_string(n)); + } + if (retraction == "exponential") { + impl_.emplace(n); + } else if (retraction == "projection") { + impl_.emplace(n); + } else { + throw std::invalid_argument("Unknown retraction: '" + retraction + + "'. Options: 'exponential', 'projection'"); + } + } + + int dim() const { + return std::visit([](const auto& m) { return m.dim(); }, impl_); + } + + Eigen::VectorXd random_point() const { + return std::visit([](const auto& m) -> Eigen::VectorXd { return m.random_point(); }, impl_); + } + + Eigen::VectorXd project(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { + return std::visit([&](const auto& m) -> Eigen::VectorXd { return m.project(p, v); }, impl_); + } + + double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) const { + return std::visit([&](const auto& m) { return m.inner(p, u, v); }, impl_); + } + + double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { + return std::visit([&](const auto& m) { return m.norm(p, v); }, impl_); + } + + Eigen::VectorXd exp(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { + return std::visit([&](const auto& m) -> Eigen::VectorXd { return m.exp(p, v); }, impl_); + } + + Eigen::VectorXd log(const Eigen::VectorXd& p, const Eigen::VectorXd& q) const { + return std::visit([&](const auto& m) -> Eigen::VectorXd { return m.log(p, q); }, impl_); + } + + double distance(const Eigen::VectorXd& p, const Eigen::VectorXd& q) const { + return std::visit([&](const auto& m) { return m.distance(p, q); }, impl_); + } + + Eigen::VectorXd geodesic(const Eigen::VectorXd& p, const Eigen::VectorXd& q, double t) const { + return std::visit([&](const auto& m) -> Eigen::VectorXd { return m.geodesic(p, q, t); }, impl_); + } + + DynamicManifold to_dynamic_manifold() const { + auto shared = std::make_shared(impl_); + return DynamicManifold{ + [shared]() { return std::visit([](const auto& m) { return m.dim(); }, *shared); }, + [shared]() -> Eigen::VectorXd { + return std::visit([](const auto& m) -> Eigen::VectorXd { return m.random_point(); }, + *shared); + }, + [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) -> Eigen::VectorXd { + return std::visit([&](const auto& m) -> Eigen::VectorXd { return m.exp(p, v); }, *shared); + }, + [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& q) -> Eigen::VectorXd { + return std::visit([&](const auto& m) -> Eigen::VectorXd { return m.log(p, q); }, *shared); + }, + [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, + const Eigen::VectorXd& v) -> double { + return std::visit([&](const auto& m) { return m.inner(p, u, v); }, *shared); + }, + [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) -> double { + return std::visit([&](const auto& m) { return m.norm(p, v); }, *shared); + }, + [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) -> Eigen::VectorXd { + return std::visit([&](const auto& m) -> Eigen::VectorXd { return m.project(p, v); }, + *shared); + }}; + } + + std::string repr() const { + return "Sphere(dim=" + std::to_string(dim_) + ", retraction='" + retraction_name_ + "')"; + } + + private: + V impl_; + int dim_; + std::string retraction_name_; +}; + +} // namespace geodex::python diff --git a/python/src/wrappers/py_torus.hpp b/python/src/wrappers/py_torus.hpp index 239b7c6..7c1cc2e 100644 --- a/python/src/wrappers/py_torus.hpp +++ b/python/src/wrappers/py_torus.hpp @@ -3,11 +3,13 @@ #pragma once -#include -#include #include #include +#include + +#include "geodex/manifold/torus.hpp" + #include "dynamic_manifold.hpp" namespace geodex::python { @@ -22,14 +24,11 @@ class PyTorus { Eigen::VectorXd random_point() const { return impl_.random_point(); } - double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) const { + double inner(const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) const { return impl_.inner(p, u, v); } - double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { - return impl_.norm(p, v); - } + double norm(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { return impl_.norm(p, v); } Eigen::VectorXd exp(const Eigen::VectorXd& p, const Eigen::VectorXd& v) const { return impl_.exp(p, v); @@ -43,8 +42,7 @@ class PyTorus { return impl_.distance(p, q); } - Eigen::VectorXd geodesic(const Eigen::VectorXd& p, const Eigen::VectorXd& q, - double t) const { + Eigen::VectorXd geodesic(const Eigen::VectorXd& p, const Eigen::VectorXd& q, double t) const { return impl_.geodesic(p, q, t); } @@ -59,18 +57,15 @@ class PyTorus { [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& q) -> Eigen::VectorXd { return shared->log(p, q); }, - [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, - const Eigen::VectorXd& v) { return shared->inner(p, u, v); }, - [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { - return shared->norm(p, v); + [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& u, const Eigen::VectorXd& v) { + return shared->inner(p, u, v); }, + [shared](const Eigen::VectorXd& p, const Eigen::VectorXd& v) { return shared->norm(p, v); }, // Torus tangent space = ambient R^n (angle parameterization); projection is identity. [](const Eigen::VectorXd& /*p*/, const Eigen::VectorXd& v) { return v; }}; } - std::string repr() const { - return "Torus(dim=" + std::to_string(impl_.dim()) + ")"; - } + std::string repr() const { return "Torus(dim=" + std::to_string(impl_.dim()) + ")"; } private: Impl impl_; diff --git a/python/tests/test_algorithms.py b/python/tests/test_algorithms.py index 568b021..e0141ea 100644 --- a/python/tests/test_algorithms.py +++ b/python/tests/test_algorithms.py @@ -1,4 +1,5 @@ -"""Tests for algorithm bindings: distance_midpoint.""" +"""Tests for M5 algorithm bindings: InterpolationSettings, distance_midpoint, +discrete_geodesic, EuclideanHeuristic.""" import numpy as np import pytest @@ -6,6 +7,88 @@ import geodex +# --------------------------------------------------------------------------- +# InterpolationSettings +# --------------------------------------------------------------------------- + + +class TestInterpolationSettings: + def test_default_values(self): + s = geodex.InterpolationSettings() + assert s.step_size == pytest.approx(0.5) + assert s.convergence_tol == pytest.approx(1e-4) + assert s.convergence_rel == pytest.approx(1e-3) + assert s.max_steps == 100 + assert s.fd_epsilon == pytest.approx(0.0) + assert s.distortion_ratio == pytest.approx(1.5) + assert s.growth_factor == pytest.approx(1.5) + assert s.force_log_direction is False + assert s.fd_midpoint_guard_tau == pytest.approx(0.25) + + def test_keyword_construction(self): + s = geodex.InterpolationSettings(step_size=0.1, max_steps=50) + assert s.step_size == pytest.approx(0.1) + assert s.max_steps == 50 + # Other fields keep defaults + assert s.convergence_tol == pytest.approx(1e-4) + + def test_new_fields_keyword_construction(self): + s = geodex.InterpolationSettings(force_log_direction=True, fd_midpoint_guard_tau=0.1) + assert s.force_log_direction is True + assert s.fd_midpoint_guard_tau == pytest.approx(0.1) + # Unrelated fields keep defaults + assert s.step_size == pytest.approx(0.5) + + def test_field_mutation(self): + s = geodex.InterpolationSettings() + s.step_size = 0.25 + s.max_steps = 200 + s.force_log_direction = True + s.fd_midpoint_guard_tau = 0.05 + assert s.step_size == pytest.approx(0.25) + assert s.max_steps == 200 + assert s.force_log_direction is True + assert s.fd_midpoint_guard_tau == pytest.approx(0.05) + + def test_repr(self): + s = geodex.InterpolationSettings() + r = repr(s) + assert "InterpolationSettings" in r + assert "step_size" in r + + +# --------------------------------------------------------------------------- +# EuclideanHeuristic +# --------------------------------------------------------------------------- + + +class TestEuclideanHeuristic: + def test_zero_distance(self): + h = geodex.EuclideanHeuristic() + a = np.array([1.0, 2.0, 3.0]) + assert h(a, a) == pytest.approx(0.0) + + def test_known_distance(self): + h = geodex.EuclideanHeuristic() + a = np.zeros(3) + b = np.array([3.0, 4.0, 0.0]) + assert h(a, b) == pytest.approx(5.0) + + def test_symmetry(self): + h = geodex.EuclideanHeuristic() + a = np.array([1.0, 2.0]) + b = np.array([4.0, 6.0]) + assert h(a, b) == pytest.approx(h(b, a)) + + def test_agrees_with_numpy(self): + h = geodex.EuclideanHeuristic() + rng = np.random.default_rng(42) + for _ in range(10): + a = rng.standard_normal(5) + b = rng.standard_normal(5) + assert h(a, b) == pytest.approx(np.linalg.norm(a - b)) + + # --------------------------------------------------------------------------- # distance_midpoint # --------------------------------------------------------------------------- @@ -104,3 +187,297 @@ def test_with_config_space(self): def test_invalid_manifold_raises(self): with pytest.raises(Exception): geodex.distance_midpoint("not_a_manifold", np.zeros(3), np.ones(3)) + + +# --------------------------------------------------------------------------- +# discrete_geodesic +# --------------------------------------------------------------------------- + + +class TestDiscreteGeodesicSphere: + def setup_method(self): + self.sphere = geodex.Sphere() + self.settings = geodex.InterpolationSettings(step_size=0.3, max_steps=200) + + def test_returns_result_with_list_of_arrays(self): + p = np.array([0.0, 0.0, 1.0]) + q = np.array([0.0, 1.0, 0.0]) + r = geodex.discrete_geodesic(self.sphere, p, q, self.settings) + assert isinstance(r, geodex.InterpolationResult) + assert isinstance(r.path, list) + assert len(r.path) >= 2 + assert all(isinstance(pt, np.ndarray) for pt in r.path) + + def test_first_point_is_start(self): + p = np.array([0.0, 0.0, 1.0]) + q = np.array([0.0, 1.0, 0.0]) + r = geodex.discrete_geodesic(self.sphere, p, q, self.settings) + np.testing.assert_allclose(r.path[0], p, atol=1e-12) + + def test_last_point_near_goal(self): + p = np.array([0.0, 0.0, 1.0]) + q = np.array([0.0, 1.0, 0.0]) + r = geodex.discrete_geodesic(self.sphere, p, q, self.settings) + # Final point should be close to goal + d_end = self.sphere.distance(r.path[-1], q) + assert d_end < 0.1 + assert r.status == geodex.InterpolationStatus.Converged + + def test_all_points_on_sphere(self): + p = np.array([1.0, 0.0, 0.0]) + q = np.array([0.0, 0.0, 1.0]) + r = geodex.discrete_geodesic(self.sphere, p, q, self.settings) + for pt in r.path: + assert abs(np.linalg.norm(pt) - 1.0) < 1e-8 + + def test_start_equals_goal_returns_single_point(self): + p = np.array([0.0, 0.0, 1.0]) + r = geodex.discrete_geodesic(self.sphere, p, p, self.settings) + assert len(r.path) == 1 + assert r.status == geodex.InterpolationStatus.DegenerateInput + np.testing.assert_allclose(r.path[0], p, atol=1e-12) + + def test_default_settings(self): + p = np.array([0.0, 0.0, 1.0]) + q = np.array([0.0, 1.0, 0.0]) + # Should work without explicit settings + r = geodex.discrete_geodesic(self.sphere, p, q) + assert len(r.path) >= 2 + + def test_projection_retraction(self): + sphere_proj = geodex.Sphere(retraction="projection") + p = np.array([1.0, 0.0, 0.0]) + q = np.array([0.0, 0.0, 1.0]) + r = geodex.discrete_geodesic(sphere_proj, p, q, self.settings) + assert len(r.path) >= 2 + np.testing.assert_allclose(r.path[0], p, atol=1e-12) + + +class TestDiscreteGeodesicEuclidean: + def setup_method(self): + self.euc = geodex.Euclidean(3) + self.settings = geodex.InterpolationSettings(step_size=0.3, max_steps=200) + + def test_reaches_goal(self): + p = np.zeros(3) + q = np.array([1.0, 0.0, 0.0]) + r = geodex.discrete_geodesic(self.euc, p, q, self.settings) + assert len(r.path) >= 2 + np.testing.assert_allclose(r.path[0], p, atol=1e-12) + np.testing.assert_allclose(r.path[-1], q, atol=0.05) + + def test_path_is_approximately_straight(self): + """Points on a Euclidean path should lie close to the straight line.""" + p = np.zeros(3) + q = np.array([2.0, 0.0, 0.0]) + r = geodex.discrete_geodesic(self.euc, p, q, self.settings) + for pt in r.path: + # y and z components should stay near 0 + assert abs(pt[1]) < 0.05 + assert abs(pt[2]) < 0.05 + + +class TestDiscreteGeodesicTorus: + def setup_method(self): + self.torus = geodex.Torus(2) + self.settings = geodex.InterpolationSettings(step_size=0.3, max_steps=300) + + def test_first_point_is_start(self): + p = np.array([0.5, 0.5]) + q = np.array([2.0, 2.0]) + r = geodex.discrete_geodesic(self.torus, p, q, self.settings) + assert len(r.path) >= 1 + np.testing.assert_allclose(r.path[0], p, atol=1e-12) + + def test_path_length_positive(self): + p = np.array([0.5, 0.5]) + q = np.array([2.0, 2.0]) + r = geodex.discrete_geodesic(self.torus, p, q, self.settings) + assert len(r.path) >= 2 + + +class TestDiscreteGeodesicSE2: + def setup_method(self): + self.se2 = geodex.SE2(wx=1.0, wy=1.0, wtheta=0.5, x_lo=0.0, x_hi=5.0, + y_lo=0.0, y_hi=5.0) + self.settings = geodex.InterpolationSettings(step_size=0.3, max_steps=300) + + def test_first_point_is_start(self): + p = np.array([1.0, 1.0, 0.0]) + q = np.array([3.0, 3.0, 0.5]) + r = geodex.discrete_geodesic(self.se2, p, q, self.settings) + assert len(r.path) >= 1 + np.testing.assert_allclose(r.path[0], p, atol=1e-12) + + def test_returns_list(self): + p = np.array([1.0, 1.0, 0.0]) + q = np.array([2.0, 2.0, 0.0]) + r = geodex.discrete_geodesic(self.se2, p, q, self.settings) + assert isinstance(r.path, list) + assert len(r.path) >= 2 + + +class TestDiscreteGeodesicConfigSpace: + def setup_method(self): + self.sphere = geodex.Sphere() + metric = geodex.ConstantSPDMetric(np.eye(3)) + self.cs = geodex.ConfigurationSpace(self.sphere, metric) + self.settings = geodex.InterpolationSettings(step_size=0.3, max_steps=200) + + def test_first_point_is_start(self): + p = np.array([0.0, 0.0, 1.0]) + q = np.array([0.0, 1.0, 0.0]) + r = geodex.discrete_geodesic(self.cs, p, q, self.settings) + assert len(r.path) >= 1 + np.testing.assert_allclose(r.path[0], p, atol=1e-12) + + def test_all_points_on_sphere(self): + p = np.array([1.0, 0.0, 0.0]) + q = np.array([0.0, 0.0, 1.0]) + r = geodex.discrete_geodesic(self.cs, p, q, self.settings) + for pt in r.path: + assert abs(np.linalg.norm(pt) - 1.0) < 1e-8 + + def test_torus_with_kinetic_metric(self): + torus = geodex.Torus(2) + metric = geodex.KineticEnergyMetric(lambda q: np.eye(2)) + cs = geodex.ConfigurationSpace(torus, metric) + p = np.array([0.5, 0.5]) + q = np.array([2.0, 2.0]) + settings = geodex.InterpolationSettings(step_size=0.3, max_steps=300) + r = geodex.discrete_geodesic(cs, p, q, settings) + assert len(r.path) >= 1 + np.testing.assert_allclose(r.path[0], p, atol=1e-12) + + +class TestDiscreteGeodesicInvalidInput: + def test_invalid_manifold_raises(self): + with pytest.raises(Exception): + geodex.discrete_geodesic("not_a_manifold", np.zeros(3), np.ones(3)) + + +# --------------------------------------------------------------------------- +# Status reporting +# --------------------------------------------------------------------------- + + +class TestInterpolationStatus: + def setup_method(self): + self.sphere = geodex.Sphere() + + def test_converged_status(self): + p = np.array([0.0, 0.0, 1.0]) + q = np.array([np.sin(1.0), 0.0, np.cos(1.0)]) + r = geodex.discrete_geodesic(self.sphere, p, q) + assert r.status == geodex.InterpolationStatus.Converged + assert r.iterations > 0 + assert r.initial_distance > 0.5 + assert r.final_distance < 1e-3 + assert r.distortion_halvings == 0 + + def test_max_steps_status(self): + # Target far away with a tight iteration budget. + p = np.array([0.0, 0.0, 1.0]) + q = np.array([np.sin(2.5), 0.0, np.cos(2.5)]) + settings = geodex.InterpolationSettings(step_size=0.1, max_steps=2) + r = geodex.discrete_geodesic(self.sphere, p, q, settings) + assert r.status == geodex.InterpolationStatus.MaxStepsReached + assert r.iterations == 2 + + def test_cut_locus_status(self): + # Antipodal points on the sphere — log collapses to zero. + p = np.array([0.0, 0.0, 1.0]) + q = np.array([0.0, 0.0, -1.0]) + r = geodex.discrete_geodesic(self.sphere, p, q) + assert r.status == geodex.InterpolationStatus.CutLocus + assert len(r.path) == 1 + + def test_degenerate_input_status(self): + p = np.array([0.0, 0.0, 1.0]) + r = geodex.discrete_geodesic(self.sphere, p, p) + assert r.status == geodex.InterpolationStatus.DegenerateInput + assert r.iterations == 0 + assert r.initial_distance == 0.0 + + def test_repr_includes_status(self): + p = np.array([0.0, 0.0, 1.0]) + q = np.array([np.sin(1.0), 0.0, np.cos(1.0)]) + r = geodex.discrete_geodesic(self.sphere, p, q) + text = repr(r) + assert "InterpolationResult" in text + assert "Converged" in text + + def test_final_distance_reported(self): + p = np.array([0.0, 0.0, 1.0]) + q = np.array([np.sin(1.0), 0.0, np.cos(1.0)]) + r = geodex.discrete_geodesic(self.sphere, p, q) + # Final distance should match distance from last path point to target. + expected = self.sphere.distance(r.path[-1], q) + assert r.final_distance == pytest.approx(expected, abs=1e-6) + + +# --------------------------------------------------------------------------- +# force_log_direction: skip the FD fallback even when the metric is non-Riemannian +# --------------------------------------------------------------------------- + + +class TestForceLogDirection: + """``force_log_direction = True`` makes the walk always use -log as its + descent direction. Under a non-identity SPD metric attached to the sphere + (where ``is_riemannian_log`` is false), this changes the walk from the FD + path to the fast path.""" + + def setup_method(self): + self.sphere = geodex.Sphere() + self.metric = geodex.ConstantSPDMetric(np.diag([4.0, 1.0, 1.0])) + self.cs = geodex.ConfigurationSpace(self.sphere, self.metric) + self.p = np.array([0.0, 0.0, 1.0]) + self.q = np.array([np.sin(1.0), 0.0, np.cos(1.0)]) + + def test_default_converges_via_fd(self): + settings = geodex.InterpolationSettings(step_size=0.1, max_steps=500) + r = geodex.discrete_geodesic(self.cs, self.p, self.q, settings) + assert r.status == geodex.InterpolationStatus.Converged + assert r.fd_midpoint_fallbacks >= 0 # field readable, value meaningful + + def test_force_log_skips_fd(self): + """With force_log_direction=True the FD path never runs, so the + midpoint fallback counter stays at zero.""" + settings = geodex.InterpolationSettings( + step_size=0.1, max_steps=500, force_log_direction=True + ) + r = geodex.discrete_geodesic(self.cs, self.p, self.q, settings) + assert r.status == geodex.InterpolationStatus.Converged + assert r.fd_midpoint_fallbacks == 0 + + +# --------------------------------------------------------------------------- +# fd_midpoint_guard_tau + InterpolationResult.fd_midpoint_fallbacks +# --------------------------------------------------------------------------- + + +class TestFdMidpointGuard: + def test_fallbacks_zero_on_clean_sphere_geodesic(self): + """Clean round sphere uses the fast path; FD never runs.""" + sphere = geodex.Sphere() + p = np.array([0.0, 0.0, 1.0]) + q = np.array([np.sin(1.0), 0.0, np.cos(1.0)]) + r = geodex.discrete_geodesic(sphere, p, q) + assert isinstance(r.fd_midpoint_fallbacks, int) + assert r.fd_midpoint_fallbacks == 0 + + def test_guard_tau_zero_forces_via_log_samples(self): + """``fd_midpoint_guard_tau = 0`` rejects every midpoint sample, so + every FD basis direction falls back to |log|_R and the counter + increments throughout the walk.""" + sphere = geodex.Sphere() + metric = geodex.ConstantSPDMetric(np.diag([4.0, 1.0, 1.0])) + cs = geodex.ConfigurationSpace(sphere, metric) + p = np.array([0.0, 0.0, 1.0]) + q = np.array([np.sin(1.0), 0.0, np.cos(1.0)]) + settings = geodex.InterpolationSettings( + step_size=0.1, max_steps=500, fd_midpoint_guard_tau=0.0 + ) + r = geodex.discrete_geodesic(cs, p, q, settings) + assert r.status == geodex.InterpolationStatus.Converged + assert r.fd_midpoint_fallbacks > 0 diff --git a/python/tests/test_clearance_metric.py b/python/tests/test_clearance_metric.py new file mode 100644 index 0000000..96489ef --- /dev/null +++ b/python/tests/test_clearance_metric.py @@ -0,0 +1,38 @@ +"""Tests for geodex.ClearanceMetric.""" + +import numpy as np +import pytest + +import geodex + + +class TestClearanceMetric: + def test_far_from_obstacle(self): + """Far from obstacle, conformal factor -> 1, inner product ~ base.""" + base = geodex.ConstantSPDMetric(np.eye(2)) + sdf = lambda q: 100.0 # very far from any obstacle + metric = geodex.ClearanceMetric(base, sdf, kappa=5.0, beta=3.0) + p = np.array([0.0, 0.0]) + u = np.array([1.0, 0.0]) + v = np.array([1.0, 0.0]) + base_val = base.inner(p, u, v) + clearance_val = metric.inner(p, u, v) + # c(q) = 1 + 5*exp(-3*100) ~ 1.0 + assert clearance_val == pytest.approx(base_val, rel=1e-6) + + def test_near_obstacle(self): + """Near obstacle, conformal factor > 1, inner product increases.""" + base = geodex.ConstantSPDMetric(np.eye(2)) + sdf = lambda q: 0.1 # close to obstacle surface + metric = geodex.ClearanceMetric(base, sdf, kappa=5.0, beta=3.0) + p = np.array([0.0, 0.0]) + u = np.array([1.0, 0.0]) + base_val = base.inner(p, u, u) + clearance_val = metric.inner(p, u, u) + assert clearance_val > base_val * 1.5 # should be noticeably scaled up + + def test_properties(self): + base = geodex.ConstantSPDMetric(np.eye(2)) + metric = geodex.ClearanceMetric(base, lambda q: 1.0, kappa=7.0, beta=2.0) + assert metric.kappa == pytest.approx(7.0) + assert metric.beta == pytest.approx(2.0) diff --git a/python/tests/test_collision.py b/python/tests/test_collision.py new file mode 100644 index 0000000..60dc54a --- /dev/null +++ b/python/tests/test_collision.py @@ -0,0 +1,50 @@ +"""Tests for geodex.collision module.""" + +import numpy as np +import pytest + +import geodex + + +class TestCircleSDF: + def test_outside(self): + sdf = geodex.collision.CircleSDF(0.0, 0.0, 1.0) + assert sdf(2.0, 0.0) == pytest.approx(1.0, abs=1e-10) + + def test_inside(self): + sdf = geodex.collision.CircleSDF(0.0, 0.0, 1.0) + assert sdf(0.0, 0.0) == pytest.approx(-1.0, abs=1e-10) + + def test_on_boundary(self): + sdf = geodex.collision.CircleSDF(0.0, 0.0, 1.0) + assert sdf(1.0, 0.0) == pytest.approx(0.0, abs=1e-10) + + def test_properties(self): + sdf = geodex.collision.CircleSDF(1.0, 2.0, 3.0) + assert sdf.cx == pytest.approx(1.0) + assert sdf.cy == pytest.approx(2.0) + assert sdf.radius == pytest.approx(3.0) + + +class TestCircleSmoothSDF: + def test_smooth_distance(self): + c1 = geodex.collision.CircleSDF(0.0, 0.0, 1.0) + c2 = geodex.collision.CircleSDF(5.0, 0.0, 1.0) + smooth = geodex.collision.CircleSmoothSDF([c1, c2], beta=20.0) + # Far from both -> positive + assert smooth(2.5, 5.0) > 0.0 + + def test_is_free(self): + c1 = geodex.collision.CircleSDF(0.0, 0.0, 1.0) + c2 = geodex.collision.CircleSDF(5.0, 0.0, 1.0) + smooth = geodex.collision.CircleSmoothSDF([c1, c2]) + assert smooth.is_free(2.5, 0.0) + assert not smooth.is_free(0.0, 0.0) + + +class TestPolygonFootprint: + def test_rectangle(self): + fp = geodex.collision.PolygonFootprint.rectangle(1.0, 0.5, 8) + assert fp.sample_count() == 32 # 4 edges * 8 samples + assert fp.bounding_radius() > 0.0 + assert fp.bounding_radius() == pytest.approx(np.sqrt(1.0 + 0.25), abs=0.1) diff --git a/python/tests/test_path_smoothing.py b/python/tests/test_path_smoothing.py new file mode 100644 index 0000000..b838e7e --- /dev/null +++ b/python/tests/test_path_smoothing.py @@ -0,0 +1,50 @@ +"""Tests for geodex.smooth_path and related types.""" + +import numpy as np +import pytest + +import geodex + + +class TestPathSmoothingSettings: + def test_defaults(self): + s = geodex.PathSmoothingSettings() + assert s.max_shortcut_attempts == 200 + assert s.lbfgs_max_iterations == 200 + assert s.armijo_max_backtracks == 30 + assert s.grad_tol == pytest.approx(1e-8) + + def test_set_fields(self): + s = geodex.PathSmoothingSettings() + s.max_shortcut_attempts = 100 + assert s.max_shortcut_attempts == 100 + + +class TestSmoothPath: + def test_euclidean_detour(self): + """Smooth a path with a detour in Euclidean space.""" + manifold = geodex.Euclidean(2) + # Path: (0,0) -> (1,2) -> (2,0) -- detour through (1,2) + path = [np.array([0.0, 0.0]), np.array([1.0, 2.0]), np.array([2.0, 0.0])] + validity_fn = lambda q: True # no obstacles + settings = geodex.PathSmoothingSettings() + settings.max_shortcut_attempts = 50 + settings.lbfgs_max_iterations = 50 + result = geodex.smooth_path(manifold, validity_fn, path, settings) + assert isinstance(result, geodex.PathSmoothingResult) + assert len(result.path) >= 2 + assert result.energy >= 0.0 + assert result.distance >= 0.0 + + def test_straight_path_unchanged(self): + """A straight path should have minimal smoothing effect.""" + manifold = geodex.Euclidean(2) + path = [np.array([0.0, 0.0]), np.array([1.0, 0.0]), np.array([2.0, 0.0])] + validity_fn = lambda q: True + settings = geodex.PathSmoothingSettings() + settings.max_shortcut_attempts = 10 + settings.lbfgs_max_iterations = 10 + result = geodex.smooth_path(manifold, validity_fn, path, settings) + # Should still be roughly along x-axis + for pt in result.path: + assert abs(pt[1]) < 0.5 # y-coordinate stays small diff --git a/scripts/animate_se2_tutorial.py b/scripts/animate_se2_tutorial.py new file mode 100644 index 0000000..57cf75f --- /dev/null +++ b/scripts/animate_se2_tutorial.py @@ -0,0 +1,178 @@ +#!/usr/bin/env python3 +"""Animate robot footprint sweeping along a planned SE(2) path. + +Reads JSON output from se2_tutorial and produces a GIF animation showing the +robot footprint translating and rotating along the smoothed path with a +fading trail of previous footprints. + +Usage: + python scripts/animate_se2_tutorial.py result.json -o sweep.gif --fps 15 + python scripts/animate_se2_tutorial.py result.json -o sweep.gif --map corridor.png +""" + +import argparse +import json +import os + +import matplotlib.patches as mpatches +import matplotlib.pyplot as plt +import numpy as np +from matplotlib.animation import FuncAnimation, PillowWriter + +# geodex docs style. +plt.rcParams.update( + { + "font.family": "sans-serif", + "font.sans-serif": ["Lato", "Helvetica", "Arial", "DejaVu Sans"], + "font.size": 12, + "mathtext.fontset": "stixsans", + } +) + + +def draw_rect(ax, cx, cy, theta, hl, hw, **kwargs): + ct, st = np.cos(theta), np.sin(theta) + corners = [] + for sx, sy in [(-1, -1), (1, -1), (1, 1), (-1, 1)]: + lx, ly = sx * hl, sy * hw + corners.append((cx + ct * lx - st * ly, cy + st * lx + ct * ly)) + return ax.add_patch(mpatches.Polygon(corners, closed=True, **kwargs)) + + +def load_map_png(map_path, data): + from PIL import Image + + candidates = [] + if map_path: + candidates.append(map_path) + map_info = data.get("map") + if map_info and map_info.get("file"): + base = os.path.splitext(os.path.basename(map_info["file"]))[0].replace("_dist", "") + candidates.append(os.path.join(os.path.dirname(map_info["file"]), base + ".png")) + for path in candidates: + if os.path.isfile(path): + return np.array(Image.open(path).convert("L")) + return None + + +def get_extent(data, map_img): + map_info = data.get("map") + if map_info: + w = map_info["width"] * map_info["resolution"] + h = map_info["height"] * map_info["resolution"] + return [0, w, 0, h] + rects = data.get("rect_obstacles", []) + if rects: + all_x = [o["center"][0] for o in rects] + [data["start"][0], data["goal"][0]] + all_y = [o["center"][1] for o in rects] + [data["start"][1], data["goal"][1]] + margin = 3.0 + return [min(all_x) - margin, max(all_x) + margin, + min(all_y) - margin, max(all_y) + margin] + return [0, 15, 0, 10] + + +def main(): + parser = argparse.ArgumentParser(description="Animate SE(2) footprint sweep") + parser.add_argument("input", help="JSON from se2_tutorial") + parser.add_argument("-o", "--output", default="se2_sweep.gif", help="Output GIF") + parser.add_argument("--map", default=None, help="Map PNG for background") + parser.add_argument("--fps", type=int, default=15, help="Frames per second") + parser.add_argument("--trail", type=int, default=8, help="Number of ghost trail footprints") + args = parser.parse_args() + + with open(args.input) as f: + data = json.load(f) + + map_img = load_map_png(args.map, data) + extent = get_extent(data, map_img) + robot = data.get("robot", {}) + start, goal = data["start"], data["goal"] + + # Use smoothed path from first run. + run = data["runs"][0] + path = np.array(run.get("smoothed_path", run.get("raw_path", []))) + if len(path) == 0: + print("Error: no path data in JSON") + return + + # Subsample path to ~40 frames for reasonable GIF size. + n_frames = min(40, len(path)) + indices = np.linspace(0, len(path) - 1, n_frames, dtype=int) + frames = path[indices] + + # Determine figure size from extent aspect ratio. + aspect = (extent[1] - extent[0]) / (extent[3] - extent[2]) + fig_h = 6 + fig_w = max(6, fig_h * aspect) + fig, ax = plt.subplots(figsize=(fig_w, fig_h)) + + def animate(frame_idx): + ax.clear() + + # Background. + if map_img is not None: + ax.imshow(map_img, cmap="gray", extent=extent, origin="lower", alpha=0.7, zorder=0) + for obs in data.get("rect_obstacles", []): + cx, cy = obs["center"] + theta = obs.get("theta", 0.0) + hl, hw = obs["half_length"], obs["half_width"] + draw_rect(ax, cx, cy, theta, hl, hw, + fc="salmon", alpha=0.6, ec="darkred", lw=1.5, zorder=0) + + # Full path line. + ax.plot(path[:, 0], path[:, 1], color="royalblue", lw=1.5, alpha=0.4, zorder=1) + + # Ghost trail. + trail_start = max(0, frame_idx - args.trail) + for t in range(trail_start, frame_idx): + alpha = 0.05 + 0.15 * (t - trail_start) / max(1, frame_idx - trail_start) + px, py, pth = frames[t] + if robot.get("type") == "circle": + ax.add_patch(mpatches.Circle( + (px, py), robot["radius"], fc="royalblue", alpha=alpha, + ec="navy", lw=0.3, zorder=2)) + elif robot.get("type") == "rectangle": + draw_rect(ax, px, py, pth, robot["half_length"], robot["half_width"], + fc="royalblue", alpha=alpha, ec="navy", lw=0.3, zorder=2) + + # Current footprint (solid). + px, py, pth = frames[frame_idx] + if robot.get("type") == "circle": + ax.add_patch(mpatches.Circle( + (px, py), robot["radius"], fc="royalblue", alpha=0.7, + ec="navy", lw=2, zorder=5)) + elif robot.get("type") == "rectangle": + draw_rect(ax, px, py, pth, robot["half_length"], robot["half_width"], + fc="royalblue", alpha=0.7, ec="navy", lw=2, zorder=5) + + # Heading arrow on current robot. + arrow_len = 0.8 if robot.get("type") == "rectangle" else 0.5 + dx = arrow_len * np.cos(pth) + dy = arrow_len * np.sin(pth) + ax.annotate( + "", xy=(px + dx, py + dy), xytext=(px, py), + arrowprops=dict(arrowstyle="-|>", color="white", lw=2.5), zorder=6, + ) + + # Start / goal. + ax.plot(start[0], start[1], "o", color="limegreen", ms=10, zorder=7, + mec="darkgreen", mew=1.5) + ax.plot(goal[0], goal[1], "*", color="orange", ms=14, zorder=7, + mec="darkorange", mew=1.5) + + ax.set_title(f"{run['label']} (frame {frame_idx + 1}/{n_frames})", fontsize=12) + ax.set_xlim(extent[0], extent[1]) + ax.set_ylim(extent[2], extent[3]) + ax.set_aspect("equal") + ax.grid(True, alpha=0.2) + ax.set_xlabel("x (m)") + ax.set_ylabel("y (m)") + + anim = FuncAnimation(fig, animate, frames=n_frames, interval=1000 // args.fps, repeat=True) + anim.save(args.output, writer=PillowWriter(fps=args.fps)) + print(f"Saved {args.output} ({n_frames} frames, {args.fps} fps)") + plt.close() + + +if __name__ == "__main__": + main() diff --git a/scripts/crop_and_preprocess.py b/scripts/crop_and_preprocess.py new file mode 100644 index 0000000..6fdb3bd --- /dev/null +++ b/scripts/crop_and_preprocess.py @@ -0,0 +1,84 @@ +#!/usr/bin/env python3 +"""Crop an occupancy grid PNG and produce a distance transform text file. + +Reads a grayscale PNG, optionally crops to a pixel rectangle, computes the +Euclidean distance transform, scales by resolution, and writes a text file +usable by the C++ planner. Also saves the cropped PNG alongside the output +for use as a visualization background. + +Usage: + python scripts/crop_and_preprocess.py input.png -o output_dist.txt \\ + --crop 460,340,760,540 --resolution 0.05 +""" + +import argparse +import os + +import numpy as np +from PIL import Image +from scipy.ndimage import distance_transform_edt + + +def main(): + parser = argparse.ArgumentParser( + description="Crop occupancy PNG and produce distance transform txt" + ) + parser.add_argument("input", help="Input PNG (grayscale occupancy grid)") + parser.add_argument("-o", "--output", required=True, help="Output distance grid txt file") + parser.add_argument( + "--crop", + default=None, + help="Pixel crop rectangle: x1,y1,x2,y2 (column-start,row-start,column-end,row-end)", + ) + parser.add_argument( + "--resolution", + type=float, + default=0.05, + help="Map resolution in m/pixel (default: 0.05)", + ) + args = parser.parse_args() + + img = Image.open(args.input).convert("L") + pixels = np.array(img) + + if args.crop: + parts = [int(x) for x in args.crop.split(",")] + if len(parts) != 4: + parser.error("--crop requires exactly 4 values: x1,y1,x2,y2") + x1, y1, x2, y2 = parts + pixels = pixels[y1:y2, x1:x2] + print(f"Cropped to pixel rect ({x1},{y1})–({x2},{y2}): {x2-x1}×{y2-y1} px") + + # Save cropped PNG alongside output for visualization. + out_dir = os.path.dirname(os.path.abspath(args.output)) + out_base = os.path.splitext(os.path.basename(args.output))[0] + cropped_png = os.path.join(out_dir, out_base.replace("_dist", "") + ".png") + Image.fromarray(pixels).save(cropped_png) + print(f"Saved cropped PNG: {cropped_png}") + + # Binary: occupied where pixel < 128 + occupied = pixels < 128 + free = ~occupied + + # Euclidean distance transform (in pixels), then scale to meters. + # Interior of obstacles gets negative distance. + dist_free = distance_transform_edt(free) * args.resolution + dist_occ = distance_transform_edt(occupied) * args.resolution + dist_meters = dist_free - dist_occ + + height, width = dist_meters.shape + world_w = width * args.resolution + world_h = height * args.resolution + print(f"Map: {width}×{height} px, resolution={args.resolution} m/px") + print(f"World size: {world_w:.1f} × {world_h:.1f} m") + + with open(args.output, "w") as f: + f.write(f"{width} {height} {args.resolution}\n") + for row in dist_meters: + f.write(" ".join(f"{v:.4f}" for v in row) + "\n") + + print(f"Wrote distance grid: {args.output}") + + +if __name__ == "__main__": + main() diff --git a/scripts/draw_se2_diagrams.py b/scripts/draw_se2_diagrams.py new file mode 100644 index 0000000..6078d41 --- /dev/null +++ b/scripts/draw_se2_diagrams.py @@ -0,0 +1,330 @@ +#!/usr/bin/env python3 +"""Generate concept diagrams for the SE(2) motion planning tutorial. + +Produces three SVG figures (pure matplotlib, no C++ data needed): + 1. se2_poses_and_footprints.svg — Three robot types with coordinate axes and footprints + 2. se2_inflation.svg — Inflation of obstacle boundary by robot radius + 3. se2_footprint_checking.svg — Polygon perimeter sampling in body and world frame + +Usage: + python scripts/draw_se2_diagrams.py --output-dir docs/tutorials/figs/ +""" + +import argparse +import os + +import matplotlib.patches as mpatches +import matplotlib.pyplot as plt +import numpy as np + +# geodex docs style: Lato font, stixsans math, large figures. +plt.rcParams.update( + { + "font.family": "sans-serif", + "font.sans-serif": ["Lato", "Helvetica", "Arial", "DejaVu Sans"], + "font.size": 14, + "mathtext.fontset": "stixsans", + "axes.linewidth": 1.2, + } +) + + +def draw_pose_arrow(ax, x, y, theta, length=0.6, color="black", lw=2.0, head_width=0.08): + """Draw a heading arrow at (x, y) pointing in direction theta.""" + dx = length * np.cos(theta) + dy = length * np.sin(theta) + ax.arrow( + x, y, dx, dy, head_width=head_width, head_length=head_width * 0.7, + fc=color, ec=color, lw=lw, zorder=5, + ) + + +def draw_axes(ax, x, y, theta, length=0.5, lw=1.5): + """Draw x (red) and y (green) body-frame axes at a pose.""" + ct, st = np.cos(theta), np.sin(theta) + # x-axis (body forward) + ax.arrow(x, y, length * ct, length * st, head_width=0.06, head_length=0.04, + fc="tab:red", ec="tab:red", lw=lw, zorder=4) + ax.text(x + (length + 0.12) * ct, y + (length + 0.12) * st, r"$x$", + color="tab:red", fontsize=12, ha="center", va="center", zorder=6) + # y-axis (body left) + ax.arrow(x, y, -length * st, length * ct, head_width=0.06, head_length=0.04, + fc="tab:green", ec="tab:green", lw=lw, zorder=4) + ax.text(x - (length + 0.12) * st, y + (length + 0.12) * ct, r"$y$", + color="tab:green", fontsize=12, ha="center", va="center", zorder=6) + + +def draw_circle_footprint(ax, x, y, radius, color="royalblue", alpha=0.15): + """Draw a circular robot footprint.""" + circle = mpatches.Circle((x, y), radius, fc=color, alpha=alpha, ec=color, lw=1.5, zorder=2) + ax.add_patch(circle) + + +def draw_rect_footprint(ax, x, y, theta, hl, hw, color="royalblue", alpha=0.15): + """Draw a rectangular robot footprint at pose (x, y, theta).""" + ct, st = np.cos(theta), np.sin(theta) + corners = [] + for sx, sy in [(-1, -1), (1, -1), (1, 1), (-1, 1)]: + lx, ly = sx * hl, sy * hw + corners.append((x + ct * lx - st * ly, y + st * lx + ct * ly)) + patch = mpatches.Polygon( + corners, closed=True, fc=color, alpha=alpha, ec=color, lw=1.5, zorder=2, + ) + ax.add_patch(patch) + return corners + + +# --------------------------------------------------------------------------- +# Figure 1: Three robot types with poses and footprints +# --------------------------------------------------------------------------- + +def draw_poses_and_footprints(output_dir): + fig, axes = plt.subplots(1, 3, figsize=(11, 4)) + + configs = [ + {"title": "Holonomic (circular)", "theta": np.pi / 6, + "footprint": "circle", "radius": 0.5}, + {"title": "Differential drive", "theta": np.pi / 4, + "footprint": "rect", "hl": 0.55, "hw": 0.35}, + {"title": "Car-like", "theta": -np.pi / 8, + "footprint": "rect", "hl": 0.7, "hw": 0.35}, + ] + + for ax, cfg in zip(axes, configs): + cx, cy = 1.5, 1.5 + theta = cfg["theta"] + + # Draw footprint. + if cfg["footprint"] == "circle": + draw_circle_footprint(ax, cx, cy, cfg["radius"]) + else: + draw_rect_footprint(ax, cx, cy, theta, cfg["hl"], cfg["hw"]) + + # Draw body-frame axes. + draw_axes(ax, cx, cy, theta, length=0.6) + + # Draw heading arrow. + draw_pose_arrow(ax, cx, cy, theta, length=0.8, color="navy") + + # Draw pose dot. + ax.plot(cx, cy, "o", color="navy", ms=6, zorder=6) + + # Theta arc. + arc_r = 0.35 + arc_angles = np.linspace(0, theta, 40) if theta >= 0 else np.linspace(theta, 0, 40) + ax.plot(cx + arc_r * np.cos(arc_angles), cy + arc_r * np.sin(arc_angles), + color="gray", lw=1.0, ls="--", zorder=3) + mid_angle = theta / 2 + ax.text(cx + (arc_r + 0.15) * np.cos(mid_angle), + cy + (arc_r + 0.15) * np.sin(mid_angle), + r"$\theta$", fontsize=13, color="gray", ha="center", va="center") + + # Pose label. + ax.text(cx, cy - 0.85, r"$(x, y, \theta)$", fontsize=13, ha="center", color="navy") + + ax.set_title(cfg["title"], fontsize=14, fontweight="bold") + ax.set_xlim(0.2, 2.8) + ax.set_ylim(0.2, 2.8) + ax.set_aspect("equal") + ax.axis("off") + + plt.tight_layout() + path = os.path.join(output_dir, "se2_poses_and_footprints.svg") + fig.savefig(path, bbox_inches="tight") + plt.close(fig) + print(f"Saved {path}") + + +# --------------------------------------------------------------------------- +# Figure 2: Inflation illustration +# --------------------------------------------------------------------------- + +def draw_inflation(output_dir): + fig, ax = plt.subplots(figsize=(9, 5)) + + # Obstacle (irregular polygon approximated by rectangle for clarity). + obs_x, obs_y = 4.0, 2.5 + obs_w, obs_h = 3.0, 1.8 + obstacle = mpatches.FancyBboxPatch( + (obs_x - obs_w / 2, obs_y - obs_h / 2), obs_w, obs_h, + boxstyle="round,pad=0.1", fc="salmon", ec="darkred", lw=2, alpha=0.7, zorder=2, + ) + ax.add_patch(obstacle) + ax.text(obs_x, obs_y, "Obstacle", ha="center", va="center", fontsize=13, + color="darkred", fontweight="bold", zorder=3) + + # Original boundary (solid). + # Draw a dashed inflated boundary. + robot_r = 0.5 + inflated = mpatches.FancyBboxPatch( + (obs_x - obs_w / 2 - robot_r, obs_y - obs_h / 2 - robot_r), + obs_w + 2 * robot_r, obs_h + 2 * robot_r, + boxstyle="round,pad=0.1", fc="none", ec="navy", lw=2, ls="--", zorder=2, + ) + ax.add_patch(inflated) + + # Robot at the inflated boundary (collision-free). + rx_safe = obs_x + obs_w / 2 + robot_r + 0.1 + ry_safe = obs_y + draw_circle_footprint(ax, rx_safe, ry_safe, robot_r, color="forestgreen", alpha=0.25) + ax.plot(rx_safe, ry_safe, "o", color="forestgreen", ms=5, zorder=6) + ax.annotate("Safe", xy=(rx_safe, ry_safe + robot_r + 0.15), + fontsize=12, color="forestgreen", ha="center", fontweight="bold") + + # Robot at the original boundary (collision). + rx_coll = obs_x + obs_w / 2 - 0.1 + ry_coll = obs_y + obs_h / 2 + 0.3 + draw_circle_footprint(ax, rx_coll, ry_coll, robot_r, color="tomato", alpha=0.25) + ax.plot(rx_coll, ry_coll, "o", color="tomato", ms=5, zorder=6) + ax.annotate("Collision", xy=(rx_coll, ry_coll + robot_r + 0.15), + fontsize=12, color="tomato", ha="center", fontweight="bold") + + # Dimension arrow for inflation radius. + arr_y = obs_y - obs_h / 2 - 0.7 + arr_x1 = obs_x + obs_w / 2 + arr_x2 = obs_x + obs_w / 2 + robot_r + ax.annotate("", xy=(arr_x2, arr_y), xytext=(arr_x1, arr_y), + arrowprops=dict(arrowstyle="<->", color="navy", lw=1.5)) + ax.text((arr_x1 + arr_x2) / 2, arr_y - 0.25, r"$r$", fontsize=14, ha="center", color="navy") + + # Legend labels. + ax.plot([], [], color="darkred", lw=2, label="Original boundary") + ax.plot([], [], color="navy", lw=2, ls="--", label="Inflated boundary") + ax.legend(loc="upper left", fontsize=11, framealpha=0.9) + + ax.set_xlim(0.5, 8.0) + ax.set_ylim(-0.2, 4.8) + ax.set_aspect("equal") + ax.axis("off") + ax.set_title("Inflating the obstacle boundary by robot radius", fontsize=14, fontweight="bold") + + plt.tight_layout() + path = os.path.join(output_dir, "se2_inflation.svg") + fig.savefig(path, bbox_inches="tight") + plt.close(fig) + print(f"Saved {path}") + + +# --------------------------------------------------------------------------- +# Figure 3: Footprint collision checking (body frame → world frame) +# --------------------------------------------------------------------------- + +def draw_footprint_checking(output_dir): + fig, axes = plt.subplots(1, 2, figsize=(11, 5)) + + hl, hw = 0.55, 0.35 + samples_per_edge = 4 + + # Generate perimeter samples (matching PolygonFootprint::rectangle). + body_samples = [] + corners = [(-hl, -hw), (hl, -hw), (hl, hw), (-hl, hw)] + for i in range(4): + c0 = corners[i] + c1 = corners[(i + 1) % 4] + for j in range(samples_per_edge): + t = j / samples_per_edge + bx = c0[0] + t * (c1[0] - c0[0]) + by = c0[1] + t * (c1[1] - c0[1]) + body_samples.append((bx, by)) + body_samples = np.array(body_samples) + + # --- Left: body frame --- + ax = axes[0] + # Draw rectangle outline. + rect = mpatches.FancyBboxPatch( + (-hl, -hw), 2 * hl, 2 * hw, + boxstyle="square,pad=0", fc="royalblue", alpha=0.1, ec="royalblue", lw=1.5, zorder=2, + ) + ax.add_patch(rect) + + # Draw samples. + ax.scatter(body_samples[:, 0], body_samples[:, 1], c="navy", s=30, zorder=5, + label="Perimeter samples") + + # Draw body axes. + ax.arrow(0, 0, 0.4, 0, head_width=0.04, head_length=0.03, fc="tab:red", ec="tab:red", lw=1.5) + ax.text(0.5, 0, r"$x_b$", color="tab:red", fontsize=12, va="center") + ax.arrow(0, 0, 0, 0.4, head_width=0.04, head_length=0.03, fc="tab:green", ec="tab:green", + lw=1.5) + ax.text(0.05, 0.48, r"$y_b$", color="tab:green", fontsize=12) + ax.plot(0, 0, "o", color="navy", ms=5, zorder=6) + + ax.set_title("Body frame", fontsize=14, fontweight="bold") + ax.set_xlim(-0.9, 0.9) + ax.set_ylim(-0.7, 0.7) + ax.set_aspect("equal") + ax.grid(True, alpha=0.3) + ax.legend(fontsize=10, loc="upper left") + + # --- Right: world frame (after rotation) --- + ax = axes[1] + pose_x, pose_y, pose_theta = 3.0, 2.5, np.pi / 5 + + # Draw a simple grid background to suggest the distance grid. + grid_res = 0.3 + for gx in np.arange(0, 6.01, grid_res): + ax.axvline(gx, color="lightgray", lw=0.3, zorder=0) + for gy in np.arange(0, 5.01, grid_res): + ax.axhline(gy, color="lightgray", lw=0.3, zorder=0) + + # Draw some "obstacles" for context. + wall1 = mpatches.Rectangle((0, 0), 6, 0.3, fc="salmon", alpha=0.5, ec="darkred", lw=1) + wall2 = mpatches.Rectangle((0, 4.7), 6, 0.3, fc="salmon", alpha=0.5, ec="darkred", lw=1) + ax.add_patch(wall1) + ax.add_patch(wall2) + + # Transform samples to world frame. + ct, st = np.cos(pose_theta), np.sin(pose_theta) + world_x = pose_x + ct * body_samples[:, 0] - st * body_samples[:, 1] + world_y = pose_y + st * body_samples[:, 0] + ct * body_samples[:, 1] + + # Draw robot footprint. + draw_rect_footprint(ax, pose_x, pose_y, pose_theta, hl, hw) + + # Draw samples in world frame. + ax.scatter(world_x, world_y, c="navy", s=30, zorder=5, label="Transformed samples") + + # Draw world axes at robot center. + draw_axes(ax, pose_x, pose_y, pose_theta, length=0.5) + ax.plot(pose_x, pose_y, "o", color="navy", ms=5, zorder=6) + + # Draw distance query lines from a few samples to nearest wall. + for i in [0, 4, 8, 12]: + sx, sy = world_x[i], world_y[i] + # Distance to bottom wall. + nearest_y = 0.3 if sy < 2.5 else 4.7 + ax.plot([sx, sx], [sy, nearest_y], color="orange", lw=1.0, ls=":", alpha=0.7, zorder=3) + + ax.set_title("World frame (on distance grid)", fontsize=14, fontweight="bold") + ax.set_xlim(0, 6) + ax.set_ylim(-0.3, 5.3) + ax.set_aspect("equal") + ax.legend(fontsize=10, loc="upper left") + ax.set_xlabel("x (m)") + ax.set_ylabel("y (m)") + + plt.tight_layout() + path = os.path.join(output_dir, "se2_footprint_checking.svg") + fig.savefig(path, bbox_inches="tight") + plt.close(fig) + print(f"Saved {path}") + + +def main(): + parser = argparse.ArgumentParser(description="Generate SE(2) tutorial concept diagrams") + parser.add_argument( + "--output-dir", + default="docs/tutorials/figs", + help="Output directory for SVG files (default: docs/tutorials/figs)", + ) + args = parser.parse_args() + + os.makedirs(args.output_dir, exist_ok=True) + + draw_poses_and_footprints(args.output_dir) + draw_inflation(args.output_dir) + draw_footprint_checking(args.output_dir) + + +if __name__ == "__main__": + main() diff --git a/scripts/visualize_metric_grid.py b/scripts/visualize_metric_grid.py index 919e4d2..63f1d04 100644 --- a/scripts/visualize_metric_grid.py +++ b/scripts/visualize_metric_grid.py @@ -7,7 +7,7 @@ Usage: python scripts/visualize_metric_grid.py minimum_energy_grid.json \\ - --output-dir docs/tutorials/figs + --output-dir docs/tutorials/figs/minimum-energy-planning """ import argparse diff --git a/scripts/visualize_minimum_energy_planning.py b/scripts/visualize_minimum_energy_planning.py new file mode 100644 index 0000000..cc3e82a --- /dev/null +++ b/scripts/visualize_minimum_energy_planning.py @@ -0,0 +1,501 @@ +#!/usr/bin/env python3 +"""Visualize RRT* planning under flat, KE, and Jacobi metrics. + +Reads a JSON file produced by minimum_energy_planning and writes an SVG figure +with three panels showing the RRT* tree and solution path for each metric, +overlaid on the respective metric tensor determinant. + +Usage: + python scripts/visualize_minimum_energy_planning.py minimum_energy_planning.json \ + --output-dir docs/tutorials/figs/minimum-energy-planning +""" + +import argparse +import json +import math +import os + +import matplotlib +import matplotlib.colors as mcolors +import matplotlib.patches as mpatches +import matplotlib.pyplot as plt +import numpy as np +from matplotlib.animation import FuncAnimation, PillowWriter +from matplotlib.collections import LineCollection, PatchCollection + +matplotlib.use("Agg") + +plt.rcParams.update({ + "text.usetex": True, + "font.family": "serif", + "font.serif": ["Computer Modern Roman"], + "axes.labelsize": 11, + "axes.titlesize": 12, + "xtick.labelsize": 10, + "ytick.labelsize": 10, +}) + +pink_cmap = mcolors.ListedColormap(plt.get_cmap("pink")(np.linspace(0.20, 1, 256))) + + +# --------------------------------------------------------------------------- +# Arm physics (recomputed in Python from embedded JSON parameters) +# --------------------------------------------------------------------------- + +def make_mass_matrix_fn(arm): + """Return a vectorized mass matrix function from arm parameters.""" + l1, lc1, lc2 = arm["l1"], arm["lc1"], arm["lc2"] + m1, m2 = arm["m1"], arm["m2"] + I1, I2 = arm["I1"], arm["I2"] + + def mass_matrix(q1, q2): + """Return (M00, M01, M11) arrays evaluated on a grid.""" + c2 = np.cos(q2) + h = l1 * lc2 * c2 + M00 = I1 + I2 + m1 * lc1**2 + m2 * (l1**2 + lc2**2 + 2.0 * h) + M01 = I2 + m2 * (lc2**2 + h) + M11 = I2 + m2 * lc2**2 + return M00, M01, M11 + + return mass_matrix + + +def compute_potential(q1, q2, arm): + """Compute gravitational potential P(q) on a grid.""" + g = arm["g"] + m1, m2 = arm["m1"], arm["m2"] + l1, lc1, lc2 = arm["l1"], arm["lc1"], arm["lc2"] + return (m1 * g * lc1 * np.sin(q1) + + m2 * g * (l1 * np.sin(q1) + lc2 * np.sin(q1 + q2))) + + +def compute_backgrounds(arm, H, n=80): + """Compute metric determinant backgrounds on an n x n grid in [-pi, pi]. + + Returns (q1, q2, det_flat, det_ke, det_jacobi) where each det is (n, n). + """ + q1 = np.linspace(-math.pi, math.pi, n) + q2 = np.linspace(-math.pi, math.pi, n) + Q1, Q2 = np.meshgrid(q1, q2, indexing="ij") # shape (n, n) + + mass_fn = make_mass_matrix_fn(arm) + M00, M01, M11 = mass_fn(Q1, Q2) + + # det(M) = M00*M11 - M01^2 + det_M = M00 * M11 - M01**2 + + # Flat: det(I) = 1 everywhere + det_flat = np.ones_like(det_M) + + # Jacobi: det(J) = [2(H - P)]^2 * det(M) + P = compute_potential(Q1, Q2, arm) + conformal = 2.0 * (H - P) + det_J = conformal**2 * det_M + + return q1, q2, det_flat, det_M, det_J + + +# --------------------------------------------------------------------------- +# Helpers +# --------------------------------------------------------------------------- + +def _pi_ticks(): + """Tick positions and labels for [-pi, pi].""" + positions = [-math.pi, -math.pi / 2, 0, math.pi / 2, math.pi] + labels = [r"$-\pi$", r"$-\pi/2$", r"$0$", r"$\pi/2$", r"$\pi$"] + return positions, labels + + +def _finalize_axes(ax, title=None, show_ylabel=True, fontsize=None): + ticks, labels = _pi_ticks() + ax.set_xlim(-math.pi, math.pi) + ax.set_ylim(-math.pi, math.pi) + ax.set_xticks(ticks) + ax.set_xticklabels(labels, fontsize=fontsize) + ax.set_yticks(ticks) + ax.set_yticklabels(labels, fontsize=fontsize) + ax.set_xlabel(r"$q_1$ \textrm{[rad]}", fontsize=fontsize) + if show_ylabel: + ax.set_ylabel(r"$q_2$ \textrm{[rad]}", fontsize=fontsize) + if title is not None: + ax.set_title(title, fontsize=fontsize) + ax.set_aspect("equal") + + +# --------------------------------------------------------------------------- +# Main figure +# --------------------------------------------------------------------------- + +def plot_planning(data, output_path): + runs = data["runs"] + arm = data["arm"] + H = data["H"] + start = data["start"] + goal = data["goal"] + + # Compute metric backgrounds + q1, q2, det_flat, det_ke, det_jacobi = compute_backgrounds(arm, H) + backgrounds = [det_flat, det_ke, det_jacobi] + extent = [-math.pi, math.pi, -math.pi, math.pi] + + titles = [r"\textbf{Euclidean}", r"\textbf{Kinetic Energy}", r"\textbf{Jacobi}"] + + fig, axes = plt.subplots( + 1, 3, figsize=(16.5, 5.5), + gridspec_kw={"wspace": 0.15}, + ) + + for idx, (ax, run, bg, title) in enumerate(zip(axes, runs, backgrounds, titles)): + # Normalize background independently to [0, 1] + bg_min, bg_max = bg.min(), bg.max() + if bg_max > bg_min: + bg_norm = (bg - bg_min) / (bg_max - bg_min) + else: + bg_norm = np.ones_like(bg) + + ax.imshow( + bg_norm.T, + origin="lower", + extent=extent, + aspect="equal", + cmap=pink_cmap, + interpolation="bilinear", + vmin=0.0, + vmax=1.0, + ) + + # Tree edges + if "tree" in run: + segments = [[(e[0][0], e[0][1]), (e[1][0], e[1][1])] + for e in run["tree"]] + lc = LineCollection( + segments, colors="#2e3236", linewidths=0.15, alpha=0.2, zorder=1 + ) + ax.add_collection(lc) + + # Raw planner path (dashed) vs smoothed path (solid). + # Falls back to legacy "path" field for backward compatibility. + raw = run.get("raw_path") or run.get("path") or [] + smoothed = run.get("smoothed_path") or [] + + if raw: + xs = [p[0] for p in raw] + ys = [p[1] for p in raw] + ax.plot( + xs, ys, + color="#1f77b4", linewidth=1.5, linestyle="--", + alpha=0.7, zorder=3, label="raw", + ) + + # if smoothed: + # xs = [p[0] for p in smoothed] + # ys = [p[1] for p in smoothed] + # ax.plot( + # xs, ys, + # color="#d62728", linewidth=2.5, zorder=4, label="smoothed", + # ) + + # ax.legend(loc="lower right", fontsize=11, framealpha=0.85) + + # Start and goal markers + ax.plot(start[0], start[1], "o", color="#2ca02c", markersize=9, zorder=5) + ax.plot(goal[0], goal[1], "*", color="#ff7f0e", markersize=13, zorder=5) + + _finalize_axes(ax, title=title, show_ylabel=(idx == 0), fontsize=16) + + fig.savefig(output_path, format="svg", dpi=150, bbox_inches="tight") + plt.close(fig) + print(f"Wrote {output_path}") + + +# --------------------------------------------------------------------------- +# Two-link arm animation +# --------------------------------------------------------------------------- + +ARM_LINK_COLOR = "#3a5988" +ARM_BASE_COLOR = "#2d4675" +ARM_PATH_COLOR = "#ffb32a" + + +def forward_kinematics(q1, q2, l1, l2): + """Return (shoulder, elbow, end-effector) Cartesian positions.""" + sh = np.array([0.0, 0.0]) + el = np.array([l1 * np.cos(q1), l1 * np.sin(q1)]) + ee = el + np.array([l2 * np.cos(q1 + q2), l2 * np.sin(q1 + q2)]) + return sh, el, ee + + +def _capsule_link(q_abs, length, base_xy, half_width): + """Return vertices of a horizontal capsule of given length and half-width + (rounded-rectangle outline), rotated by ``q_abs`` and anchored at ``base_xy``.""" + nb = 30 + t1 = np.linspace(0.0, -np.pi, nb // 2) + t2 = np.linspace(np.pi, 0.0, nb // 2) + x = np.concatenate((half_width * np.sin(t1), length + half_width * np.sin(t2))) + y = np.concatenate((np.cos(t1), np.cos(t2))) * half_width + xy = np.vstack((x, y)) + R = np.array([[np.cos(q_abs), -np.sin(q_abs)], + [np.sin(q_abs), np.cos(q_abs)]]) + return (R @ xy).T + np.asarray(base_xy) + + +def _base_wedge_verts(base_xy, size): + """Vertices for a half-circle-on-a-stub wedge that reads as a ground-bolted base.""" + nb = 30 + sz = size * 1.2 + t = np.linspace(0.0, np.pi, nb - 2) + x = np.concatenate(([1.5], 1.5 * np.cos(t), [-1.5])) * sz + y = np.concatenate(([-1.2], 1.5 * np.sin(t), [-1.2])) * sz + return np.c_[x, y] + np.asarray(base_xy) + + +def draw_arm(ax, q1, q2, l1, l2, *, alpha=1.0, half_width=0.22, + joint_radius=0.095, link_color=ARM_LINK_COLOR, zorder=5): + """Draw one arm pose: two capsule-polygon links with a thin white outline, + plus three joint pins drawn navy-filled with a thicker white outline. + ``half_width`` sets the link thickness in data units; ``joint_radius`` is smaller than + ``half_width`` so the joint reads as a small blue disc ringed by white + against the link body.""" + sh = np.array([0.0, 0.0]) + # Link 1: horizontal capsule rotated by q1, anchored at shoulder. + verts1 = _capsule_link(q1, l1, sh, half_width) + ax.add_patch(mpatches.Polygon( + verts1, closed=True, + facecolor=link_color, edgecolor="white", + linewidth=2.0, alpha=alpha, zorder=zorder, + )) + + # Link 2: horizontal capsule rotated by q1+q2, anchored at elbow. + el = sh + np.array([l1 * np.cos(q1), l1 * np.sin(q1)]) + verts2 = _capsule_link(q1 + q2, l2, el, half_width) + ax.add_patch(mpatches.Polygon( + verts2, closed=True, + facecolor=link_color, edgecolor="white", + linewidth=2.0, alpha=alpha, zorder=zorder, + )) + + # Joint pins: solid navy disc with a thick white stroke + ee = el + np.array([l2 * np.cos(q1 + q2), l2 * np.sin(q1 + q2)]) + for pt in (sh, el, ee): + ax.add_patch(mpatches.Circle( + pt, joint_radius, facecolor=link_color, + edgecolor="white", linewidth=3.0, + alpha=alpha, zorder=zorder + 1)) + + +def draw_base(ax, *, size=0.20, color=ARM_BASE_COLOR, zorder=8): + """Wedge-shaped base at the origin, a dark navy mount with a white outline""" + verts = _base_wedge_verts((0.0, 0.0), size) + ax.add_patch(mpatches.Polygon( + verts, closed=True, + facecolor=color, edgecolor="white", + linewidth=2.0, zorder=zorder, + )) + + +def _densify_path(path, step=0.03): + """Linearly densify a waypoint list so the arm moves smoothly between + frames. Waypoints coming out of RRT* are typically too sparse for a + visually continuous animation.""" + pts = np.asarray(path, dtype=float) + if len(pts) < 2: + return pts + out = [pts[0]] + for a, b in zip(pts[:-1], pts[1:]): + seg_len = np.linalg.norm(b - a) + n = max(2, int(np.ceil(seg_len / step))) + for i in range(1, n + 1): + out.append(a + (b - a) * (i / n)) + return np.asarray(out) + + +def _resample_path(pts, n): + """Resample a polyline to ``n`` points spaced uniformly by arc length. + Lets us play paths of different lengths side-by-side in sync.""" + pts = np.asarray(pts, dtype=float) + if len(pts) < 2: + return np.tile(pts, (n, 1)) + seg_lens = np.linalg.norm(np.diff(pts, axis=0), axis=1) + arc = np.concatenate(([0.0], np.cumsum(seg_lens))) + total = arc[-1] + if total == 0: + return np.tile(pts[0], (n, 1)) + target = np.linspace(0.0, total, n) + out = np.empty((n, pts.shape[1])) + for d in range(pts.shape[1]): + out[:, d] = np.interp(target, arc, pts[:, d]) + return out + + +def animate_arm(data, output_path, *, fps=15, + ghost_count=6, ghost_stride_frac=0.11, + panel_size=(3.2, 3.2), dpi=110, pad=0.08, + n_frames=150, pause_frames=30, + bg_color="#f7fbfe", + titles=(r"\textbf{Euclidean}", + r"\textbf{Kinetic Energy}", + r"\textbf{Jacobi}")): + """Write a GIF with three side-by-side panels — one arm per metric — + animating in sync from start to goal, with a hold at the goal pose + before the loop restarts. + + The visual style (dark-navy links, white joint pins, amber end-effector + trace, faded ghosts of previous poses) matches the paper's ``two-link + planar arm`` figure. Paths are resampled uniformly by arc length so all + three arms finish at the same frame regardless of planner waypoint count. + ``bg_color`` defaults to the landing-page card background so the GIF + blends in when embedded in the docs. + """ + arm = data["arm"] + l1, l2 = arm["l1"], arm["l2"] + runs = data["runs"] + if len(runs) != len(titles): + raise ValueError( + f"Expected {len(titles)} runs (one per metric), got {len(runs)}.") + + paths = [] + for i, run in enumerate(runs): + raw = run.get("smoothed_path") or run.get("raw_path") or run.get("path") + if not raw: + raise ValueError(f"Run {i} ({titles[i]}) has no path to animate.") + dense = _densify_path(raw, step=0.03) + paths.append(_resample_path(dense, n_frames)) + + ees = [np.array([forward_kinematics(q1, q2, l1, l2)[2] for q1, q2 in p]) + for p in paths] + + # Shared view that encloses every joint (shoulder, elbow, end-effector) + # of every arm across every frame, then expanded by link half-width + + # joint radius + `pad` so thick links and the base wedge never clip. + all_pts = [] + for path in paths: + for q1, q2 in path: + sh, el, ee = forward_kinematics(q1, q2, l1, l2) + all_pts.extend([sh, el, ee]) + all_pts = np.asarray(all_pts) + slack = 0.22 + 0.095 + pad # link half-width + joint radius + user pad + xmin = all_pts[:, 0].min() - slack + xmax = all_pts[:, 0].max() + slack + ymin = min(all_pts[:, 1].min(), -0.30) - slack # include base wedge + ymax = all_pts[:, 1].max() + slack + half = 0.5 * max(xmax - xmin, ymax - ymin) + cx, cy = 0.5 * (xmin + xmax), 0.5 * (ymin + ymax) + xlim = (cx - half, cx + half) + ylim = (cy - half, cy + half) + + pw, ph = panel_size + fig, axes = plt.subplots( + 1, 3, figsize=(3 * pw, ph), dpi=dpi, + gridspec_kw={"wspace": 0.0}, + ) + # Drop outer figure margins entirely so the three panels fill the frame. + fig.subplots_adjust(left=0.0, right=1.0, bottom=0.0, top=0.93) + fig.patch.set_facecolor(bg_color) + for ax in axes: + ax.set_facecolor(bg_color) + + ghost_stride = max(1, int(np.ceil(n_frames * ghost_stride_frac))) + + def render_frame(frame): + for ax, path, ee, title in zip(axes, paths, ees, titles): + ax.clear() + ax.set_facecolor(bg_color) + ax.set_aspect("equal") + ax.set_xlim(*xlim) + ax.set_ylim(*ylim) + ax.axis("off") + + for g in range(1, ghost_count + 1): + idx = frame - g * ghost_stride + if idx < 0: + break + alpha = max(0.12, 0.65 - 0.09 * g) + q1g, q2g = path[idx] + draw_arm(ax, q1g, q2g, l1, l2, alpha=alpha, zorder=5 - g) + + draw_base(ax) + q1c, q2c = path[frame] + draw_arm(ax, q1c, q2c, l1, l2, alpha=1.0, zorder=10) + + # Amber trace drawn last so it sits on top of every link and joint. + ax.plot(ee[: frame + 1, 0], ee[: frame + 1, 1], + color=ARM_PATH_COLOR, linewidth=2.6, + solid_capstyle="round", zorder=20) + + ax.set_title(title, fontsize=13, pad=4) + + # Render each motion frame once, convert to PIL, then write a GIF with a + # longer per-frame duration on the final pose. Doing it this way (rather + # than duplicating the last frame through FuncAnimation) avoids + # PillowWriter deduplicating identical trailing frames. + from io import BytesIO + import PIL.Image + + frame_ms = int(round(1000 / fps)) + pause_ms = frame_ms * max(1, pause_frames) + durations = [frame_ms] * (n_frames - 1) + [pause_ms] + + images = [] + for f in range(n_frames): + render_frame(f) + buf = BytesIO() + fig.savefig(buf, format="png", dpi=dpi, facecolor=bg_color) + buf.seek(0) + images.append(PIL.Image.open(buf).convert("RGBA").copy()) + buf.close() + + images[0].save( + output_path, + save_all=True, + append_images=images[1:], + duration=durations, + loop=0, + optimize=False, + disposal=2, + ) + plt.close(fig) + print(f"Wrote {output_path}") + + +# --------------------------------------------------------------------------- +# CLI +# --------------------------------------------------------------------------- + +def main(): + parser = argparse.ArgumentParser( + description="Visualize minimum-energy RRT* planning results." + ) + parser.add_argument("json_file", help="Path to minimum_energy_planning.json") + parser.add_argument( + "--output-dir", default=".", help="Directory for output files (default: .)" + ) + parser.add_argument( + "--no-svg", action="store_true", + help="Skip the three-panel SVG comparison figure.", + ) + parser.add_argument( + "--no-gif", action="store_true", + help="Skip the arm animation GIF.", + ) + parser.add_argument( + "--gif-fps", type=int, default=15, + help="Frames per second for the arm GIF (default: 15).", + ) + args = parser.parse_args() + + with open(args.json_file) as f: + data = json.load(f) + + os.makedirs(args.output_dir, exist_ok=True) + + if not args.no_svg: + svg_path = os.path.join(args.output_dir, "planning_result.svg") + plot_planning(data, svg_path) + + if not args.no_gif: + gif_path = os.path.join(args.output_dir, "arm.gif") + animate_arm(data, gif_path, fps=args.gif_fps) + + +if __name__ == "__main__": + main() diff --git a/scripts/visualize_se2_tutorial.py b/scripts/visualize_se2_tutorial.py new file mode 100644 index 0000000..0bd212f --- /dev/null +++ b/scripts/visualize_se2_tutorial.py @@ -0,0 +1,411 @@ +#!/usr/bin/env python3 +"""Visualize SE(2) tutorial planning results. + +Reads JSON output from se2_tutorial and produces SVG figures for the tutorial. +Supports multiple rendering modes via --mode: + - result: Planning result with tree, paths, and footprints (default) + - map: Environment only (occupancy grid + distance heatmap) + - conformal: Conformal factor heatmap overlaid on map + - comparison: Two-panel side-by-side (pass two JSON files) + - env: Parking environment layout (no planning data) + +Usage: + python scripts/visualize_se2_tutorial.py result.json -o figure.svg + python scripts/visualize_se2_tutorial.py result.json -o figure.svg --map corridor.png + python scripts/visualize_se2_tutorial.py a.json b.json -o comparison.svg --mode comparison +""" + +import argparse +import json +import os + +import matplotlib.patches as mpatches +import matplotlib.pyplot as plt +import numpy as np + +# geodex docs style: Lato font, stixsans math, large figures. +plt.rcParams.update( + { + "font.family": "sans-serif", + "font.sans-serif": ["Lato", "Helvetica", "Arial", "DejaVu Sans"], + "font.size": 14, + "mathtext.fontset": "stixsans", + "axes.linewidth": 1.2, + } +) + + +def draw_pose_arrow(ax, x, y, theta, length=0.4, color="black", lw=1.5): + dx = length * np.cos(theta) + dy = length * np.sin(theta) + ax.annotate( + "", + xy=(x + dx, y + dy), + xytext=(x, y), + arrowprops=dict(arrowstyle="->", color=color, lw=lw), + ) + + +def draw_circle_footprint(ax, x, y, radius, color="royalblue", alpha=0.12, ec="navy"): + circle = mpatches.Circle( + (x, y), radius, fc=color, alpha=alpha, ec=ec, lw=0.5, zorder=4, + ) + ax.add_patch(circle) + + +def draw_rect_footprint(ax, x, y, theta, hl, hw, color="royalblue", alpha=0.12, ec="navy"): + ct, st = np.cos(theta), np.sin(theta) + corners = [] + for sx, sy in [(-1, -1), (1, -1), (1, 1), (-1, 1)]: + lx, ly = sx * hl, sy * hw + corners.append((x + ct * lx - st * ly, y + st * lx + ct * ly)) + patch = mpatches.Polygon( + corners, closed=True, fc=color, alpha=alpha, ec=ec, lw=0.5, zorder=4, + ) + ax.add_patch(patch) + + +def draw_rect_obstacle(ax, obs, fc="salmon", alpha=0.6, ec="darkred", lw=1.5): + cx, cy = obs["center"] + theta = obs.get("theta", 0.0) + hl, hw = obs["half_length"], obs["half_width"] + ct, st = np.cos(theta), np.sin(theta) + corners = [] + for sx, sy in [(-1, -1), (1, -1), (1, 1), (-1, 1)]: + lx, ly = sx * hl, sy * hw + corners.append((cx + ct * lx - st * ly, cy + st * lx + ct * ly)) + patch = mpatches.Polygon( + corners, closed=True, fc=fc, alpha=alpha, ec=ec, lw=lw, zorder=0, + ) + ax.add_patch(patch) + + +def load_map_png(map_path, data): + """Load map PNG image. Tries explicit path, then sibling of dist map file.""" + from PIL import Image + + candidates = [] + if map_path: + candidates.append(map_path) + map_info = data.get("map") + if map_info and map_info.get("file"): + dist_file = map_info["file"] + base = os.path.splitext(os.path.basename(dist_file))[0].replace("_dist", "") + candidates.append(os.path.join(os.path.dirname(dist_file), base + ".png")) + for path in candidates: + if os.path.isfile(path): + return np.array(Image.open(path).convert("L")) + return None + + +def get_extent(data, map_img): + """Get world extent [x0, x1, y0, y1] from map info or obstacle bounds.""" + map_info = data.get("map") + if map_info: + w = map_info["width"] * map_info["resolution"] + h = map_info["height"] * map_info["resolution"] + return [0, w, 0, h] + # For rect obstacle scenarios, compute from obstacles + start/goal. + rects = data.get("rect_obstacles", []) + if rects: + all_x = [o["center"][0] for o in rects] + [data["start"][0], data["goal"][0]] + all_y = [o["center"][1] for o in rects] + [data["start"][1], data["goal"][1]] + margin = 3.0 + return [min(all_x) - margin, max(all_x) + margin, + min(all_y) - margin, max(all_y) + margin] + return [0, 15, 0, 10] + + +def draw_background(ax, data, map_img, extent): + """Draw the environment background (map image or rectangle obstacles).""" + if map_img is not None: + ax.imshow(map_img, cmap="gray", extent=extent, origin="lower", alpha=0.7, zorder=0) + for obs in data.get("rect_obstacles", []): + draw_rect_obstacle(ax, obs) + + +def draw_planning_result(ax, data, run, map_img, extent, show_tree=True, arrow_len=None): + """Draw a full planning result: tree, paths, footprints, start/goal.""" + draw_background(ax, data, map_img, extent) + + start = data["start"] + goal = data["goal"] + robot = data.get("robot", {}) + is_map = map_img is not None + has_rects = len(data.get("rect_obstacles", [])) > 0 + + if arrow_len is None: + arrow_len = 1.0 if is_map else (0.8 if has_rects else 0.5) + + # Tree edges. + if show_tree: + for edge in run.get("tree", []): + ax.plot([edge[0][0], edge[1][0]], [edge[0][1], edge[1][1]], + color="lightgray", lw=0.3, zorder=1) + + # Paths. + raw = np.array(run.get("raw_path", [])) + smoothed = np.array(run.get("smoothed_path", [])) + + if len(smoothed) > 0: + if len(raw) > 0: + ax.plot(raw[:, 0], raw[:, 1], color="tomato", lw=1.5, ls="--", zorder=2, + label="Raw", alpha=0.7) + ax.plot(smoothed[:, 0], smoothed[:, 1], color="royalblue", lw=2.5, zorder=3, + label="Smoothed") + path = smoothed + elif len(raw) > 0: + ax.plot(raw[:, 0], raw[:, 1], color="royalblue", lw=2.5, zorder=3, label="Path") + path = raw + else: + path = np.empty((0, 3)) + + # Footprints and heading arrows along smoothed path. + if len(path) > 0: + n_fp = min(15, len(path)) + indices = np.linspace(0, len(path) - 1, n_fp, dtype=int) + for i in indices: + px, py, pth = path[i] + draw_pose_arrow(ax, px, py, pth, length=arrow_len, color="navy", lw=1.2) + if robot.get("type") == "circle": + draw_circle_footprint(ax, px, py, robot["radius"]) + elif robot.get("type") == "rectangle": + draw_rect_footprint(ax, px, py, pth, robot["half_length"], robot["half_width"]) + + # Start / goal. + ms_s = 12 if is_map else 10 + ms_g = 16 if is_map else 14 + pose_len = 1.5 if is_map else (1.0 if has_rects else 0.6) + ax.plot(start[0], start[1], "o", color="limegreen", ms=ms_s, zorder=5, + mec="darkgreen", mew=1.5) + draw_pose_arrow(ax, start[0], start[1], start[2], length=pose_len, color="darkgreen", lw=2) + ax.plot(goal[0], goal[1], "*", color="orange", ms=ms_g, zorder=5, + mec="darkorange", mew=1.5) + draw_pose_arrow(ax, goal[0], goal[1], goal[2], length=pose_len, color="darkorange", lw=2) + + # Title and labels. + timing = [] + if "planning_time_ms" in run: + timing.append(f"plan={run['planning_time_ms']:.0f}ms") + if "smoothing_time_ms" in run: + timing.append(f"smooth={run['smoothing_time_ms']:.0f}ms") + title = run["label"] + if timing: + title += f"\n({', '.join(timing)})" + ax.set_title(title, fontsize=13) + ax.legend(loc="upper left", fontsize=9) + ax.set_xlim(extent[0], extent[1]) + ax.set_ylim(extent[2], extent[3]) + ax.set_aspect("equal") + ax.grid(True, alpha=0.3) + ax.set_xlabel("x (m)") + ax.set_ylabel("y (m)") + + +# --------------------------------------------------------------------------- +# Mode: result (default) +# --------------------------------------------------------------------------- + +def mode_result(data, map_img, output): + runs = data["runs"] + extent = get_extent(data, map_img) + n = len(runs) + fig_w = 10 if map_img is not None else 9 + fig, axes = plt.subplots(1, n, figsize=(fig_w * n, fig_w), squeeze=False) + for i, run in enumerate(runs): + draw_planning_result(axes[0, i], data, run, map_img, extent) + plt.tight_layout() + fig.savefig(output, dpi=150, bbox_inches="tight") + plt.close(fig) + + +# --------------------------------------------------------------------------- +# Mode: map (environment with distance heatmap) +# --------------------------------------------------------------------------- + +def mode_map(data, map_img, output): + from mpl_toolkits.axes_grid1 import make_axes_locatable + + extent = get_extent(data, map_img) + fig, axes = plt.subplots(1, 2, figsize=(11, 5)) + + # Left: occupancy grid. + if map_img is not None: + axes[0].imshow(map_img, cmap="gray", extent=extent, origin="lower") + axes[0].set_title("Occupancy grid", fontsize=14, fontweight="bold") + axes[0].set_xlim(extent[0], extent[1]) + axes[0].set_ylim(extent[2], extent[3]) + axes[0].set_aspect("equal") + axes[0].set_xlabel("x (m)") + axes[0].set_ylabel("y (m)") + + # Reserve an identically-sized colorbar slot on the left so the two image + # axes end up the same width after layout. + cax0 = make_axes_locatable(axes[0]).append_axes("right", size="4%", pad=0.12) + cax0.axis("off") + + # Right: distance transform. Walls are rendered as a gray base layer and + # the distance colormap is applied only to free cells, so obstacles read + # as obstacles rather than as the dominant "dark = traversable" region. + map_info = data.get("map", {}) + if map_img is not None: + from scipy.ndimage import distance_transform_edt + + free = map_img >= 128 + dist = distance_transform_edt(free) * map_info.get("resolution", 0.05) + dist_masked = np.ma.masked_where(~free, dist) + axes[1].imshow(map_img, cmap="gray", extent=extent, origin="lower") + im = axes[1].imshow( + dist_masked, cmap="viridis", extent=extent, origin="lower" + ) + cax1 = make_axes_locatable(axes[1]).append_axes("right", size="4%", pad=0.12) + plt.colorbar(im, cax=cax1, label="Distance (m)") + axes[1].set_title("Distance transform", fontsize=14, fontweight="bold") + axes[1].set_xlim(extent[0], extent[1]) + axes[1].set_ylim(extent[2], extent[3]) + axes[1].set_aspect("equal") + axes[1].set_xlabel("x (m)") + axes[1].set_ylabel("y (m)") + + plt.tight_layout() + fig.savefig(output, dpi=150, bbox_inches="tight") + plt.close(fig) + + +# --------------------------------------------------------------------------- +# Mode: conformal factor heatmap +# --------------------------------------------------------------------------- + +def mode_conformal(data, map_img, output): + extent = get_extent(data, map_img) + cgrid = data.get("conformal_grid") + if cgrid is None: + print("Error: no conformal_grid in JSON (run holo_clearance scenario)") + return + + values = np.array(cgrid["values"]).reshape(cgrid["height"], cgrid["width"]) + + fig, ax = plt.subplots(figsize=(10, 8)) + if map_img is not None: + ax.imshow(map_img, cmap="gray", extent=extent, origin="lower", alpha=0.4, zorder=0) + im = ax.imshow(values, cmap="YlOrRd", extent=extent, origin="lower", alpha=0.7, zorder=1) + plt.colorbar(im, ax=ax, label=r"Conformal factor $c(q)$", shrink=0.8) + + ax.set_title(r"Conformal clearance metric: $c(q) = 1 + \kappa \exp(-\beta \cdot \mathrm{sdf}(q))$", + fontsize=13) + ax.set_xlim(extent[0], extent[1]) + ax.set_ylim(extent[2], extent[3]) + ax.set_aspect("equal") + ax.set_xlabel("x (m)") + ax.set_ylabel("y (m)") + + plt.tight_layout() + fig.savefig(output, dpi=150, bbox_inches="tight") + plt.close(fig) + + +# --------------------------------------------------------------------------- +# Mode: comparison (two-panel side-by-side from two JSON files) +# --------------------------------------------------------------------------- + +def mode_comparison(data_list, map_img, output): + n = len(data_list) + extent = get_extent(data_list[0], map_img) + fig, axes = plt.subplots(1, n, figsize=(10 * n, 9), squeeze=False) + for i, data in enumerate(data_list): + if data["runs"]: + draw_planning_result(axes[0, i], data, data["runs"][0], map_img, extent) + plt.tight_layout() + fig.savefig(output, dpi=150, bbox_inches="tight") + plt.close(fig) + + +# --------------------------------------------------------------------------- +# Mode: env (parking environment layout) +# --------------------------------------------------------------------------- + +def mode_env(data, output): + extent = get_extent(data, None) + robot = data.get("robot", {}) + start, goal = data["start"], data["goal"] + + fig, ax = plt.subplots(figsize=(11, 5)) + + for obs in data.get("rect_obstacles", []): + draw_rect_obstacle(ax, obs) + + # Draw goal pose (dashed outline). + if robot.get("type") == "rectangle": + hl, hw = robot["half_length"], robot["half_width"] + ct, st = np.cos(goal[2]), np.sin(goal[2]) + corners = [] + for sx, sy in [(-1, -1), (1, -1), (1, 1), (-1, 1)]: + lx, ly = sx * hl, sy * hw + corners.append((goal[0] + ct * lx - st * ly, goal[1] + st * lx + ct * ly)) + ax.add_patch(mpatches.Polygon( + corners, closed=True, fc="none", ec="limegreen", lw=2, ls="--", zorder=3)) + + # Start and goal markers. + ax.plot(start[0], start[1], "o", color="limegreen", ms=12, zorder=5, + mec="darkgreen", mew=1.5) + draw_pose_arrow(ax, start[0], start[1], start[2], length=1.5, color="darkgreen", lw=2) + ax.annotate("Start", xy=(start[0], start[1] + 1.5), fontsize=12, ha="center", + color="darkgreen", fontweight="bold") + + ax.plot(goal[0], goal[1], "*", color="orange", ms=16, zorder=5, + mec="darkorange", mew=1.5) + draw_pose_arrow(ax, goal[0], goal[1], goal[2], length=1.0, color="darkorange", lw=2) + ax.annotate("Goal", xy=(goal[0], goal[1] + 1.5), fontsize=12, ha="center", + color="darkorange", fontweight="bold") + + ax.set_title("Parallel parking scenario", fontsize=14, fontweight="bold") + ax.set_xlim(extent[0], extent[1]) + ax.set_ylim(extent[2], extent[3]) + ax.set_aspect("equal") + ax.grid(True, alpha=0.2) + ax.set_xlabel("x (m)") + ax.set_ylabel("y (m)") + + plt.tight_layout() + fig.savefig(output, dpi=150, bbox_inches="tight") + plt.close(fig) + + +# --------------------------------------------------------------------------- +# Main +# --------------------------------------------------------------------------- + +def main(): + parser = argparse.ArgumentParser(description="Visualize SE(2) tutorial planning results") + parser.add_argument("json_files", nargs="+", help="JSON from se2_tutorial") + parser.add_argument("-o", "--output", required=True, help="Output SVG/PNG") + parser.add_argument("--map", default=None, help="Map PNG for background") + parser.add_argument("--mode", default="result", + choices=["result", "map", "conformal", "comparison", "env"], + help="Rendering mode (default: result)") + args = parser.parse_args() + + data_list = [] + for jf in args.json_files: + with open(jf) as f: + data_list.append(json.load(f)) + data = data_list[0] + + map_img = load_map_png(args.map, data) + + if args.mode == "result": + mode_result(data, map_img, args.output) + elif args.mode == "map": + mode_map(data, map_img, args.output) + elif args.mode == "conformal": + mode_conformal(data, map_img, args.output) + elif args.mode == "comparison": + mode_comparison(data_list, map_img, args.output) + elif args.mode == "env": + mode_env(data, args.output) + + print(f"Saved {args.output}") + + +if __name__ == "__main__": + main() diff --git a/tests/CMakeLists.txt b/tests/CMakeLists.txt index 46fa433..6b54693 100644 --- a/tests/CMakeLists.txt +++ b/tests/CMakeLists.txt @@ -6,6 +6,7 @@ FetchContent_Declare( GIT_TAG v1.14.0 GIT_SHALLOW TRUE ) +set(INSTALL_GTEST OFF CACHE BOOL "" FORCE) FetchContent_MakeAvailable(googletest) add_executable(test_concepts test_concepts.cpp) @@ -14,9 +15,17 @@ target_link_libraries(test_concepts PRIVATE geodex GTest::gtest_main) add_executable(test_sphere test_sphere.cpp) target_link_libraries(test_sphere PRIVATE geodex GTest::gtest_main) +add_executable(test_sphere_ndim test_sphere_ndim.cpp) +target_link_libraries(test_sphere_ndim PRIVATE geodex GTest::gtest_main) + include(GoogleTest) gtest_discover_tests(test_concepts) gtest_discover_tests(test_sphere) +gtest_discover_tests(test_sphere_ndim) + +add_executable(test_interpolation test_interpolation.cpp) +target_link_libraries(test_interpolation PRIVATE geodex GTest::gtest_main) +gtest_discover_tests(test_interpolation) add_executable(test_euclidean test_euclidean.cpp) target_link_libraries(test_euclidean PRIVATE geodex GTest::gtest_main) @@ -38,3 +47,27 @@ gtest_discover_tests(test_metrics) add_executable(test_configuration_space test_configuration_space.cpp) target_link_libraries(test_configuration_space PRIVATE geodex GTest::gtest_main) gtest_discover_tests(test_configuration_space) + +add_executable(test_clearance_metric test_clearance_metric.cpp) +target_link_libraries(test_clearance_metric PRIVATE geodex GTest::gtest_main) +gtest_discover_tests(test_clearance_metric) + +add_executable(test_sampler test_sampler.cpp) +target_link_libraries(test_sampler PRIVATE geodex GTest::gtest_main) +gtest_discover_tests(test_sampler) + +add_executable(test_collision test_collision.cpp) +target_link_libraries(test_collision PRIVATE geodex GTest::gtest_main) +gtest_discover_tests(test_collision) + +if(BUILD_OMPL_EXAMPLES) + add_executable(test_geodex_state_space test_geodex_state_space.cpp) + # GTest must come before ompl::ompl so FetchContent headers take priority + # over any system-installed GTest (e.g. /opt/homebrew/include/gtest). + target_link_libraries(test_geodex_state_space PRIVATE geodex GTest::gtest_main ompl::ompl) + gtest_discover_tests(test_geodex_state_space) + + add_executable(test_path_resampling test_path_resampling.cpp) + target_link_libraries(test_path_resampling PRIVATE geodex GTest::gtest_main ompl::ompl) + gtest_discover_tests(test_path_resampling) +endif() diff --git a/tests/fixtures/planar_manipulator_metric.hpp b/tests/fixtures/planar_manipulator_metric.hpp index 883e628..44b6d2b 100644 --- a/tests/fixtures/planar_manipulator_metric.hpp +++ b/tests/fixtures/planar_manipulator_metric.hpp @@ -1,9 +1,11 @@ #pragma once -#include #include + #include +#include + namespace geodex { /// Configuration-dependent mass-inertia matrix metric for a 2-link planar arm. diff --git a/tests/test_clearance_metric.cpp b/tests/test_clearance_metric.cpp new file mode 100644 index 0000000..0a267b0 --- /dev/null +++ b/tests/test_clearance_metric.cpp @@ -0,0 +1,340 @@ +/// @file test_clearance_metric.cpp +/// @brief Tests for SDFConformalMetric. + +#include + +#include +#include + +#include + +#include "geodex/algorithm/path_smoothing.hpp" +#include "geodex/manifold/configuration_space.hpp" +#include "geodex/manifold/euclidean.hpp" +#include "geodex/manifold/se2.hpp" +#include "geodex/metrics/clearance.hpp" + +// --------------------------------------------------------------------------- +// Simple circular obstacle SDF (individual, exact) +// --------------------------------------------------------------------------- + +struct CircleSDF { + double cx, cy, radius; + + double operator()(const auto& q) const { + double dx = q[0] - cx, dy = q[1] - cy; + return std::sqrt(dx * dx + dy * dy) - radius; + } +}; + +// --------------------------------------------------------------------------- +// Smooth-min SDF over multiple circles via log-sum-exp +// --------------------------------------------------------------------------- + +struct CircleSmoothSDF { + struct Circle { + double cx, cy, radius; + }; + + std::vector circles; + double beta_sdf = 20.0; // smoothness (higher = closer to true min) + + double operator()(const auto& q) const { + if (circles.empty()) return 1e10; + + // log-sum-exp smooth-min: d = -1/β * log(Σ exp(-β * d_i)) + double max_neg_d = -1e30; + for (const auto& c : circles) { + double dx = q[0] - c.cx, dy = q[1] - c.cy; + double d_i = std::sqrt(dx * dx + dy * dy) - c.radius; + max_neg_d = std::max(max_neg_d, -beta_sdf * d_i); + } + + double sum = 0.0; + for (const auto& c : circles) { + double dx = q[0] - c.cx, dy = q[1] - c.cy; + double d_i = std::sqrt(dx * dx + dy * dy) - c.radius; + sum += std::exp(-beta_sdf * d_i - max_neg_d); + } + + return -(max_neg_d + std::log(sum)) / beta_sdf; + } +}; + +// --------------------------------------------------------------------------- +// Tests +// --------------------------------------------------------------------------- + +// (a) Far from obstacles: conformal factor should be ~1.0. +TEST(SDFConformalMetric, FarFromObstacle) { + geodex::SE2LeftInvariantMetric base{1.0, 1.0, 0.5}; + CircleSDF sdf{5.0, 5.0, 1.0}; + geodex::SDFConformalMetric metric{base, sdf, 5.0, 3.0}; + + Eigen::Vector3d q_far(50.0, 50.0, 0.0); // far from obstacle at (5,5) + double c = metric.conformal_factor(q_far); + EXPECT_NEAR(c, 1.0, 1e-6); // exp(-3*45) ≈ 0 +} + +// (b) At obstacle surface: conformal factor should be 1 + kappa. +TEST(SDFConformalMetric, AtObstacleSurface) { + geodex::SE2LeftInvariantMetric base{1.0, 1.0, 0.5}; + CircleSDF sdf{5.0, 5.0, 1.0}; + double kappa = 5.0; + geodex::SDFConformalMetric metric{base, sdf, kappa, 3.0}; + + // Point on the obstacle boundary (sdf = 0) + Eigen::Vector3d q_surface(6.0, 5.0, 0.0); + double c = metric.conformal_factor(q_surface); + EXPECT_NEAR(c, 1.0 + kappa, 1e-6); +} + +// (c) Inside obstacle: conformal factor should be > 1 + kappa. +TEST(SDFConformalMetric, InsideObstacle) { + geodex::SE2LeftInvariantMetric base{1.0, 1.0, 0.5}; + CircleSDF sdf{5.0, 5.0, 1.0}; + double kappa = 5.0; + geodex::SDFConformalMetric metric{base, sdf, kappa, 3.0}; + + // Point inside obstacle (sdf < 0) + Eigen::Vector3d q_inside(5.0, 5.0, 0.0); + double c = metric.conformal_factor(q_inside); + EXPECT_GT(c, 1.0 + kappa); +} + +// (d) Monotonicity: conformal factor decreases with distance from obstacle. +TEST(SDFConformalMetric, MonotonicDecrease) { + geodex::SE2LeftInvariantMetric base{1.0, 1.0, 0.5}; + CircleSDF sdf{5.0, 5.0, 1.0}; + geodex::SDFConformalMetric metric{base, sdf, 5.0, 3.0}; + + double c_prev = 1e10; + for (double d = 0.0; d <= 5.0; d += 0.5) { + Eigen::Vector3d q(5.0 + 1.0 + d, 5.0, 0.0); // distance d from surface + double c = metric.conformal_factor(q); + EXPECT_LT(c, c_prev) << "at distance " << d; + c_prev = c; + } +} + +// (e) Inner product scales correctly. +TEST(SDFConformalMetric, InnerProductScaling) { + geodex::SE2LeftInvariantMetric base{1.0, 2.0, 0.5}; + CircleSDF sdf{5.0, 5.0, 1.0}; + geodex::SDFConformalMetric metric{base, sdf, 5.0, 3.0}; + + Eigen::Vector3d q(7.0, 5.0, 0.0); // sdf = 1.0 + Eigen::Vector3d u(1.0, 0.5, 0.2); + Eigen::Vector3d v(0.3, 1.0, -0.1); + + double c = metric.conformal_factor(q); + double base_inner = base.inner(q, u, v); + double scaled_inner = metric.inner(q, u, v); + + EXPECT_NEAR(scaled_inner, c * base_inner, 1e-12); +} + +// (f) Norm scales correctly (sqrt of conformal factor). +TEST(SDFConformalMetric, NormScaling) { + geodex::SE2LeftInvariantMetric base{1.0, 2.0, 0.5}; + CircleSDF sdf{5.0, 5.0, 1.0}; + geodex::SDFConformalMetric metric{base, sdf, 5.0, 3.0}; + + Eigen::Vector3d q(7.0, 5.0, 0.0); + Eigen::Vector3d v(1.0, 0.5, 0.2); + + double c = metric.conformal_factor(q); + double base_norm = base.norm(q, v); + double scaled_norm = metric.norm(q, v); + + EXPECT_NEAR(scaled_norm, std::sqrt(c) * base_norm, 1e-12); +} + +// (g) Smooth-min SDF: agrees with true min for well-separated obstacles. +TEST(CircleSmoothSDF, AgreesWithTrueMin) { + CircleSmoothSDF smooth; + smooth.circles = {{0.0, 0.0, 1.0}, {10.0, 0.0, 1.0}}; + smooth.beta_sdf = 20.0; + + // Point near first obstacle only — smooth-min ≈ true min + Eigen::Vector2d q_near(2.0, 0.0); + double d_true = 1.0; // dist to first circle surface = 2-1 = 1 + double d_smooth = smooth(q_near); + EXPECT_NEAR(d_smooth, d_true, 0.1); + + // Point equidistant between obstacles + Eigen::Vector2d q_mid(5.0, 0.0); + double d_true_mid = 4.0; // dist to either surface = 5-1 = 4 + double d_smooth_mid = smooth(q_mid); + // Smooth-min slightly below true min at Voronoi boundary + EXPECT_NEAR(d_smooth_mid, d_true_mid, 0.1); +} + +// (h) Smooth-min SDF: smooth gradient at Voronoi boundary. +TEST(CircleSmoothSDF, SmoothGradientAtVoronoi) { + CircleSmoothSDF smooth; + smooth.circles = {{0.0, 0.0, 1.0}, {6.0, 0.0, 1.0}}; + smooth.beta_sdf = 20.0; + + // Finite-difference gradient at the midpoint (Voronoi boundary) + double h = 1e-5; + Eigen::Vector2d q_mid(3.0, 0.0); + Eigen::Vector2d q_plus(3.0 + h, 0.0); + Eigen::Vector2d q_minus(3.0 - h, 0.0); + + double grad_x = (smooth(q_plus) - smooth(q_minus)) / (2.0 * h); + + // At midpoint between equal obstacles: gradient in x should be ~0 by symmetry + EXPECT_NEAR(grad_x, 0.0, 1e-3); + + // Gradient should be continuous: check on both sides + Eigen::Vector2d q_left(2.9, 0.0); + Eigen::Vector2d q_right(3.1, 0.0); + Eigen::Vector2d q_left_p(2.9 + h, 0.0); + Eigen::Vector2d q_left_m(2.9 - h, 0.0); + Eigen::Vector2d q_right_p(3.1 + h, 0.0); + Eigen::Vector2d q_right_m(3.1 - h, 0.0); + + double grad_left = (smooth(q_left_p) - smooth(q_left_m)) / (2.0 * h); + double grad_right = (smooth(q_right_p) - smooth(q_right_m)) / (2.0 * h); + + // Gradients point away from nearest obstacle (SDF increases away from surface) + EXPECT_GT(grad_left, 0.0); // closer to obstacle 1: gradient points right (away) + EXPECT_LT(grad_right, 0.0); // closer to obstacle 2: gradient points left (away) +} + +// (i) SDFConformalMetric works with ConfigurationSpace. +TEST(SDFConformalMetric, WorksWithConfigurationSpace) { + geodex::SE2LeftInvariantMetric base{1.0, 1.0, 0.5}; + CircleSDF sdf{5.0, 5.0, 1.0}; + geodex::SDFConformalMetric metric{base, sdf, 5.0, 3.0}; + + geodex::SE2<> se2{geodex::SE2LeftInvariantMetric{1.0, 1.0, 0.5}}; + geodex::ConfigurationSpace cspace{se2, metric}; + + Eigen::Vector3d p(7.0, 5.0, 0.0); + Eigen::Vector3d u(1.0, 0.0, 0.0); + Eigen::Vector3d v(0.0, 1.0, 0.0); + + // Should compile and return a valid inner product + double ip = cspace.inner(p, u, v); + double expected = metric.inner(p, u, v); + EXPECT_NEAR(ip, expected, 1e-12); +} + +// (j) Euclidean manifold: conformal metric produces longer paths near obstacles. +TEST(SDFConformalMetric, EuclideanDistanceIncreasesNearObstacle) { + using Euclidean2 = geodex::Euclidean<2>; + geodex::IdentityMetric<2> base; + CircleSDF sdf{5.0, 5.0, 1.0}; + geodex::SDFConformalMetric metric{base, sdf, 5.0, 3.0}; + + Euclidean2 euc; + geodex::ConfigurationSpace cspace{euc, metric}; + + // Two points, same Euclidean distance apart + Eigen::Vector2d a_far(50.0, 50.0), b_far(51.0, 50.0); // far from obstacle + Eigen::Vector2d a_near(6.5, 5.0), b_near(7.5, 5.0); // near obstacle + + double d_far = cspace.distance(a_far, b_far); + double d_near = cspace.distance(a_near, b_near); + + // Distance near obstacle should be larger (higher metric cost) + EXPECT_GT(d_near, d_far); +} + +// --------------------------------------------------------------------------- +// Path smoothing tests +// --------------------------------------------------------------------------- + +// (k) Shortcutting reduces path length on SE(2). +TEST(PathSmoothing, ShortcuttingReducesVertices) { + geodex::SE2LeftInvariantMetric metric{1.0, 1.0, 0.5}; + geodex::SE2<> manifold{metric}; + + // Create a zigzag path with redundant vertices. + std::vector path = { + {0.0, 0.0, 0.0}, {1.0, 1.0, 0.1}, {2.0, 0.5, 0.0}, + {3.0, 1.5, 0.2}, {4.0, 0.0, -0.1}, {5.0, 1.0, 0.0}, + }; + auto validity = [](const Eigen::Vector3d&) { return true; }; // no obstacles + + geodex::algorithm::PathSmoothingSettings settings; + settings.max_shortcut_attempts = 100; + settings.lbfgs_target_segments = 16; + settings.lbfgs_max_iterations = 50; + + auto result = geodex::algorithm::smooth_path(manifold, validity, path, settings); + + // Should have removed some vertices and reduced energy. + EXPECT_GE(result.vertices_removed, 0); + EXPECT_TRUE(result.collision_free); + EXPECT_GT(result.path.size(), 1u); +} + +// (l) L-BFGS smoothing reduces energy on SE(2) with anisotropic metric. +TEST(PathSmoothing, LBFGSReducesEnergy) { + geodex::SE2LeftInvariantMetric metric{1.0, 100.0, 0.5}; + geodex::SE2<> manifold{metric}; + + // Straight-line path in coordinates — not a geodesic for anisotropic metric. + std::vector path; + for (int i = 0; i <= 10; ++i) { + double t = static_cast(i) / 10.0; + path.push_back({t * 5.0, t * 2.0 + 0.5 * std::sin(t * 6.0), t * 0.5}); + } + + auto validity = [](const Eigen::Vector3d&) { return true; }; + + // Compute initial energy. + double E_before = 0.0; + for (std::size_t k = 0; k + 1 < path.size(); ++k) { + double d = manifold.distance(path[k], path[k + 1]); + E_before += d * d; + } + E_before *= static_cast(path.size() - 1); + + geodex::algorithm::PathSmoothingSettings settings; + settings.max_shortcut_attempts = 50; + settings.lbfgs_target_segments = 32; + settings.lbfgs_max_iterations = 100; + + auto result = geodex::algorithm::smooth_path(manifold, validity, path, settings); + + // Smoothed path should have lower energy. + EXPECT_LT(result.energy, E_before); + EXPECT_TRUE(result.collision_free); +} + +// (m) Collision-constrained smoothing respects obstacles. +TEST(PathSmoothing, RespectsObstacles) { + geodex::SE2LeftInvariantMetric metric{1.0, 1.0, 0.5}; + geodex::SE2<> manifold{metric}; + + // Path that goes around an obstacle at (2.5, 0.5). + std::vector path = { + {0.0, 0.0, 0.0}, {1.0, -1.0, 0.0}, {2.0, -2.0, 0.0}, + {3.0, -2.0, 0.0}, {4.0, -1.0, 0.0}, {5.0, 0.0, 0.0}, + }; + + double obs_cx = 2.5, obs_cy = 0.5, obs_r = 0.8; + auto validity = [&](const Eigen::Vector3d& q) { + double dx = q[0] - obs_cx, dy = q[1] - obs_cy; + return dx * dx + dy * dy > obs_r * obs_r; + }; + + geodex::algorithm::PathSmoothingSettings settings; + settings.max_shortcut_attempts = 100; + settings.lbfgs_target_segments = 32; + settings.lbfgs_max_iterations = 100; + + auto result = geodex::algorithm::smooth_path(manifold, validity, path, settings); + + EXPECT_TRUE(result.collision_free); + + // All path points should be outside the obstacle. + for (const auto& q : result.path) { + double dx = q[0] - obs_cx, dy = q[1] - obs_cy; + EXPECT_GT(dx * dx + dy * dy, obs_r * obs_r * 0.99); + } +} diff --git a/tests/test_collision.cpp b/tests/test_collision.cpp new file mode 100644 index 0000000..7178ca3 --- /dev/null +++ b/tests/test_collision.cpp @@ -0,0 +1,344 @@ +/// @file test_collision.cpp +/// @brief Tests for geodex::collision module. + +#include + +#include + +#include +#include + +#include "geodex/collision/circle_sdf.hpp" +#include "geodex/collision/distance_grid.hpp" +#include "geodex/collision/footprint_grid_checker.hpp" +#include "geodex/collision/polygon_footprint.hpp" +#include "geodex/collision/rectangle_sdf.hpp" +#include "geodex/utils/math.hpp" + +using namespace geodex::collision; + +// --------------------------------------------------------------------------- +// Fast exp +// --------------------------------------------------------------------------- + +TEST(FastExp, ApproximatesStdExp) { + // Schraudolph's trick with bias correction (c=60801, scaled by 2^32 for + // the 64-bit adaptation) gives ~4% max relative error — the inherent limit + // of a linear chord approximation to 2^f on each unit interval. + for (double x = -10.0; x <= 10.0; x += 0.5) { + const double approx = geodex::utils::fast_exp(x); + const double exact = std::exp(x); + EXPECT_NEAR(approx / exact, 1.0, 0.04) << "x=" << x; + } +} + +TEST(FastExp, ClampsLargeNegative) { + const double result = geodex::utils::fast_exp(-800.0); + EXPECT_GE(result, 0.0); + EXPECT_LT(result, 1e-300); +} + +// --------------------------------------------------------------------------- +// CircleSDF +// --------------------------------------------------------------------------- + +TEST(CircleSDF, DistanceOutside) { + CircleSDF c(0.0, 0.0, 1.0); + Eigen::Vector3d q(3.0, 0.0, 0.0); + EXPECT_NEAR(c(q), 2.0, 1e-12); +} + +TEST(CircleSDF, DistanceInside) { + CircleSDF c(0.0, 0.0, 2.0); + Eigen::Vector3d q(0.5, 0.0, 0.0); + EXPECT_NEAR(c(q), -1.5, 1e-12); +} + +TEST(CircleSDF, OnBoundary) { + CircleSDF c(1.0, 1.0, 0.5); + Eigen::Vector3d q(1.5, 1.0, 0.0); + EXPECT_NEAR(c(q), 0.0, 1e-12); +} + +TEST(CircleSmoothSDF, SingleCircle) { + CircleSmoothSDF sdf({CircleSDF(0.0, 0.0, 1.0)}, 20.0); + Eigen::Vector3d q(3.0, 0.0, 0.0); + EXPECT_NEAR(sdf(q), 2.0, 0.05); // smooth-min ~= exact for single obstacle +} + +TEST(CircleSmoothSDF, TwoCircles) { + CircleSmoothSDF sdf({CircleSDF(0.0, 0.0, 1.0), CircleSDF(5.0, 0.0, 1.0)}, 20.0); + // Midpoint between two circles: distance to each = 1.5. + Eigen::Vector3d q(2.5, 0.0, 0.0); + double d = sdf(q); + EXPECT_GT(d, 0.0); + // smooth-min should be slightly less than hard min (1.5). + EXPECT_LT(d, 1.5); + EXPECT_GT(d, 1.0); +} + +TEST(CircleSmoothSDF, IsFree) { + CircleSmoothSDF sdf({CircleSDF(0.0, 0.0, 1.0)}, 20.0); + Eigen::Vector3d inside(0.0, 0.0, 0.0); + Eigen::Vector3d outside(3.0, 0.0, 0.0); + EXPECT_FALSE(sdf.is_free(inside)); + EXPECT_TRUE(sdf.is_free(outside)); +} + +// --------------------------------------------------------------------------- +// RectObstacle and SAT +// --------------------------------------------------------------------------- + +TEST(RectOverlap, OverlappingRects) { + RectObstacle a{0.0, 0.0, 0.0, 1.0, 1.0}; + RectObstacle b{1.5, 0.0, 0.0, 1.0, 1.0}; + EXPECT_TRUE(rects_overlap(a, b)); +} + +TEST(RectOverlap, NonOverlappingRects) { + RectObstacle a{0.0, 0.0, 0.0, 1.0, 1.0}; + RectObstacle b{5.0, 0.0, 0.0, 1.0, 1.0}; + EXPECT_FALSE(rects_overlap(a, b)); +} + +TEST(RectOverlap, RotatedOverlap) { + RectObstacle a{0.0, 0.0, 0.0, 2.0, 0.5}; + RectObstacle b{1.0, 1.0, std::numbers::pi / 4.0, 2.0, 0.5}; + // Diagonal rectangle overlaps axis-aligned one. + EXPECT_TRUE(rects_overlap(a, b)); +} + +TEST(RectCorners, AxisAligned) { + RectObstacle r{0.0, 0.0, 0.0, 1.0, 0.5}; + auto corners = rect_corners(r); + EXPECT_NEAR(corners[0][0], -1.0, 1e-12); + EXPECT_NEAR(corners[0][1], -0.5, 1e-12); + EXPECT_NEAR(corners[2][0], 1.0, 1e-12); + EXPECT_NEAR(corners[2][1], 0.5, 1e-12); +} + +// --------------------------------------------------------------------------- +// RectSmoothSDF +// --------------------------------------------------------------------------- + +TEST(RectSmoothSDF, OutsideDistance) { + RectSmoothSDF sdf({RectObstacle{0.0, 0.0, 0.0, 1.0, 1.0}}, 20.0); + // Use a point within bounding sphere (skip_dist=1.0, diag=1.414, so br=2.414). + Eigen::Vector3d q(1.5, 0.0, 0.0); + double d = sdf(q); + EXPECT_NEAR(d, 0.5, 0.05); +} + +TEST(RectSmoothSDF, InsideDistance) { + RectSmoothSDF sdf({RectObstacle{0.0, 0.0, 0.0, 2.0, 2.0}}, 20.0); + Eigen::Vector3d q(0.0, 0.0, 0.0); + double d = sdf(q); + EXPECT_LT(d, 0.0); +} + +TEST(RectSmoothSDF, InflationReducesDistance) { + RectSmoothSDF no_infl({RectObstacle{0.0, 0.0, 0.0, 1.0, 1.0}}, 20.0, 0.0); + RectSmoothSDF with_infl({RectObstacle{0.0, 0.0, 0.0, 1.0, 1.0}}, 20.0, 0.5); + // Use a point within bounding sphere so SDF is computed, not clipped. + Eigen::Vector3d q(1.5, 0.0, 0.0); + EXPECT_NEAR(no_infl(q) - with_infl(q), 0.5, 0.05); +} + +// --------------------------------------------------------------------------- +// DistanceGrid +// --------------------------------------------------------------------------- + +TEST(DistanceGrid, BilinearInterpolation) { + // 3x3 grid with known values. + std::vector data = {0.0, 1.0, 2.0, 1.0, 2.0, 3.0, 2.0, 3.0, 4.0}; + DistanceGrid grid(3, 3, 1.0, data); + + // Exact grid points. + EXPECT_NEAR(grid.distance_at(0.0, 0.0), 0.0, 1e-12); + EXPECT_NEAR(grid.distance_at(1.0, 0.0), 1.0, 1e-12); + EXPECT_NEAR(grid.distance_at(1.0, 1.0), 2.0, 1e-12); + + // Bilinear midpoint: (0.5, 0.5) = avg(0, 1, 1, 2) = 1.0. + EXPECT_NEAR(grid.distance_at(0.5, 0.5), 1.0, 1e-12); +} + +TEST(DistanceGrid, BatchMatchesScalar) { + std::vector data = {0.0, 1.0, 2.0, 3.0, 1.0, 2.0, 3.0, 4.0, + 2.0, 3.0, 4.0, 5.0, 3.0, 4.0, 5.0, 6.0}; + DistanceGrid grid(4, 4, 1.0, data); + + double xs[] = {0.5, 1.3, 2.7, 0.1, 1.8}; + double ys[] = {0.5, 1.7, 0.2, 2.5, 2.1}; + double batch_out[5], scalar_out[5]; + + grid.distance_at_batch(xs, ys, batch_out, 5); + for (int i = 0; i < 5; ++i) { + scalar_out[i] = grid.distance_at(xs[i], ys[i]); + } + + for (int i = 0; i < 5; ++i) { + EXPECT_NEAR(batch_out[i], scalar_out[i], 1e-12) << "i=" << i; + } +} + +TEST(GridSDF, Callable) { + std::vector data = {1.0, 2.0, 3.0, 4.0}; + DistanceGrid grid(2, 2, 1.0, data); + GridSDF sdf(&grid); + + Eigen::Vector3d q(0.5, 0.5, 0.0); + EXPECT_NEAR(sdf(q), 2.5, 1e-12); +} + +TEST(InflatedSDF, SubtractsInflation) { + std::vector data = {5.0, 5.0, 5.0, 5.0}; + DistanceGrid grid(2, 2, 1.0, data); + GridSDF base_sdf(&grid); + InflatedSDF inflated(base_sdf, 1.5); + + Eigen::Vector3d q(0.0, 0.0, 0.0); + EXPECT_NEAR(inflated(q), 3.5, 1e-12); +} + +// --------------------------------------------------------------------------- +// PolygonFootprint +// --------------------------------------------------------------------------- + +TEST(PolygonFootprint, RectangleSampleCount) { + auto fp = PolygonFootprint::rectangle(2.0, 1.0, 4); + // 4 edges * 4 samples = 16, padded to even = 16. + EXPECT_EQ(fp.sample_count_raw(), 16); + EXPECT_EQ(fp.sample_count() % 2, 0); +} + +TEST(PolygonFootprint, BoundingRadius) { + auto fp = PolygonFootprint::rectangle(3.0, 4.0, 2); + // Diagonal of 3x4 rect = 5.0 + EXPECT_NEAR(fp.bounding_radius(), 5.0, 1e-12); +} + +TEST(PolygonFootprint, TransformIdentity) { + auto fp = PolygonFootprint::rectangle(1.0, 0.5, 2); + const int n = fp.sample_count(); + std::vector wx(n), wy(n); + + // Zero rotation, zero translation. + fp.transform(0.0, 0.0, 0.0, wx.data(), wy.data()); + + // World coords should match body coords. + for (int i = 0; i < fp.sample_count_raw(); ++i) { + EXPECT_NEAR(wx[i], fp.body_x()[i], 1e-12); + EXPECT_NEAR(wy[i], fp.body_y()[i], 1e-12); + } +} + +TEST(PolygonFootprint, TransformRotation90) { + auto fp = PolygonFootprint::rectangle(1.0, 0.5, 1); + // 4 edges * 1 sample = 4 samples (just corners). + const int n = fp.sample_count(); + std::vector wx(n), wy(n); + + fp.transform(0.0, 0.0, std::numbers::pi / 2.0, wx.data(), wy.data()); + + // After 90 deg rotation: (x,y) → (-y,x). + for (int i = 0; i < fp.sample_count_raw(); ++i) { + EXPECT_NEAR(wx[i], -fp.body_y()[i], 1e-10); + EXPECT_NEAR(wy[i], fp.body_x()[i], 1e-10); + } +} + +TEST(PolygonFootprint, TransformTranslation) { + auto fp = PolygonFootprint::rectangle(1.0, 0.5, 1); + const int n = fp.sample_count(); + std::vector wx(n), wy(n); + + fp.transform(10.0, 20.0, 0.0, wx.data(), wy.data()); + + for (int i = 0; i < fp.sample_count_raw(); ++i) { + EXPECT_NEAR(wx[i], fp.body_x()[i] + 10.0, 1e-12); + EXPECT_NEAR(wy[i], fp.body_y()[i] + 20.0, 1e-12); + } +} + +// --------------------------------------------------------------------------- +// FootprintGridChecker +// --------------------------------------------------------------------------- + +TEST(FootprintGridChecker, ClearInFreeSpace) { + // Uniform distance field: everywhere 5.0m clear. + std::vector data(100 * 100, 5.0); + DistanceGrid grid(100, 100, 0.1, data); // 10m x 10m world + + auto fp = PolygonFootprint::rectangle(0.5, 0.3, 4); + FootprintGridChecker checker(&grid, fp, 0.1); + + Eigen::Vector3d q(5.0, 5.0, 0.5); // center of the world + EXPECT_TRUE(checker.is_valid(q)); + EXPECT_GT(checker(q), 0.0); +} + +TEST(FootprintGridChecker, CollisionInObstacle) { + // Create a grid with a wall at x = 5m (columns 50+). + std::vector data(100 * 100, 5.0); + for (int r = 0; r < 100; ++r) { + for (int c = 50; c < 100; ++c) { + // Distance decreases as we approach the wall. + data[r * 100 + c] = static_cast(c - 50) * 0.1; + } + } + DistanceGrid grid(100, 100, 0.1, data); + + auto fp = PolygonFootprint::rectangle(0.5, 0.3, 4); + FootprintGridChecker checker(&grid, fp, 0.0); + + // Robot right at the wall edge — footprint extends into wall. + Eigen::Vector3d q(5.0, 5.0, 0.0); + EXPECT_FALSE(checker.is_valid(q)); + + // Robot well away from wall — should be clear. + Eigen::Vector3d q2(2.0, 5.0, 0.0); + EXPECT_TRUE(checker.is_valid(q2)); +} + +TEST(FootprintGridChecker, SafetyMargin) { + std::vector data(100 * 100, 1.0); // 1m clearance everywhere + DistanceGrid grid(100, 100, 0.1, data); + + auto fp = PolygonFootprint::rectangle(0.2, 0.2, 2); + + // With 0.5m safety margin, effective clearance = 1.0 - 0.5 = 0.5. + FootprintGridChecker small_margin(&grid, fp, 0.5); + EXPECT_TRUE(small_margin.is_valid(Eigen::Vector3d(5.0, 5.0, 0.0))); + + // With 1.5m safety margin, effective clearance = 1.0 - 1.5 = -0.5. + FootprintGridChecker big_margin(&grid, fp, 1.5); + EXPECT_FALSE(big_margin.is_valid(Eigen::Vector3d(5.0, 5.0, 0.0))); +} + +TEST(FootprintGridChecker, SDFCallable) { + std::vector data(100 * 100, 3.0); + DistanceGrid grid(100, 100, 0.1, data); + + auto fp = PolygonFootprint::rectangle(0.2, 0.2, 2); + FootprintGridChecker checker(&grid, fp, 0.5); + + Eigen::Vector3d q(5.0, 5.0, 0.0); + double sdf = checker(q); + // Early-out returns center_dist - bounding_radius - safety_margin. + // = 3.0 - sqrt(0.2^2+0.2^2) - 0.5 ~ 2.217 + const double expected = 3.0 - fp.bounding_radius() - 0.5; + EXPECT_NEAR(sdf, expected, 0.01); + EXPECT_GT(sdf, 0.0); +} + +TEST(FootprintGridChecker, Accessors) { + std::vector data(100 * 100, 3.0); + DistanceGrid grid(100, 100, 0.1, data); + + const auto fp = PolygonFootprint::rectangle(0.5, 0.3, 4); + const FootprintGridChecker checker(&grid, fp, 0.25); + + EXPECT_EQ(checker.grid(), &grid); + EXPECT_EQ(checker.footprint().sample_count(), fp.sample_count()); + EXPECT_DOUBLE_EQ(checker.safety_margin(), 0.25); +} diff --git a/tests/test_concepts.cpp b/tests/test_concepts.cpp index e234991..afe5014 100644 --- a/tests/test_concepts.cpp +++ b/tests/test_concepts.cpp @@ -1,7 +1,7 @@ +#include #include -#include -#include +#include "geodex/geodex.hpp" // A mock Euclidean manifold that satisfies all concepts. struct MockEuclidean { diff --git a/tests/test_configuration_space.cpp b/tests/test_configuration_space.cpp index f887cd0..761ed92 100644 --- a/tests/test_configuration_space.cpp +++ b/tests/test_configuration_space.cpp @@ -1,16 +1,17 @@ /// @file test_configuration_space.cpp /// @brief Tests for ConfigurationSpace manifold wrapper. -#include +#include #include -#include -#include -#include -#include -#include -#include -#include +#include + +#include "geodex/core/concepts.hpp" +#include "geodex/manifold/configuration_space.hpp" +#include "geodex/manifold/euclidean.hpp" +#include "geodex/manifold/torus.hpp" +#include "geodex/metrics/kinetic_energy.hpp" +#include "geodex/metrics/weighted.hpp" // --------------------------------------------------------------------------- // Concept checks @@ -27,8 +28,11 @@ static_assert(geodex::RiemannianManifold>; static_assert( geodex::RiemannianManifold, WeightedFlat>>); +// ConfigurationSpace, WeightedMetric>> no longer exposes +// injectivity_radius: after the refactor, ConstantSPDMetric is topology-agnostic and +// does not provide one, so WeightedMetric's forwarder drops out. static_assert( - geodex::HasInjectivityRadius, WeightedFlat>>); + !geodex::HasInjectivityRadius, WeightedFlat>>); // --------------------------------------------------------------------------- // Tests diff --git a/tests/test_euclidean.cpp b/tests/test_euclidean.cpp index d1d04db..75074b0 100644 --- a/tests/test_euclidean.cpp +++ b/tests/test_euclidean.cpp @@ -1,12 +1,14 @@ -#include - -#include -#include #include -#include + #include #include +#include +#include +#include + +#include "geodex/geodex.hpp" + using namespace geodex; // Compile-time concept checks diff --git a/tests/test_geodex_state_space.cpp b/tests/test_geodex_state_space.cpp new file mode 100644 index 0000000..38aab16 --- /dev/null +++ b/tests/test_geodex_state_space.cpp @@ -0,0 +1,527 @@ +/// @file test_geodex_state_space.cpp +/// @brief Tests for GeodexStateSpace OMPL integration. + +#include + +#include + +#include +#include +#include +#include + +#include "geodex/algorithm/interpolation.hpp" +#include "geodex/integration/ompl/geodex_state_space.hpp" +#include "geodex/manifold/euclidean.hpp" +#include "geodex/manifold/se2.hpp" +#include "geodex/metrics/constant_spd.hpp" + +namespace ob = ompl::base; +using SE2Manifold = geodex::SE2<>; +using StateSpace = geodex::integration::ompl::GeodexStateSpace; +using StateType = geodex::integration::ompl::GeodexState; + +// Anisotropic SE2 types (car-like: expensive lateral motion). +using AnisotropicSE2 = geodex::SE2; +using AnisotropicSE2Space = geodex::integration::ompl::GeodexStateSpace; +using AnisotropicSE2State = geodex::integration::ompl::GeodexState; + +// Anisotropic Euclidean types. +using AnisotropicEuclidean = geodex::Euclidean<2, geodex::ConstantSPDMetric<2>>; +using AnisotropicEuclideanSpace = geodex::integration::ompl::GeodexStateSpace; +using AnisotropicEuclideanState = geodex::integration::ompl::GeodexState; + +/// Helper: create SE(2) OMPL bounds. +static ob::RealVectorBounds makeSE2Bounds(double x_lo, double x_hi, double y_lo, double y_hi) { + ob::RealVectorBounds bounds(3); + bounds.setLow(0, x_lo); + bounds.setHigh(0, x_hi); + bounds.setLow(1, y_lo); + bounds.setHigh(1, y_hi); + bounds.setLow(2, -std::numbers::pi); + bounds.setHigh(2, std::numbers::pi); + return bounds; +} + +/// Helper: create a large SE(2) state space (mimicking Willow Garage scale). +static std::shared_ptr makeLargeSpace() { + geodex::SE2LeftInvariantMetric metric{1.0, 1.0, 0.5}; + geodex::SE2<> manifold{metric, geodex::SE2ExponentialMap{}, + Eigen::Vector3d(0.0, 0.0, -std::numbers::pi), + Eigen::Vector3d(60.0, 48.0, std::numbers::pi)}; + + return std::make_shared(manifold, makeSE2Bounds(0.0, 60.0, 0.0, 48.0)); +} + +/// Helper: set state values. +static void setState(ob::State* state, double x, double y, double theta) { + auto* s = state->as(); + s->values[0] = x; + s->values[1] = y; + s->values[2] = theta; +} + +// ----------------------------------------------------------------------- +// Test (a): Without collision resolution, validSegmentCount matches OMPL default +// ----------------------------------------------------------------------- + +TEST(GeodexStateSpaceTest, ValidSegmentCount_DefaultMatchesOMPL) { + auto space = makeLargeSpace(); + + // Must create SpaceInformation and call setup() so longestValidSegmentLength_ + // is computed from longestValidSegmentFraction * maxExtent. + auto si = std::make_shared(space); + si->setStateValidityChecker([](const ob::State*) { return true; }); + si->setup(); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + setState(s1, 2.0, 5.0, 0.0); + setState(s2, 8.0, 5.0, 0.0); + + // OMPL default: ceil(distance / (longestValidSegmentFraction * maxExtent)) + double dist = space->distance(s1, s2); + double lvs = space->getLongestValidSegmentFraction() * space->getMaximumExtent(); + unsigned int expected = static_cast(std::ceil(dist / lvs)); + + EXPECT_EQ(space->validSegmentCount(s1, s2), expected); + + space->freeState(s1); + space->freeState(s2); +} + +// ----------------------------------------------------------------------- +// Test (b): Collision resolution increases segment count +// ----------------------------------------------------------------------- + +TEST(GeodexStateSpaceTest, ValidSegmentCount_CollisionResolutionIncreasesCount) { + auto space = makeLargeSpace(); + space->setCollisionResolution(0.05); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + setState(s1, 0.0, 5.0, 0.0); + setState(s2, 10.0, 5.0, 0.0); + + unsigned int n = space->validSegmentCount(s1, s2); + // 10m / 0.05m = 200 segments minimum + EXPECT_GE(n, 200u); + + space->freeState(s1); + space->freeState(s2); +} + +// ----------------------------------------------------------------------- +// Test (c): Thin wall detection — the critical regression test +// ----------------------------------------------------------------------- + +/// Validity checker that rejects states with 5.0 < x < 5.2 (a 0.2m wall). +class ThinWallChecker : public ob::StateValidityChecker { + public: + using ob::StateValidityChecker::StateValidityChecker; + + bool isValid(const ob::State* state) const override { + const auto* s = state->as(); + double x = s->values[0]; + return x <= 5.0 || x >= 5.2; + } +}; + +TEST(GeodexStateSpaceTest, CollisionCheck_ThinWallDetected) { + auto space = makeLargeSpace(); + + auto si = std::make_shared(space); + si->setStateValidityChecker(std::make_shared(si)); + + // Without collision resolution: wall should be missed + si->setup(); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + setState(s1, 2.0, 5.0, 0.0); + setState(s2, 8.0, 5.0, 0.0); + + auto mv_default = std::make_shared(si); + // The default segment length is ~0.78m, so the 0.2m wall is likely missed + EXPECT_TRUE(mv_default->checkMotion(s1, s2)) + << "Expected OMPL default to miss the thin wall (test setup issue if this fails)"; + + // With collision resolution: wall should be detected + space->setCollisionResolution(0.05); + si->setup(); // recalculate internal state + + auto mv_fine = std::make_shared(si); + EXPECT_FALSE(mv_fine->checkMotion(s1, s2)) + << "With collision resolution 0.05m, the 0.2m wall must be detected"; + + space->freeState(s1); + space->freeState(s2); +} + +// ----------------------------------------------------------------------- +// Test (d): Thin wall detection with rotation +// ----------------------------------------------------------------------- + +TEST(GeodexStateSpaceTest, CollisionCheck_ThinWallDetected_WithRotation) { + auto space = makeLargeSpace(); + space->setCollisionResolution(0.05); + + auto si = std::make_shared(space); + si->setStateValidityChecker(std::make_shared(si)); + si->setup(); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + setState(s1, 2.0, 5.0, 0.0); + setState(s2, 8.0, 5.0, std::numbers::pi / 2.0); + + auto mv = std::make_shared(si); + EXPECT_FALSE(mv->checkMotion(s1, s2)) << "Wall must be detected even when path includes rotation"; + + space->freeState(s1); + space->freeState(s2); +} + +// ----------------------------------------------------------------------- +// Test (e): Interpolated path stays collision-free on a valid edge +// ----------------------------------------------------------------------- + +TEST(GeodexStateSpaceTest, Interpolation_StaysCollisionFree) { + auto space = makeLargeSpace(); + space->setCollisionResolution(0.05); + + auto si = std::make_shared(space); + si->setStateValidityChecker(std::make_shared(si)); + si->setup(); + + // Both states on the same side of the wall — valid edge + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + setState(s1, 1.0, 5.0, 0.0); + setState(s2, 4.0, 10.0, 1.0); + + auto mv = std::make_shared(si); + EXPECT_TRUE(mv->checkMotion(s1, s2)) << "Edge that doesn't cross the wall should be valid"; + + // Interpolate and verify all points are valid + unsigned int n = space->validSegmentCount(s1, s2); + auto* interp = space->allocState(); + for (unsigned int i = 0; i <= n; ++i) { + double t = static_cast(i) / static_cast(n); + space->interpolate(s1, s2, t, interp); + EXPECT_TRUE(si->isValid(interp)) << "Interpolated state at t=" << t << " is invalid"; + } + + space->freeState(interp); + space->freeState(s1); + space->freeState(s2); +} + +// ======================================================================== +// Discrete geodesic interpolation tests +// ======================================================================== + +// ----------------------------------------------------------------------- +// Test (f): Identity metric takes the fast path (no discrete geodesic) +// ----------------------------------------------------------------------- + +TEST(GeodexDiscreteGeodesicTest, IdentityMetric_InterpolateUnchanged) { + geodex::SE2LeftInvariantMetric metric{1.0, 1.0, 1.0}; // unit weights → fast path + geodex::SE2<> manifold{metric}; + + auto bounds = makeSE2Bounds(0.0, 10.0, 0.0, 10.0); + auto space = std::make_shared(manifold, bounds); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + auto* result = space->allocState(); + setState(s1, 2.0, 3.0, 0.5); + setState(s2, 8.0, 7.0, -1.0); + + // Auto mode: identity metric should take the fast path via is_riemannian_log + // (default is nullopt = auto) + + // Compute expected result using manifold.geodesic() directly + auto p1 = s1->as()->asEigen(); + auto p2 = s2->as()->asEigen(); + + for (int j = 1; j <= 10; ++j) { + double t = j / 10.0; + space->interpolate(s1, s2, t, result); + auto expected = manifold.geodesic(p1, p2, t); + auto* r = result->as(); + for (int i = 0; i < 3; ++i) { + EXPECT_DOUBLE_EQ(r->values[i], expected[i]) << "Mismatch at t=" << t << " dim=" << i; + } + } + + space->freeState(result); + space->freeState(s1); + space->freeState(s2); +} + +// ----------------------------------------------------------------------- +// Test (g): DisableFlag forces simple geodesic even for anisotropic metric +// ----------------------------------------------------------------------- + +TEST(GeodexDiscreteGeodesicTest, DisableFlag_ForcesSimpleGeodesic) { + geodex::SE2LeftInvariantMetric metric{1.0, 100.0, 0.5}; + AnisotropicSE2 manifold{metric}; + + auto bounds = makeSE2Bounds(0.0, 10.0, 0.0, 10.0); + auto space = std::make_shared(manifold, bounds); + space->setInterpolationMode(geodex::integration::ompl::InterpolationMode::BaseGeodesic); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + auto* result = space->allocState(); + s1->as()->values[0] = 2.0; + s1->as()->values[1] = 3.0; + s1->as()->values[2] = 0.0; + s2->as()->values[0] = 8.0; + s2->as()->values[1] = 7.0; + s2->as()->values[2] = 0.0; + + // With discrete geodesic disabled, result should match manifold.geodesic() + auto p1 = s1->as()->asEigen(); + auto p2 = s2->as()->asEigen(); + + for (int j = 1; j <= 10; ++j) { + double t = j / 10.0; + space->interpolate(s1, s2, t, result); + auto expected = manifold.geodesic(p1, p2, t); + auto* r = result->as(); + for (int i = 0; i < 3; ++i) { + EXPECT_NEAR(r->values[i], expected[i], 1e-12) + << "Disabled discrete geodesic should match manifold.geodesic() at t=" << t; + } + } + + space->freeState(result); + space->freeState(s1); + space->freeState(s2); +} + +// ----------------------------------------------------------------------- +// Test (h): Boundary values return exact endpoints +// ----------------------------------------------------------------------- + +TEST(GeodexDiscreteGeodesicTest, BoundaryValues_ExactEndpoints) { + geodex::SE2LeftInvariantMetric metric{1.0, 100.0, 0.5}; + AnisotropicSE2 manifold{metric}; + + auto bounds = makeSE2Bounds(0.0, 10.0, 0.0, 10.0); + auto space = std::make_shared(manifold, bounds); + space->setInterpolationMode(geodex::integration::ompl::InterpolationMode::RiemannianGeodesic); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + auto* result = space->allocState(); + s1->as()->values[0] = 2.0; + s1->as()->values[1] = 3.0; + s1->as()->values[2] = 0.5; + s2->as()->values[0] = 8.0; + s2->as()->values[1] = 7.0; + s2->as()->values[2] = -1.0; + + // t=0 should return exact start + space->interpolate(s1, s2, 0.0, result); + for (int i = 0; i < 3; ++i) { + EXPECT_DOUBLE_EQ(result->as()->values[i], + s1->as()->values[i]) + << "t=0 should return exact start at dim=" << i; + } + + // t=1 should return exact end + space->interpolate(s1, s2, 1.0, result); + for (int i = 0; i < 3; ++i) { + EXPECT_DOUBLE_EQ(result->as()->values[i], + s2->as()->values[i]) + << "t=1 should return exact end at dim=" << i; + } + + space->freeState(result); + space->freeState(s1); + space->freeState(s2); +} + +// ----------------------------------------------------------------------- +// Test (i): Anisotropic Euclidean — monotone distance along interpolation +// ----------------------------------------------------------------------- + +TEST(GeodexDiscreteGeodesicTest, AnisotropicEuclidean_MonotoneDistance) { + Eigen::Matrix2d A; + A << 4.0, 0.0, 0.0, 1.0; // 4x weight on x-axis + geodex::ConstantSPDMetric<2> metric{A}; + AnisotropicEuclidean manifold{metric}; + + ob::RealVectorBounds bounds(2); + bounds.setLow(0.0); + bounds.setHigh(10.0); + auto space = std::make_shared(manifold, bounds); + space->setInterpolationMode(geodex::integration::ompl::InterpolationMode::RiemannianGeodesic); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + auto* result = space->allocState(); + s1->as()->values[0] = 1.0; + s1->as()->values[1] = 1.0; + s2->as()->values[0] = 9.0; + s2->as()->values[1] = 9.0; + + // distance(from, interp(t)) should be monotonically increasing + double prev_dist = 0.0; + const int N = 20; + for (int j = 1; j <= N; ++j) { + double t = static_cast(j) / N; + space->interpolate(s1, s2, t, result); + double d = space->distance(s1, result); + EXPECT_GE(d, prev_dist - 1e-10) << "Distance should be monotonically increasing at t=" << t; + prev_dist = d; + } + + space->freeState(result); + space->freeState(s1); + space->freeState(s2); +} + +// ----------------------------------------------------------------------- +// Test (j): Anisotropic SE2 — discrete geodesic path has lower energy +// ----------------------------------------------------------------------- + +TEST(GeodexDiscreteGeodesicTest, AnisotropicSE2_BetterThanRetraction) { + geodex::SE2LeftInvariantMetric metric{1.0, 100.0, 0.5}; + AnisotropicSE2 manifold{metric}; + + auto bounds = makeSE2Bounds(0.0, 10.0, 0.0, 10.0); + auto space = std::make_shared(manifold, bounds); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + s1->as()->values[0] = 2.0; + s1->as()->values[1] = 2.0; + s1->as()->values[2] = 0.0; + s2->as()->values[0] = 8.0; + s2->as()->values[1] = 8.0; + s2->as()->values[2] = 1.0; + + auto p1 = s1->as()->asEigen(); + auto p2 = s2->as()->asEigen(); + + // Compute total path length with discrete geodesic interpolation + const int N = 20; + auto* prev = space->allocState(); + auto* curr = space->allocState(); + space->copyState(prev, s1); + + double discrete_length = 0.0; + space->setInterpolationMode(geodex::integration::ompl::InterpolationMode::RiemannianGeodesic); + for (int j = 1; j <= N; ++j) { + space->interpolate(s1, s2, static_cast(j) / N, curr); + discrete_length += space->distance(prev, curr); + space->copyState(prev, curr); + } + + // Compute total path length with simple retraction interpolation + double retraction_length = 0.0; + space->copyState(prev, s1); + space->setInterpolationMode(geodex::integration::ompl::InterpolationMode::BaseGeodesic); + for (int j = 1; j <= N; ++j) { + space->interpolate(s1, s2, static_cast(j) / N, curr); + retraction_length += space->distance(prev, curr); + space->copyState(prev, curr); + } + + // Discrete geodesic path should be shorter or equal (energy-minimizing) + EXPECT_LE(discrete_length, retraction_length + 1e-6) + << "Discrete geodesic path should have lower or equal total length.\n" + << " discrete: " << discrete_length << "\n" + << " retraction: " << retraction_length; + + space->freeState(curr); + space->freeState(prev); + space->freeState(s1); + space->freeState(s2); +} + +// ----------------------------------------------------------------------- +// Test (k): Anisotropic SE2 — thin wall still detected +// ----------------------------------------------------------------------- + +TEST(GeodexDiscreteGeodesicTest, AnisotropicSE2_ThinWallDetected) { + geodex::SE2LeftInvariantMetric metric{1.0, 100.0, 0.5}; + AnisotropicSE2 manifold{metric}; + + auto bounds = makeSE2Bounds(0.0, 60.0, 0.0, 48.0); + auto space = std::make_shared(manifold, bounds); + space->setCollisionResolution(0.05); + space->setInterpolationMode(geodex::integration::ompl::InterpolationMode::RiemannianGeodesic); + + auto si = std::make_shared(space); + // Thin wall at x in [5.0, 5.2] + si->setStateValidityChecker([](const ob::State* state) { + const auto* s = state->as(); + double x = s->values[0]; + return x <= 5.0 || x >= 5.2; + }); + si->setup(); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + s1->as()->values[0] = 2.0; + s1->as()->values[1] = 5.0; + s1->as()->values[2] = 0.0; + s2->as()->values[0] = 8.0; + s2->as()->values[1] = 5.0; + s2->as()->values[2] = 0.0; + + auto mv = std::make_shared(si); + EXPECT_FALSE(mv->checkMotion(s1, s2)) + << "Thin wall must be detected with anisotropic metric + discrete geodesic"; + + space->freeState(s1); + space->freeState(s2); +} + +// ----------------------------------------------------------------------- +// Test (l): Convergence failure falls back gracefully +// ----------------------------------------------------------------------- + +TEST(GeodexDiscreteGeodesicTest, ConvFailure_GracefulFallback) { + geodex::SE2LeftInvariantMetric metric{1.0, 100.0, 0.5}; + AnisotropicSE2 manifold{metric}; + + auto bounds = makeSE2Bounds(0.0, 10.0, 0.0, 10.0); + auto space = std::make_shared(manifold, bounds); + space->setInterpolationMode(geodex::integration::ompl::InterpolationMode::RiemannianGeodesic); + + // Use very restrictive settings to force convergence issues + geodex::InterpolationSettings settings; + settings.max_steps = 1; // very limited budget + settings.step_size = 0.01; + space->setInterpolationSettings(settings); + + auto* s1 = space->allocState(); + auto* s2 = space->allocState(); + auto* result = space->allocState(); + s1->as()->values[0] = 1.0; + s1->as()->values[1] = 1.0; + s1->as()->values[2] = 0.0; + s2->as()->values[0] = 9.0; + s2->as()->values[1] = 9.0; + s2->as()->values[2] = 2.0; + + // Should not crash — falls back to simple geodesic or uses partial path + EXPECT_NO_FATAL_FAILURE({ space->interpolate(s1, s2, 0.5, result); }); + + // Result should be a valid state (not NaN) + auto* r = result->as(); + for (int i = 0; i < 3; ++i) { + EXPECT_FALSE(std::isnan(r->values[i])) << "Result should not be NaN at dim=" << i; + EXPECT_TRUE(std::isfinite(r->values[i])) << "Result should be finite at dim=" << i; + } + + space->freeState(result); + space->freeState(s1); + space->freeState(s2); +} diff --git a/tests/test_interpolation.cpp b/tests/test_interpolation.cpp new file mode 100644 index 0000000..608d2de --- /dev/null +++ b/tests/test_interpolation.cpp @@ -0,0 +1,419 @@ +#include + +#include + +#include +#include + +#include "geodex/geodex.hpp" +#include "geodex/metrics/clearance.hpp" + +using namespace geodex; + +static Eigen::Vector3d point_at_theta(double theta) { + return Eigen::Vector3d(std::sin(theta), 0.0, std::cos(theta)); +} + +// --------------------------------------------------------------------------- +// Round metric tests +// --------------------------------------------------------------------------- + +class InterpolationRoundTest : public ::testing::Test { + protected: + Sphere<> sphere; + Eigen::Vector3d north{0.0, 0.0, 1.0}; +}; + +TEST_F(InterpolationRoundTest, ConvergesToTarget) { + auto target = point_at_theta(1.0); + auto r = discrete_geodesic(sphere, north, target); + + EXPECT_EQ(r.status, InterpolationStatus::Converged); + ASSERT_GE(r.path.size(), 2u); + double final_dist = sphere.distance(r.path.back(), target); + EXPECT_LT(final_dist, 1e-3); +} + +TEST_F(InterpolationRoundTest, PathOnSphere) { + auto target = point_at_theta(1.0); + auto r = discrete_geodesic(sphere, north, target); + + for (const auto& p : r.path) { + EXPECT_NEAR(p.norm(), 1.0, 1e-10); + } +} + +TEST_F(InterpolationRoundTest, PathLength) { + auto target = point_at_theta(1.0); + auto r = discrete_geodesic(sphere, north, target); + + double total_length = 0.0; + for (size_t i = 1; i < r.path.size(); ++i) { + total_length += distance_midpoint(sphere, r.path[i - 1], r.path[i]); + } + + double expected = sphere.distance(north, target); + EXPECT_NEAR(total_length, expected, 0.05); +} + +TEST_F(InterpolationRoundTest, Antipodal) { + // At the cut locus, log returns zero, so we report CutLocus status and + // return a single-point path. The distance between start and target is + // still pi, but log can't give us a direction. + Eigen::Vector3d south(0.0, 0.0, -1.0); + auto r = discrete_geodesic(sphere, north, south); + + EXPECT_EQ(r.status, InterpolationStatus::CutLocus); + ASSERT_EQ(r.path.size(), 1u); + EXPECT_NEAR((r.path[0] - north).norm(), 0.0, 1e-12); +} + +// --------------------------------------------------------------------------- +// Anisotropic metric tests +// --------------------------------------------------------------------------- + +TEST(InterpolationAnisotropic, ConvergesToTarget) { + Eigen::Matrix3d A = Eigen::Matrix3d::Identity(); + A(0, 0) = 4.0; + Sphere<2, ConstantSPDMetric<3>> sphere{ConstantSPDMetric<3>{A}}; + + Eigen::Vector3d north(0.0, 0.0, 1.0); + auto target = point_at_theta(0.8); + + auto r = discrete_geodesic(sphere, north, target); + EXPECT_EQ(r.status, InterpolationStatus::Converged); + ASSERT_GE(r.path.size(), 2u); + + double final_dist = distance_midpoint(sphere, r.path.back(), target); + EXPECT_LT(final_dist, 1e-3); +} + +// --------------------------------------------------------------------------- +// Edge cases +// --------------------------------------------------------------------------- + +TEST_F(InterpolationRoundTest, IdenticalPoints) { + auto r = discrete_geodesic(sphere, north, north); + + EXPECT_EQ(r.status, InterpolationStatus::DegenerateInput); + ASSERT_EQ(r.path.size(), 1u); + EXPECT_NEAR((r.path[0] - north).norm(), 0.0, 1e-12); +} + +TEST_F(InterpolationRoundTest, RespectsMaxSteps) { + auto target = point_at_theta(2.5); + + InterpolationSettings settings; + settings.max_steps = 3; + settings.step_size = 0.1; + + auto r = discrete_geodesic(sphere, north, target, settings); + + // Path should have at most max_steps + 1 points (start + up to max_steps steps). + EXPECT_LE(static_cast(r.path.size()), settings.max_steps + 1); +} + +// --------------------------------------------------------------------------- +// Status reporting +// --------------------------------------------------------------------------- + +TEST_F(InterpolationRoundTest, ReportsConvergedOnSuccess) { + auto target = point_at_theta(1.0); + auto r = discrete_geodesic(sphere, north, target); + + EXPECT_EQ(r.status, InterpolationStatus::Converged); + EXPECT_GT(r.iterations, 0); + EXPECT_GT(r.initial_distance, 0.5); + EXPECT_LT(r.final_distance, 1e-3); + EXPECT_EQ(r.distortion_halvings, 0); +} + +TEST_F(InterpolationRoundTest, ReportsMaxStepsOnTightBudget) { + // Walk across ~2.5 rad with step_size 0.1 needs ~25 steps; give only 2. + auto target = point_at_theta(2.5); + InterpolationSettings settings; + settings.max_steps = 2; + settings.step_size = 0.1; + + auto r = discrete_geodesic(sphere, north, target, settings); + + EXPECT_EQ(r.status, InterpolationStatus::MaxStepsReached); + EXPECT_EQ(r.iterations, 2); + EXPECT_GT(r.final_distance, settings.convergence_tol); +} + +TEST_F(InterpolationRoundTest, ReportsCutLocusOnAntipodal) { + Eigen::Vector3d south(0.0, 0.0, -1.0); + auto r = discrete_geodesic(sphere, north, south); + + EXPECT_EQ(r.status, InterpolationStatus::CutLocus); + EXPECT_EQ(r.iterations, 0); + ASSERT_EQ(r.path.size(), 1u); +} + +TEST_F(InterpolationRoundTest, ReportsDegenerateOnIdenticalInput) { + auto r = discrete_geodesic(sphere, north, north); + + EXPECT_EQ(r.status, InterpolationStatus::DegenerateInput); + EXPECT_EQ(r.iterations, 0); + EXPECT_EQ(r.initial_distance, 0.0); + EXPECT_EQ(r.final_distance, 0.0); + ASSERT_EQ(r.path.size(), 1u); +} + +// --------------------------------------------------------------------------- +// Monotone distance decrease +// --------------------------------------------------------------------------- + +TEST_F(InterpolationRoundTest, MonotoneDistanceDecrease) { + auto target = point_at_theta(1.5); + InterpolationSettings settings; + settings.step_size = 0.2; + auto r = discrete_geodesic(sphere, north, target, settings); + + ASSERT_GE(r.path.size(), 2u); + double prev_dist = sphere.distance(r.path.front(), target); + for (size_t i = 1; i < r.path.size(); ++i) { + double cur_dist = sphere.distance(r.path[i], target); + // Allow 1% slack for numerical noise. + EXPECT_LE(cur_dist, prev_dist * 1.01 + 1e-9) + << "Distance increased from " << prev_dist << " to " << cur_dist << " at step " << i; + prev_dist = cur_dist; + } +} + +// --------------------------------------------------------------------------- +// Non-Riemannian retraction — projection retract on the sphere +// --------------------------------------------------------------------------- + +TEST(InterpolationNonRiemannian, SphereProjectionRetractionConverges) { + // Projection retraction is first-order, not the true exp map. The log-fast-path + // will still make progress (strict monotone decrease), but may be less accurate + // per step than the true exp map. + using SphereProj = Sphere<2, SphereRoundMetric, SphereProjectionRetraction>; + SphereProj sphere; + Eigen::Vector3d north(0.0, 0.0, 1.0); + Eigen::Vector3d target(std::sin(1.0), 0.0, std::cos(1.0)); + + InterpolationSettings settings; + settings.step_size = 0.3; + settings.max_steps = 200; + + auto r = discrete_geodesic(sphere, north, target, settings); + EXPECT_EQ(r.status, InterpolationStatus::Converged); + ASSERT_GE(r.path.size(), 2u); + + // Final point should be close to target. + const double final_dist = sphere.distance(r.path.back(), target); + EXPECT_LT(final_dist, 1e-2); + + // All points should remain on the unit sphere. + for (const auto& p : r.path) { + EXPECT_NEAR(p.norm(), 1.0, 1e-10); + } +} + +TEST(InterpolationNonRiemannian, SE2EulerRetractionConverges) { + // Euler retraction treats SE(2) as R^2 x S^1 — ignores group structure, but the + // log-fast-path should still reach target under strict monotone decrease. + using SE2Euler = SE2; + SE2Euler se2; + Eigen::Vector3d start(1.0, 1.0, 0.0); + Eigen::Vector3d target(3.0, 3.0, 0.5); + + InterpolationSettings settings; + settings.step_size = 0.3; + auto r = discrete_geodesic(se2, start, target, settings); + EXPECT_EQ(r.status, InterpolationStatus::Converged); + EXPECT_LT(r.final_distance, 1e-2); +} + +TEST(InterpolationNonRiemannian, SE2AnisotropicWeights) { + // Anisotropic weights on SE(2) make the Lie group exp/log disagree with the + // Riemannian geodesic, but the algorithm should still reach the target. + SE2 se2(SE2LeftInvariantMetric{1.0, 1.0, 5.0}); + Eigen::Vector3d start(1.0, 1.0, 0.0); + Eigen::Vector3d target(4.0, 3.0, 1.0); + + InterpolationSettings settings; + settings.step_size = 0.3; + auto r = discrete_geodesic(se2, start, target, settings); + EXPECT_EQ(r.status, InterpolationStatus::Converged); + EXPECT_LT(r.final_distance, 1e-2); +} + +// --------------------------------------------------------------------------- +// Dynamic vs fixed-size manifolds +// --------------------------------------------------------------------------- + +TEST(InterpolationDynamic, TorusDynamicMatchesFixed) { + Eigen::Vector2d start_fixed(0.5, 0.5); + Eigen::Vector2d target_fixed(2.5, 2.5); + Eigen::VectorXd start_dyn(2), target_dyn(2); + start_dyn << 0.5, 0.5; + target_dyn << 2.5, 2.5; + + InterpolationSettings settings; + settings.step_size = 0.3; + + Torus<2> torus_fixed; + auto r_fixed = discrete_geodesic(torus_fixed, start_fixed, target_fixed, settings); + + Torus torus_dyn(2); + auto r_dyn = discrete_geodesic(torus_dyn, start_dyn, target_dyn, settings); + + ASSERT_EQ(r_fixed.path.size(), r_dyn.path.size()); + for (size_t i = 0; i < r_fixed.path.size(); ++i) { + EXPECT_LT((r_fixed.path[i] - r_dyn.path[i]).norm(), 1e-12); + } + EXPECT_EQ(r_fixed.status, r_dyn.status); + EXPECT_EQ(r_fixed.iterations, r_dyn.iterations); +} + +// --------------------------------------------------------------------------- +// ConfigurationSpace with KineticEnergyMetric (constant mass matrix) +// --------------------------------------------------------------------------- + +TEST(InterpolationConfigSpace, TorusConstantKineticEnergyConverges) { + // Constant mass matrix = diag(2, 1). The KE metric is flat (point-independent), + // so the base log is still the Riemannian log of the KE metric (same geodesics). + // The fast path should apply and the walk should reach the target. + auto mass_matrix_fn = [](const Eigen::Vector2d& /*q*/) { + Eigen::Matrix2d M; + M << 2.0, 0.0, 0.0, 1.0; + return M; + }; + auto ke = KineticEnergyMetric{mass_matrix_fn}; + ConfigurationSpace cspace{Torus<2>{}, std::move(ke)}; + + Eigen::Vector2d start(0.5, 0.5); + Eigen::Vector2d target(2.5, 2.5); + + InterpolationSettings settings; + settings.step_size = 0.3; + auto r = discrete_geodesic(cspace, start, target, settings); + EXPECT_EQ(r.status, InterpolationStatus::Converged); + EXPECT_LT(r.final_distance, 1e-2); + + // For a constant mass matrix, the geodesic is still linear in base coordinates. + // Check that intermediate path points lie approximately on the line segment. + for (const auto& p : r.path) { + // Parameterize: start + t * (target - start), solve for t. + Eigen::Vector2d delta = target - start; + double t = (p - start).dot(delta) / delta.squaredNorm(); + Eigen::Vector2d on_line = start + t * delta; + EXPECT_LT((p - on_line).norm(), 1e-2); + } +} + +// --------------------------------------------------------------------------- +// Workspace reuse +// --------------------------------------------------------------------------- + +TEST_F(InterpolationRoundTest, WorkspaceReuseProducesIdenticalResults) { + auto target = point_at_theta(1.0); + auto r_no_ws = discrete_geodesic(sphere, north, target); + + InterpolationCache> ws; + auto r_with_ws = discrete_geodesic(sphere, north, target, {}, &ws); + + ASSERT_EQ(r_no_ws.path.size(), r_with_ws.path.size()); + for (size_t i = 0; i < r_no_ws.path.size(); ++i) { + EXPECT_LT((r_no_ws.path[i] - r_with_ws.path[i]).norm(), 1e-12); + } + EXPECT_EQ(r_no_ws.status, r_with_ws.status); + EXPECT_EQ(r_no_ws.iterations, r_with_ws.iterations); + + // Reuse across multiple calls — should still produce identical results. + auto r_reused = discrete_geodesic(sphere, north, target, {}, &ws); + ASSERT_EQ(r_with_ws.path.size(), r_reused.path.size()); +} + +// --------------------------------------------------------------------------- +// Midpoint FD surrogate with runtime guard +// --------------------------------------------------------------------------- + +// Arc cost = sum of per-segment Riemannian norms along the path, measured with +// the given manifold's metric. Useful for comparing surrogate quality. +template +static double arc_cost(const M& m, const std::vector& path) { + double sum = 0.0; + for (size_t i = 1; i < path.size(); ++i) { + const auto v = m.log(path[i - 1], path[i]); + sum += m.norm(path[i - 1], v); + } + return sum; +} + +TEST(InterpolationGuardedMidpoint, SE2SDFConformalConverges) { + // SE(2) with a mild SDFConformalMetric over a circular obstacle. Both the + // midpoint FD (default) and via-log FD (tau=0) should converge, and the new + // counter should be exposed and correctly reporting. + auto sdf = [](const Eigen::Vector3d& q) { + const double r = std::sqrt(q[0] * q[0] + q[1] * q[1]); + return r - 1.0; // unit circle at origin, positive outside + }; + + SE2LeftInvariantMetric base_metric{1.0, 1.0, 0.5}; + SE2 se2{base_metric}; + SDFConformalMetric clearance_metric{base_metric, sdf, 2.0, 2.0}; + ConfigurationSpace cspace{se2, clearance_metric}; + + // Path above the obstacle; the straight-line path only grazes high-c region. + const Eigen::Vector3d start(-2.0, 1.5, 0.0); + const Eigen::Vector3d target(2.0, 1.5, 0.0); + + InterpolationSettings midpoint_settings; + midpoint_settings.step_size = 0.2; + midpoint_settings.max_steps = 200; + midpoint_settings.convergence_tol = 1e-3; + // default fd_midpoint_guard_tau = 0.25 + + InterpolationSettings vialog_settings = midpoint_settings; + vialog_settings.fd_midpoint_guard_tau = 0.0; // force via-log on every sample + + auto r_midpoint = discrete_geodesic(cspace, start, target, midpoint_settings); + auto r_vialog = discrete_geodesic(cspace, start, target, vialog_settings); + + EXPECT_EQ(r_midpoint.status, InterpolationStatus::Converged); + EXPECT_EQ(r_vialog.status, InterpolationStatus::Converged); + + // SE(2) + SE2ExponentialMap gives v_ma + v_mb = 0 exactly (group midpoint + // identity), so the default-tau guard should not trip. + EXPECT_EQ(r_midpoint.fd_midpoint_fallbacks, 0); + + // Every FD sample trips under tau=0 (any nonzero imbalance exceeds zero); + // counter should be nonzero. + EXPECT_GT(r_vialog.fd_midpoint_fallbacks, 0); +} + +TEST(InterpolationGuardedMidpoint, IdenticalResultsOnRiemannianLog) { + // For manifolds whose base log IS the Riemannian log of the metric, the FD + // path isn't even exercised (fast path wins). This is a sanity check: the + // presence of the midpoint/guard machinery must not perturb the result for + // Riemannian-log configurations. + Sphere<> sphere; + const Eigen::Vector3d north(0.0, 0.0, 1.0); + const Eigen::Vector3d target = point_at_theta(1.0); + + InterpolationSettings default_settings; + + InterpolationSettings tau_zero = default_settings; + tau_zero.fd_midpoint_guard_tau = 0.0; + + auto r_default = discrete_geodesic(sphere, north, target, default_settings); + auto r_tau_zero = discrete_geodesic(sphere, north, target, tau_zero); + + EXPECT_EQ(r_default.status, InterpolationStatus::Converged); + EXPECT_EQ(r_tau_zero.status, InterpolationStatus::Converged); + + // Fast path only — FD path never runs, so the fallback counter stays at zero + // regardless of tau. + EXPECT_EQ(r_default.fd_midpoint_fallbacks, 0); + EXPECT_EQ(r_tau_zero.fd_midpoint_fallbacks, 0); + + ASSERT_EQ(r_default.path.size(), r_tau_zero.path.size()); + for (size_t i = 0; i < r_default.path.size(); ++i) { + EXPECT_LT((r_default.path[i] - r_tau_zero.path[i]).norm(), 1e-12); + } +} diff --git a/tests/test_metrics.cpp b/tests/test_metrics.cpp index cb54d45..d147ac5 100644 --- a/tests/test_metrics.cpp +++ b/tests/test_metrics.cpp @@ -1,16 +1,17 @@ /// @file test_metrics.cpp /// @brief Tests for extracted and new metric types. -#include +#include #include -#include -#include -#include -#include -#include -#include -#include +#include + +#include "geodex/metrics/constant_spd.hpp" +#include "geodex/metrics/jacobi.hpp" +#include "geodex/metrics/kinetic_energy.hpp" +#include "geodex/metrics/pullback.hpp" +#include "geodex/metrics/se2_left_invariant.hpp" +#include "geodex/metrics/weighted.hpp" // --------------------------------------------------------------------------- // Helpers @@ -156,8 +157,8 @@ TEST(JacobiMetric, ScalesWithEnergy) { auto mass_fn = [](const Eigen::Vector2d& /*q*/) { return Eigen::Matrix2d::Identity(); }; auto pot_fn = [](const Eigen::Vector2d& /*q*/) { return 1.0; }; - geodex::JacobiMetric metric1{mass_fn, pot_fn, 3.0}; // factor = 2*(3-1) = 4 - geodex::JacobiMetric metric2{mass_fn, pot_fn, 6.0}; // factor = 2*(6-1) = 10 + geodex::JacobiMetric metric1{mass_fn, pot_fn, 3.0}; // factor = 2*(3-1) = 4 + geodex::JacobiMetric metric2{mass_fn, pot_fn, 6.0}; // factor = 2*(6-1) = 10 Eigen::Vector2d q(0, 0); Eigen::Vector2d v(1, 0); @@ -177,9 +178,7 @@ TEST(PullbackMetric, InnerProductProperties) { J << 1.0, 0.0, 0.0, 1.0, 0.5, 0.5; return J; }; - auto task_metric_fn = [](const Eigen::Vector2d& /*q*/) { - return Eigen::Matrix3d::Identity(); - }; + auto task_metric_fn = [](const Eigen::Vector2d& /*q*/) { return Eigen::Matrix3d::Identity(); }; geodex::PullbackMetric metric{jac_fn, task_metric_fn}; @@ -247,3 +246,121 @@ TEST(WeightedMetric, InnerProductProperties) { check_bilinearity(metric, p, u, v, w, 2.5, -1.3); check_positive_definite(metric, p, u); } + +// --------------------------------------------------------------------------- +// inner_matrix batch consistency — each metric's `inner_matrix` must agree +// with d^2 scalar `inner` calls. +// --------------------------------------------------------------------------- + +namespace { +/// Reference: compute G_ij = inner(p, B.col(i), B.col(j)) one call at a time. +template +Eigen::MatrixXd scalar_gram(const Metric& m, const Point& p, const Eigen::MatrixXd& B) { + const int d = static_cast(B.cols()); + Eigen::MatrixXd G(d, d); + for (int i = 0; i < d; ++i) { + for (int j = 0; j < d; ++j) { + G(i, j) = m.inner(p, B.col(i), B.col(j)); + } + } + return G; +} +} // namespace + +TEST(InnerMatrixBatch, ConstantSPDMatchesScalar) { + Eigen::Matrix3d A = Eigen::Matrix3d::Identity(); + A(0, 0) = 3.0; + A(1, 2) = 0.5; + A(2, 1) = 0.5; + geodex::ConstantSPDMetric<3> metric{A}; + + Eigen::Vector3d p(0.5, -0.2, 1.0); + Eigen::MatrixXd B(3, 2); + B << 1.0, 0.3, 0.0, 1.0, 0.5, -0.4; + + const Eigen::MatrixXd expected = scalar_gram(metric, p, B); + const Eigen::MatrixXd actual = metric.inner_matrix(p, B, B); + EXPECT_LT((expected - actual).norm(), 1e-12); +} + +TEST(InnerMatrixBatch, KineticEnergyMatchesScalar) { + // Position-dependent mass matrix: M(q) = I + q * q^T. + auto mass = [](const Eigen::Vector2d& q) { + Eigen::Matrix2d M = Eigen::Matrix2d::Identity(); + M += q * q.transpose(); + return M; + }; + geodex::KineticEnergyMetric metric{mass}; + + Eigen::Vector2d q(0.7, -0.3); + Eigen::MatrixXd B(2, 2); + B << 1.0, 0.5, 0.2, 1.0; + + const Eigen::MatrixXd expected = scalar_gram(metric, q, B); + const Eigen::MatrixXd actual = metric.inner_matrix(q, B, B); + EXPECT_LT((expected - actual).norm(), 1e-12); +} + +TEST(InnerMatrixBatch, SE2LeftInvariantMatchesScalar) { + geodex::SE2LeftInvariantMetric metric{1.0, 2.5, 0.7}; + + Eigen::Vector3d p(0.0, 0.0, 0.0); + Eigen::MatrixXd B(3, 3); + B << 1.0, 0.2, -0.1, 0.0, 1.0, 0.4, 0.5, -0.3, 1.0; + + const Eigen::MatrixXd expected = scalar_gram(metric, p, B); + const Eigen::MatrixXd actual = metric.inner_matrix(p, B, B); + EXPECT_LT((expected - actual).norm(), 1e-12); +} + +TEST(InnerMatrixBatch, WeightedMatchesScalar) { + Eigen::Matrix2d A; + A << 2.0, 0.5, 0.5, 3.0; + geodex::ConstantSPDMetric<2> base{A}; + geodex::WeightedMetric weighted{base, 2.5}; + + Eigen::Vector2d p(1.0, 2.0); + Eigen::MatrixXd B(2, 2); + B << 1.0, 0.3, 0.5, -0.4; + + const Eigen::MatrixXd expected = scalar_gram(weighted, p, B); + const Eigen::MatrixXd actual = weighted.inner_matrix(p, B, B); + EXPECT_LT((expected - actual).norm(), 1e-12); +} + +TEST(InnerMatrixBatch, JacobiMatchesScalar) { + auto mass = [](const Eigen::Vector2d& /*q*/) { return Eigen::Matrix2d::Identity(); }; + auto potential = [](const Eigen::Vector2d& q) { return 0.5 * q.squaredNorm(); }; + geodex::JacobiMetric metric{mass, potential, 10.0}; + + Eigen::Vector2d q(0.3, 0.4); + Eigen::MatrixXd B(2, 2); + B << 1.0, 0.2, 0.1, 1.0; + + const Eigen::MatrixXd expected = scalar_gram(metric, q, B); + const Eigen::MatrixXd actual = metric.inner_matrix(q, B, B); + EXPECT_LT((expected - actual).norm(), 1e-12); +} + +TEST(InnerMatrixBatch, PullbackMatchesScalar) { + // A 2-joint planar-arm Jacobian (2x2) with unit link lengths. + auto jac = [](const Eigen::Vector2d& q) { + Eigen::Matrix2d J; + const double s1 = std::sin(q[0]); + const double s12 = std::sin(q[0] + q[1]); + const double c1 = std::cos(q[0]); + const double c12 = std::cos(q[0] + q[1]); + J << -s1 - s12, -s12, c1 + c12, c12; + return J; + }; + auto task_metric = [](const Eigen::Vector2d& /*q*/) { return Eigen::Matrix2d::Identity(); }; + geodex::PullbackMetric metric{jac, task_metric, 1e-3}; + + Eigen::Vector2d q(0.3, 0.8); + Eigen::MatrixXd B(2, 2); + B << 1.0, 0.2, 0.1, 1.0; + + const Eigen::MatrixXd expected = scalar_gram(metric, q, B); + const Eigen::MatrixXd actual = metric.inner_matrix(q, B, B); + EXPECT_LT((expected - actual).norm(), 1e-10); +} diff --git a/tests/test_path_resampling.cpp b/tests/test_path_resampling.cpp new file mode 100644 index 0000000..fa70c61 --- /dev/null +++ b/tests/test_path_resampling.cpp @@ -0,0 +1,381 @@ +/// @file test_path_resampling.cpp +/// @brief Tests for uniform arc-length path resampling used in the Nav2 planner. + +#include + +#include +#include + +#include +#include +#include +#include + +#include "geodex/integration/ompl/geodex_state_space.hpp" +#include "geodex/manifold/se2.hpp" + +namespace ob = ompl::base; +namespace og = ompl::geometric; + +using SE2Manifold = geodex::SE2<>; +using AnisotropicSE2 = geodex::SE2; +using StateSpace = geodex::integration::ompl::GeodexStateSpace; +using AnisotropicStateSpace = geodex::integration::ompl::GeodexStateSpace; +template +using StateType = geodex::integration::ompl::GeodexState; + +// --------------------------------------------------------------------------- +// Resampling function extracted from Nav2 planner for testability +// --------------------------------------------------------------------------- + +/// Resample an OMPL PathGeometric at uniform Euclidean xy spacing. +/// Uses geodesic interpolation (exp/log) for intermediate poses. +/// Returns a vector of (x, y, theta) waypoints. +template +static std::vector resamplePath(const og::PathGeometric& solution, + const ob::SpaceInformationPtr& si, + double waypoint_spacing) { + using ST = geodex::integration::ompl::GeodexState; + + size_t n = solution.getStateCount(); + if (n < 2) { + if (n == 1) { + const auto* s = solution.getState(0)->as(); + return {{s->values[0], s->values[1], s->values[2]}}; + } + return {}; + } + + // Compute cumulative Euclidean xy arc-length + std::vector cumDist(n, 0.0); + for (size_t i = 1; i < n; ++i) { + const auto* prev = solution.getState(i - 1)->as(); + const auto* curr = solution.getState(i)->as(); + double dx = curr->values[0] - prev->values[0]; + double dy = curr->values[1] - prev->values[1]; + cumDist[i] = cumDist[i - 1] + std::hypot(dx, dy); + } + double totalLength = cumDist.back(); + + // Resample at uniform xy spacing with geodesic interpolation + std::vector poses; + const auto* first = solution.getState(0)->as(); + poses.push_back({first->values[0], first->values[1], first->values[2]}); + + double targetDist = waypoint_spacing; + size_t segIdx = 0; + while (targetDist < totalLength - 1e-6) { + while (segIdx + 1 < n - 1 && cumDist[segIdx + 1] < targetDist) { + ++segIdx; + } + + double segStart = cumDist[segIdx]; + double segEnd = cumDist[segIdx + 1]; + double segLength = segEnd - segStart; + + if (segLength > 1e-9) { + double t = (targetDist - segStart) / segLength; + ob::State* interp = si->allocState(); + si->getStateSpace()->interpolate(solution.getState(segIdx), solution.getState(segIdx + 1), t, + interp); + const auto* s = interp->as(); + poses.push_back({s->values[0], s->values[1], s->values[2]}); + si->freeState(interp); + } + + targetDist += waypoint_spacing; + } + + // Always include goal + const auto* last = solution.getState(n - 1)->as(); + poses.push_back({last->values[0], last->values[1], last->values[2]}); + + return poses; +} + +// --------------------------------------------------------------------------- +// Helpers +// --------------------------------------------------------------------------- + +static std::pair, ob::SpaceInformationPtr> makeIsotropicSetup() { + geodex::SE2LeftInvariantMetric metric{1.0, 1.0, 0.5}; + SE2Manifold manifold{metric, geodex::SE2ExponentialMap{}, + Eigen::Vector3d(0.0, 0.0, -std::numbers::pi), + Eigen::Vector3d(100.0, 100.0, std::numbers::pi)}; + ob::RealVectorBounds bounds(3); + bounds.setLow(0, 0.0); + bounds.setHigh(0, 100.0); + bounds.setLow(1, 0.0); + bounds.setHigh(1, 100.0); + bounds.setLow(2, -std::numbers::pi); + bounds.setHigh(2, std::numbers::pi); + auto space = std::make_shared(manifold, bounds); + auto si = std::make_shared(space); + si->setStateValidityChecker([](const ob::State*) { return true; }); + si->setup(); + return {space, si}; +} + +static std::pair, ob::SpaceInformationPtr> +makeAnisotropicSetup() { + geodex::SE2LeftInvariantMetric metric{1.0, 100.0, 0.5}; + AnisotropicSE2 manifold{metric, geodex::SE2ExponentialMap{}, + Eigen::Vector3d(0.0, 0.0, -std::numbers::pi), + Eigen::Vector3d(100.0, 100.0, std::numbers::pi)}; + ob::RealVectorBounds bounds(3); + bounds.setLow(0, 0.0); + bounds.setHigh(0, 100.0); + bounds.setLow(1, 0.0); + bounds.setHigh(1, 100.0); + bounds.setLow(2, -std::numbers::pi); + bounds.setHigh(2, std::numbers::pi); + auto space = std::make_shared(manifold, bounds); + // Use the closed-form Lie-group geodesic for interpolation. The default Auto + // mode routes anisotropic metrics through the iterative discrete_geodesic + // cache, whose FD natural-gradient descent oscillates and hits + // MaxStepsReached under heavy anisotropy (w_y=100) — producing a non-straight + // cached path that breaks the uniform xy spacing assertion below. This test + // only asks whether `resamplePath` produces 0.1m xy spacing, which is + // well-defined against the Lie-group geodesic. + space->setInterpolationMode(geodex::integration::ompl::InterpolationMode::BaseGeodesic); + auto si = std::make_shared(space); + si->setStateValidityChecker([](const ob::State*) { return true; }); + si->setup(); + return {space, si}; +} + +template +static void setState(ob::State* state, double x, double y, double theta) { + auto* s = state->as>(); + s->values[0] = x; + s->values[1] = y; + s->values[2] = theta; +} + +/// Compute Euclidean xy distance between consecutive poses. +static std::vector xySpacings(const std::vector& poses) { + std::vector spacings; + for (size_t i = 1; i < poses.size(); ++i) { + double dx = poses[i][0] - poses[i - 1][0]; + double dy = poses[i][1] - poses[i - 1][1]; + spacings.push_back(std::hypot(dx, dy)); + } + return spacings; +} + +// --------------------------------------------------------------------------- +// Tests +// --------------------------------------------------------------------------- + +// A straight 10m path should produce ~10/0.1 = 100 interior waypoints + start + goal +TEST(PathResampling, StraightPath_CorrectCount) { + auto [space, si] = makeIsotropicSetup(); + + og::PathGeometric path(si); + auto* s0 = space->allocState(); + auto* s1 = space->allocState(); + setState(s0, 10.0, 20.0, 0.0); + setState(s1, 20.0, 20.0, 0.0); // 10m along x + path.append(s0); + path.append(s1); + + // Densify (like the Nav2 planner does) + path.interpolate(); + + auto poses = resamplePath(path, si, 0.1); + + // 10m / 0.1m = 100 intervals → 101 waypoints, plus possible goal + // Allow some tolerance for floating point + EXPECT_GE(poses.size(), 100u); + EXPECT_LE(poses.size(), 103u); + + // First and last poses should match start and goal + EXPECT_NEAR(poses.front()[0], 10.0, 1e-6); + EXPECT_NEAR(poses.front()[1], 20.0, 1e-6); + EXPECT_NEAR(poses.back()[0], 20.0, 1e-6); + EXPECT_NEAR(poses.back()[1], 20.0, 1e-6); + + space->freeState(s0); + space->freeState(s1); +} + +// All interior spacings should be approximately equal to waypoint_spacing +TEST(PathResampling, StraightPath_UniformSpacing) { + auto [space, si] = makeIsotropicSetup(); + + og::PathGeometric path(si); + auto* s0 = space->allocState(); + auto* s1 = space->allocState(); + setState(s0, 5.0, 5.0, 0.0); + setState(s1, 25.0, 5.0, 0.0); // 20m along x + path.append(s0); + path.append(s1); + path.interpolate(); + + auto poses = resamplePath(path, si, 0.5); + auto spacings = xySpacings(poses); + + // All interior spacings (except possibly the last) should be ~0.5m + for (size_t i = 0; i + 1 < spacings.size(); ++i) { + EXPECT_NEAR(spacings[i], 0.5, 0.05) << "Spacing at index " << i << " is " << spacings[i]; + } + // Last spacing can be shorter (remainder) + EXPECT_LE(spacings.back(), 0.5 + 0.05); + + space->freeState(s0); + space->freeState(s1); +} + +// Short path (2m) and long path (50m) should both have ~0.1m spacing +TEST(PathResampling, ShortAndLongPaths_SameSpacing) { + auto [space, si] = makeIsotropicSetup(); + double target = 0.1; + + auto testPath = [&](double x0, double x1) { + og::PathGeometric path(si); + auto* s0 = space->allocState(); + auto* s1 = space->allocState(); + setState(s0, x0, 10.0, 0.0); + setState(s1, x1, 10.0, 0.0); + path.append(s0); + path.append(s1); + path.interpolate(); + auto poses = resamplePath(path, si, target); + space->freeState(s0); + space->freeState(s1); + return poses; + }; + + auto short_poses = testPath(10.0, 12.0); // 2m + auto long_poses = testPath(10.0, 60.0); // 50m + + auto short_spacings = xySpacings(short_poses); + auto long_spacings = xySpacings(long_poses); + + // Both should have uniform ~0.1m spacing + for (size_t i = 0; i + 1 < short_spacings.size(); ++i) { + EXPECT_NEAR(short_spacings[i], target, 0.02) + << "Short path spacing[" << i << "] = " << short_spacings[i]; + } + for (size_t i = 0; i + 1 < long_spacings.size(); ++i) { + EXPECT_NEAR(long_spacings[i], target, 0.02) + << "Long path spacing[" << i << "] = " << long_spacings[i]; + } + + // Count check: 2m → ~20 waypoints, 50m → ~500 waypoints + EXPECT_GE(short_poses.size(), 19u); + EXPECT_LE(short_poses.size(), 23u); + EXPECT_GE(long_poses.size(), 498u); + EXPECT_LE(long_poses.size(), 503u); +} + +// Anisotropic metric (wy=100) should NOT affect physical xy spacing +TEST(PathResampling, AnisotropicMetric_UniformXYSpacing) { + auto [space, si] = makeAnisotropicSetup(); + + // Path along x (low-weight direction) + { + og::PathGeometric path(si); + auto* s0 = space->allocState(); + auto* s1 = space->allocState(); + setState(s0, 10.0, 20.0, 0.0); + setState(s1, 20.0, 20.0, 0.0); // 10m along x + path.append(s0); + path.append(s1); + path.interpolate(); + + auto poses = resamplePath(path, si, 0.1); + auto spacings = xySpacings(poses); + + for (size_t i = 0; i + 1 < spacings.size(); ++i) { + EXPECT_NEAR(spacings[i], 0.1, 0.02) << "X-path spacing[" << i << "] = " << spacings[i]; + } + EXPECT_GE(poses.size(), 99u); + + space->freeState(s0); + space->freeState(s1); + } + + // Path along y (high-weight direction) — should still be 0.1m physical + { + og::PathGeometric path(si); + auto* s0 = space->allocState(); + auto* s1 = space->allocState(); + setState(s0, 20.0, 10.0, 0.0); + setState(s1, 20.0, 20.0, 0.0); // 10m along y + path.append(s0); + path.append(s1); + path.interpolate(); + + auto poses = resamplePath(path, si, 0.1); + auto spacings = xySpacings(poses); + + for (size_t i = 0; i + 1 < spacings.size(); ++i) { + EXPECT_NEAR(spacings[i], 0.1, 0.02) << "Y-path spacing[" << i << "] = " << spacings[i]; + } + EXPECT_GE(poses.size(), 99u); + + space->freeState(s0); + space->freeState(s1); + } +} + +// Diagonal path should also have uniform xy spacing +TEST(PathResampling, DiagonalPath_UniformSpacing) { + auto [space, si] = makeIsotropicSetup(); + + og::PathGeometric path(si); + auto* s0 = space->allocState(); + auto* s1 = space->allocState(); + setState(s0, 10.0, 10.0, 0.0); + setState(s1, 20.0, 20.0, std::numbers::pi / 4.0); + path.append(s0); + path.append(s1); + path.interpolate(); + + // xy distance = sqrt(100+100) ≈ 14.14m + auto poses = resamplePath(path, si, 0.2); + auto spacings = xySpacings(poses); + + for (size_t i = 0; i + 1 < spacings.size(); ++i) { + EXPECT_NEAR(spacings[i], 0.2, 0.05) << "Diagonal spacing[" << i << "] = " << spacings[i]; + } + + space->freeState(s0); + space->freeState(s1); +} + +// Multi-segment path (like an RRT* solution with multiple waypoints) +TEST(PathResampling, MultiSegmentPath_UniformSpacing) { + auto [space, si] = makeIsotropicSetup(); + + og::PathGeometric path(si); + // Simulate an RRT*-like path with 4 waypoints + std::vector> waypoints = { + {5.0, 5.0, 0.0}, + {15.0, 5.0, 0.0}, // 10m east + {15.0, 15.0, 1.57}, // 10m north + {25.0, 15.0, 0.0}, // 10m east + }; + + for (auto& [x, y, th] : waypoints) { + auto* s = space->allocState(); + setState(s, x, y, th); + path.append(s); + space->freeState(s); + } + path.interpolate(); + + // Total xy length ≈ 30m, spacing 0.5 → ~60 waypoints + auto poses = resamplePath(path, si, 0.5); + auto spacings = xySpacings(poses); + + for (size_t i = 0; i + 1 < spacings.size(); ++i) { + EXPECT_NEAR(spacings[i], 0.5, 0.1) << "Multi-segment spacing[" << i << "] = " << spacings[i]; + } + + // Roughly 30m / 0.5m = 60 waypoints (geodesic SE(2) paths with rotation + // can be slightly longer in xy than straight-line segments) + EXPECT_GE(poses.size(), 55u); + EXPECT_LE(poses.size(), 70u); +} diff --git a/tests/test_sampler.cpp b/tests/test_sampler.cpp new file mode 100644 index 0000000..190ee88 --- /dev/null +++ b/tests/test_sampler.cpp @@ -0,0 +1,120 @@ +#include +#include + +#include "geodex/core/sampler.hpp" + +using geodex::HaltonSampler; +using geodex::Sampler; +using geodex::SeedableSampler; +using geodex::StochasticSampler; + +// --------------------------------------------------------------------------- +// Halton sampler +// --------------------------------------------------------------------------- + +TEST(HaltonSampler, DeterministicAcrossInstances) { + HaltonSampler a, b; + Eigen::VectorXd out_a(3), out_b(3); + for (int i = 0; i < 100; ++i) { + a.sample_box(3, out_a); + b.sample_box(3, out_b); + EXPECT_EQ(out_a, out_b); + } +} + +TEST(HaltonSampler, ReseedResetsSequence) { + HaltonSampler a; + Eigen::VectorXd expected(2), out(2); + a.sample_box(2, expected); + a.seed(0); + a.sample_box(2, out); + EXPECT_EQ(expected, out); +} + +TEST(HaltonSampler, FirstFewValuesMatchKnownSequence) { + // Known van-der-Corput values: + // index=1: base2=0.5, base3=1/3 + // index=2: base2=0.25, base3=2/3 + // index=3: base2=0.75, base3=1/9 + HaltonSampler s; + Eigen::VectorXd out(2); + + s.sample_box(2, out); + EXPECT_NEAR(out[0], 0.5, 1e-15); + EXPECT_NEAR(out[1], 1.0 / 3.0, 1e-15); + + s.sample_box(2, out); + EXPECT_NEAR(out[0], 0.25, 1e-15); + EXPECT_NEAR(out[1], 2.0 / 3.0, 1e-15); + + s.sample_box(2, out); + EXPECT_NEAR(out[0], 0.75, 1e-15); + EXPECT_NEAR(out[1], 1.0 / 9.0, 1e-15); +} + +TEST(HaltonSampler, OutputsInUnitBox) { + HaltonSampler s; + Eigen::VectorXd out(5); + for (int i = 0; i < 1000; ++i) { + s.sample_box(5, out); + for (int j = 0; j < 5; ++j) { + EXPECT_GE(out[j], 0.0); + EXPECT_LT(out[j], 1.0); + } + } +} + +// --------------------------------------------------------------------------- +// Stochastic sampler +// --------------------------------------------------------------------------- + +TEST(StochasticSampler, SeedReproducibility) { + StochasticSampler a{42}; + StochasticSampler b{42}; + Eigen::VectorXd out_a(3), out_b(3); + for (int i = 0; i < 100; ++i) { + a.sample_box(3, out_a); + b.sample_box(3, out_b); + EXPECT_EQ(out_a, out_b); + } +} + +TEST(StochasticSampler, DifferentSeedsDiverge) { + StochasticSampler a{1}; + StochasticSampler b{2}; + Eigen::VectorXd out_a(3), out_b(3); + a.sample_box(3, out_a); + b.sample_box(3, out_b); + EXPECT_NE(out_a, out_b); +} + +TEST(StochasticSampler, OutputsInUnitBox) { + StochasticSampler s{7}; + Eigen::VectorXd out(4); + for (int i = 0; i < 1000; ++i) { + s.sample_box(4, out); + for (int j = 0; j < 4; ++j) { + EXPECT_GE(out[j], 0.0); + EXPECT_LT(out[j], 1.0); + } + } +} + +TEST(StochasticSampler, DefaultShareThreadLocalState) { + // Default-constructed samplers share the same thread_local generator, so + // back-to-back draws from two instances differ with overwhelming probability. + StochasticSampler a, b; + Eigen::VectorXd out_a(3), out_b(3); + a.sample_box(3, out_a); + b.sample_box(3, out_b); + EXPECT_NE(out_a, out_b); +} + +// --------------------------------------------------------------------------- +// Concept satisfaction +// --------------------------------------------------------------------------- + +static_assert(Sampler); +static_assert(Sampler); +static_assert(SeedableSampler); +static_assert(SeedableSampler); diff --git a/tests/test_se2.cpp b/tests/test_se2.cpp index b9b2738..e421808 100644 --- a/tests/test_se2.cpp +++ b/tests/test_se2.cpp @@ -1,11 +1,14 @@ -#include - -#include #include -#include + #include +#include +#include + +#include "geodex/geodex.hpp" + using namespace geodex; +using namespace geodex::utils; // Compile-time concept checks static_assert(RiemannianManifold>); diff --git a/tests/test_sphere.cpp b/tests/test_sphere.cpp index 62e05bd..767352a 100644 --- a/tests/test_sphere.cpp +++ b/tests/test_sphere.cpp @@ -1,22 +1,25 @@ -#include - -#include #include -#include + #include +#include +#include + +#include "geodex/geodex.hpp" + using namespace geodex; // Compile-time concept checks static_assert(RiemannianManifold>); -static_assert(RiemannianManifold>>); -static_assert(RiemannianManifold>); +static_assert(RiemannianManifold>>); +static_assert(RiemannianManifold>); static_assert(Retraction); static_assert(Retraction); -// HasInjectivityRadius checks +// HasInjectivityRadius is now unconditional on Sphere (topological). +// The default metric (ConstantSPDMetric<3> identity) gives the canonical π. static_assert(HasInjectivityRadius>); -static_assert(!HasInjectivityRadius>>); +static_assert(HasInjectivityRadius>); // Helper: create a known point pair with known geodesic distance. // North pole to a point at latitude θ on the great circle through x-axis. @@ -117,7 +120,7 @@ TEST_F(SphereRoundTest, MidpointDistanceVariousAngles) { // --------------------------------------------------------------------------- TEST(SphereProjection, RetractionReturnsSpherePoint) { - Sphere sphere; + Sphere<2, SphereRoundMetric, SphereProjectionRetraction> sphere; Eigen::Vector3d p(0.0, 0.0, 1.0); Eigen::Vector3d v(0.3, 0.4, 0.0); @@ -126,7 +129,7 @@ TEST(SphereProjection, RetractionReturnsSpherePoint) { } TEST(SphereProjection, InverseRetractIsTangent) { - Sphere sphere; + Sphere<2, SphereRoundMetric, SphereProjectionRetraction> sphere; Eigen::Vector3d p(0.0, 0.0, 1.0); Eigen::Vector3d q = point_at_theta(0.5); @@ -136,7 +139,7 @@ TEST(SphereProjection, InverseRetractIsTangent) { } TEST(SphereProjection, AntipodalReturnsZero) { - Sphere sphere; + Sphere<2, SphereRoundMetric, SphereProjectionRetraction> sphere; Eigen::Vector3d p(0.0, 0.0, 1.0); Eigen::Vector3d south(0.0, 0.0, -1.0); @@ -151,7 +154,7 @@ TEST(SphereProjection, AntipodalReturnsZero) { TEST(SphereAnisotropic, ConceptSatisfied) { Eigen::Matrix3d A = Eigen::Matrix3d::Identity(); A(0, 0) = 2.0; - Sphere> sphere{ConstantSPDMetric<3>{A}}; + Sphere<2, ConstantSPDMetric<3>> sphere{ConstantSPDMetric<3>{A}}; EXPECT_EQ(sphere.dim(), 2); } @@ -160,7 +163,7 @@ TEST(SphereAnisotropic, DistanceDiffersFromRound) { A(0, 0) = 4.0; // stretch x-direction Sphere<> round_sphere; - Sphere> aniso_sphere{ConstantSPDMetric<3>{A}}; + Sphere<2, ConstantSPDMetric<3>> aniso_sphere{ConstantSPDMetric<3>{A}}; Eigen::Vector3d p(0.0, 0.0, 1.0); auto q = point_at_theta(0.5); @@ -176,7 +179,7 @@ TEST(SphereAnisotropic, MidpointDistance) { Eigen::Matrix3d A = Eigen::Matrix3d::Identity(); A(0, 0) = 2.0; - Sphere> sphere{ConstantSPDMetric<3>{A}}; + Sphere<2, ConstantSPDMetric<3>> sphere{ConstantSPDMetric<3>{A}}; Eigen::Vector3d p(0.0, 0.0, 1.0); auto q = point_at_theta(0.5); @@ -195,7 +198,7 @@ TEST(SphereAnisotropic, DistanceAntipodal) { Eigen::Matrix3d A = Eigen::Matrix3d::Identity(); A(0, 0) = 2.0; - Sphere> sphere{ConstantSPDMetric<3>{A}}; + Sphere<2, ConstantSPDMetric<3>> sphere{ConstantSPDMetric<3>{A}}; Eigen::Vector3d north(0.0, 0.0, 1.0); Eigen::Vector3d south(0.0, 0.0, -1.0); diff --git a/tests/test_sphere_ndim.cpp b/tests/test_sphere_ndim.cpp new file mode 100644 index 0000000..4b82905 --- /dev/null +++ b/tests/test_sphere_ndim.cpp @@ -0,0 +1,171 @@ +#include + +#include + +#include +#include + +#include "geodex/geodex.hpp" + +using namespace geodex; + +// --------------------------------------------------------------------------- +// Compile-time concept checks for static n-dim Sphere instantiations +// --------------------------------------------------------------------------- + +static_assert(RiemannianManifold>); +static_assert(RiemannianManifold>); +static_assert(RiemannianManifold>); +static_assert(RiemannianManifold>); + +static_assert(HasInjectivityRadius>); +static_assert(HasInjectivityRadius>); + +// --------------------------------------------------------------------------- +// Dimension and Ambient checks +// --------------------------------------------------------------------------- + +TEST(SphereNDim, DimensionReportedCorrectly) { + Sphere<3> s3; + Sphere<4> s4; + Sphere s_dyn(5); + + EXPECT_EQ(s3.dim(), 3); + EXPECT_EQ(s4.dim(), 4); + EXPECT_EQ(s_dyn.dim(), 5); +} + +TEST(SphereNDim, AmbientIsDimPlusOne) { + Sphere<3> s3; + auto p3 = s3.random_point(); + EXPECT_EQ(p3.size(), 4); // S^3 lives in R^4 + + Sphere s_dyn(4); + auto p_dyn = s_dyn.random_point(); + EXPECT_EQ(p_dyn.size(), 5); // S^4 lives in R^5 +} + +// --------------------------------------------------------------------------- +// Random sampling produces unit vectors +// --------------------------------------------------------------------------- + +TEST(SphereNDim, RandomPointIsUnitVectorS3) { + Sphere<3> s; + for (int i = 0; i < 100; ++i) { + auto p = s.random_point(); + EXPECT_NEAR(p.norm(), 1.0, 1e-12); + } +} + +TEST(SphereNDim, RandomPointIsUnitVectorDynamic) { + Sphere s(5); + for (int i = 0; i < 100; ++i) { + auto p = s.random_point(); + EXPECT_NEAR(p.norm(), 1.0, 1e-12); + } +} + +// --------------------------------------------------------------------------- +// Exp/log round trip +// --------------------------------------------------------------------------- + +TEST(SphereNDim, ExpLogRoundTripS3) { + Sphere<3> s; + Eigen::Vector4d p(1.0, 0.0, 0.0, 0.0); + Eigen::Vector4d q(0.0, 1.0, 0.0, 0.0); + + auto v = s.log(p, q); + auto q_recovered = s.exp(p, v); + EXPECT_LT((q_recovered - q).norm(), 1e-10); +} + +TEST(SphereNDim, ExpLogRoundTripS4) { + Sphere<4> s; + Eigen::Vector p; + Eigen::Vector q; + p << 1.0, 0.0, 0.0, 0.0, 0.0; + q << 0.0, 0.0, 1.0, 0.0, 0.0; + + auto v = s.log(p, q); + auto q_recovered = s.exp(p, v); + EXPECT_LT((q_recovered - q).norm(), 1e-10); +} + +// --------------------------------------------------------------------------- +// Geodesic distances +// --------------------------------------------------------------------------- + +TEST(SphereNDim, DistanceOrthogonalPointsS3) { + // Distance between orthogonal unit vectors on S^3 should be π/2. + Sphere<3> s; + Eigen::Vector4d p(1.0, 0.0, 0.0, 0.0); + Eigen::Vector4d q(0.0, 1.0, 0.0, 0.0); + EXPECT_NEAR(s.distance(p, q), std::numbers::pi / 2.0, 1e-10); +} + +TEST(SphereNDim, DistanceAntipodalS3) { + Sphere<3> s; + Eigen::Vector4d p(1.0, 0.0, 0.0, 0.0); + Eigen::Vector4d q(-1.0, 0.0, 0.0, 0.0); + EXPECT_NEAR(s.distance(p, q), std::numbers::pi, 1e-10); +} + +// --------------------------------------------------------------------------- +// Injectivity radius +// --------------------------------------------------------------------------- + +TEST(SphereNDim, InjectivityRadiusIsPi) { + Sphere<3> s3; + Sphere<4> s4; + Sphere s_dyn(5); + + EXPECT_NEAR(s3.injectivity_radius(), std::numbers::pi, 1e-15); + EXPECT_NEAR(s4.injectivity_radius(), std::numbers::pi, 1e-15); + EXPECT_NEAR(s_dyn.injectivity_radius(), std::numbers::pi, 1e-15); +} + +// --------------------------------------------------------------------------- +// Projection onto tangent space +// --------------------------------------------------------------------------- + +TEST(SphereNDim, ProjectRemovesRadialComponentS3) { + Sphere<3> s; + Eigen::Vector4d p(1.0, 0.0, 0.0, 0.0); + Eigen::Vector4d v(3.0, 2.0, 1.0, 0.5); // arbitrary ambient vector + + auto v_tangent = s.project(p, v); + // Tangent vectors are orthogonal to p. + EXPECT_NEAR(v_tangent.dot(p), 0.0, 1e-12); +} + +// --------------------------------------------------------------------------- +// has_riemannian_log for default Sphere<3> +// --------------------------------------------------------------------------- + +TEST(SphereNDim, DefaultSphereHasRiemannianLogS3) { + Sphere<3> s; + EXPECT_TRUE(is_riemannian_log(s)); +} + +TEST(SphereNDim, SphereWithAnisotropicMetricIsNotRiemannianLogS3) { + Eigen::Matrix4d A = Eigen::Matrix4d::Identity(); + A(0, 0) = 10.0; + Sphere<3, ConstantSPDMetric<4>> s{ConstantSPDMetric<4>{A}}; + EXPECT_FALSE(is_riemannian_log(s)); +} + +// --------------------------------------------------------------------------- +// Sphere with ProjectionRetraction in n-dim +// --------------------------------------------------------------------------- + +TEST(SphereNDim, ProjectionRetractionS3) { + Sphere<3, SphereRoundMetric, SphereProjectionRetraction> s; + Eigen::Vector4d p(1.0, 0.0, 0.0, 0.0); + Eigen::Vector4d v(0.0, 0.5, 0.0, 0.0); + + auto q = s.exp(p, v); + EXPECT_NEAR(q.norm(), 1.0, 1e-12); + + // Projection retraction is not exact, but `is_riemannian_log` should be false. + EXPECT_FALSE(is_riemannian_log(s)); +} diff --git a/tests/test_torus.cpp b/tests/test_torus.cpp index 18aa3ac..a4e6d74 100644 --- a/tests/test_torus.cpp +++ b/tests/test_torus.cpp @@ -1,11 +1,14 @@ -#include - -#include #include -#include + #include +#include +#include + +#include "geodex/geodex.hpp" + using namespace geodex; +using namespace geodex::utils; // Compile-time concept checks static_assert(RiemannianManifold>);