From 749b0e0abeb2260ca1f7d2858ee308a4659d59b7 Mon Sep 17 00:00:00 2001 From: twidmer Date: Thu, 2 Apr 2026 11:33:38 +0200 Subject: [PATCH 01/10] First attempt to bring support for speculative contacts into the collision pipeline --- newton/__init__.py | 2 + newton/_src/geometry/narrow_phase.py | 64 ++++- newton/_src/sim/__init__.py | 3 +- newton/_src/sim/collide.py | 354 ++++++++++++++++++++------- newton/_src/sim/model.py | 6 +- 5 files changed, 339 insertions(+), 90 deletions(-) diff --git a/newton/__init__.py b/newton/__init__.py index 6b1517e1b1..fa3f07f7f8 100644 --- a/newton/__init__.py +++ b/newton/__init__.py @@ -56,6 +56,7 @@ JointType, Model, ModelBuilder, + SpeculativeContactConfig, State, eval_fk, eval_ik, @@ -73,6 +74,7 @@ "JointType", "Model", "ModelBuilder", + "SpeculativeContactConfig", "State", "eval_fk", "eval_ik", diff --git a/newton/_src/geometry/narrow_phase.py b/newton/_src/geometry/narrow_phase.py index bf070428ca..e43cdd5e76 100644 --- a/newton/_src/geometry/narrow_phase.py +++ b/newton/_src/geometry/narrow_phase.py @@ -125,7 +125,7 @@ def write_contact_simple( writer_data.contact_tangent[index] = wp.normalize(world_x - wp.dot(world_x, normal) * normal) -def create_narrow_phase_primitive_kernel(writer_func: Any): +def create_narrow_phase_primitive_kernel(writer_func: Any, speculative: bool = False): """ Create a kernel for fast analytical collision detection of primitive shapes. @@ -136,6 +136,8 @@ def create_narrow_phase_primitive_kernel(writer_func: Any): Args: writer_func: Contact writer function (e.g., write_contact_simple) + speculative: When True, the kernel reads per-shape velocity arrays and + extends ``gap_sum`` by a scalar speculative margin. Returns: A warp kernel for primitive collision detection @@ -153,6 +155,10 @@ def narrow_phase_primitive_kernel( shape_flags: wp.array[wp.int32], writer_data: Any, total_num_threads: int, + shape_lin_vel: wp.array[wp.vec3], + shape_ang_speed_bound: wp.array[float], + speculative_dt: float, + max_speculative_extension: float, # Output: pairs that need GJK/MPR processing gjk_candidate_pairs: wp.array[wp.vec2i], gjk_candidate_pairs_count: wp.array[int], @@ -233,6 +239,11 @@ def narrow_phase_primitive_kernel( gap_b = shape_gap[shape_b] gap_sum = gap_a + gap_b + if wp.static(speculative): + vel_rel = shape_lin_vel[shape_b] - shape_lin_vel[shape_a] + rel_speed = wp.length(vel_rel) + shape_ang_speed_bound[shape_a] + shape_ang_speed_bound[shape_b] + gap_sum = gap_sum + wp.min(rel_speed * speculative_dt, max_speculative_extension) + # ===================================================================== # Route heightfield pairs. # Heightfield-vs-mesh and heightfield-vs-heightfield go through the @@ -593,7 +604,11 @@ def narrow_phase_primitive_kernel( def create_narrow_phase_kernel_gjk_mpr( - external_aabb: bool, writer_func: Any, support_func: Any = None, post_process_contact: Any = None + external_aabb: bool, + writer_func: Any, + support_func: Any = None, + post_process_contact: Any = None, + speculative: bool = False, ): """ Create a GJK/MPR narrow phase kernel for complex convex shape collisions. @@ -606,6 +621,10 @@ def create_narrow_phase_kernel_gjk_mpr( The remaining pairs are complex convex-convex (plane-box, plane-cylinder, plane-cone, box-box, cylinder-cylinder, etc.) that need GJK/MPR. + + Args: + speculative: When True, extends ``gap_sum`` by a scalar speculative + margin derived from per-shape velocity arrays. """ @wp.kernel(enable_backward=False, module="unique") @@ -622,6 +641,10 @@ def narrow_phase_kernel_gjk_mpr( shape_aabb_upper: wp.array[wp.vec3], writer_data: Any, total_num_threads: int, + shape_lin_vel: wp.array[wp.vec3], + shape_ang_speed_bound: wp.array[float], + speculative_dt: float, + max_speculative_extension: float, ): """ GJK/MPR collision detection for complex convex pairs. @@ -737,6 +760,11 @@ def narrow_phase_kernel_gjk_mpr( gap_b = shape_gap[shape_b] gap_sum = gap_a + gap_b + if wp.static(speculative): + vel_rel = shape_lin_vel[shape_b] - shape_lin_vel[shape_a] + rel_speed = wp.length(vel_rel) + shape_ang_speed_bound[shape_a] + shape_ang_speed_bound[shape_b] + gap_sum = gap_sum + wp.min(rel_speed * speculative_dt, max_speculative_extension) + # Find and write contacts using GJK/MPR wp.static( create_find_contacts(writer_func, support_func=support_func, post_process_contact=post_process_contact) @@ -1390,6 +1418,7 @@ def __init__( has_meshes: bool = True, has_heightfields: bool = False, use_lean_gjk_mpr: bool = False, + speculative: bool = False, ) -> None: """ Initialize NarrowPhase with pre-allocated buffers. @@ -1413,6 +1442,10 @@ def __init__( Defaults to True for safety. Set to False when constructing from a model with no meshes. has_heightfields: Whether the scene contains any heightfield shapes (GeoType.HFIELD). When True, heightfield collision buffers and kernels are allocated. Defaults to False. + speculative: Enable speculative contact support in narrow-phase kernels. + When True, kernel variants that read per-shape velocity arrays and + extend gap thresholds are compiled. When False (default), the + speculative code paths are eliminated at compile time. """ self.max_candidate_pairs = max_candidate_pairs self.max_triangle_pairs = max_triangle_pairs @@ -1460,9 +1493,11 @@ def __init__( self.tile_size_mesh_plane = 512 self.block_dim = 128 + self.speculative = speculative + # Create the appropriate kernel variants # Primitive kernel handles lightweight primitives and routes remaining pairs - self.primitive_kernel = create_narrow_phase_primitive_kernel(writer_func) + self.primitive_kernel = create_narrow_phase_primitive_kernel(writer_func, speculative=speculative) # GJK/MPR kernel handles remaining convex-convex pairs if use_lean_gjk_mpr: # Use lean support function (CONVEX_MESH, BOX, SPHERE only) and lean post-processing @@ -1472,9 +1507,12 @@ def __init__( writer_func, support_func=support_map_lean, post_process_contact=post_process_minkowski_only, + speculative=speculative, ) else: - self.narrow_phase_kernel = create_narrow_phase_kernel_gjk_mpr(self.external_aabb, writer_func) + self.narrow_phase_kernel = create_narrow_phase_kernel_gjk_mpr( + self.external_aabb, writer_func, speculative=speculative + ) # Create triangle contacts kernel when meshes or heightfields are present if has_meshes or has_heightfields: self.mesh_triangle_contacts_kernel = create_narrow_phase_process_mesh_triangle_contacts_kernel(writer_func) @@ -1649,6 +1687,10 @@ def launch_custom_write( heightfield_elevations: wp.array[wp.float32] | None = None, writer_data: Any, device: Devicelike | None = None, # Device to launch on + shape_lin_vel: wp.array[wp.vec3] | None = None, + shape_ang_speed_bound: wp.array[wp.float32] | None = None, + speculative_dt: float = 0.0, + max_speculative_extension: float = 0.0, ) -> None: """ Launch narrow phase collision detection with a custom contact writer struct. @@ -1680,6 +1722,12 @@ def launch_custom_write( # Clear all counters with a single kernel launch (consolidated counter array) self._counter_array.zero_() + # Resolve speculative velocity arrays (empty when disabled) + _empty_vec3 = wp.empty(0, dtype=wp.vec3, device=device) + _empty_float = wp.empty(0, dtype=wp.float32, device=device) + _slv = shape_lin_vel if shape_lin_vel is not None else _empty_vec3 + _sasb = shape_ang_speed_bound if shape_ang_speed_bound is not None else _empty_float + # Stage 1: Launch primitive kernel for fast analytical collisions # This handles sphere-sphere, sphere-capsule, capsule-capsule, plane-sphere, plane-capsule # and routes remaining pairs to gjk_candidate_pairs and mesh buffers @@ -1697,6 +1745,10 @@ def launch_custom_write( shape_flags, writer_data, self.total_num_threads, + _slv, + _sasb, + speculative_dt, + max_speculative_extension, ], outputs=[ self.gjk_candidate_pairs, @@ -1736,6 +1788,10 @@ def launch_custom_write( self.shape_aabb_upper, writer_data, self.total_num_threads, + _slv, + _sasb, + speculative_dt, + max_speculative_extension, ], device=device, block_dim=self.block_dim, diff --git a/newton/_src/sim/__init__.py b/newton/_src/sim/__init__.py index bd68e0a42f..1bca490976 100644 --- a/newton/_src/sim/__init__.py +++ b/newton/_src/sim/__init__.py @@ -3,7 +3,7 @@ from .articulation import eval_fk, eval_ik, eval_jacobian, eval_mass_matrix from .builder import ModelBuilder -from .collide import CollisionPipeline +from .collide import CollisionPipeline, SpeculativeContactConfig from .contacts import Contacts from .control import Control from .enums import ( @@ -25,6 +25,7 @@ "JointType", "Model", "ModelBuilder", + "SpeculativeContactConfig", "State", "eval_fk", "eval_ik", diff --git a/newton/_src/sim/collide.py b/newton/_src/sim/collide.py index 49cc22bba9..6a0cbead6f 100644 --- a/newton/_src/sim/collide.py +++ b/newton/_src/sim/collide.py @@ -3,6 +3,7 @@ from __future__ import annotations +import dataclasses from typing import Literal import numpy as np @@ -27,6 +28,25 @@ from ..sim.state import State +@dataclasses.dataclass +class SpeculativeContactConfig: + """Configuration for speculative contact detection. + + When passed to :class:`CollisionPipeline`, AABBs and gap thresholds are + expanded based on per-shape velocity so that contacts which will occur + within the next collision update interval are detected early. + + Attributes: + max_speculative_extension: Maximum speculative gap extension [m]. + Clamps ``vel * dt`` to prevent excessively large AABBs. + collision_update_dt: Default time interval between collision updates [s]. + Can be overridden per-call via ``CollisionPipeline.collide(dt=...)``. + """ + + max_speculative_extension: float = 0.1 + collision_update_dt: float = 1.0 / 60.0 + + @wp.struct class ContactWriterData: """Contact writer data for collide write_contact function.""" @@ -53,6 +73,11 @@ class ContactWriterData: out_stiffness: wp.array[float] out_damping: wp.array[float] out_friction: wp.array[float] + # Speculative contact fields (empty arrays / 0.0 when disabled) + shape_lin_vel: wp.array[wp.vec3] + shape_ang_speed_bound: wp.array[float] + speculative_dt: float + max_speculative_extension: float @wp.func @@ -95,6 +120,21 @@ def write_contact( gap_b = writer_data.shape_gap[contact_data.shape_b] contact_gap = gap_a + gap_b + # Directed speculative gap extension: only extend for approaching pairs + if writer_data.speculative_dt > 0.0: + vel_a = writer_data.shape_lin_vel[contact_data.shape_a] + vel_b = writer_data.shape_lin_vel[contact_data.shape_b] + v_approach = ( + wp.dot(vel_b - vel_a, contact_normal_a_to_b) + + writer_data.shape_ang_speed_bound[contact_data.shape_a] + + writer_data.shape_ang_speed_bound[contact_data.shape_b] + ) + spec_gap = wp.min( + wp.max(v_approach * writer_data.speculative_dt, 0.0), + writer_data.max_speculative_extension, + ) + contact_gap = contact_gap + spec_gap + index = output_index if index < 0: @@ -138,105 +178,186 @@ def write_contact( writer_data.out_friction[index] = contact_data.contact_friction_scale +def _create_compute_shape_aabbs(speculative: bool): + """Factory for the AABB kernel. When *speculative* is True the kernel reads + per-shape velocity arrays and applies directed linear + isotropic angular + expansion. When False the extra code is eliminated at compile time via + ``wp.static``.""" + + @wp.kernel(enable_backward=False) + def compute_shape_aabbs( + body_q: wp.array[wp.transform], + shape_transform: wp.array[wp.transform], + shape_body: wp.array[int], + shape_type: wp.array[int], + shape_scale: wp.array[wp.vec3], + shape_collision_radius: wp.array[float], + shape_source_ptr: wp.array[wp.uint64], + shape_margin: wp.array[float], + shape_gap: wp.array[float], + shape_collision_aabb_lower: wp.array[wp.vec3], + shape_collision_aabb_upper: wp.array[wp.vec3], + shape_lin_vel: wp.array[wp.vec3], + shape_ang_speed_bound: wp.array[float], + speculative_dt: float, + # outputs + aabb_lower: wp.array[wp.vec3], + aabb_upper: wp.array[wp.vec3], + ): + """Compute axis-aligned bounding boxes for each shape in world space. + + Uses support function for most shapes. Meshes and heightfields use the + pre-computed local AABB transformed to world frame. Infinite planes use + bounding sphere fallback. AABBs are enlarged by per-shape effective gap + for contact detection (``shape_margin + shape_gap``), and optionally by + speculative velocity expansion when enabled. + """ + shape_id = wp.tid() + + rigid_id = shape_body[shape_id] + geo_type = shape_type[shape_id] + + # Compute world transform + if rigid_id == -1: + X_ws = shape_transform[shape_id] + else: + X_ws = wp.transform_multiply(body_q[rigid_id], shape_transform[shape_id]) + + pos = wp.transform_get_translation(X_ws) + orientation = wp.transform_get_rotation(X_ws) + + # Enlarge AABB by per-shape effective gap for contact detection + effective_gap = shape_margin[shape_id] + shape_gap[shape_id] + margin_vec = wp.vec3(effective_gap, effective_gap, effective_gap) + + # Check if this is an infinite plane, mesh, or heightfield + scale = shape_scale[shape_id] + is_infinite_plane = (geo_type == GeoType.PLANE) and (scale[0] == 0.0 and scale[1] == 0.0) + is_mesh = geo_type == GeoType.MESH + is_hfield = geo_type == GeoType.HFIELD + + if is_infinite_plane: + # Bounding sphere fallback for infinite planes + radius = shape_collision_radius[shape_id] + half_extents = wp.vec3(radius, radius, radius) + aabb_lower[shape_id] = pos - half_extents - margin_vec + aabb_upper[shape_id] = pos + half_extents + margin_vec + elif is_mesh or is_hfield: + # Tight local AABB transformed to world space. + # Scale is already baked into shape_collision_aabb by the builder, + # so we only need to handle the rotation here. + local_lo = shape_collision_aabb_lower[shape_id] + local_hi = shape_collision_aabb_upper[shape_id] + + center = (local_lo + local_hi) * 0.5 + half = (local_hi - local_lo) * 0.5 + + # Rotate center to world frame + world_center = wp.quat_rotate(orientation, center) + pos + + # Rotated AABB half-extents via abs of rotation matrix columns + r0 = wp.quat_rotate(orientation, wp.vec3(1.0, 0.0, 0.0)) + r1 = wp.quat_rotate(orientation, wp.vec3(0.0, 1.0, 0.0)) + r2 = wp.quat_rotate(orientation, wp.vec3(0.0, 0.0, 1.0)) + + world_half = wp.vec3( + wp.abs(r0[0]) * half[0] + wp.abs(r1[0]) * half[1] + wp.abs(r2[0]) * half[2], + wp.abs(r0[1]) * half[0] + wp.abs(r1[1]) * half[1] + wp.abs(r2[1]) * half[2], + wp.abs(r0[2]) * half[0] + wp.abs(r1[2]) * half[1] + wp.abs(r2[2]) * half[2], + ) + + lo = world_center - world_half - margin_vec + hi = world_center + world_half + margin_vec + + if wp.static(speculative): + v = shape_lin_vel[shape_id] + vel_dt = v * speculative_dt + ang_ext = shape_ang_speed_bound[shape_id] * speculative_dt + ang_vec = wp.vec3(ang_ext, ang_ext, ang_ext) + lo = lo - wp.max(-vel_dt, wp.vec3(0.0, 0.0, 0.0)) - ang_vec + hi = hi + wp.max(vel_dt, wp.vec3(0.0, 0.0, 0.0)) + ang_vec + + aabb_lower[shape_id] = lo + aabb_upper[shape_id] = hi + else: + # Use support function to compute tight AABB + shape_data = GenericShapeData() + shape_data.shape_type = geo_type + shape_data.scale = scale + shape_data.auxiliary = wp.vec3(0.0, 0.0, 0.0) + + if geo_type == GeoType.CONVEX_MESH: + shape_data.auxiliary = pack_mesh_ptr(shape_source_ptr[shape_id]) + + data_provider = SupportMapDataProvider() + + aabb_min_world, aabb_max_world = compute_tight_aabb_from_support( + shape_data, orientation, pos, data_provider + ) + + lo = aabb_min_world - margin_vec + hi = aabb_max_world + margin_vec + + if wp.static(speculative): + v = shape_lin_vel[shape_id] + vel_dt = v * speculative_dt + ang_ext = shape_ang_speed_bound[shape_id] * speculative_dt + ang_vec = wp.vec3(ang_ext, ang_ext, ang_ext) + lo = lo - wp.max(-vel_dt, wp.vec3(0.0, 0.0, 0.0)) - ang_vec + hi = hi + wp.max(vel_dt, wp.vec3(0.0, 0.0, 0.0)) + ang_vec + + aabb_lower[shape_id] = lo + aabb_upper[shape_id] = hi + + return compute_shape_aabbs + + +_compute_shape_aabbs = _create_compute_shape_aabbs(speculative=False) +_compute_shape_aabbs_speculative = _create_compute_shape_aabbs(speculative=True) + + @wp.kernel(enable_backward=False) -def compute_shape_aabbs( - body_q: wp.array[wp.transform], - shape_transform: wp.array[wp.transform], +def compute_shape_vel( + body_qd: wp.array[wp.spatial_vector], shape_body: wp.array[int], - shape_type: wp.array[int], - shape_scale: wp.array[wp.vec3], - shape_collision_radius: wp.array[float], - shape_source_ptr: wp.array[wp.uint64], - shape_margin: wp.array[float], - shape_gap: wp.array[float], + shape_transform: wp.array[wp.transform], shape_collision_aabb_lower: wp.array[wp.vec3], shape_collision_aabb_upper: wp.array[wp.vec3], # outputs - aabb_lower: wp.array[wp.vec3], - aabb_upper: wp.array[wp.vec3], + shape_lin_vel: wp.array[wp.vec3], + shape_ang_speed_bound: wp.array[float], ): - """Compute axis-aligned bounding boxes for each shape in world space. + """Compute per-shape linear velocity and angular speed bound for speculative contacts. - Uses support function for most shapes. Meshes and heightfields use the pre-computed - local AABB transformed to world frame. Infinite planes use bounding sphere fallback. - AABBs are enlarged by per-shape effective gap for contact detection. - Effective expansion is ``shape_margin + shape_gap``. + Linear velocity is the body COM velocity. The angular speed bound is + ``|omega| * r_max`` where ``r_max`` is the distance from the body COM to the + farthest point of the shape, estimated as + ``|shape_offset| + local_aabb_half_diagonal``. """ shape_id = wp.tid() - rigid_id = shape_body[shape_id] - geo_type = shape_type[shape_id] - # Compute world transform if rigid_id == -1: - X_ws = shape_transform[shape_id] - else: - X_ws = wp.transform_multiply(body_q[rigid_id], shape_transform[shape_id]) - - pos = wp.transform_get_translation(X_ws) - orientation = wp.transform_get_rotation(X_ws) - - # Enlarge AABB by per-shape effective gap for contact detection - effective_gap = shape_margin[shape_id] + shape_gap[shape_id] - margin_vec = wp.vec3(effective_gap, effective_gap, effective_gap) - - # Check if this is an infinite plane, mesh, or heightfield - scale = shape_scale[shape_id] - is_infinite_plane = (geo_type == GeoType.PLANE) and (scale[0] == 0.0 and scale[1] == 0.0) - is_mesh = geo_type == GeoType.MESH - is_hfield = geo_type == GeoType.HFIELD - - if is_infinite_plane: - # Bounding sphere fallback for infinite planes - radius = shape_collision_radius[shape_id] - half_extents = wp.vec3(radius, radius, radius) - aabb_lower[shape_id] = pos - half_extents - margin_vec - aabb_upper[shape_id] = pos + half_extents + margin_vec - elif is_mesh or is_hfield: - # Tight local AABB transformed to world space. - # Scale is already baked into shape_collision_aabb by the builder, - # so we only need to handle the rotation here. - local_lo = shape_collision_aabb_lower[shape_id] - local_hi = shape_collision_aabb_upper[shape_id] - - center = (local_lo + local_hi) * 0.5 - half = (local_hi - local_lo) * 0.5 - - # Rotate center to world frame - world_center = wp.quat_rotate(orientation, center) + pos + shape_lin_vel[shape_id] = wp.vec3(0.0, 0.0, 0.0) + shape_ang_speed_bound[shape_id] = 0.0 + return - # Rotated AABB half-extents via abs of rotation matrix columns - r0 = wp.quat_rotate(orientation, wp.vec3(1.0, 0.0, 0.0)) - r1 = wp.quat_rotate(orientation, wp.vec3(0.0, 1.0, 0.0)) - r2 = wp.quat_rotate(orientation, wp.vec3(0.0, 0.0, 1.0)) + qd = body_qd[rigid_id] + v_lin = wp.vec3(qd[0], qd[1], qd[2]) + omega = wp.vec3(qd[3], qd[4], qd[5]) - world_half = wp.vec3( - wp.abs(r0[0]) * half[0] + wp.abs(r1[0]) * half[1] + wp.abs(r2[0]) * half[2], - wp.abs(r0[1]) * half[0] + wp.abs(r1[1]) * half[1] + wp.abs(r2[1]) * half[2], - wp.abs(r0[2]) * half[0] + wp.abs(r1[2]) * half[1] + wp.abs(r2[2]) * half[2], - ) + shape_lin_vel[shape_id] = v_lin - aabb_lower[shape_id] = world_center - world_half - margin_vec - aabb_upper[shape_id] = world_center + world_half + margin_vec + omega_mag = wp.length(omega) + if omega_mag > 0.0: + shape_offset = wp.transform_get_translation(shape_transform[shape_id]) + local_lo = shape_collision_aabb_lower[shape_id] + local_hi = shape_collision_aabb_upper[shape_id] + half_diag = wp.length((local_hi - local_lo) * 0.5) + r_max = wp.length(shape_offset) + half_diag + shape_ang_speed_bound[shape_id] = omega_mag * r_max else: - # Use support function to compute tight AABB - # Create generic shape data - shape_data = GenericShapeData() - shape_data.shape_type = geo_type - shape_data.scale = scale - shape_data.auxiliary = wp.vec3(0.0, 0.0, 0.0) - - # For CONVEX_MESH, pack the mesh pointer - if geo_type == GeoType.CONVEX_MESH: - shape_data.auxiliary = pack_mesh_ptr(shape_source_ptr[shape_id]) - - data_provider = SupportMapDataProvider() - - # Compute tight AABB using helper function - aabb_min_world, aabb_max_world = compute_tight_aabb_from_support(shape_data, orientation, pos, data_provider) - - aabb_lower[shape_id] = aabb_min_world - margin_vec - aabb_upper[shape_id] = aabb_max_world + margin_vec + shape_ang_speed_bound[shape_id] = 0.0 @wp.kernel(enable_backward=False) @@ -428,6 +549,7 @@ def __init__( | None = None, narrow_phase: NarrowPhase | None = None, sdf_hydroelastic_config: HydroelasticSDF.Config | None = None, + speculative_config: SpeculativeContactConfig | None = None, ): """ Initialize the CollisionPipeline (expert API). @@ -459,6 +581,12 @@ def __init__( "nxn"/"sap" modes, ignored. sdf_hydroelastic_config: Configuration for hydroelastic collision handling. Defaults to None. + speculative_config: Configuration for speculative contact detection. + When provided, AABBs and gap thresholds are expanded based on + per-shape velocity (linear + angular) so that contacts expected + within the next collision update interval are detected early. + ``None`` (default) disables speculative contacts with zero + runtime overhead via compile-time elimination. .. note:: When ``requires_grad`` is true (explicitly or via ``model.requires_grad``), @@ -477,6 +605,9 @@ def __init__( particle_count = model.particle_count device = model.device + self.speculative_config = speculative_config + self._speculative_enabled = speculative_config is not None + # Resolve rigid contact capacity with explicit > model > estimated precedence. if rigid_contact_max is None: model_rigid_contact_max = int(getattr(model, "rigid_contact_max", 0) or 0) @@ -627,6 +758,7 @@ def __init__( has_meshes=has_meshes, has_heightfields=has_heightfields, use_lean_gjk_mpr=use_lean_gjk_mpr, + speculative=self._speculative_enabled, ) self.hydroelastic_sdf = self.narrow_phase.hydroelastic_sdf @@ -659,6 +791,14 @@ def __init__( self._soft_contact_max = soft_contact_max self.requires_grad = requires_grad + if self._speculative_enabled: + with wp.ScopedDevice(device): + self._shape_lin_vel = wp.zeros(shape_count, dtype=wp.vec3, device=device) + self._shape_ang_speed_bound = wp.zeros(shape_count, dtype=wp.float32, device=device) + else: + self._shape_lin_vel = wp.empty(0, dtype=wp.vec3, device=device) + self._shape_ang_speed_bound = wp.empty(0, dtype=wp.float32, device=device) + @property def rigid_contact_max(self) -> int: """Maximum rigid contact buffer capacity used by this pipeline.""" @@ -717,6 +857,7 @@ def collide( contacts: Contacts, *, soft_contact_margin: float | None = None, + dt: float | None = None, ): """Run the collision pipeline using NarrowPhase. @@ -741,6 +882,9 @@ def collide( contacts: The contacts buffer to populate (will be cleared first). soft_contact_margin: Margin for soft contact generation. If ``None``, uses the value from construction. + dt: Override for the speculative collision update interval [s]. + When ``None``, uses ``speculative_config.collision_update_dt``. + Ignored when speculative contacts are disabled. """ contacts.clear() @@ -753,15 +897,45 @@ def collide( # update any additional parameters soft_contact_margin = soft_contact_margin if soft_contact_margin is not None else self.soft_contact_margin + # Resolve speculative dt and max extension + if self._speculative_enabled: + cfg = self.speculative_config + speculative_dt = dt if dt is not None else cfg.collision_update_dt + max_speculative_extension = cfg.max_speculative_extension + else: + speculative_dt = 0.0 + max_speculative_extension = 0.0 + # Rigid contact detection -- broad phase + narrow phase. # These kernels hardcode record_tape=False internally so they are # never captured on an active wp.Tape. The differentiable # augmentation and soft-contact kernels that follow are tape-safe # and recorded normally. + # Compute per-shape velocity for speculative AABB expansion + if self._speculative_enabled: + wp.launch( + kernel=compute_shape_vel, + dim=model.shape_count, + inputs=[ + state.body_qd, + model.shape_body, + model.shape_transform, + model.shape_collision_aabb_lower, + model.shape_collision_aabb_upper, + ], + outputs=[ + self._shape_lin_vel, + self._shape_ang_speed_bound, + ], + device=self.device, + record_tape=False, + ) + # Compute AABBs for all shapes (already expanded by per-shape effective gaps) + aabb_kernel = _compute_shape_aabbs_speculative if self._speculative_enabled else _compute_shape_aabbs wp.launch( - kernel=compute_shape_aabbs, + kernel=aabb_kernel, dim=model.shape_count, inputs=[ state.body_q, @@ -775,6 +949,9 @@ def collide( model.shape_gap, model.shape_collision_aabb_lower, model.shape_collision_aabb_upper, + self._shape_lin_vel, + self._shape_ang_speed_bound, + speculative_dt, ], outputs=[ self.narrow_phase.shape_aabb_lower, @@ -867,6 +1044,11 @@ def collide( writer_data.out_damping = contacts.rigid_contact_damping writer_data.out_friction = contacts.rigid_contact_friction + writer_data.shape_lin_vel = self._shape_lin_vel + writer_data.shape_ang_speed_bound = self._shape_ang_speed_bound + writer_data.speculative_dt = speculative_dt + writer_data.max_speculative_extension = max_speculative_extension + # Run narrow phase with custom contact writer (writes directly to Contacts format) self.narrow_phase.launch_custom_write( candidate_pair=self.broad_phase_shape_pairs, @@ -888,6 +1070,10 @@ def collide( heightfield_elevations=model.heightfield_elevations, writer_data=writer_data, device=self.device, + shape_lin_vel=self._shape_lin_vel if self._speculative_enabled else None, + shape_ang_speed_bound=self._shape_ang_speed_bound if self._speculative_enabled else None, + speculative_dt=speculative_dt, + max_speculative_extension=max_speculative_extension, ) # Differentiable contact augmentation: reconstruct world-space contact diff --git a/newton/_src/sim/model.py b/newton/_src/sim/model.py index a7539c66fb..f39017a7df 100644 --- a/newton/_src/sim/model.py +++ b/newton/_src/sim/model.py @@ -971,6 +971,7 @@ def collide( contacts: Contacts | None = None, *, collision_pipeline: CollisionPipeline | None = None, + dt: float | None = None, ) -> Contacts: """ Generate contact points for the particles and rigid bodies in the model using the default collision @@ -981,6 +982,9 @@ def collide( contacts: The contacts buffer to populate (will be cleared first). If None, a new contacts buffer is allocated via :meth:`contacts`. collision_pipeline: Optional collision pipeline override. + dt: Override for the speculative collision update interval [s]. + Forwarded to :meth:`CollisionPipeline.collide`. Ignored when + speculative contacts are disabled. """ if collision_pipeline is not None: self._collision_pipeline = collision_pipeline @@ -990,7 +994,7 @@ def collide( if contacts is None: contacts = self._collision_pipeline.contacts() - self._collision_pipeline.collide(state, contacts) + self._collision_pipeline.collide(state, contacts, dt=dt) return contacts def request_state_attributes(self, *attributes: str) -> None: From 41ca9d79d07d4d6c7d48a3dcfed199b095d9579b Mon Sep 17 00:00:00 2001 From: twidmer Date: Thu, 2 Apr 2026 11:55:06 +0200 Subject: [PATCH 02/10] Add more unit tests for speculative contacts --- newton/tests/test_speculative_contacts.py | 265 ++++++++++++++++++++++ 1 file changed, 265 insertions(+) create mode 100644 newton/tests/test_speculative_contacts.py diff --git a/newton/tests/test_speculative_contacts.py b/newton/tests/test_speculative_contacts.py new file mode 100644 index 0000000000..315700b62a --- /dev/null +++ b/newton/tests/test_speculative_contacts.py @@ -0,0 +1,265 @@ +# SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers +# SPDX-License-Identifier: Apache-2.0 + +"""Tests for speculative contact support in the collision pipeline.""" + +import unittest + +import numpy as np +import warp as wp + +import newton +from newton.tests.unittest_utils import add_function_test, get_cuda_test_devices + + +def _build_two_sphere_model( + device, + gap: float = 3.0, + velocity: float = 0.0, + speculative_config: newton.SpeculativeContactConfig | None = None, +): + """Build a simple scene with two spheres separated along the X axis. + + Body A is at ``(-gap/2, 0, 0)`` moving with ``+velocity`` in X. + Body B is at ``(+gap/2, 0, 0)`` and is static (body index -1 via ground plane trick + is avoided; instead it's a dynamic body with zero velocity). + + Returns: + model, state, pipeline, contacts + """ + builder = newton.ModelBuilder(gravity=0.0) + builder.rigid_gap = 0.0 + + body_a = builder.add_body(xform=wp.transform(wp.vec3(-gap / 2.0, 0.0, 0.0))) + builder.add_shape_sphere(body_a, radius=0.5) + builder.body_qd[-1] = (velocity, 0.0, 0.0, 0.0, 0.0, 0.0) + + body_b = builder.add_body(xform=wp.transform(wp.vec3(gap / 2.0, 0.0, 0.0))) + builder.add_shape_sphere(body_b, radius=0.5) + + model = builder.finalize(device=device) + state = model.state() + + pipeline = newton.CollisionPipeline( + model, + broad_phase="nxn", + speculative_config=speculative_config, + ) + contacts = pipeline.contacts() + return model, state, pipeline, contacts + + +def test_speculative_disabled_no_contacts(test, device): + """Two spheres far apart with no speculative config produce zero contacts.""" + _, state, pipeline, contacts = _build_two_sphere_model(device, gap=3.0, velocity=100.0) + pipeline.collide(state, contacts) + count = contacts.rigid_contact_count.numpy()[0] + test.assertEqual(count, 0, "Non-speculative pipeline should not detect contacts for separated spheres") + + +def test_speculative_enabled_catches_fast_object(test, device): + """Two spheres far apart but approaching fast produce speculative contacts.""" + config = newton.SpeculativeContactConfig( + max_speculative_extension=10.0, + collision_update_dt=1.0 / 60.0, + ) + _, state, pipeline, contacts = _build_two_sphere_model( + device, + gap=3.0, + velocity=200.0, + speculative_config=config, + ) + pipeline.collide(state, contacts) + count = contacts.rigid_contact_count.numpy()[0] + test.assertGreater(count, 0, "Speculative pipeline should detect contacts for fast approaching spheres") + + +def test_speculative_diverging_no_contacts(test, device): + """Two spheres moving apart should not produce speculative contacts. + + Body A moves in -X (away from B). The directed gap extension should be + zero because the approach velocity is negative. + """ + config = newton.SpeculativeContactConfig( + max_speculative_extension=10.0, + collision_update_dt=1.0 / 60.0, + ) + _, state, pipeline, contacts = _build_two_sphere_model( + device, + gap=3.0, + velocity=-200.0, + speculative_config=config, + ) + pipeline.collide(state, contacts) + count = contacts.rigid_contact_count.numpy()[0] + test.assertEqual(count, 0, "Speculative pipeline should not detect contacts for diverging spheres") + + +def test_speculative_max_extension_clamp(test, device): + """Max speculative extension clamps the gap so very far objects are not detected.""" + config = newton.SpeculativeContactConfig( + max_speculative_extension=0.01, + collision_update_dt=1.0 / 60.0, + ) + _, state, pipeline, contacts = _build_two_sphere_model( + device, + gap=3.0, + velocity=200.0, + speculative_config=config, + ) + pipeline.collide(state, contacts) + count = contacts.rigid_contact_count.numpy()[0] + test.assertEqual(count, 0, "Max extension clamp should prevent detection of far-away objects") + + +def test_speculative_dt_override(test, device): + """Passing dt to collide() overrides the config default.""" + config = newton.SpeculativeContactConfig( + max_speculative_extension=10.0, + collision_update_dt=1e-6, + ) + _, state, pipeline, contacts = _build_two_sphere_model( + device, + gap=3.0, + velocity=200.0, + speculative_config=config, + ) + # With the tiny default dt, no contacts + pipeline.collide(state, contacts) + count_tiny = contacts.rigid_contact_count.numpy()[0] + test.assertEqual(count_tiny, 0, "Tiny default dt should not produce contacts") + + # Override with a large dt + contacts.clear() + pipeline.collide(state, contacts, dt=1.0 / 60.0) + count_override = contacts.rigid_contact_count.numpy()[0] + test.assertGreater(count_override, 0, "Overridden dt should produce contacts") + + +def test_speculative_angular_velocity(test, device): + """Angular velocity contributes to speculative extension. + + A spinning body should produce speculative contacts even with zero linear + velocity if the angular speed bound is large enough. + """ + builder = newton.ModelBuilder(gravity=0.0) + builder.rigid_gap = 0.0 + + body_a = builder.add_body(xform=wp.transform(wp.vec3(-0.75, 0.0, 0.0))) + builder.add_shape_box(body_a, hx=0.5, hy=0.5, hz=0.5) + builder.body_qd[-1] = (0.0, 0.0, 0.0, 0.0, 0.0, 200.0) + + body_b = builder.add_body(xform=wp.transform(wp.vec3(0.75, 0.0, 0.0))) + builder.add_shape_box(body_b, hx=0.5, hy=0.5, hz=0.5) + + model = builder.finalize(device=device) + state = model.state() + + config = newton.SpeculativeContactConfig( + max_speculative_extension=10.0, + collision_update_dt=1.0 / 60.0, + ) + pipeline = newton.CollisionPipeline(model, broad_phase="nxn", speculative_config=config) + contacts = pipeline.contacts() + pipeline.collide(state, contacts) + count = contacts.rigid_contact_count.numpy()[0] + test.assertGreater(count, 0, "Angular velocity should contribute to speculative extension") + + +def _run_sphere_vs_thin_box_sim(device, speculative_config, num_frames=5): + """Simulate a fast sphere aimed at a thin static box. + + The sphere (radius 0.25) starts at x = -2 moving at +50 m/s. + The thin box (half-thickness 0.02 in X) is centred at the origin. + With dt = 1/60 the sphere travels ~0.83 m per frame -- much more than + the box thickness (0.04 m), so without speculative contacts the sphere + tunnels straight through. + + Returns the final X position of the sphere body. + """ + builder = newton.ModelBuilder(gravity=0.0) + builder.rigid_gap = 0.0 + + sphere_body = builder.add_body(xform=wp.transform(wp.vec3(-2.0, 0.0, 0.0))) + builder.add_shape_sphere(sphere_body, radius=0.25) + builder.body_qd[-1] = (50.0, 0.0, 0.0, 0.0, 0.0, 0.0) + + builder.add_shape_box( + body=-1, + xform=wp.transform_identity(), + hx=0.02, + hy=1.0, + hz=1.0, + ) + + model = builder.finalize(device=device) + + pipeline = newton.CollisionPipeline( + model, + broad_phase="nxn", + speculative_config=speculative_config, + ) + contacts = pipeline.contacts() + solver = newton.solvers.SolverXPBD(model) + + state_0 = model.state() + state_1 = model.state() + control = model.control() + frame_dt = 1.0 / 60.0 + + for _ in range(num_frames): + pipeline.collide(state_0, contacts, dt=frame_dt) + state_0.clear_forces() + solver.step(state_0, state_1, control, contacts, frame_dt) + state_0, state_1 = state_1, state_0 + + body_q = state_0.body_q.numpy() + sphere_x = float(body_q[0][0]) + return sphere_x + + +def test_speculative_tunneling_without(test, device): + """Without speculative contacts the sphere tunnels through the thin box.""" + final_x = _run_sphere_vs_thin_box_sim(device, speculative_config=None) + test.assertGreater( + final_x, + 0.5, + f"Sphere should tunnel through the thin box (final x={final_x:.3f})", + ) + + +def test_speculative_tunneling_with(test, device): + """With speculative contacts the sphere is stopped by the thin box.""" + config = newton.SpeculativeContactConfig( + max_speculative_extension=2.0, + collision_update_dt=1.0 / 60.0, + ) + final_x = _run_sphere_vs_thin_box_sim(device, speculative_config=config) + test.assertLess( + final_x, + -0.2, + f"Sphere should be stopped by the thin box (final x={final_x:.3f})", + ) + + +class TestSpeculativeContacts(unittest.TestCase): + pass + + +devices = get_cuda_test_devices() +if not devices: + devices = [wp.get_device("cpu")] + +add_function_test(TestSpeculativeContacts, "test_speculative_disabled_no_contacts", test_speculative_disabled_no_contacts, devices=devices) +add_function_test(TestSpeculativeContacts, "test_speculative_enabled_catches_fast_object", test_speculative_enabled_catches_fast_object, devices=devices) +add_function_test(TestSpeculativeContacts, "test_speculative_diverging_no_contacts", test_speculative_diverging_no_contacts, devices=devices) +add_function_test(TestSpeculativeContacts, "test_speculative_max_extension_clamp", test_speculative_max_extension_clamp, devices=devices) +add_function_test(TestSpeculativeContacts, "test_speculative_dt_override", test_speculative_dt_override, devices=devices) +add_function_test(TestSpeculativeContacts, "test_speculative_angular_velocity", test_speculative_angular_velocity, devices=devices) +add_function_test(TestSpeculativeContacts, "test_speculative_tunneling_without", test_speculative_tunneling_without, devices=devices) +add_function_test(TestSpeculativeContacts, "test_speculative_tunneling_with", test_speculative_tunneling_with, devices=devices) + + +if __name__ == "__main__": + wp.clear_kernel_cache() + unittest.main(verbosity=2) From 888118390cf862a6e7320e14823700621edea622 Mon Sep 17 00:00:00 2001 From: twidmer Date: Thu, 2 Apr 2026 11:55:29 +0200 Subject: [PATCH 03/10] Ran ruff --- newton/tests/test_speculative_contacts.py | 45 ++++++++++++++++++----- 1 file changed, 36 insertions(+), 9 deletions(-) diff --git a/newton/tests/test_speculative_contacts.py b/newton/tests/test_speculative_contacts.py index 315700b62a..97ca9a4370 100644 --- a/newton/tests/test_speculative_contacts.py +++ b/newton/tests/test_speculative_contacts.py @@ -5,7 +5,6 @@ import unittest -import numpy as np import warp as wp import newton @@ -250,14 +249,42 @@ class TestSpeculativeContacts(unittest.TestCase): if not devices: devices = [wp.get_device("cpu")] -add_function_test(TestSpeculativeContacts, "test_speculative_disabled_no_contacts", test_speculative_disabled_no_contacts, devices=devices) -add_function_test(TestSpeculativeContacts, "test_speculative_enabled_catches_fast_object", test_speculative_enabled_catches_fast_object, devices=devices) -add_function_test(TestSpeculativeContacts, "test_speculative_diverging_no_contacts", test_speculative_diverging_no_contacts, devices=devices) -add_function_test(TestSpeculativeContacts, "test_speculative_max_extension_clamp", test_speculative_max_extension_clamp, devices=devices) -add_function_test(TestSpeculativeContacts, "test_speculative_dt_override", test_speculative_dt_override, devices=devices) -add_function_test(TestSpeculativeContacts, "test_speculative_angular_velocity", test_speculative_angular_velocity, devices=devices) -add_function_test(TestSpeculativeContacts, "test_speculative_tunneling_without", test_speculative_tunneling_without, devices=devices) -add_function_test(TestSpeculativeContacts, "test_speculative_tunneling_with", test_speculative_tunneling_with, devices=devices) +add_function_test( + TestSpeculativeContacts, + "test_speculative_disabled_no_contacts", + test_speculative_disabled_no_contacts, + devices=devices, +) +add_function_test( + TestSpeculativeContacts, + "test_speculative_enabled_catches_fast_object", + test_speculative_enabled_catches_fast_object, + devices=devices, +) +add_function_test( + TestSpeculativeContacts, + "test_speculative_diverging_no_contacts", + test_speculative_diverging_no_contacts, + devices=devices, +) +add_function_test( + TestSpeculativeContacts, + "test_speculative_max_extension_clamp", + test_speculative_max_extension_clamp, + devices=devices, +) +add_function_test( + TestSpeculativeContacts, "test_speculative_dt_override", test_speculative_dt_override, devices=devices +) +add_function_test( + TestSpeculativeContacts, "test_speculative_angular_velocity", test_speculative_angular_velocity, devices=devices +) +add_function_test( + TestSpeculativeContacts, "test_speculative_tunneling_without", test_speculative_tunneling_without, devices=devices +) +add_function_test( + TestSpeculativeContacts, "test_speculative_tunneling_with", test_speculative_tunneling_with, devices=devices +) if __name__ == "__main__": From de66f9077c259e75666809ca81912bcc28b225f6 Mon Sep 17 00:00:00 2001 From: twidmer Date: Wed, 8 Apr 2026 15:03:38 +0200 Subject: [PATCH 04/10] Implement MR comments --- docs/api/newton.rst | 1 + newton/_src/geometry/narrow_phase.py | 18 ++++++++++++++- newton/_src/sim/collide.py | 34 +++++++++++++++++++++++----- 3 files changed, 46 insertions(+), 7 deletions(-) diff --git a/docs/api/newton.rst b/docs/api/newton.rst index 129e536b9e..8c02409c3a 100644 --- a/docs/api/newton.rst +++ b/docs/api/newton.rst @@ -55,6 +55,7 @@ newton ParticleFlags SDF ShapeFlags + SpeculativeContactConfig State TetMesh diff --git a/newton/_src/geometry/narrow_phase.py b/newton/_src/geometry/narrow_phase.py index f111b5cd6e..5cfaf079d0 100644 --- a/newton/_src/geometry/narrow_phase.py +++ b/newton/_src/geometry/narrow_phase.py @@ -527,7 +527,23 @@ def narrow_phase_primitive_kernel( contact_data.margin_b = margin_offset_b contact_data.shape_a = shape_a contact_data.shape_b = shape_b - contact_data.gap_sum = gap_sum + + # Recompute gap_sum with directed approach speed now that the + # contact normal is available (the pre-routing gap_sum used + # undirected speed as a conservative candidate-generation bound). + directed_gap_sum = gap_a + gap_b + if wp.static(speculative): + vel_rel = shape_lin_vel[shape_b] - shape_lin_vel[shape_a] + v_approach = ( + -wp.dot(vel_rel, contact_normal) + + shape_ang_speed_bound[shape_a] + + shape_ang_speed_bound[shape_b] + ) + directed_gap_sum = directed_gap_sum + wp.min( + wp.max(v_approach * speculative_dt, 0.0), + max_speculative_extension, + ) + contact_data.gap_sum = directed_gap_sum # Check margin for all possible contacts contact_0_valid = False diff --git a/newton/_src/sim/collide.py b/newton/_src/sim/collide.py index cf3c866254..73b3841bb7 100644 --- a/newton/_src/sim/collide.py +++ b/newton/_src/sim/collide.py @@ -28,6 +28,12 @@ from ..sim.state import State +def _validate_speculative_scalar(value: float, name: str) -> None: + """Raise ``ValueError`` for negative or non-finite speculative parameters.""" + if not np.isfinite(value) or value < 0.0: + raise ValueError(f"{name} must be a non-negative finite number, got {value!r}") + + @dataclasses.dataclass class SpeculativeContactConfig: """Configuration for speculative contact detection. @@ -46,6 +52,10 @@ class SpeculativeContactConfig: max_speculative_extension: float = 0.1 collision_update_dt: float = 1.0 / 60.0 + def __post_init__(self): + _validate_speculative_scalar(self.collision_update_dt, "collision_update_dt") + _validate_speculative_scalar(self.max_speculative_extension, "max_speculative_extension") + @wp.struct class ContactWriterData: @@ -120,12 +130,14 @@ def write_contact( gap_b = writer_data.shape_gap[contact_data.shape_b] contact_gap = gap_a + gap_b - # Directed speculative gap extension: only extend for approaching pairs + # Directed speculative gap extension: only extend for approaching pairs. + # contact_normal_a_to_b points from A toward B, so approaching motion + # gives dot(vel_b - vel_a, n) < 0. Negate to get a positive approach speed. if writer_data.speculative_dt > 0.0: vel_a = writer_data.shape_lin_vel[contact_data.shape_a] vel_b = writer_data.shape_lin_vel[contact_data.shape_b] v_approach = ( - wp.dot(vel_b - vel_a, contact_normal_a_to_b) + -wp.dot(vel_b - vel_a, contact_normal_a_to_b) + writer_data.shape_ang_speed_bound[contact_data.shape_a] + writer_data.shape_ang_speed_bound[contact_data.shape_b] ) @@ -200,6 +212,7 @@ def compute_shape_aabbs( shape_lin_vel: wp.array[wp.vec3], shape_ang_speed_bound: wp.array[float], speculative_dt: float, + max_speculative_extension: float, # outputs aabb_lower: wp.array[wp.vec3], aabb_upper: wp.array[wp.vec3], @@ -273,9 +286,12 @@ def compute_shape_aabbs( v = shape_lin_vel[shape_id] vel_dt = v * speculative_dt ang_ext = shape_ang_speed_bound[shape_id] * speculative_dt + ext_neg = wp.max(-vel_dt, wp.vec3(0.0, 0.0, 0.0)) + ext_pos = wp.max(vel_dt, wp.vec3(0.0, 0.0, 0.0)) ang_vec = wp.vec3(ang_ext, ang_ext, ang_ext) - lo = lo - wp.max(-vel_dt, wp.vec3(0.0, 0.0, 0.0)) - ang_vec - hi = hi + wp.max(vel_dt, wp.vec3(0.0, 0.0, 0.0)) + ang_vec + cap = wp.vec3(max_speculative_extension, max_speculative_extension, max_speculative_extension) + lo = lo - wp.min(ext_neg + ang_vec, cap) + hi = hi + wp.min(ext_pos + ang_vec, cap) aabb_lower[shape_id] = lo aabb_upper[shape_id] = hi @@ -302,9 +318,12 @@ def compute_shape_aabbs( v = shape_lin_vel[shape_id] vel_dt = v * speculative_dt ang_ext = shape_ang_speed_bound[shape_id] * speculative_dt + ext_neg = wp.max(-vel_dt, wp.vec3(0.0, 0.0, 0.0)) + ext_pos = wp.max(vel_dt, wp.vec3(0.0, 0.0, 0.0)) ang_vec = wp.vec3(ang_ext, ang_ext, ang_ext) - lo = lo - wp.max(-vel_dt, wp.vec3(0.0, 0.0, 0.0)) - ang_vec - hi = hi + wp.max(vel_dt, wp.vec3(0.0, 0.0, 0.0)) + ang_vec + cap = wp.vec3(max_speculative_extension, max_speculative_extension, max_speculative_extension) + lo = lo - wp.min(ext_neg + ang_vec, cap) + hi = hi + wp.min(ext_pos + ang_vec, cap) aabb_lower[shape_id] = lo aabb_upper[shape_id] = hi @@ -901,6 +920,8 @@ def collide( if self._speculative_enabled: cfg = self.speculative_config speculative_dt = dt if dt is not None else cfg.collision_update_dt + if dt is not None: + _validate_speculative_scalar(dt, "dt") max_speculative_extension = cfg.max_speculative_extension else: speculative_dt = 0.0 @@ -952,6 +973,7 @@ def collide( self._shape_lin_vel, self._shape_ang_speed_bound, speculative_dt, + max_speculative_extension, ], outputs=[ self.narrow_phase.shape_aabb_lower, From 2e8bf6b47669e5784ff0167317e2ceaf043e61d2 Mon Sep 17 00:00:00 2001 From: twidmer Date: Wed, 8 Apr 2026 15:40:13 +0200 Subject: [PATCH 05/10] Update the docs --- CHANGELOG.md | 1 + docs/concepts/collisions.rst | 41 ++++++++++++++++++++++++++++++++++++ newton/_src/sim/collide.py | 11 +++++----- 3 files changed, 47 insertions(+), 6 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index a5e457acc6..b5d39e6b5e 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -36,6 +36,7 @@ - Add `total_force_friction` and `force_matrix_friction` to `SensorContact` for tangential (friction) force decomposition - Add `compute_normals` and `compute_uvs` optional arguments to `Mesh.create_heightfield()` and `Mesh.create_terrain()` - Add RJ45 plug-socket insertion example with SDF contacts, latch joint, and interactive gizmo +- Add `SpeculativeContactConfig` and speculative contact support in `CollisionPipeline` to detect contacts for fast-moving objects before they tunnel through thin geometry ### Changed diff --git a/docs/concepts/collisions.rst b/docs/concepts/collisions.rst index f7e856b915..83624e0274 100644 --- a/docs/concepts/collisions.rst +++ b/docs/concepts/collisions.rst @@ -1089,6 +1089,47 @@ Example (mesh SDF workflow): The builder's ``rigid_gap`` (default 0.1) applies to shapes without explicit ``gap``. Alternatively, use ``builder.default_shape_cfg.gap``. +.. _Speculative Contacts: + +Speculative Contacts +-------------------- + +Fast-moving objects can travel farther than the contact gap in a single time +step, causing them to tunnel through thin geometry. **Speculative contacts** +widen the detection window based on per-shape velocity so that contacts which +*will* occur within the next collision update interval are caught early. + +Enable speculative contacts by passing a :class:`SpeculativeContactConfig` to +:class:`CollisionPipeline`: + +.. code-block:: python + + config = newton.SpeculativeContactConfig( + max_speculative_extension=0.5, # cap per-axis AABB growth [m] + collision_update_dt=1.0 / 60.0, # expected interval between collide() calls + ) + pipeline = newton.CollisionPipeline(model, speculative_config=config) + +At each ``collide()`` call the pipeline: + +1. Computes per-shape linear velocity and an angular-speed bound from + ``State.body_qd``. +2. Expands each shape AABB by the clamped velocity contribution (capped by + ``max_speculative_extension``) so the broad phase returns candidate pairs + that are about to collide. +3. In the narrow phase, widens the contact gap using the **directed** approach + speed along the contact normal, so only genuinely approaching pairs are + accepted. + +The ``collision_update_dt`` can be overridden per call: + +.. code-block:: python + + pipeline.collide(state, contacts, dt=sim_dt) + +When ``speculative_config`` is ``None`` (the default), all speculative code +paths are eliminated at compile time with zero runtime overhead. + .. _Common Patterns: Common Patterns diff --git a/newton/_src/sim/collide.py b/newton/_src/sim/collide.py index 73b3841bb7..827ee6cf5f 100644 --- a/newton/_src/sim/collide.py +++ b/newton/_src/sim/collide.py @@ -41,16 +41,15 @@ class SpeculativeContactConfig: When passed to :class:`CollisionPipeline`, AABBs and gap thresholds are expanded based on per-shape velocity so that contacts which will occur within the next collision update interval are detected early. - - Attributes: - max_speculative_extension: Maximum speculative gap extension [m]. - Clamps ``vel * dt`` to prevent excessively large AABBs. - collision_update_dt: Default time interval between collision updates [s]. - Can be overridden per-call via ``CollisionPipeline.collide(dt=...)``. """ max_speculative_extension: float = 0.1 + """Maximum speculative gap extension [m]. Clamps ``vel * dt`` to + prevent excessively large AABBs.""" + collision_update_dt: float = 1.0 / 60.0 + """Default time interval between collision updates [s]. Can be + overridden per-call via ``CollisionPipeline.collide(dt=...)``.""" def __post_init__(self): _validate_speculative_scalar(self.collision_update_dt, "collision_update_dt") From 09071409bd2a7418948fcb684d4a4460742f1836 Mon Sep 17 00:00:00 2001 From: twidmer Date: Thu, 9 Apr 2026 16:06:05 +0200 Subject: [PATCH 06/10] Improve the docs --- docs/concepts/collisions.rst | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/docs/concepts/collisions.rst b/docs/concepts/collisions.rst index 83624e0274..d999b07628 100644 --- a/docs/concepts/collisions.rst +++ b/docs/concepts/collisions.rst @@ -1117,9 +1117,10 @@ At each ``collide()`` call the pipeline: 2. Expands each shape AABB by the clamped velocity contribution (capped by ``max_speculative_extension``) so the broad phase returns candidate pairs that are about to collide. -3. In the narrow phase, widens the contact gap using the **directed** approach - speed along the contact normal, so only genuinely approaching pairs are - accepted. +3. In the narrow phase, recomputes the contact gap using the normal-projected + approach speed of the relative linear velocity **plus** per-shape + angular-speed bounds (clamped by ``max_speculative_extension``), so only + genuinely approaching pairs are accepted. The ``collision_update_dt`` can be overridden per call: From 5113899d468e4626449a92b34f1924983714933c Mon Sep 17 00:00:00 2001 From: twidmer Date: Fri, 10 Apr 2026 09:32:03 +0200 Subject: [PATCH 07/10] Extend speculative contacts to support meshes --- .../_src/geometry/contact_reduction_global.py | 209 ++++++------ newton/_src/geometry/narrow_phase.py | 311 ++++++++++++------ newton/_src/geometry/sdf_contact.py | 67 +++- newton/tests/test_speculative_contacts.py | 212 ++++++++++++ 4 files changed, 598 insertions(+), 201 deletions(-) diff --git a/newton/_src/geometry/contact_reduction_global.py b/newton/_src/geometry/contact_reduction_global.py index 349f47a056..d0a793408a 100644 --- a/newton/_src/geometry/contact_reduction_global.py +++ b/newton/_src/geometry/contact_reduction_global.py @@ -1214,105 +1214,126 @@ def export_reduced_contacts_kernel( return export_reduced_contacts_kernel -@wp.kernel(enable_backward=False, module="unique") -def mesh_triangle_contacts_to_reducer_kernel( - shape_types: wp.array[int], - shape_data: wp.array[wp.vec4], - shape_transform: wp.array[wp.transform], - shape_source: wp.array[wp.uint64], - shape_gap: wp.array[float], - shape_heightfield_index: wp.array[wp.int32], - heightfield_data: wp.array[HeightfieldData], - heightfield_elevations: wp.array[wp.float32], - triangle_pairs: wp.array[wp.vec3i], - triangle_pairs_count: wp.array[int], - reducer_data: GlobalContactReducerData, - total_num_threads: int, -): - """Process mesh/heightfield-triangle contacts and store them in GlobalContactReducer. +def create_mesh_triangle_contacts_to_reducer_kernel(speculative: bool = False): + """Factory for the mesh/heightfield-triangle → reducer kernel. - This kernel processes triangle pairs (mesh-or-hfield shape, convex-shape, triangle_index) - and computes contacts using GJK/MPR, storing results in the GlobalContactReducer for - subsequent reduction and export. - - Uses grid stride loop over triangle pairs. + When *speculative* is True the kernel reads per-shape velocity arrays and + extends ``gap_sum`` by a scalar speculative margin. When False the extra + code is eliminated at compile time via ``wp.static``. """ - tid = wp.tid() - num_triangle_pairs = triangle_pairs_count[0] + @wp.kernel(enable_backward=False, module="unique") + def mesh_triangle_contacts_to_reducer_kernel( + shape_types: wp.array[int], + shape_data: wp.array[wp.vec4], + shape_transform: wp.array[wp.transform], + shape_source: wp.array[wp.uint64], + shape_gap: wp.array[float], + shape_heightfield_index: wp.array[wp.int32], + heightfield_data: wp.array[HeightfieldData], + heightfield_elevations: wp.array[wp.float32], + triangle_pairs: wp.array[wp.vec3i], + triangle_pairs_count: wp.array[int], + reducer_data: GlobalContactReducerData, + total_num_threads: int, + shape_lin_vel: wp.array[wp.vec3], + shape_ang_speed_bound: wp.array[float], + speculative_dt: float, + max_speculative_extension: float, + ): + """Process mesh/heightfield-triangle contacts and store them in GlobalContactReducer. + + This kernel processes triangle pairs (mesh-or-hfield shape, convex-shape, triangle_index) + and computes contacts using GJK/MPR, storing results in the GlobalContactReducer for + subsequent reduction and export. - for i in range(tid, num_triangle_pairs, total_num_threads): - if i >= triangle_pairs.shape[0]: - break + Uses grid stride loop over triangle pairs. + """ + tid = wp.tid() - triple = triangle_pairs[i] - shape_a = triple[0] # Mesh or heightfield shape - shape_b = triple[1] # Convex shape - tri_idx = triple[2] + num_triangle_pairs = triangle_pairs_count[0] - type_a = shape_types[shape_a] + for i in range(tid, num_triangle_pairs, total_num_threads): + if i >= triangle_pairs.shape[0]: + break - if type_a == GeoType.HFIELD: - # Heightfield triangle - hfd = heightfield_data[shape_heightfield_index[shape_a]] - X_ws_a = shape_transform[shape_a] - shape_data_a, v0_world = get_triangle_shape_from_heightfield(hfd, heightfield_elevations, X_ws_a, tri_idx) - else: - # Mesh triangle (mesh_id already validated by midphase) - mesh_id_a = shape_source[shape_a] - scale_data_a = shape_data[shape_a] - mesh_scale_a = wp.vec3(scale_data_a[0], scale_data_a[1], scale_data_a[2]) - X_ws_a = shape_transform[shape_a] - shape_data_a, v0_world = get_triangle_shape_from_mesh(mesh_id_a, mesh_scale_a, X_ws_a, tri_idx) - - # Extract shape B data - pos_b, quat_b, shape_data_b, _scale_b, margin_offset_b = extract_shape_data( - shape_b, - shape_transform, - shape_types, - shape_data, - shape_source, - ) + triple = triangle_pairs[i] + shape_a = triple[0] # Mesh or heightfield shape + shape_b = triple[1] # Convex shape + tri_idx = triple[2] - # Triangle position is vertex A in world space. - # For heightfield prisms, edges are in heightfield-local space - # so we pass the heightfield rotation to let MPR/GJK work in - # that frame (where -Z is always the down axis). - pos_a = v0_world - if type_a == GeoType.HFIELD: - quat_a = wp.transform_get_rotation(shape_transform[shape_a]) - else: - quat_a = wp.quat_identity() - - # Back-face culling: skip when the convex center is behind the - # triangle face. TRIANGLE_PRISM (heightfields) handles this - # via its extruded support function. - if shape_data_a.shape_type == int(GeoTypeEx.TRIANGLE): - face_normal = wp.cross(shape_data_a.scale, shape_data_a.auxiliary) - center_dist = wp.dot(face_normal, pos_b - pos_a) - if center_dist < 0.0: - continue - - # Extract margin offset for shape A (signed distance padding) - margin_offset_a = shape_data[shape_a][3] - - # Use additive per-shape contact gap for detection threshold - gap_a = shape_gap[shape_a] - gap_b = shape_gap[shape_b] - gap_sum = gap_a + gap_b - - # Compute and write contacts using GJK/MPR - wp.static(create_compute_gjk_mpr_contacts(write_contact_to_reducer))( - shape_data_a, - shape_data_b, - quat_a, - quat_b, - pos_a, - pos_b, - gap_sum, - shape_a, - shape_b, - margin_offset_a, - margin_offset_b, - reducer_data, - ) + type_a = shape_types[shape_a] + + if type_a == GeoType.HFIELD: + # Heightfield triangle + hfd = heightfield_data[shape_heightfield_index[shape_a]] + X_ws_a = shape_transform[shape_a] + shape_data_a, v0_world = get_triangle_shape_from_heightfield( + hfd, heightfield_elevations, X_ws_a, tri_idx + ) + else: + # Mesh triangle (mesh_id already validated by midphase) + mesh_id_a = shape_source[shape_a] + scale_data_a = shape_data[shape_a] + mesh_scale_a = wp.vec3(scale_data_a[0], scale_data_a[1], scale_data_a[2]) + X_ws_a = shape_transform[shape_a] + shape_data_a, v0_world = get_triangle_shape_from_mesh(mesh_id_a, mesh_scale_a, X_ws_a, tri_idx) + + # Extract shape B data + pos_b, quat_b, shape_data_b, _scale_b, margin_offset_b = extract_shape_data( + shape_b, + shape_transform, + shape_types, + shape_data, + shape_source, + ) + + # Triangle position is vertex A in world space. + # For heightfield prisms, edges are in heightfield-local space + # so we pass the heightfield rotation to let MPR/GJK work in + # that frame (where -Z is always the down axis). + pos_a = v0_world + if type_a == GeoType.HFIELD: + quat_a = wp.transform_get_rotation(shape_transform[shape_a]) + else: + quat_a = wp.quat_identity() + + # Back-face culling: skip when the convex center is behind the + # triangle face. TRIANGLE_PRISM (heightfields) handles this + # via its extruded support function. + if shape_data_a.shape_type == int(GeoTypeEx.TRIANGLE): + face_normal = wp.cross(shape_data_a.scale, shape_data_a.auxiliary) + center_dist = wp.dot(face_normal, pos_b - pos_a) + if center_dist < 0.0: + continue + + # Extract margin offset for shape A (signed distance padding) + margin_offset_a = shape_data[shape_a][3] + + # Use additive per-shape contact gap for detection threshold + gap_a = shape_gap[shape_a] + gap_b = shape_gap[shape_b] + gap_sum = gap_a + gap_b + + if wp.static(speculative): + vel_rel = shape_lin_vel[shape_b] - shape_lin_vel[shape_a] + rel_speed = wp.length(vel_rel) + shape_ang_speed_bound[shape_a] + shape_ang_speed_bound[shape_b] + gap_sum = gap_sum + wp.min(rel_speed * speculative_dt, max_speculative_extension) + + # Compute and write contacts using GJK/MPR + wp.static(create_compute_gjk_mpr_contacts(write_contact_to_reducer))( + shape_data_a, + shape_data_b, + quat_a, + quat_b, + pos_a, + pos_b, + gap_sum, + shape_a, + shape_b, + margin_offset_a, + margin_offset_b, + reducer_data, + ) + + return mesh_triangle_contacts_to_reducer_kernel diff --git a/newton/_src/geometry/narrow_phase.py b/newton/_src/geometry/narrow_phase.py index 036c51af66..d577f05ac4 100644 --- a/newton/_src/geometry/narrow_phase.py +++ b/newton/_src/geometry/narrow_phase.py @@ -36,7 +36,7 @@ from ..geometry.contact_reduction_global import ( GlobalContactReducer, create_export_reduced_contacts_kernel, - mesh_triangle_contacts_to_reducer_kernel, + create_mesh_triangle_contacts_to_reducer_kernel, reduce_buffered_contacts_kernel, write_contact_to_reducer, ) @@ -807,115 +807,140 @@ def narrow_phase_kernel_gjk_mpr( return narrow_phase_kernel_gjk_mpr -@wp.kernel(enable_backward=False) -def narrow_phase_find_mesh_triangle_overlaps_kernel( - shape_types: wp.array[int], - shape_transform: wp.array[wp.transform], - shape_source: wp.array[wp.uint64], - shape_gap: wp.array[float], # Per-shape contact gaps - shape_data: wp.array[wp.vec4], # Shape data (scale xyz, margin w) - shape_collision_radius: wp.array[float], - shape_heightfield_index: wp.array[wp.int32], - heightfield_data: wp.array[HeightfieldData], - shape_pairs_mesh: wp.array[wp.vec2i], - shape_pairs_mesh_count: wp.array[int], - total_num_threads: int, - # outputs - triangle_pairs: wp.array[wp.vec3i], # (shape_a, shape_b, triangle_idx) - triangle_pairs_count: wp.array[int], -): - """Find triangles that overlap with a convex shape for mesh and heightfield pairs. - - For mesh pairs, uses a tiled BVH query. For heightfield pairs, projects the - convex shape's bounding sphere onto the heightfield grid and emits triangle - pairs for each overlapping cell. +def _create_find_mesh_triangle_overlaps_kernel(speculative: bool): + """Factory for the midphase kernel that finds mesh/heightfield triangle overlaps. - Outputs triples of ``(mesh_or_hfield_shape, other_shape, triangle_idx)``. + When *speculative* is True the kernel reads per-shape velocity arrays and + expands the BVH query AABB by the speculative margin so that triangles + about to be hit are included as candidates. """ - tid, j = wp.tid() - - num_mesh_pairs = shape_pairs_mesh_count[0] - - # Strided loop over mesh pairs - for i in range(tid, num_mesh_pairs, total_num_threads): - pair = shape_pairs_mesh[i] - shape_a = pair[0] - shape_b = pair[1] - - type_a = shape_types[shape_a] - type_b = shape_types[shape_b] - - # ----------------------------------------------------------------- - # Heightfield-vs-convex midphase (grid cell lookup) - # Pairs are normalized so the heightfield is always shape_a. - # ----------------------------------------------------------------- - if type_a == GeoType.HFIELD: - # Only run on j==0; the j dimension is for tiled BVH queries (mesh only). - if j != 0: + + @wp.kernel(enable_backward=False) + def narrow_phase_find_mesh_triangle_overlaps_kernel( + shape_types: wp.array[int], + shape_transform: wp.array[wp.transform], + shape_source: wp.array[wp.uint64], + shape_gap: wp.array[float], # Per-shape contact gaps + shape_data: wp.array[wp.vec4], # Shape data (scale xyz, margin w) + shape_collision_radius: wp.array[float], + shape_heightfield_index: wp.array[wp.int32], + heightfield_data: wp.array[HeightfieldData], + shape_pairs_mesh: wp.array[wp.vec2i], + shape_pairs_mesh_count: wp.array[int], + total_num_threads: int, + shape_lin_vel: wp.array[wp.vec3], + shape_ang_speed_bound: wp.array[float], + speculative_dt: float, + max_speculative_extension: float, + # outputs + triangle_pairs: wp.array[wp.vec3i], # (shape_a, shape_b, triangle_idx) + triangle_pairs_count: wp.array[int], + ): + """Find triangles that overlap with a convex shape for mesh and heightfield pairs. + + For mesh pairs, uses a tiled BVH query. For heightfield pairs, projects the + convex shape's bounding sphere onto the heightfield grid and emits triangle + pairs for each overlapping cell. + + Outputs triples of ``(mesh_or_hfield_shape, other_shape, triangle_idx)``. + """ + tid, j = wp.tid() + + num_mesh_pairs = shape_pairs_mesh_count[0] + + # Strided loop over mesh pairs + for i in range(tid, num_mesh_pairs, total_num_threads): + pair = shape_pairs_mesh[i] + shape_a = pair[0] + shape_b = pair[1] + + type_a = shape_types[shape_a] + type_b = shape_types[shape_b] + + # ----------------------------------------------------------------- + # Heightfield-vs-convex midphase (grid cell lookup) + # Pairs are normalized so the heightfield is always shape_a. + # ----------------------------------------------------------------- + if type_a == GeoType.HFIELD: + # Only run on j==0; the j dimension is for tiled BVH queries (mesh only). + if j != 0: + continue + hfd = heightfield_data[shape_heightfield_index[shape_a]] + heightfield_vs_convex_midphase( + shape_a, + shape_b, + hfd, + shape_transform, + shape_collision_radius, + shape_gap, + triangle_pairs, + triangle_pairs_count, + ) continue - hfd = heightfield_data[shape_heightfield_index[shape_a]] - heightfield_vs_convex_midphase( - shape_a, - shape_b, - hfd, - shape_transform, - shape_collision_radius, - shape_gap, + + # ----------------------------------------------------------------- + # Mesh-vs-convex midphase (BVH query) + # ----------------------------------------------------------------- + mesh_shape = -1 + non_mesh_shape = -1 + + if type_a == GeoType.MESH and type_b != GeoType.MESH: + mesh_shape = shape_a + non_mesh_shape = shape_b + elif type_b == GeoType.MESH and type_a != GeoType.MESH: + mesh_shape = shape_b + non_mesh_shape = shape_a + else: + # Mesh-mesh collision not supported in this path + continue + + # Get mesh BVH ID and mesh transform + mesh_id = shape_source[mesh_shape] + if mesh_id == wp.uint64(0): + continue + + # Get mesh world transform + X_mesh_ws = shape_transform[mesh_shape] + + # Get non-mesh shape world transform + X_ws = shape_transform[non_mesh_shape] + + # Use per-shape contact gaps for consistent pairwise thresholding. + gap_non_mesh = shape_gap[non_mesh_shape] + gap_mesh = shape_gap[mesh_shape] + gap_sum = gap_non_mesh + gap_mesh + + if wp.static(speculative): + vel_rel = shape_lin_vel[non_mesh_shape] - shape_lin_vel[mesh_shape] + rel_speed = ( + wp.length(vel_rel) + shape_ang_speed_bound[mesh_shape] + shape_ang_speed_bound[non_mesh_shape] + ) + gap_sum = gap_sum + wp.min(rel_speed * speculative_dt, max_speculative_extension) + + # Call mesh_vs_convex_midphase with the shape_data and pair gap sum. + mesh_vs_convex_midphase( + j, + mesh_shape, + non_mesh_shape, + X_mesh_ws, + X_ws, + mesh_id, + shape_types, + shape_data, + shape_source, + gap_sum, triangle_pairs, triangle_pairs_count, ) - continue - - # ----------------------------------------------------------------- - # Mesh-vs-convex midphase (BVH query) - # ----------------------------------------------------------------- - mesh_shape = -1 - non_mesh_shape = -1 - - if type_a == GeoType.MESH and type_b != GeoType.MESH: - mesh_shape = shape_a - non_mesh_shape = shape_b - elif type_b == GeoType.MESH and type_a != GeoType.MESH: - mesh_shape = shape_b - non_mesh_shape = shape_a - else: - # Mesh-mesh collision not supported in this path - continue - - # Get mesh BVH ID and mesh transform - mesh_id = shape_source[mesh_shape] - if mesh_id == wp.uint64(0): - continue - - # Get mesh world transform - X_mesh_ws = shape_transform[mesh_shape] - - # Get non-mesh shape world transform - X_ws = shape_transform[non_mesh_shape] - - # Use per-shape contact gaps for consistent pairwise thresholding. - gap_non_mesh = shape_gap[non_mesh_shape] - gap_mesh = shape_gap[mesh_shape] - gap_sum = gap_non_mesh + gap_mesh - - # Call mesh_vs_convex_midphase with the shape_data and pair gap sum. - mesh_vs_convex_midphase( - j, - mesh_shape, - non_mesh_shape, - X_mesh_ws, - X_ws, - mesh_id, - shape_types, - shape_data, - shape_source, - gap_sum, - triangle_pairs, - triangle_pairs_count, - ) + + return narrow_phase_find_mesh_triangle_overlaps_kernel + + +_find_mesh_triangle_overlaps = _create_find_mesh_triangle_overlaps_kernel(speculative=False) +_find_mesh_triangle_overlaps_speculative = _create_find_mesh_triangle_overlaps_kernel(speculative=True) -def create_narrow_phase_process_mesh_triangle_contacts_kernel(writer_func: Any): +def create_narrow_phase_process_mesh_triangle_contacts_kernel(writer_func: Any, speculative: bool = False): @wp.kernel(enable_backward=False, module="unique") def narrow_phase_process_mesh_triangle_contacts_kernel( shape_types: wp.array[int], @@ -930,6 +955,10 @@ def narrow_phase_process_mesh_triangle_contacts_kernel( triangle_pairs_count: wp.array[int], writer_data: Any, total_num_threads: int, + shape_lin_vel: wp.array[wp.vec3], + shape_ang_speed_bound: wp.array[float], + speculative_dt: float, + max_speculative_extension: float, ): """ Process triangle pairs to generate contacts using GJK/MPR. @@ -1001,6 +1030,11 @@ def narrow_phase_process_mesh_triangle_contacts_kernel( gap_b = shape_gap[shape_b] gap_sum = gap_a + gap_b + if wp.static(speculative): + vel_rel = shape_lin_vel[shape_b] - shape_lin_vel[shape_a] + rel_speed = wp.length(vel_rel) + shape_ang_speed_bound[shape_a] + shape_ang_speed_bound[shape_b] + gap_sum = gap_sum + wp.min(rel_speed * speculative_dt, max_speculative_extension) + # Compute and write contacts using GJK/MPR with standard post-processing wp.static(create_compute_gjk_mpr_contacts(writer_func))( shape_data_a, @@ -1096,6 +1130,7 @@ def compute_mesh_plane_block_offsets_scan( def create_narrow_phase_process_mesh_plane_contacts_kernel( writer_func: Any, reduce_contacts: bool = False, + speculative: bool = False, ): """ Create a mesh-plane collision kernel. @@ -1103,6 +1138,8 @@ def create_narrow_phase_process_mesh_plane_contacts_kernel( Args: writer_func: Contact writer function (e.g., write_contact_simple) reduce_contacts: If True, return multi-block load-balanced variant for global reduction. + speculative: When True, extends ``gap_sum`` by a scalar speculative + margin derived from per-shape velocity arrays. Returns: A warp kernel that processes mesh-plane collisions @@ -1121,6 +1158,10 @@ def narrow_phase_process_mesh_plane_contacts_kernel( shape_pairs_mesh_plane_count: wp.array[int], writer_data: Any, total_num_blocks: int, + shape_lin_vel: wp.array[wp.vec3], + shape_ang_speed_bound: wp.array[float], + speculative_dt: float, + max_speculative_extension: float, ): """ Process mesh-plane collisions without contact reduction. @@ -1169,6 +1210,13 @@ def narrow_phase_process_mesh_plane_contacts_kernel( gap_plane = shape_gap[plane_shape] gap_sum = gap_mesh + gap_plane + if wp.static(speculative): + vel_rel = shape_lin_vel[plane_shape] - shape_lin_vel[mesh_shape] + rel_speed = ( + wp.length(vel_rel) + shape_ang_speed_bound[mesh_shape] + shape_ang_speed_bound[plane_shape] + ) + gap_sum = gap_sum + wp.min(rel_speed * speculative_dt, max_speculative_extension) + # Strided loop over vertices across all threads in the launch total_num_threads = total_num_blocks * wp.block_dim() for vertex_idx in range(tid, num_vertices, total_num_threads): @@ -1227,6 +1275,10 @@ def narrow_phase_process_mesh_plane_contacts_reduce_kernel( block_offsets: wp.array[wp.int32], writer_data: Any, total_num_blocks: int, + shape_lin_vel: wp.array[wp.vec3], + shape_ang_speed_bound: wp.array[float], + speculative_dt: float, + max_speculative_extension: float, ): """Process mesh-plane collisions with dynamic load balancing. @@ -1300,6 +1352,13 @@ def narrow_phase_process_mesh_plane_contacts_reduce_kernel( gap_plane = shape_gap[plane_shape] gap_sum = gap_mesh + gap_plane + if wp.static(speculative): + vel_rel = shape_lin_vel[plane_shape] - shape_lin_vel[mesh_shape] + rel_speed = ( + wp.length(vel_rel) + shape_ang_speed_bound[mesh_shape] + shape_ang_speed_bound[plane_shape] + ) + gap_sum = gap_sum + wp.min(rel_speed * speculative_dt, max_speculative_extension) + # Process this block's chunk of vertices — write contacts directly # to the global reducer buffer (no per-block shared memory reduction). chunk_len = vert_end - vert_start @@ -1548,9 +1607,15 @@ def __init__( ) # Create triangle contacts kernel when meshes or heightfields are present if has_meshes or has_heightfields: - self.mesh_triangle_contacts_kernel = create_narrow_phase_process_mesh_triangle_contacts_kernel(writer_func) + self.mesh_triangle_contacts_kernel = create_narrow_phase_process_mesh_triangle_contacts_kernel( + writer_func, speculative=speculative + ) + self.mesh_triangle_overlaps_kernel = ( + _find_mesh_triangle_overlaps_speculative if speculative else _find_mesh_triangle_overlaps + ) else: self.mesh_triangle_contacts_kernel = None + self.mesh_triangle_overlaps_kernel = _find_mesh_triangle_overlaps # Create mesh-specific kernels only when has_meshes=True if has_meshes: @@ -1561,10 +1626,12 @@ def __init__( self.mesh_plane_contacts_kernel = create_narrow_phase_process_mesh_plane_contacts_kernel( write_contact_to_reducer, reduce_contacts=True, + speculative=speculative, ) else: self.mesh_plane_contacts_kernel = create_narrow_phase_process_mesh_plane_contacts_kernel( writer_func, + speculative=speculative, ) # Only create mesh-mesh SDF kernel on CUDA (uses __shared__ memory via func_native) if is_gpu_device: @@ -1573,11 +1640,13 @@ def __init__( write_contact_to_reducer, enable_heightfields=has_heightfields, reduce_contacts=True, + speculative=speculative, ) else: self.mesh_mesh_contacts_kernel = create_narrow_phase_process_mesh_mesh_contacts_kernel( writer_func, enable_heightfields=has_heightfields, + speculative=speculative, ) else: self.mesh_mesh_contacts_kernel = None @@ -1590,10 +1659,14 @@ def __init__( # Global contact reducer uses hardcoded BETA_THRESHOLD (0.1mm) same as shared-memory reduction # Slot layout: NUM_SPATIAL_DIRECTIONS spatial + 1 max-depth = VALUES_PER_KEY slots per key self.export_reduced_contacts_kernel = create_export_reduced_contacts_kernel(writer_func) + self.mesh_triangle_to_reducer_kernel = create_mesh_triangle_contacts_to_reducer_kernel( + speculative=speculative + ) # Global contact reducer for all mesh contact types self.global_contact_reducer = GlobalContactReducer(max_triangle_pairs, device=device) else: self.export_reduced_contacts_kernel = None + self.mesh_triangle_to_reducer_kernel = None self.global_contact_reducer = None self.hydroelastic_sdf = hydroelastic_sdf @@ -1860,6 +1933,10 @@ def launch_custom_write( self.shape_pairs_mesh_plane_count, writer_data, self.num_tile_blocks, + _slv, + _sasb, + speculative_dt, + max_speculative_extension, ], device=device, block_dim=self.block_dim, @@ -1869,7 +1946,7 @@ def launch_custom_write( # Launch midphase: finds overlapping triangles for both mesh and heightfield pairs second_dim = self.tile_size_mesh_convex if ENABLE_TILE_BVH_QUERY else 1 wp.launch( - kernel=narrow_phase_find_mesh_triangle_overlaps_kernel, + kernel=self.mesh_triangle_overlaps_kernel, dim=[self.num_tile_blocks, second_dim], inputs=[ shape_types, @@ -1883,6 +1960,10 @@ def launch_custom_write( self.shape_pairs_mesh, self.shape_pairs_mesh_count, self.num_tile_blocks, + _slv, + _sasb, + speculative_dt, + max_speculative_extension, ], outputs=[ self.triangle_pairs, @@ -1929,6 +2010,10 @@ def launch_custom_write( self.mesh_plane_block_offsets, reducer_data, self.num_mesh_plane_blocks, + _slv, + _sasb, + speculative_dt, + max_speculative_extension, ], device=device, block_dim=self.tile_size_mesh_plane, @@ -1937,7 +2022,7 @@ def launch_custom_write( # Mesh/heightfield-triangle contacts → same global reducer wp.launch( - kernel=mesh_triangle_contacts_to_reducer_kernel, + kernel=self.mesh_triangle_to_reducer_kernel, dim=self.total_num_threads, inputs=[ shape_types, @@ -1952,6 +2037,10 @@ def launch_custom_write( self.triangle_pairs_count, reducer_data, self.total_num_threads, + _slv, + _sasb, + speculative_dt, + max_speculative_extension, ], device=device, block_dim=self.block_dim, @@ -1975,6 +2064,10 @@ def launch_custom_write( self.triangle_pairs_count, writer_data, self.total_num_threads, + _slv, + _sasb, + speculative_dt, + max_speculative_extension, ], device=device, block_dim=self.block_dim, @@ -2050,6 +2143,10 @@ def launch_custom_write( self.mesh_mesh_block_offsets, reducer_data, self.num_mesh_mesh_blocks, + _slv, + _sasb, + speculative_dt, + max_speculative_extension, ], device=device, block_dim=self.tile_size_mesh_mesh, @@ -2079,6 +2176,10 @@ def launch_custom_write( shape_edge_range, writer_data, self.num_tile_blocks, + _slv, + _sasb, + speculative_dt, + max_speculative_extension, ], device=device, block_dim=self.tile_size_mesh_mesh, diff --git a/newton/_src/geometry/sdf_contact.py b/newton/_src/geometry/sdf_contact.py index b739b939db..b78f9c7c49 100644 --- a/newton/_src/geometry/sdf_contact.py +++ b/newton/_src/geometry/sdf_contact.py @@ -22,6 +22,30 @@ _get_shared_memory_sdf_cache = create_shared_memory_pointer_block_dim_mul_func(1) +@wp.func +def _query_mesh_face_normal( + mesh_id: wp.uint64, + point_local: wp.vec3, + max_dist: float = 1000.0, +) -> wp.vec3: + """Return the outward face normal of the closest triangle on a mesh. + + Falls back to the point-to-center direction when the query misses. + The returned vector is in mesh-local space and is normalized. + """ + face_index = int(0) + face_u = float(0.0) + face_v = float(0.0) + sign = float(0.0) + res = wp.mesh_query_point_sign_normal(mesh_id, point_local, max_dist, sign, face_index, face_u, face_v) + if res: + n = wp.mesh_eval_face_normal(mesh_id, face_index) + if sign < 0.0: + n = -n + return n + return wp.vec3(0.0, 1.0, 0.0) + + @wp.func def scale_sdf_result_to_world( distance: float, @@ -999,6 +1023,7 @@ def create_narrow_phase_process_mesh_mesh_contacts_kernel( writer_func: Any, enable_heightfields: bool = True, reduce_contacts: bool = False, + speculative: bool = False, ): find_interesting_edges, do_edge_sdf_collision = _create_sdf_contact_funcs(enable_heightfields) @@ -1022,6 +1047,10 @@ def mesh_sdf_collision_kernel( shape_edge_range: wp.array[wp.vec2i], writer_data: Any, total_num_blocks: int, + shape_lin_vel: wp.array[wp.vec3], + shape_ang_speed_bound: wp.array[float], + speculative_dt: float, + max_speculative_extension: float, ): """Process mesh-mesh and mesh-heightfield collisions using SDF-based detection.""" block_id, t = wp.tid() @@ -1038,7 +1067,13 @@ def mesh_sdf_collision_kernel( has_hfield = False pair = pair_encoded - gap_sum = shape_gap[pair[0]] + shape_gap[pair[1]] + base_gap_sum = shape_gap[pair[0]] + shape_gap[pair[1]] + gap_sum = base_gap_sum + + if wp.static(speculative): + vel_rel = shape_lin_vel[pair[1]] - shape_lin_vel[pair[0]] + rel_speed = wp.length(vel_rel) + shape_ang_speed_bound[pair[0]] + shape_ang_speed_bound[pair[1]] + gap_sum = gap_sum + wp.min(rel_speed * speculative_dt, max_speculative_extension) for mode in range(2): tri_shape = pair[mode] @@ -1246,6 +1281,15 @@ def mesh_sdf_collision_kernel( else: direction_world = wp.vec3(0.0, 1.0, 0.0) + if wp.static(speculative): + base_threshold = base_gap_sum + triangle_mesh_margin + sdf_mesh_margin + if dist > base_threshold and not sdf_is_hfield: + face_n = _query_mesh_face_normal(mesh_id_sdf, point) + face_n_world = wp.transform_vector(X_sdf_ws, face_n) + fn_len = wp.length(face_n_world) + if fn_len > 0.0: + direction_world = face_n_world / fn_len + contact_normal = -direction_world if mode == 0 else direction_world contact_data = ContactData() @@ -1298,6 +1342,10 @@ def mesh_sdf_collision_global_reduce_kernel( block_offsets: wp.array[wp.int32], reducer_data: GlobalContactReducerData, total_num_blocks: int, + shape_lin_vel: wp.array[wp.vec3], + shape_ang_speed_bound: wp.array[float], + speculative_dt: float, + max_speculative_extension: float, ): """Process mesh-mesh collisions with global hashtable contact reduction. @@ -1334,7 +1382,13 @@ def mesh_sdf_collision_global_reduce_kernel( has_hfield = False pair = pair_encoded - gap_sum = shape_gap[pair[0]] + shape_gap[pair[1]] + base_gap_sum = shape_gap[pair[0]] + shape_gap[pair[1]] + gap_sum = base_gap_sum + + if wp.static(speculative): + vel_rel = shape_lin_vel[pair[1]] - shape_lin_vel[pair[0]] + rel_speed = wp.length(vel_rel) + shape_ang_speed_bound[pair[0]] + shape_ang_speed_bound[pair[1]] + gap_sum = gap_sum + wp.min(rel_speed * speculative_dt, max_speculative_extension) for mode in range(2): tri_shape = pair[mode] @@ -1546,6 +1600,15 @@ def mesh_sdf_collision_global_reduce_kernel( else: direction_world = wp.vec3(0.0, 1.0, 0.0) + if wp.static(speculative): + base_threshold = base_gap_sum + triangle_mesh_margin + sdf_mesh_margin + if dist > base_threshold and not sdf_is_hfield: + face_n = _query_mesh_face_normal(mesh_id_sdf, point) + face_n_world = wp.transform_vector(X_sdf_ws, face_n) + fn_len = wp.length(face_n_world) + if fn_len > 0.0: + direction_world = face_n_world / fn_len + contact_normal = -direction_world if mode == 0 else direction_world export_and_reduce_contact_centered( diff --git a/newton/tests/test_speculative_contacts.py b/newton/tests/test_speculative_contacts.py index 97ca9a4370..d8a36b60a0 100644 --- a/newton/tests/test_speculative_contacts.py +++ b/newton/tests/test_speculative_contacts.py @@ -5,6 +5,7 @@ import unittest +import numpy as np import warp as wp import newton @@ -241,6 +242,193 @@ def test_speculative_tunneling_with(test, device): ) +def _make_thin_wall_mesh(hx=0.02, hy=1.0, hz=1.0): + """Return a :class:`newton.Mesh` representing a thin box (wall). + + The wall is centred at the origin with half-extents ``(hx, hy, hz)``. + Winding is CCW when viewed from the +X side so that the face normals + point outward. + """ + verts = np.array( + [ + [-hx, -hy, -hz], + [hx, -hy, -hz], + [hx, hy, -hz], + [-hx, hy, -hz], + [-hx, -hy, hz], + [hx, -hy, hz], + [hx, hy, hz], + [-hx, hy, hz], + ], + dtype=np.float32, + ) + tris = np.array( + [ + # -X face + 0, 3, 7, 0, 7, 4, + # +X face + 1, 5, 6, 1, 6, 2, + # -Y face + 0, 4, 5, 0, 5, 1, + # +Y face + 3, 2, 6, 3, 6, 7, + # -Z face + 0, 1, 2, 0, 2, 3, + # +Z face + 4, 7, 6, 4, 6, 5, + ], + dtype=np.int32, + ) + return newton.Mesh(verts, tris, compute_inertia=False) + + +# -- Sphere vs mesh wall (mesh-triangle path) -------------------------------- + + +def _run_sphere_vs_mesh_wall_sim(device, speculative_config, num_frames=5): + """Simulate a fast sphere aimed at a thin *mesh* wall. + + Same geometry as ``_run_sphere_vs_thin_box_sim`` but the wall is a + triangle mesh instead of a primitive box, exercising the mesh-triangle + contact path. + """ + builder = newton.ModelBuilder(gravity=0.0) + builder.rigid_gap = 0.0 + + sphere_body = builder.add_body(xform=wp.transform(wp.vec3(-2.0, 0.0, 0.0))) + builder.add_shape_sphere(sphere_body, radius=0.25) + builder.body_qd[-1] = (50.0, 0.0, 0.0, 0.0, 0.0, 0.0) + + wall_mesh = _make_thin_wall_mesh() + builder.add_shape_mesh(body=-1, mesh=wall_mesh, xform=wp.transform_identity()) + + model = builder.finalize(device=device) + + pipeline = newton.CollisionPipeline( + model, + broad_phase="nxn", + speculative_config=speculative_config, + ) + contacts = pipeline.contacts() + solver = newton.solvers.SolverXPBD(model) + + state_0 = model.state() + state_1 = model.state() + control = model.control() + frame_dt = 1.0 / 60.0 + + for _ in range(num_frames): + pipeline.collide(state_0, contacts, dt=frame_dt) + state_0.clear_forces() + solver.step(state_0, state_1, control, contacts, frame_dt) + state_0, state_1 = state_1, state_0 + + body_q = state_0.body_q.numpy() + return float(body_q[0][0]) + + +def test_speculative_tunneling_mesh_wall_without(test, device): + """Without speculative contacts the sphere tunnels through the mesh wall.""" + final_x = _run_sphere_vs_mesh_wall_sim(device, speculative_config=None) + test.assertGreater( + final_x, + 0.5, + f"Sphere should tunnel through the mesh wall (final x={final_x:.3f})", + ) + + +def test_speculative_tunneling_mesh_wall_with(test, device): + """With speculative contacts the sphere is stopped by the mesh wall.""" + config = newton.SpeculativeContactConfig( + max_speculative_extension=2.0, + collision_update_dt=1.0 / 60.0, + ) + final_x = _run_sphere_vs_mesh_wall_sim(device, speculative_config=config) + test.assertLess( + final_x, + -0.2, + f"Sphere should be stopped by the mesh wall (final x={final_x:.3f})", + ) + + +# -- Mesh box vs mesh wall (mesh-mesh SDF path) ------------------------------ + + +def _run_mesh_box_vs_mesh_wall_sim(device, speculative_config, num_frames=10): + """Simulate a fast mesh box aimed at a thin mesh wall. + + Both the projectile and the wall are triangle meshes with SDFs, + exercising the mesh-mesh SDF contact path. Same geometry as the + sphere-vs-primitive-box test (wall half-thickness 0.02 m). + + Uses ``max_resolution=256`` so the SDF has enough voxels across the + 0.04 m wall, and 8 XPBD iterations because mesh-mesh SDF contacts + have zero effective radii (unlike sphere contacts) and need more + solver work to fully resolve the large speculative gap. + """ + builder = newton.ModelBuilder(gravity=0.0) + builder.rigid_gap = 0.0 + + box_mesh = newton.Mesh.create_box(0.25, compute_normals=False, compute_uvs=False) + box_mesh.build_sdf(device=device, max_resolution=256) + + box_body = builder.add_body(xform=wp.transform(wp.vec3(-2.0, 0.0, 0.0))) + builder.add_shape_mesh(box_body, mesh=box_mesh) + builder.body_qd[-1] = (50.0, 0.0, 0.0, 0.0, 0.0, 0.0) + + wall_mesh = _make_thin_wall_mesh() + wall_mesh.build_sdf(device=device, max_resolution=256) + builder.add_shape_mesh(body=-1, mesh=wall_mesh, xform=wp.transform_identity()) + + model = builder.finalize(device=device) + + pipeline = newton.CollisionPipeline( + model, + broad_phase="nxn", + speculative_config=speculative_config, + ) + contacts = pipeline.contacts() + solver = newton.solvers.SolverXPBD(model, iterations=8) + + state_0 = model.state() + state_1 = model.state() + control = model.control() + frame_dt = 1.0 / 60.0 + + for _ in range(num_frames): + pipeline.collide(state_0, contacts, dt=frame_dt) + state_0.clear_forces() + solver.step(state_0, state_1, control, contacts, frame_dt) + state_0, state_1 = state_1, state_0 + + body_q = state_0.body_q.numpy() + return float(body_q[0][0]) + + +def test_speculative_tunneling_mesh_mesh_without(test, device): + """Without speculative contacts the mesh box tunnels through the mesh wall.""" + final_x = _run_mesh_box_vs_mesh_wall_sim(device, speculative_config=None) + test.assertGreater( + final_x, + 0.5, + f"Mesh box should tunnel through the mesh wall (final x={final_x:.3f})", + ) + + +def test_speculative_tunneling_mesh_mesh_with(test, device): + """With speculative contacts the mesh box is stopped by the mesh wall.""" + config = newton.SpeculativeContactConfig( + max_speculative_extension=2.0, + collision_update_dt=1.0 / 60.0, + ) + final_x = _run_mesh_box_vs_mesh_wall_sim(device, speculative_config=config) + test.assertLess( + final_x, + -0.2, + f"Mesh box should be stopped by the mesh wall (final x={final_x:.3f})", + ) + + class TestSpeculativeContacts(unittest.TestCase): pass @@ -285,6 +473,30 @@ class TestSpeculativeContacts(unittest.TestCase): add_function_test( TestSpeculativeContacts, "test_speculative_tunneling_with", test_speculative_tunneling_with, devices=devices ) +add_function_test( + TestSpeculativeContacts, + "test_speculative_tunneling_mesh_wall_without", + test_speculative_tunneling_mesh_wall_without, + devices=devices, +) +add_function_test( + TestSpeculativeContacts, + "test_speculative_tunneling_mesh_wall_with", + test_speculative_tunneling_mesh_wall_with, + devices=devices, +) +add_function_test( + TestSpeculativeContacts, + "test_speculative_tunneling_mesh_mesh_without", + test_speculative_tunneling_mesh_mesh_without, + devices=devices, +) +add_function_test( + TestSpeculativeContacts, + "test_speculative_tunneling_mesh_mesh_with", + test_speculative_tunneling_mesh_mesh_with, + devices=devices, +) if __name__ == "__main__": From 8751e228b66fc079b8804464f00c8d2fcd98e56a Mon Sep 17 00:00:00 2001 From: twidmer Date: Thu, 16 Apr 2026 08:45:03 +0200 Subject: [PATCH 08/10] Merge branch 'main' into dev/tw2/speculative_contacts # Conflicts: # newton/_src/geometry/contact_reduction_global.py # newton/_src/geometry/narrow_phase.py # newton/_src/sim/collide.py --- .github/workflows/aws_gpu_benchmarks.yml | 4 +- .github/workflows/aws_gpu_tests.yml | 4 +- .github/workflows/minimum_deps_tests.yml | 4 +- .github/workflows/mujoco_warp_tests.yml | 4 +- .github/workflows/warp_nightly_tests.yml | 4 +- CHANGELOG.md | 65 +- docs/concepts/collisions.rst | 42 +- docs/guide/release.rst | 30 +- newton/_src/geometry/collision_convex.py | 2 + newton/_src/geometry/collision_core.py | 3 + newton/_src/geometry/contact_data.py | 29 + .../_src/geometry/contact_reduction_global.py | 293 ++- .../contact_reduction_hydroelastic.py | 22 +- newton/_src/geometry/contact_sort.py | 376 ++++ newton/_src/geometry/multicontact.py | 2 + newton/_src/geometry/narrow_phase.py | 84 +- newton/_src/geometry/raycast.py | 54 +- newton/_src/geometry/sdf_contact.py | 15 +- newton/_src/geometry/sdf_hydroelastic.py | 68 +- newton/_src/geometry/support_function.py | 25 +- newton/_src/geometry/types.py | 18 + newton/_src/sim/builder.py | 2 +- newton/_src/sim/collide.py | 66 +- newton/_src/sim/contacts.py | 30 +- .../_src/solvers/kamino/_src/core/builder.py | 4 +- .../_src/solvers/kamino/_src/core/geometry.py | 25 + newton/_src/solvers/kamino/_src/core/model.py | 11 +- .../_src/solvers/kamino/_src/core/shapes.py | 77 +- .../solvers/kamino/_src/geometry/unified.py | 64 +- .../kamino/examples/rl/example_rl_bipedal.py | 120 +- .../solvers/kamino/examples/rl/simulation.py | 111 +- .../tests/test_geometry_mesh_heightfield.py | 604 ++++++ .../kamino/tests/test_geometry_unified.py | 2 +- newton/_src/solvers/mujoco/kernels.py | 408 ++-- newton/_src/solvers/mujoco/solver_mujoco.py | 84 +- newton/_src/solvers/xpbd/kernels.py | 99 + newton/_src/solvers/xpbd/solver_xpbd.py | 102 + newton/_src/utils/import_usd.py | 454 +++- newton/_src/viewer/gl/newton_envmap.jpg | Bin 187281 -> 105653 bytes newton/_src/viewer/gl/opengl.py | 68 +- newton/_src/viewer/gl/shaders.py | 193 +- newton/_src/viewer/kernels.py | 12 + newton/_src/viewer/picking.py | 52 + newton/_src/viewer/viewer.py | 55 +- newton/_src/viewer/viewer_gl.py | 100 +- newton/_src/viewer/viewer_viser.py | 144 +- newton/examples/__init__.py | 51 +- .../examples/basic/example_basic_conveyor.py | 4 +- newton/examples/cloth/example_cloth_franka.py | 174 +- .../robot/example_robot_panda_hydro.py | 16 +- newton/tests/assets/humanoid_mjc.usda | 1878 +++++++++++++++++ newton/tests/test_broad_phase.py | 10 - newton/tests/test_collision_pipeline.py | 319 +++ newton/tests/test_contact_reduction_global.py | 501 ++++- newton/tests/test_hashtable.py | 7 - newton/tests/test_hydroelastic.py | 1 - newton/tests/test_import_usd.py | 152 ++ newton/tests/test_import_usd_multi_dof.py | 67 + newton/tests/test_menagerie_mujoco.py | 2 - newton/tests/test_menagerie_usd_mujoco.py | 15 +- newton/tests/test_mujoco_solver.py | 108 + newton/tests/test_narrow_phase.py | 2 - newton/tests/test_raycast.py | 497 +++-- newton/tests/test_remesh.py | 6 - newton/tests/test_sensor_raycast.py | 75 + newton/tests/test_solver_xpbd.py | 383 ++++ newton/tests/test_viewer_picking.py | 2 - uv.lock | 188 +- 68 files changed, 7602 insertions(+), 891 deletions(-) create mode 100644 newton/_src/geometry/contact_sort.py create mode 100644 newton/_src/solvers/kamino/tests/test_geometry_mesh_heightfield.py create mode 100644 newton/tests/assets/humanoid_mjc.usda create mode 100644 newton/tests/test_import_usd_multi_dof.py diff --git a/.github/workflows/aws_gpu_benchmarks.yml b/.github/workflows/aws_gpu_benchmarks.yml index 189f05d6ab..7f98144f8a 100644 --- a/.github/workflows/aws_gpu_benchmarks.yml +++ b/.github/workflows/aws_gpu_benchmarks.yml @@ -71,7 +71,7 @@ jobs: echo "LATEST_AMI_ID=$LATEST_AMI_ID" >> "$GITHUB_ENV" - name: Start EC2 runner id: start-ec2-runner - uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 + uses: machulav/ec2-github-runner@343a1b2ae682e681c3cec9a235d882da17ff04ef # v2.6.1 with: mode: start github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} @@ -219,7 +219,7 @@ jobs: role-duration-seconds: ${{ env.AWS_ROLE_DURATION }} - name: Stop EC2 runner - uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 + uses: machulav/ec2-github-runner@343a1b2ae682e681c3cec9a235d882da17ff04ef # v2.6.1 with: mode: stop github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} diff --git a/.github/workflows/aws_gpu_tests.yml b/.github/workflows/aws_gpu_tests.yml index 2185027d95..2e28c1cab2 100644 --- a/.github/workflows/aws_gpu_tests.yml +++ b/.github/workflows/aws_gpu_tests.yml @@ -88,7 +88,7 @@ jobs: echo "LATEST_AMI_ID=$LATEST_AMI_ID" >> "$GITHUB_ENV" - name: Start EC2 runner id: start-ec2-runner - uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 + uses: machulav/ec2-github-runner@343a1b2ae682e681c3cec9a235d882da17ff04ef # v2.6.1 with: mode: start github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} @@ -236,7 +236,7 @@ jobs: role-duration-seconds: ${{ env.AWS_ROLE_DURATION }} - name: Stop EC2 runner - uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 + uses: machulav/ec2-github-runner@343a1b2ae682e681c3cec9a235d882da17ff04ef # v2.6.1 with: mode: stop github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} diff --git a/.github/workflows/minimum_deps_tests.yml b/.github/workflows/minimum_deps_tests.yml index f42538560a..b1dd22bcde 100644 --- a/.github/workflows/minimum_deps_tests.yml +++ b/.github/workflows/minimum_deps_tests.yml @@ -64,7 +64,7 @@ jobs: - name: Start EC2 runner id: start-ec2-runner - uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 + uses: machulav/ec2-github-runner@343a1b2ae682e681c3cec9a235d882da17ff04ef # v2.6.1 with: mode: start github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} @@ -186,7 +186,7 @@ jobs: role-duration-seconds: ${{ env.AWS_ROLE_DURATION }} - name: Stop EC2 runner - uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 + uses: machulav/ec2-github-runner@343a1b2ae682e681c3cec9a235d882da17ff04ef # v2.6.1 with: mode: stop github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} diff --git a/.github/workflows/mujoco_warp_tests.yml b/.github/workflows/mujoco_warp_tests.yml index c6992a8503..adcc68aa40 100644 --- a/.github/workflows/mujoco_warp_tests.yml +++ b/.github/workflows/mujoco_warp_tests.yml @@ -63,7 +63,7 @@ jobs: - name: Start EC2 runner id: start-ec2-runner - uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 + uses: machulav/ec2-github-runner@343a1b2ae682e681c3cec9a235d882da17ff04ef # v2.6.1 with: mode: start github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} @@ -194,7 +194,7 @@ jobs: role-duration-seconds: ${{ env.AWS_ROLE_DURATION }} - name: Stop EC2 runner - uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 + uses: machulav/ec2-github-runner@343a1b2ae682e681c3cec9a235d882da17ff04ef # v2.6.1 with: mode: stop github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} diff --git a/.github/workflows/warp_nightly_tests.yml b/.github/workflows/warp_nightly_tests.yml index aa087f30ca..430d0e2067 100644 --- a/.github/workflows/warp_nightly_tests.yml +++ b/.github/workflows/warp_nightly_tests.yml @@ -63,7 +63,7 @@ jobs: - name: Start EC2 runner id: start-ec2-runner - uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 + uses: machulav/ec2-github-runner@343a1b2ae682e681c3cec9a235d882da17ff04ef # v2.6.1 with: mode: start github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} @@ -189,7 +189,7 @@ jobs: role-duration-seconds: ${{ env.AWS_ROLE_DURATION }} - name: Stop EC2 runner - uses: machulav/ec2-github-runner@a00f575a87f3a96ec6de9413d16eeb828a3cc0a8 # v2.5.2 + uses: machulav/ec2-github-runner@343a1b2ae682e681c3cec9a235d882da17ff04ef # v2.6.1 with: mode: stop github-token: ${{ secrets.GH_PERSONAL_ACCESS_TOKEN }} diff --git a/CHANGELOG.md b/CHANGELOG.md index bb65f599da..45e243e230 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -4,6 +4,40 @@ ### Added +- Add `SolverXPBD.update_contacts()` to populate `contacts.force` with per-contact spatial forces (linear force and torque) derived from XPBD constraint impulses +- Raise process priority automatically in `--benchmark` mode for more stable measurements; add `--realtime` for maximum priority. +- Add `TRIANGLE_PRISM` support-function type for heightfield triangles, extruding 1 m along the heightfield's local -Z so GJK/MPR naturally resolves shapes on the back side +- Add `ViewerGL.log_scalar()` for live scalar time-series plots in the viewer +- Add `deterministic` flag to `CollisionPipeline` and `NarrowPhase` for GPU-thread-scheduling-independent contact ordering via radix sort and deterministic fingerprint tiebreaking in contact reduction +- Add `ViewerBase.log_arrows()` for arrow rendering (wide line + arrowhead) in the GL viewer with a dedicated geometry shader +- Add `enable_multiccd` parameter to `SolverMuJoCo` for multi-CCD contact generation (up to 4 contact points per geom pair) +- Add `ViewerViser.log_scalar()` for live scalar time-series plots via uPlot + +### Changed + +- Render all GL viewer lines (joints, contacts, wireframes) as geometry-shader quads instead of ``GL_LINES`` for uniform width across zoom levels and non-square viewports +- Pin `mujoco` and `mujoco-warp` dependencies to `~=3.6.0` +- Update default environment map texture in GL viewer (source: https://polyhaven.com/a/brown_photostudio_02) +- Increase conveyor rail roughness in `example_basic_conveyor` to reduce mirror-like reflections + +### Fixed + +- Fix viewer crash with `imgui_bundle>=1.92.6` when editing colors by normalizing `color_edit3` input/output in `_edit_color3` +- Show prismatic joints in the GL viewer when "Show Joints" is enabled +- Fix connect constraint anchor computation to account for joint reference positions when `SolverMuJoCo` is the chosen solver. +- Fix mesh-convex back-face contacts generating inverted normals that trap shapes inside meshes and cause solver divergence (NaN) +- Fix MPR convergence failure on large and extreme-aspect-ratio mesh triangles by projecting the starting point onto the triangle nearest the convex center +- Fix O(W²·S²) memory explosion in `CollisionPipeline` shape-pair buffer allocation for NXN and SAP broad phase modes by computing per-world pair counts instead of a global N² +- Fix `SensorRaycast` ignoring `PLANE` geometry +- Fix SDF hydroelastic broadphase scatter kernel using a grid-stride loop with binary search instead of per-pair thread launch +- Fix box support-map sign flips from quaternion rotation noise (~1e-14) producing invalid GJK/MPR contacts for face-touching boxes with non-trivial base rotations +- Fix USD import of multi-DOF joints from MuJoCo-converted assets where multiple revolute joints between the same two bodies caused false cycle detection; merge them into D6 joints with correct DOF label mapping for MjcActuator target resolution +- Fix ViewerViser mesh popping artifacts caused by viser's automatic LOD simplification creating holes in complex geometry + +## [1.1.0] - 2026-04-13 + +### Added + - Add repeatable `--warp-config KEY=VALUE` CLI option for overriding `warp.config` attributes when running examples - Add 3D texture-based SDF, replacing NanoVDB volumes in the mesh-mesh collision pipeline for improved performance and CPU compatibility. - Parse URDF joint `limit effort="..."` values and propagate them to imported revolute and prismatic joint `effort_limit` settings @@ -33,8 +67,14 @@ - Add `compute_normals` and `compute_uvs` optional arguments to `Mesh.create_heightfield()` and `Mesh.create_terrain()` - Pin `newton-assets` and `mujoco_menagerie` downloads to specific commit SHAs for reproducible builds (`NEWTON_ASSETS_REF`, `MENAGERIE_REF`) - Add `ref` parameter to `download_asset()` to allow overriding the pinned revision +- Add import of `UsdGeom.TetMesh` prims as soft meshes through `ModelBuilder.add_usd()` - Add `total_force_friction` and `force_matrix_friction` to `SensorContact` for tangential (friction) force decomposition -- Add `compute_normals` and `compute_uvs` optional arguments to `Mesh.create_heightfield()` and `Mesh.create_terrain()` +- Add Gaussian Splat geometry support via `ModelBuilder.add_shape_gaussian()` and USD import +- Add configurable Gaussian sorting modes to `SensorTiledCamera` +- Add automatic box, sphere, and capsule shape fitting for convex meshes during MJCF import +- Add color and texture reading to `usd.utils.get_mesh()` +- Export `ViewerBase` from `newton.viewer` public API +- Add `custom_attributes` argument to `ModelBuilder.add_shape_convex_hull()` - Add RJ45 plug-socket insertion example with SDF contacts, latch joint, and interactive gizmo - Add `SpeculativeContactConfig` and speculative contact support in `CollisionPipeline` to detect contacts for fast-moving objects before they tunnel through thin geometry - Add `TRIANGLE_PRISM` support-function type for heightfield triangles, extruding 1 m along the heightfield's local -Z so GJK/MPR naturally resolves shapes on the back side @@ -42,31 +82,32 @@ ### Changed +- Require `mujoco ~=3.6.0` and `mujoco-warp ~=3.6.0` (previously 3.5.x) +- Replace `plyfile` dependency with `open3d` for mesh I/O. Users who depended on `plyfile` transitively should install it separately. +- Switch Python build backend from `hatchling` to `uv_build` - Switch mesh-SDF collision from triangle-based gradient descent to edge-based Brent's method to reduce contact jitter - Unify heightfield and mesh collision pipeline paths; the separate `heightfield_midphase_kernel` and `shape_pairs_heightfield` buffer are removed in favor of the shared mesh midphase -- Replace per-shape `Model.shape_heightfield_data` / `Model.heightfield_elevation_data` with compact `Model.shape_heightfield_index` / `Model.heightfield_data` / `Model.heightfield_elevations`, matching the SDF indirection pattern +- Replace per-shape `Model.shape_heightfield_data` / `Model.heightfield_elevation_data` with compact `Model.shape_heightfield_index` / `Model.heightfield_data` / `Model.heightfield_elevations`, matching the SDF indirection pattern. Use `Model.heightfield_data` indexed via `Model.shape_heightfield_index` instead. - Standardize `rigid_contact_normal` to point from shape 0 toward shape 1 (A-to-B), matching the documented convention. Consumers that previously negated the normal on read (XPBD, VBD, MuJoCo, Kamino) no longer need to. -- Replace `Model.sdf_data` / `sdf_volume` / `sdf_coarse_volume` with texture-based equivalents (`texture_sdf_data`, `texture_sdf_coarse_textures`, `texture_sdf_subgrid_textures`) +- Replace `Model.sdf_data` / `sdf_volume` / `sdf_coarse_volume` with texture-based equivalents (`texture_sdf_data`, `texture_sdf_coarse_textures`, `texture_sdf_subgrid_textures`). Use `Model.texture_sdf_data`, `texture_sdf_coarse_textures`, and `texture_sdf_subgrid_textures` instead. - Render inertia boxes as wireframe lines instead of solid boxes in the GL viewer to avoid occluding objects - Make contact reduction normal binning configurable (polyhedron, scan directions, voxel budget) via constants in ``contact_reduction.py`` - Upgrade GL viewer lighting from Blinn-Phong to Cook-Torrance PBR with GGX distribution, Schlick-GGX geometry, Fresnel-weighted ambient, and ACES filmic tone mapping - Change implicit MPM residual computation to consider both infinity and l2 norm - Change implicit MPM hardening law from exponential to hyperbolic sine (`sinh(-h * log(Jp))`), no longer scales elastic modulus -- Change implicit MPM collider velocity mode names: `"forward"` / `"backward"` replace `"instantaneous"` / `"finite_difference"` +- Change implicit MPM collider velocity mode names: `"forward"` / `"backward"` replace `"instantaneous"` / `"finite_difference"`. Old names are no longer accepted. - Simplify `SensorContact` force output: add `total_force` (aggregate per sensing object) and `force_matrix` (per-counterpart breakdown, `None` when no counterparts) - Add `sensing_obj_idx` (`list[int]`), `counterpart_indices` (`list[list[int]]`), `sensing_obj_type`, and `counterpart_type` attributes. Rename `include_total` to `measure_total` - Replace verbose Apache 2.0 boilerplate with two-line SPDX-only license headers across all source and documentation files -- Add `custom_attributes` argument to `ModelBuilder.add_shape_convex_hull()` - Improve wrench preservation in hydroelastic contacts with contact reduction. - Show Newton deprecation warnings during example runs started via `python -m newton.examples ...` or `python -m newton.examples..`; pass `-W ignore::DeprecationWarning` if you need the previous quiet behavior. - Reorder `ModelBuilder.add_shape_gaussian()` parameters so `xform` precedes `gaussian`, in line with other `add_shape_*` methods. Callers using positional arguments should switch to keyword form (`gaussian=..., xform=...`); passing a `Gaussian` as the second positional argument still works but emits a `DeprecationWarning` - Rename `ModelBuilder.add_shape_ellipsoid()` parameters `a`, `b`, `c` to `rx`, `ry`, `rz`. Old names are still accepted as keyword arguments but emit a `DeprecationWarning` -- Rename `collide_plane_cylinder()` parameter `cylinder_center` to `cylinder_pos` for consistency with other collide functions +- Rename `collide_plane_cylinder()` parameter `cylinder_center` to `cylinder_pos` for consistency with other collide functions. The old name is no longer accepted. - Add optional `state` parameter to `SolverBase.update_contacts()` to align the base-class signature with Kamino and MuJoCo solvers - Use `Literal` types for `SolverImplicitMPM.Config` string fields with fixed option sets (`solver`, `warmstart_mode`, `collider_velocity_mode`, `grid_type`, `transfer_scheme`, `integration_scheme`) - Migrate `wp.array(dtype=X)` type annotations to `wp.array[X]` bracket syntax (Warp 1.12+). - Align articulated `State.body_qd` / FK / IK / Jacobian / mass-matrix linear velocity with COM-referenced motion. If you were comparing `body_qd[:3]` against finite-differenced body-origin motion, recover origin velocity via `v_origin = v_com - omega x r_com_world`. Descendant `FREE` / `DISTANCE` `joint_qd` remains parent-frame and `joint_f` remains a world-frame COM wrench. -- Pin `mujoco` and `mujoco-warp` dependencies to `~=3.6.0` ### Deprecated @@ -102,11 +143,9 @@ - Update `ModelBuilder` internal state after fast-path (GPU kernel) inertia validation so it matches the returned `Model` - Fix MJCF mesh scale resolution to use the mesh asset's own class rather than the geom's default class, avoiding incorrect vertex scaling for models like Robotiq 2F-85 V4 - Fix articulated bodies drifting laterally on the ground in XPBD solver by solving rigid contacts before joints -- Fix viewer crash with `imgui_bundle>=1.92.6` when editing colors by normalizing `color_edit3` input/output in `_edit_color3` - Fix `hide_collision_shapes=True` not hiding collision meshes that have bound PBR materials - Filter inactive particles in viewer so only particles with `ParticleFlags.ACTIVE` are rendered - Fix concurrent asset download races on Windows by using content-addressed cache directories -- Show prismatic joints in the GL viewer when "Show Joints" is enabled - Fix body `gravcomp` not being written to the MuJoCo spec, causing it to be absent from XML saved via `save_to_mjcf` - Fix `compute_world_offsets` grid ordering to match terrain grid row-major order so replicated world indices align with terrain block indices - Fix `eq_solimp` not being written to the MuJoCo spec for equality constraints, causing it to be absent from XML saved via `save_to_mjcf` @@ -131,14 +170,12 @@ - Fix heightfield bounding-sphere radius underestimating Z extent for asymmetric height ranges (e.g. `min_z=0, max_z=10`) - Fix VBD self-contact barrier C2 discontinuity at `d = tau` caused by a factor-of-two error in the log-barrier coefficient - Fix fast inertia validation treating near-symmetric tensors within `np.allclose()` default tolerances as corrections, aligning CPU and GPU validation warnings -- Fix connect constraint anchor computation to account for joint reference positions when `SolverMuJoCo` is the chosen solver. -- Fix forward-kinematics child-origin linear velocity for articulated translated joints - Fix URDF joint dynamics friction import so specified friction values are preserved during simulation +- Fix `requires_grad` not being preserved in `ArticulationView` attribute getters, breaking gradient propagation through selection queries - Fix duplicate Reset button in brick stacking example when using the example browser -- Fix mesh-convex back-face contacts generating inverted normals that trap shapes inside meshes and cause solver divergence (NaN) -- Fix MPR convergence failure on large and extreme-aspect-ratio mesh triangles by projecting the starting point onto the triangle nearest the convex center - Cap `cbor2` dependency to `<6` to prevent recorder test failures caused by breaking deserialization changes in cbor2 6.0 -- Fix O(W²·S²) memory explosion in `CollisionPipeline` shape-pair buffer allocation for NXN and SAP broad phase modes by computing per-world pair counts instead of a global N² +- Clamp viewer picking force to prevent explosion when picking light objects near stiff contacts, configurable via `pick_max_acceleration` parameter on the `Picking` class (default 5g of effective articulation mass) +- Fix `cloth_franka` example Jacobian broken by COM-referenced `body_qd` convention change; adjust robot base height, gripper orientations, and grasp targets for improved reachability (a follow-up PR will migrate the example to `newton.ik`) ## [1.0.0] - 2026-03-10 diff --git a/docs/concepts/collisions.rst b/docs/concepts/collisions.rst index 92322a6ec4..a417621de7 100644 --- a/docs/concepts/collisions.rst +++ b/docs/concepts/collisions.rst @@ -1324,7 +1324,15 @@ and is consumed by the solver :meth:`~solvers.SolverBase.step` method for contac * - Attribute - Description * - :attr:`~Contacts.force` - - Contact spatial forces (used by :class:`~sensors.SensorContact`) + - Contact spatial forces (used by :class:`~sensors.SensorContact`). + Populated by :meth:`~solvers.SolverBase.update_contacts`. + +.. note:: + + :class:`~solvers.SolverXPBD` with ``rigid_contact_con_weighting`` enabled + (the default) does not conserve momentum at contacts. The per-contact + forces written by :meth:`~solvers.SolverXPBD.update_contacts` are + approximate -- see that method's documentation for details. Example usage: @@ -1671,6 +1679,38 @@ Custom collision properties can be authored in USD: See :doc:`custom_attributes` and :doc:`usd_parsing` for details. +.. _Deterministic Contacts: + +Deterministic Contact Ordering +------------------------------ + +GPU thread scheduling is non-deterministic, so the order in which contacts are +written to the output buffer can vary between runs. Pass ``deterministic=True`` +to :class:`~newton.CollisionPipeline` (or :class:`~newton.geometry.NarrowPhase`) to guarantee +a reproducible contact order: + +.. code-block:: python + + pipeline = newton.CollisionPipeline(model, deterministic=True) + +This enables two mechanisms: + +1. **Fingerprint tiebreaking** — each contact carries a geometry-derived + fingerprint (triangle/edge index) that is used as a deterministic tiebreaker + in the ``atomic_max`` contact reduction, so the reduction winner is + independent of thread scheduling. +2. **Radix sort** — after the narrow phase, all contact arrays are reordered by + a 64-bit key encoding ``(shape_a, shape_b, sub_key)`` via a radix sort + + gather pass. + +The overhead is small: fingerprint storage per contact, modified packing in +the reduction, and one radix sort + gather pass per frame. The sort is +fully CUDA-graph-capturable. + +.. note:: + + Hydroelastic contacts are not yet covered by deterministic ordering. + .. _Performance: Performance diff --git a/docs/guide/release.rst b/docs/guide/release.rst index c47c9eae89..e51437ad7a 100644 --- a/docs/guide/release.rst +++ b/docs/guide/release.rst @@ -75,7 +75,7 @@ Pre-release planning - Verify deprecated symbols carry proper deprecation warnings and migration guidance (see :ref:`deprecation-timeline`). - Confirm new public API has complete docstrings and is included in - Sphinx docs (run ``docs/generate_api.py``). + Sphinx docs (run ``uv run docs/generate_api.py``). * - ☐ - Communicate the timeline to the community. @@ -91,17 +91,33 @@ Code freeze and release branch creation - Create ``release-X.Y`` branch from ``main`` and push it. * - ☐ - On **main**: bump the version in ``pyproject.toml`` to ``X.(Y+1).0.dev0`` and run - ``docs/generate_api.py``. + ``uv run docs/generate_api.py``. * - ☐ - On **release-X.Y**: bump the version in ``pyproject.toml`` to ``X.Y.ZrcN`` and - run ``docs/generate_api.py``. + run ``uv run docs/generate_api.py``. * - ☐ - On **release-X.Y**: update dependencies in ``pyproject.toml`` from dev - to RC versions where applicable, then regenerate ``uv.lock`` - (``uv lock``) and commit it. + to RC versions where applicable and remove the NVIDIA package index + (``[[tool.uv.index]]`` entry for ``nvidia`` **and** the + ``warp-lang`` entry in ``[tool.uv.sources]`` that references it) so + the release wheel installs purely from PyPI, then regenerate + ``uv.lock`` (``uv lock``) and commit. * - ☐ - Push tag ``vX.Y.Zrc1``. This triggers the ``release.yml`` workflow (build wheel → PyPI publish with manual approval). + * - ☐ + - Manually trigger the **minimum-dependency** and **multi-GPU** CI + workflows on the ``release-X.Y`` branch (the nightly orchestrator + only runs on ``main``). Verify both pass before announcing the RC. + + .. code-block:: bash + + # Minimum-dependency tests (lowest compatible PyPI versions) + gh workflow run minimum_deps_tests.yml --ref release-X.Y + + # Multi-GPU tests (g7e.12xlarge = 4× L40S GPUs) + gh workflow run aws_gpu_tests.yml --ref release-X.Y \ + -f instance-type=g7e.12xlarge * - ☐ - RC1 published to PyPI (approve in GitHub environment). @@ -115,7 +131,7 @@ branch and open a pull request targeting ``release-X.Y`` — never push directly to the release branch. For each new RC (``rc2``, ``rc3``, …) bump the version in -``pyproject.toml`` and run ``docs/generate_api.py``, then tag and push. +``pyproject.toml`` and run ``uv run docs/generate_api.py``, then tag and push. Resolve any cherry-pick conflicts or missing dependent cherry-picks that cause CI failures before tagging. @@ -194,7 +210,7 @@ otherwise. dependencies remain in the lock file. * - ☐ - Bump the version in ``pyproject.toml`` to ``X.Y.Z`` (remove the RC suffix) and - run ``docs/generate_api.py``. + run ``uv run docs/generate_api.py``. * - ☐ - Commit and push tag ``vX.Y.Z``. Automated workflows trigger: diff --git a/newton/_src/geometry/collision_convex.py b/newton/_src/geometry/collision_convex.py index 906b3db94d..61d2df4769 100644 --- a/newton/_src/geometry/collision_convex.py +++ b/newton/_src/geometry/collision_convex.py @@ -104,6 +104,7 @@ def solve_convex_multi_contact( contact_data.contact_point_center = point contact_data.contact_normal_a_to_b = normal_ws contact_data.contact_distance = signed_distance + contact_data.sort_sub_key = contact_template.sort_sub_key << 3 contact_data = post_process_contact( contact_data, geom_a, position_a, orientation_a, geom_b, position_b, orientation_b ) @@ -205,6 +206,7 @@ def solve_convex_single_contact( contact_data.contact_point_center = point contact_data.contact_normal_a_to_b = normal contact_data.contact_distance = signed_distance + contact_data.sort_sub_key = contact_template.sort_sub_key << 3 contact_data = post_process_contact( contact_data, geom_a, position_a, orientation_a, geom_b, position_b, orientation_b diff --git a/newton/_src/geometry/collision_core.py b/newton/_src/geometry/collision_core.py index 8312696ceb..66f66f6c42 100644 --- a/newton/_src/geometry/collision_core.py +++ b/newton/_src/geometry/collision_core.py @@ -307,6 +307,7 @@ def compute_gjk_mpr_contacts( margin_a: float, margin_b: float, writer_data: Any, + sort_sub_key: int = 0, ): """ Compute contacts between two shapes using GJK/MPR algorithm and write them. @@ -324,6 +325,7 @@ def compute_gjk_mpr_contacts( margin_a: Per-shape margin offset for shape A (signed distance padding) margin_b: Per-shape margin offset for shape B (signed distance padding) writer_data: Data structure for contact writer + sort_sub_key: Sub-key for deterministic contact sorting (e.g. triangle/edge index) """ data_provider = SupportMapDataProvider() @@ -354,6 +356,7 @@ def compute_gjk_mpr_contacts( contact_template.shape_a = shape_a contact_template.shape_b = shape_b contact_template.gap_sum = rigid_gap + contact_template.sort_sub_key = sort_sub_key if wp.static(ENABLE_MULTI_CONTACT): wp.static(create_solve_convex_multi_contact(support_func, writer_func, post_process_contact))( diff --git a/newton/_src/geometry/contact_data.py b/newton/_src/geometry/contact_data.py index a2aa469732..8330ef992b 100644 --- a/newton/_src/geometry/contact_data.py +++ b/newton/_src/geometry/contact_data.py @@ -37,6 +37,7 @@ class ContactData: contact_stiffness: Contact stiffness. 0.0 means no stiffness was set. contact_damping: Contact damping scale. 0.0 means no damping was set. contact_friction_scale: Friction scaling factor. 0.0 means no friction was set. + sort_sub_key: Sub-key for deterministic contact sorting (encodes edge/triangle/vertex index). """ contact_point_center: wp.vec3 @@ -52,6 +53,34 @@ class ContactData: contact_stiffness: float contact_damping: float contact_friction_scale: float + sort_sub_key: int + + +@wp.func +def make_contact_sort_key(shape_a: int, shape_b: int, sort_sub_key: int) -> wp.int64: + """Build a 64-bit sort key for deterministic contact ordering. + + Layout (bit 63 kept zero so int64 order matches uint64 order):: + + [62:43] shape_a (20 bits, max 1,048,575 shapes) + [42:23] shape_b (20 bits, max 1,048,575 shapes) + [22:0] sort_sub_key (23 bits, max 8,388,607) + + Values exceeding these bit widths are silently masked. The effective + limits depend on upstream bit consumption in each contact path: + + - Mesh-triangle contacts: ``(tri_idx << 1) | 1`` — 22 effective bits + for ``tri_idx`` (~4M triangles). When expanded by the multi-contact + path (``<< 3 | i``), this drops to 19 effective bits (~524K triangles). + - SDF contacts: ``(edge_idx << 2) | (mode << 1)`` — 21 effective bits + for ``edge_idx`` (~2M edges). After multi-contact expansion + (``<< 3``), 18 effective bits (~262K edges). + """ + return ( + ((wp.int64(shape_a) & wp.int64(0xFFFFF)) << wp.int64(43)) + | ((wp.int64(shape_b) & wp.int64(0xFFFFF)) << wp.int64(23)) + | (wp.int64(sort_sub_key) & wp.int64(0x7FFFFF)) + ) @wp.func diff --git a/newton/_src/geometry/contact_reduction_global.py b/newton/_src/geometry/contact_reduction_global.py index d0a793408a..177afcbcaa 100644 --- a/newton/_src/geometry/contact_reduction_global.py +++ b/newton/_src/geometry/contact_reduction_global.py @@ -242,31 +242,217 @@ def make_contact_key(shape_a: int, shape_b: int, bin_id: int) -> wp.uint64: return key +# --------------------------------------------------------------------------- +# Contact value packing +# --------------------------------------------------------------------------- +# Two packing modes exist — **fast** (default) and **deterministic**. +# Each variant is a standalone ``@wp.func``. The dispatching wrappers +# ``make_contact_value`` and ``unpack_contact_id`` select the variant +# at runtime based on a ``deterministic`` flag passed from +# ``GlobalContactReducerData.deterministic``, making the packing mode +# a per-reducer property instead of process-global state. +# +# **Fast** — ``(float_flip(score) << 32) | contact_id``. +# Full 32-bit score precision, no fingerprint. Contact_id in low 32 bits. +# +# **Deterministic** — ``(float_flip(score)>>10 << 42) | (fp << 20) | (id & 0xFFFFF)``. +# 22-bit score, 22-bit fingerprint tiebreaker, 20-bit contact_id. +# --------------------------------------------------------------------------- + +# 22-bit fingerprint is wide enough to distinguish any two contacts that share +# the same truncated score within a single reduction slot. The remaining 20 +# bits for contact_id support up to 1,048,575 buffered contacts. +FINGERPRINT_BITS = wp.constant(wp.uint64(22)) +CONTACT_ID_BITS = wp.constant(wp.uint64(20)) +CONTACT_ID_MASK = wp.constant(wp.uint64((1 << 20) - 1)) +FINGERPRINT_MASK = wp.constant(wp.uint64((1 << 22) - 1)) +# Plain Python int (not wp.constant) because it is used inside wp.static() +# which requires a Python-level value for compile-time evaluation. +SCORE_SHIFT = 10 + + +# -- Fast (non-deterministic) variants ------------------------------------- + + @wp.func -def make_contact_value(score: float, contact_id: int) -> wp.uint64: - """Pack score and contact_id into hashtable value for atomic max. +def _make_contact_value_fast(score: float, fingerprint: int, contact_id: int) -> wp.uint64: + """Pack score and contact_id into a uint64 for ``atomic_max`` (fast path). - High 32 bits: float_flip(score) - makes floats comparable as unsigned ints - Low 32 bits: contact_id - identifies which contact in the buffer + :: - Args: - score: Spatial projection score (higher is better) - contact_id: Index into the contact buffer + 63 32 31 0 + ┌─────────────────────┬────────────────────┐ + │ float_flip(score) │ contact_id │ + │ (32 bits) │ (32 bits) │ + └─────────────────────┴────────────────────┘ - Returns: - 64-bit value for hashtable (atomic max will select highest score) + Full 32-bit IEEE-754 precision for the score. The fingerprint argument + is accepted for signature compatibility but ignored — ties are broken + by contact_id (non-deterministic, but correct). + + Args: + score: Spatial projection score or negated depth [m]. Higher is better. + fingerprint: Ignored in this variant (kept for signature compatibility). + contact_id: Index into the contact buffer (from ``atomic_add``). """ return (wp.uint64(float_flip(score)) << wp.uint64(32)) | wp.uint64(contact_id) +@wp.func +def _make_preprune_probe_fast(score: float, fingerprint: int) -> wp.uint64: + """Pre-prune ceiling probe (fast path). + + Packs the full-precision score with ``0xFFFFFFFF`` in the contact_id + field, creating the maximum possible value for this score. The + comparison ``stored < probe`` is true whenever the stored value can + be beaten, regardless of what contact_id the new contact receives. + """ + return (wp.uint64(float_flip(score)) << wp.uint64(32)) | wp.uint64(0xFFFFFFFF) + + @wp.func_native(""" return static_cast(packed & 0xFFFFFFFFull); """) -def unpack_contact_id(packed: wp.uint64) -> int: - """Extract contact_id from packed value.""" +def _unpack_contact_id_fast(packed: wp.uint64) -> int: + """Extract contact_id (low 32 bits) — fast variant.""" + ... + + +# -- Deterministic variants ------------------------------------------------ + + +@wp.func +def _make_contact_value_det(score: float, fingerprint: int, contact_id: int) -> wp.uint64: + """Pack score, fingerprint, and contact_id into a uint64 for ``atomic_max``. + + This packing enables **deterministic contact reduction**: multiple GPU + threads propose contacts for the same reduction slot via ``atomic_max``. + By encoding a deterministic fingerprint (derived from geometry) above + the non-deterministic contact_id, the ``atomic_max`` winner is always + the same regardless of thread scheduling. + + :: + + 63 42 41 20 19 0 + ┌──────────┬────────────┬──────────────┐ + │ score │ fingerprint│ contact_id │ + │ (22 bit) │ (22 bit) │ (20 bit) │ + └──────────┴────────────┴──────────────┘ + + **Score (bits 63-42, 22 bits)** — ``float_flip(score) >> 10``. + ``float_flip`` reinterprets the IEEE-754 float as an order-preserving + uint32 (see http://stereopsis.com/radix.html). The right-shift by + ``SCORE_SHIFT`` (10) discards the 10 least-significant bits of the + mantissa, keeping 1 sign-equivalent + 8 exponent + 13 mantissa = 22 + bits. This gives ~2^-13 ≈ 1.2e-4 relative precision — sufficient to + distinguish contacts whose spatial projection scores or negated depths + differ by more than ~0.1 mm at 1 m scale. + + **Fingerprint (bits 41-20, 22 bits)** — deterministic tiebreaker + derived from geometry (edge index | mode/source tag bits). When two + contacts have the same truncated score, the fingerprint breaks the tie + so that ``atomic_max`` always picks the same winner regardless of + thread scheduling. Effective limits depend on upstream bit consumption: + + - Mesh-triangle contacts: ``(tri_idx << 1) | 1`` — 21 effective bits + for ``tri_idx`` (~2M triangles). + - SDF contacts: ``(edge_idx << 2) | (mode << 1)`` — 20 effective bits + for ``edge_idx`` (~1M edges). + + Meshes exceeding these limits will overflow the fingerprint field, + causing non-deterministic tiebreaking for those contacts. + + **Contact ID (bits 19-0, 20 bits)** — buffer slot assigned by + ``atomic_add``. 20 bits supports up to 1,048,575 buffered contacts. + Non-deterministic, but only matters when both score and fingerprint + are identical, which requires two geometrically identical contacts — + an impossible case. + + The cascade ``score > fingerprint > contact_id`` means ``atomic_max`` + on this uint64 selects the contact with the best score, breaking ties + deterministically via fingerprint. + + Args: + score: Spatial projection score or negated depth [m]. Higher is better. + fingerprint: Deterministic contact identifier (e.g. ``(edge_idx << 2) | (mode << 1)``). + contact_id: Index into the contact buffer (from ``atomic_add``). + """ + return ( + (wp.uint64(float_flip(score) >> wp.uint32(wp.static(SCORE_SHIFT))) << wp.uint64(42)) + | ((wp.uint64(fingerprint) & FINGERPRINT_MASK) << CONTACT_ID_BITS) + | (wp.uint64(contact_id) & CONTACT_ID_MASK) + ) + + +@wp.func +def _make_preprune_probe_det(score: float, fingerprint: int) -> wp.uint64: + """Deterministic pre-prune probe for ``export_and_reduce_contact_centered``. + + Packs the score and fingerprint with ``CONTACT_ID_MASK`` (all 1s) in the + contact_id field, creating the *ceiling* value for this (score, fingerprint) + pair. The pre-prune comparison ``stored < probe`` is then true whenever + the stored value can be beaten by a contact with this score and fingerprint, + regardless of what ``contact_id`` it receives from ``atomic_add``. + + This makes the pre-prune decision depend only on deterministic quantities + (score and fingerprint), never on the non-deterministic contact_id. + """ + return ( + (wp.uint64(float_flip(score) >> wp.uint32(wp.static(SCORE_SHIFT))) << wp.uint64(42)) + | ((wp.uint64(fingerprint) & FINGERPRINT_MASK) << CONTACT_ID_BITS) + | CONTACT_ID_MASK + ) + + +@wp.func_native(""" +return static_cast(packed & 0xFFFFFull); +""") +def _unpack_contact_id_det(packed: wp.uint64) -> int: + """Extract contact_id (low 20 bits) — deterministic variant.""" ... +# -- Per-reducer dispatching functions ------------------------------------- +# These functions dispatch between fast and deterministic variants based on +# a ``deterministic`` flag, making the packing mode a per-reducer property +# instead of process-global state. + + +@wp.func +def make_contact_value(score: float, fingerprint: int, contact_id: int, deterministic: int) -> wp.uint64: + """Pack score, fingerprint, and contact_id into a uint64 for ``atomic_max``. + + Dispatches between fast and deterministic packing based on the + ``deterministic`` flag. See :func:`_make_contact_value_fast` and + :func:`_make_contact_value_det` for the two packing layouts. + + Args: + score: Spatial projection score or negated depth [m]. Higher is better. + fingerprint: Deterministic contact identifier (ignored in fast mode). + contact_id: Index into the contact buffer (from ``atomic_add``). + deterministic: Non-zero to use deterministic packing. + """ + if deterministic != 0: + return _make_contact_value_det(score, fingerprint, contact_id) + return _make_contact_value_fast(score, fingerprint, contact_id) + + +@wp.func +def unpack_contact_id(packed: wp.uint64, deterministic: int) -> int: + """Extract contact_id from a packed value. + + Dispatches between fast (low 32 bits) and deterministic (low 20 bits) + unpacking based on the ``deterministic`` flag. + + Args: + packed: Packed uint64 value from ``make_contact_value``. + deterministic: Non-zero to use deterministic unpacking. + """ + if deterministic != 0: + return _unpack_contact_id_det(packed) + return _unpack_contact_id_fast(packed) + + @wp.func def encode_oct(n: wp.vec3) -> wp.vec2: """Encode a unit normal into octahedral 2D representation. @@ -337,6 +523,11 @@ class GlobalContactReducerData: contact_count: wp.array[wp.int32] capacity: int + # Deterministic fingerprint per contact (triangle/edge/vertex index). + # Used as a deterministic tiebreaker in make_contact_value so that + # atomic_max picks the same winner regardless of thread scheduling. + contact_fingerprints: wp.array[wp.int32] + # Optional hydroelastic data # contact_area: area of contact surface element (per contact) contact_area: wp.array[wp.float32] @@ -376,6 +567,12 @@ class GlobalContactReducerData: ht_capacity: int ht_values_per_key: int + # When non-zero, replace the speculative pre-prune probe with a + # deterministic variant (make_preprune_probe) so that the prune + # decision depends only on score and fingerprint, never on the + # non-deterministic contact_id. + deterministic: int + @wp.kernel(enable_backward=False) def _clear_active_kernel( @@ -510,6 +707,7 @@ def __init__( device: str | None = None, store_hydroelastic_data: bool = False, store_moment_data: bool = False, + deterministic: bool = False, ): """Initialize the global contact reducer. @@ -519,10 +717,22 @@ def __init__( store_hydroelastic_data: If True, allocate arrays for contact_area and entry_k_eff store_moment_data: If True, allocate moment accumulator arrays for friction moment matching. Only needed when ``moment_matching=True``. + deterministic: If True, use deterministic fingerprint-based tiebreaking + in contact reduction and replace the pre-prune probe with a + deterministic variant. """ + max_det_contacts = 1 << int(CONTACT_ID_BITS) + if deterministic and capacity > max_det_contacts: + raise ValueError( + f"Deterministic contact packing supports at most {max_det_contacts} " + f"buffered contacts ({int(CONTACT_ID_BITS)}-bit contact_id), " + f"but capacity={capacity}. Reduce max_triangle_pairs or disable " + f"deterministic mode." + ) self.capacity = capacity self.device = device self.store_hydroelastic_data = store_hydroelastic_data + self.deterministic = deterministic self.values_per_key = NUM_SPATIAL_DIRECTIONS + 1 @@ -530,6 +740,7 @@ def __init__( self.position_depth = wp.zeros(capacity, dtype=wp.vec4, device=device) self.normal = wp.zeros(capacity, dtype=wp.vec2, device=device) # Octahedral-encoded normals self.shape_pairs = wp.zeros(capacity, dtype=wp.vec2i, device=device) + self.contact_fingerprints = wp.zeros(capacity, dtype=wp.int32, device=device) # Optional hydroelastic data arrays if store_hydroelastic_data: @@ -657,6 +868,7 @@ def get_data_struct(self) -> GlobalContactReducerData: data.shape_pairs = self.shape_pairs data.contact_count = self.contact_count data.capacity = self.capacity + data.contact_fingerprints = self.contact_fingerprints data.contact_area = self.contact_area data.contact_nbin_entry = self.contact_nbin_entry data.entry_k_eff = self.entry_k_eff @@ -671,6 +883,7 @@ def get_data_struct(self) -> GlobalContactReducerData: data.ht_insert_failures = self.ht_insert_failures data.ht_capacity = self.hashtable.capacity data.ht_values_per_key = self.values_per_key + data.deterministic = 1 if self.deterministic else 0 return data @@ -681,6 +894,7 @@ def export_contact_to_buffer( position: wp.vec3, normal: wp.vec3, depth: float, + fingerprint: int, reducer_data: GlobalContactReducerData, ) -> int: """Store a contact in the buffer without reduction. @@ -691,6 +905,7 @@ def export_contact_to_buffer( position: Contact position in world space normal: Contact normal depth: Penetration depth (negative = penetrating) + fingerprint: Deterministic contact identifier (e.g. triangle/edge/vertex index) reducer_data: GlobalContactReducerData with all arrays Returns: @@ -706,6 +921,7 @@ def export_contact_to_buffer( reducer_data.position_depth[contact_id] = wp.vec4(position[0], position[1], position[2], depth) reducer_data.normal[contact_id] = encode_oct(normal) reducer_data.shape_pairs[contact_id] = wp.vec2i(shape_a, shape_b) + reducer_data.contact_fingerprints[contact_id] = fingerprint return contact_id @@ -746,6 +962,7 @@ def reduce_contact_in_hashtable( pd = reducer_data.position_depth[contact_id] normal = decode_oct(reducer_data.normal[contact_id]) pair = reducer_data.shape_pairs[contact_id] + fingerprint = reducer_data.contact_fingerprints[contact_id] position = wp.vec3(pd[0], pd[1], pd[2]) depth = pd[3] @@ -775,11 +992,11 @@ def reduce_contact_in_hashtable( if use_beta: dir_2d = get_spatial_direction_2d(dir_i) score = wp.dot(pos_2d, dir_2d) - value = make_contact_value(score, contact_id) + value = make_contact_value(score, fingerprint, contact_id, reducer_data.deterministic) slot_id = dir_i reduction_update_slot(entry_idx, slot_id, value, reducer_data.ht_values, ht_capacity) - max_depth_value = make_contact_value(-depth, contact_id) + max_depth_value = make_contact_value(-depth, fingerprint, contact_id, reducer_data.deterministic) reduction_update_slot( entry_idx, wp.static(NUM_SPATIAL_DIRECTIONS), max_depth_value, reducer_data.ht_values, ht_capacity ) @@ -809,7 +1026,7 @@ def reduce_contact_in_hashtable( voxel_entry_idx = hashtable_find_or_insert(voxel_key, reducer_data.ht_keys, reducer_data.ht_active_slots) if voxel_entry_idx >= 0: # Use -depth so atomic_max selects most penetrating (most negative depth) - voxel_value = make_contact_value(-depth, contact_id) + voxel_value = make_contact_value(-depth, fingerprint, contact_id, reducer_data.deterministic) reduction_update_slot(voxel_entry_idx, voxel_local_slot, voxel_value, reducer_data.ht_values, ht_capacity) else: wp.atomic_add(reducer_data.ht_insert_failures, 0, 1) @@ -822,6 +1039,7 @@ def export_and_reduce_contact( position: wp.vec3, normal: wp.vec3, depth: float, + fingerprint: int, reducer_data: GlobalContactReducerData, beta: float, shape_transform: wp.array[wp.transform], @@ -830,7 +1048,7 @@ def export_and_reduce_contact( shape_voxel_resolution: wp.array[wp.vec3i], ) -> int: """Export contact to buffer and register in hashtable for reduction.""" - contact_id = export_contact_to_buffer(shape_a, shape_b, position, normal, depth, reducer_data) + contact_id = export_contact_to_buffer(shape_a, shape_b, position, normal, depth, fingerprint, reducer_data) if contact_id >= 0: reduce_contact_in_hashtable( @@ -853,6 +1071,7 @@ def export_and_reduce_contact_centered( position: wp.vec3, normal: wp.vec3, depth: float, + fingerprint: int, centered_position: wp.vec3, X_ws_voxel_shape: wp.transform, aabb_lower_voxel: wp.vec3, @@ -879,6 +1098,7 @@ def export_and_reduce_contact_centered( position: World-space contact position (stored in buffer) normal: Contact normal (a-to-b) depth: Penetration depth + fingerprint: Deterministic contact identifier (e.g. edge index) centered_position: Midpoint-centered position for spatial projection X_ws_voxel_shape: World-to-local transform for voxel computation aabb_lower_voxel: Local AABB lower for voxel grid @@ -897,11 +1117,16 @@ def export_and_reduce_contact_centered( entry_idx = hashtable_find_or_insert(key, reducer_data.ht_keys, reducer_data.ht_active_slots) # === Pre-prune normal bin: non-atomic reads === + # In deterministic mode we use _make_preprune_probe_det (score + fingerprint + + # max contact_id) so the prune decision never depends on the non-deterministic + # contact_id. In non-deterministic mode we use the cheaper floor probe. might_win = False if entry_idx >= 0: - # Check max-depth slot first (cheapest — no direction computation) - max_depth_probe = make_contact_value(-depth, 0) + if reducer_data.deterministic != 0: + max_depth_probe = _make_preprune_probe_det(-depth, fingerprint) + else: + max_depth_probe = _make_contact_value_fast(-depth, 0, 0) if reducer_data.ht_values[wp.static(NUM_SPATIAL_DIRECTIONS) * ht_capacity + entry_idx] < max_depth_probe: might_win = True @@ -910,7 +1135,10 @@ def export_and_reduce_contact_centered( if not might_win: dir_2d = get_spatial_direction_2d(dir_i) score = wp.dot(pos_2d, dir_2d) - probe = make_contact_value(score, 0) + if reducer_data.deterministic != 0: + probe = _make_preprune_probe_det(score, fingerprint) + else: + probe = _make_contact_value_fast(score, 0, 0) if reducer_data.ht_values[dir_i * ht_capacity + entry_idx] < probe: might_win = True @@ -929,7 +1157,10 @@ def export_and_reduce_contact_centered( if not might_win: voxel_entry_idx = hashtable_find_or_insert(voxel_key, reducer_data.ht_keys, reducer_data.ht_active_slots) if voxel_entry_idx >= 0: - voxel_probe = make_contact_value(-depth, 0) + if reducer_data.deterministic != 0: + voxel_probe = _make_preprune_probe_det(-depth, fingerprint) + else: + voxel_probe = _make_contact_value_fast(-depth, 0, 0) if reducer_data.ht_values[voxel_local_slot * ht_capacity + voxel_entry_idx] < voxel_probe: might_win = True @@ -937,20 +1168,20 @@ def export_and_reduce_contact_centered( return -1 # === Allocate buffer slot (only for contacts that might win) === - contact_id = export_contact_to_buffer(shape_a, shape_b, position, normal, depth, reducer_data) + contact_id = export_contact_to_buffer(shape_a, shape_b, position, normal, depth, fingerprint, reducer_data) if contact_id < 0: return -1 - # === Register in hashtable with real contact_id === + # === Register in hashtable with fingerprint for deterministic tiebreaking === if entry_idx >= 0: for dir_i in range(wp.static(NUM_SPATIAL_DIRECTIONS)): if use_beta: dir_2d = get_spatial_direction_2d(dir_i) score = wp.dot(pos_2d, dir_2d) - value = make_contact_value(score, contact_id) + value = make_contact_value(score, fingerprint, contact_id, reducer_data.deterministic) reduction_update_slot(entry_idx, dir_i, value, reducer_data.ht_values, ht_capacity) - max_depth_value = make_contact_value(-depth, contact_id) + max_depth_value = make_contact_value(-depth, fingerprint, contact_id, reducer_data.deterministic) reduction_update_slot( entry_idx, wp.static(NUM_SPATIAL_DIRECTIONS), max_depth_value, reducer_data.ht_values, ht_capacity ) @@ -961,7 +1192,7 @@ def export_and_reduce_contact_centered( if voxel_entry_idx < 0: voxel_entry_idx = hashtable_find_or_insert(voxel_key, reducer_data.ht_keys, reducer_data.ht_active_slots) if voxel_entry_idx >= 0: - voxel_value = make_contact_value(-depth, contact_id) + voxel_value = make_contact_value(-depth, fingerprint, contact_id, reducer_data.deterministic) reduction_update_slot(voxel_entry_idx, voxel_local_slot, voxel_value, reducer_data.ht_values, ht_capacity) else: wp.atomic_add(reducer_data.ht_insert_failures, 0, 1) @@ -1075,6 +1306,7 @@ def write_contact_to_reducer( position=position, normal=normal, depth=depth, + fingerprint=contact_data.sort_sub_key, reducer_data=reducer_data, ) @@ -1101,7 +1333,9 @@ def create_export_reduced_contacts_kernel(writer_func: Any): # Define vector type for tracking exported contact IDs exported_ids_vec = wp.types.vector(length=VALUES_PER_KEY, dtype=wp.int32) - @wp.kernel(enable_backward=False, module="unique") + _module = f"export_reduced_contacts_{writer_func.__name__}" + + @wp.kernel(enable_backward=False, module=_module) def export_reduced_contacts_kernel( # Hashtable arrays ht_keys: wp.array[wp.uint64], @@ -1111,6 +1345,7 @@ def export_reduced_contacts_kernel( position_depth: wp.array[wp.vec4], normal: wp.array[wp.vec2], # Octahedral-encoded shape_pairs: wp.array[wp.vec2i], + contact_fingerprints: wp.array[wp.int32], # Global dedup flags: one int per buffer contact, for cross-entry deduplication exported_flags: wp.array[wp.int32], # Shape data for extracting margin and effective radius @@ -1122,6 +1357,8 @@ def export_reduced_contacts_kernel( writer_data: Any, # Grid stride parameters total_num_threads: int, + # Packing mode (non-zero = deterministic 20-bit contact IDs) + deterministic: int, ): """Export reduced contacts to the writer. @@ -1157,8 +1394,8 @@ def export_reduced_contacts_kernel( if value == wp.uint64(0): continue - # Extract contact ID from low 32 bits - contact_id = unpack_contact_id(value) + # Extract contact ID + contact_id = unpack_contact_id(value, deterministic) # Skip if already exported within this entry if is_contact_already_exported(contact_id, exported_ids, num_exported): @@ -1207,6 +1444,7 @@ def export_reduced_contacts_kernel( contact_data.shape_a = shape_a contact_data.shape_b = shape_b contact_data.gap_sum = gap_sum + contact_data.sort_sub_key = contact_fingerprints[contact_id] # Call the writer function writer_func(contact_data, writer_data, -1) @@ -1334,6 +1572,7 @@ def mesh_triangle_contacts_to_reducer_kernel( margin_offset_a, margin_offset_b, reducer_data, + (tri_idx << 1) | 1, ) return mesh_triangle_contacts_to_reducer_kernel diff --git a/newton/_src/geometry/contact_reduction_hydroelastic.py b/newton/_src/geometry/contact_reduction_hydroelastic.py index 982307c90d..beb8a69546 100644 --- a/newton/_src/geometry/contact_reduction_hydroelastic.py +++ b/newton/_src/geometry/contact_reduction_hydroelastic.py @@ -47,13 +47,13 @@ VALUES_PER_KEY, GlobalContactReducer, GlobalContactReducerData, + _make_contact_value_fast, + _unpack_contact_id_fast, decode_oct, export_contact_to_buffer, is_contact_already_exported, make_contact_key, - make_contact_value, reduction_update_slot, - unpack_contact_id, ) # ============================================================================= @@ -137,8 +137,8 @@ def export_hydroelastic_contact_to_buffer( Returns: Contact ID if successfully stored, -1 if buffer full """ - # Use base function to store common contact data - contact_id = export_contact_to_buffer(shape_a, shape_b, position, normal, depth, reducer_data) + # Use base function to store common contact data (fingerprint=0: hydroelastic excluded from determinism) + contact_id = export_contact_to_buffer(shape_a, shape_b, position, normal, depth, 0, reducer_data) if contact_id >= 0: # Store hydroelastic-specific data (k_eff is stored per entry, not per contact) @@ -223,10 +223,10 @@ def reduce_hydroelastic_contacts_kernel( for dir_i in range(wp.static(NUM_SPATIAL_DIRECTIONS)): dir_2d = get_spatial_direction_2d(dir_i) score = wp.dot(pos_2d_centered, dir_2d) * pen_weight - value = make_contact_value(score, i) + value = _make_contact_value_fast(score, 0, i) reduction_update_slot(entry_idx, dir_i, value, reducer_data.ht_values, ht_capacity) - max_depth_value = make_contact_value(-depth, i) + max_depth_value = _make_contact_value_fast(-depth, 0, i) reduction_update_slot( entry_idx, wp.static(NUM_SPATIAL_DIRECTIONS), @@ -263,7 +263,7 @@ def reduce_hydroelastic_contacts_kernel( reducer_data.entry_k_eff[voxel_entry_idx] = _effective_stiffness( shape_material_k_hydro[shape_a], shape_material_k_hydro[shape_b] ) - voxel_value = make_contact_value(-depth, i) + voxel_value = _make_contact_value_fast(-depth, 0, i) reduction_update_slot( voxel_entry_idx, voxel_local_slot, @@ -330,7 +330,7 @@ def accumulate_reduced_depth_kernel( value = ht_values[slot * ht_capacity + entry_idx] if value == wp.uint64(0): continue - contact_id = unpack_contact_id(value) + contact_id = _unpack_contact_id_fast(value) if is_contact_already_exported(contact_id, p1_ids, p1_count): continue p1_ids[p1_count] = contact_id @@ -402,7 +402,7 @@ def accumulate_moments_kernel( value = ht_values[slot * ht_capacity + entry_idx] if value == wp.uint64(0): continue - contact_id = unpack_contact_id(value) + contact_id = _unpack_contact_id_fast(value) if is_contact_already_exported(contact_id, p2_ids, p2_count): continue p2_ids[p2_count] = contact_id @@ -565,7 +565,7 @@ def export_hydroelastic_reduced_contacts_kernel( continue # Extract contact ID from low 32 bits - contact_id = unpack_contact_id(value) + contact_id = _unpack_contact_id_fast(value) # Skip if already exported if is_contact_already_exported(contact_id, exported_ids, num_exported): @@ -762,7 +762,7 @@ def export_hydroelastic_reduced_contacts_kernel( wp.static(NUM_SPATIAL_DIRECTIONS) * ht_capacity + nbin_entry_idx ] if nbin_max_depth_value != wp.uint64(0): - nbin_max_depth_contact_id = unpack_contact_id(nbin_max_depth_value) + nbin_max_depth_contact_id = _unpack_contact_id_fast(nbin_max_depth_value) nbin_max_depth = position_depth[nbin_max_depth_contact_id][3] if nbin_max_depth < 0.0: nbin_anchor_depth = -nbin_max_depth diff --git a/newton/_src/geometry/contact_sort.py b/newton/_src/geometry/contact_sort.py new file mode 100644 index 0000000000..5e2135c86d --- /dev/null +++ b/newton/_src/geometry/contact_sort.py @@ -0,0 +1,376 @@ +# SPDX-FileCopyrightText: Copyright (c) 2026 The Newton Developers +# SPDX-License-Identifier: Apache-2.0 + +"""Deterministic contact sorting via radix sort on per-contact keys. + +Provides the machinery to reorder contact arrays into a canonical, +deterministic order after the narrow-phase collision pipeline has +written contacts in GPU-scheduling-dependent order. + +The sort always operates over the full pre-allocated buffer (for CUDA +graph capture compatibility). Unused slots beyond ``contact_count`` +are filled with ``0x7FFFFFFFFFFFFFFF`` so they sort to the end. +""" + +from __future__ import annotations + +import warp as wp + +from ..core.types import Devicelike + +# Sentinel key for unused contact slots. ``radix_sort_pairs`` treats +# keys as signed int64, so ``0x7FFF…`` (max positive int64) sorts last. +SORT_KEY_SENTINEL = wp.constant(wp.int64(0x7FFFFFFFFFFFFFFF)) + + +@wp.kernel(enable_backward=False) +def _prepare_sort( + contact_count: wp.array[int], + sort_keys_src: wp.array[wp.int64], + sort_keys_dst: wp.array[wp.int64], + sort_indices: wp.array[wp.int32], +): + """Copy active keys and init identity indices; fill unused slots with sentinel.""" + tid = wp.tid() + if tid < contact_count[0]: + sort_keys_dst[tid] = sort_keys_src[tid] + sort_indices[tid] = wp.int32(tid) + else: + sort_keys_dst[tid] = SORT_KEY_SENTINEL + sort_indices[tid] = wp.int32(tid) + + +# ----------------------------------------------------------------------- +# Structs + fused backup/gather kernels for the two contact layouts. +# +# Each layout has ONE struct holding both the live arrays and their +# scratch-buffer counterparts, plus two kernels: +# _backup_* — copies only active contacts into the scratch buffers +# _gather_* — permuted write-back from scratch into the live arrays +# This replaces the previous N x wp.copy + N x kernel-launch pattern +# with 2 kernel launches total (backup + gather) regardless of how +# many arrays are being sorted. +# ----------------------------------------------------------------------- + + +@wp.struct +class _SimpleContactArrays: + """Live + scratch arrays for the simplified narrow-phase contact layout.""" + + pair: wp.array[wp.vec2i] + position: wp.array[wp.vec3] + normal: wp.array[wp.vec3] + penetration: wp.array[float] + tangent: wp.array[wp.vec3] + pair_buf: wp.array[wp.vec2i] + position_buf: wp.array[wp.vec3] + normal_buf: wp.array[wp.vec3] + penetration_buf: wp.array[float] + tangent_buf: wp.array[wp.vec3] + has_tangent: int + + +@wp.kernel(enable_backward=False) +def _backup_simple_kernel(data: _SimpleContactArrays, count: wp.array[int]): + """Copy active contacts into scratch buffers.""" + i = wp.tid() + if i >= count[0]: + return + data.pair_buf[i] = data.pair[i] + data.position_buf[i] = data.position[i] + data.normal_buf[i] = data.normal[i] + data.penetration_buf[i] = data.penetration[i] + if data.has_tangent != 0: + data.tangent_buf[i] = data.tangent[i] + + +@wp.kernel(enable_backward=False) +def _gather_simple_kernel(data: _SimpleContactArrays, perm: wp.array[wp.int32], count: wp.array[int]): + """Permuted write-back from scratch into live arrays.""" + i = wp.tid() + if i >= count[0]: + return + p = perm[i] + data.pair[i] = data.pair_buf[p] + data.position[i] = data.position_buf[p] + data.normal[i] = data.normal_buf[p] + data.penetration[i] = data.penetration_buf[p] + if data.has_tangent != 0: + data.tangent[i] = data.tangent_buf[p] + + +@wp.struct +class _FullContactArrays: + """Live + scratch arrays for the full CollisionPipeline contact layout.""" + + shape0: wp.array[wp.int32] + shape1: wp.array[wp.int32] + point0: wp.array[wp.vec3] + point1: wp.array[wp.vec3] + offset0: wp.array[wp.vec3] + offset1: wp.array[wp.vec3] + normal: wp.array[wp.vec3] + margin0: wp.array[float] + margin1: wp.array[float] + tids: wp.array[wp.int32] + stiffness: wp.array[float] + damping: wp.array[float] + friction: wp.array[float] + shape0_buf: wp.array[wp.int32] + shape1_buf: wp.array[wp.int32] + point0_buf: wp.array[wp.vec3] + point1_buf: wp.array[wp.vec3] + offset0_buf: wp.array[wp.vec3] + offset1_buf: wp.array[wp.vec3] + normal_buf: wp.array[wp.vec3] + margin0_buf: wp.array[float] + margin1_buf: wp.array[float] + tids_buf: wp.array[wp.int32] + stiffness_buf: wp.array[float] + damping_buf: wp.array[float] + friction_buf: wp.array[float] + has_shape_props: int + + +@wp.kernel(enable_backward=False) +def _backup_full_kernel(data: _FullContactArrays, count: wp.array[int]): + """Copy active contacts into scratch buffers.""" + i = wp.tid() + if i >= count[0]: + return + data.shape0_buf[i] = data.shape0[i] + data.shape1_buf[i] = data.shape1[i] + data.point0_buf[i] = data.point0[i] + data.point1_buf[i] = data.point1[i] + data.offset0_buf[i] = data.offset0[i] + data.offset1_buf[i] = data.offset1[i] + data.normal_buf[i] = data.normal[i] + data.margin0_buf[i] = data.margin0[i] + data.margin1_buf[i] = data.margin1[i] + data.tids_buf[i] = data.tids[i] + if data.has_shape_props != 0: + data.stiffness_buf[i] = data.stiffness[i] + data.damping_buf[i] = data.damping[i] + data.friction_buf[i] = data.friction[i] + + +@wp.kernel(enable_backward=False) +def _gather_full_kernel(data: _FullContactArrays, perm: wp.array[wp.int32], count: wp.array[int]): + """Permuted write-back from scratch into live arrays.""" + i = wp.tid() + if i >= count[0]: + return + p = perm[i] + data.shape0[i] = data.shape0_buf[p] + data.shape1[i] = data.shape1_buf[p] + data.point0[i] = data.point0_buf[p] + data.point1[i] = data.point1_buf[p] + data.offset0[i] = data.offset0_buf[p] + data.offset1[i] = data.offset1_buf[p] + data.normal[i] = data.normal_buf[p] + data.margin0[i] = data.margin0_buf[p] + data.margin1[i] = data.margin1_buf[p] + data.tids[i] = data.tids_buf[p] + if data.has_shape_props != 0: + data.stiffness[i] = data.stiffness_buf[p] + data.damping[i] = data.damping_buf[p] + data.friction[i] = data.friction_buf[p] + + +class ContactSorter: + """Sort contact arrays into a deterministic canonical order. + + Pre-allocates double-buffer arrays and permutation indices at construction + time so that the per-frame :meth:`sort_simple` / :meth:`sort_full` calls + are allocation-free and fully CUDA-graph-capturable (no host synchronization). + + The radix sort always runs over the full *capacity* buffer. Slots beyond + the active ``contact_count`` are filled with a sentinel key + (``0x7FFFFFFFFFFFFFFF``) so they sort to the end and the gather kernels + skip them via the ``contact_count`` guard. + """ + + def __init__(self, capacity: int, *, per_contact_shape_properties: bool = False, device: Devicelike = None): + with wp.ScopedDevice(device): + self._capacity = capacity + # radix_sort_pairs uses the second half as scratch, so allocate 2x. + self._sort_indices = wp.zeros(2 * capacity, dtype=wp.int32) + self._sort_keys_copy = wp.zeros(2 * capacity, dtype=wp.int64) + + self._has_shape_props = per_contact_shape_properties + + # Scratch buffers for the simple gather (NarrowPhase.launch path). + self._simple_pair_buf = wp.zeros(capacity, dtype=wp.vec2i) + self._simple_position_buf = wp.zeros(capacity, dtype=wp.vec3) + self._simple_normal_buf = wp.zeros(capacity, dtype=wp.vec3) + self._simple_penetration_buf = wp.zeros(capacity, dtype=float) + self._simple_tangent_buf = wp.zeros(capacity, dtype=wp.vec3) + + # Scratch buffers for the full gather (CollisionPipeline.collide path). + self._full_shape0_buf = wp.zeros(capacity, dtype=wp.int32) + self._full_shape1_buf = wp.zeros(capacity, dtype=wp.int32) + self._full_point0_buf = wp.zeros(capacity, dtype=wp.vec3) + self._full_point1_buf = wp.zeros(capacity, dtype=wp.vec3) + self._full_offset0_buf = wp.zeros(capacity, dtype=wp.vec3) + self._full_offset1_buf = wp.zeros(capacity, dtype=wp.vec3) + self._full_normal_buf = wp.zeros(capacity, dtype=wp.vec3) + self._full_margin0_buf = wp.zeros(capacity, dtype=float) + self._full_margin1_buf = wp.zeros(capacity, dtype=float) + self._full_tids_buf = wp.zeros(capacity, dtype=wp.int32) + if per_contact_shape_properties: + self._full_stiffness_buf = wp.zeros(capacity, dtype=float) + self._full_damping_buf = wp.zeros(capacity, dtype=float) + self._full_friction_buf = wp.zeros(capacity, dtype=float) + else: + self._full_stiffness_buf = wp.zeros(0, dtype=float) + self._full_damping_buf = wp.zeros(0, dtype=float) + self._full_friction_buf = wp.zeros(0, dtype=float) + + # ------------------------------------------------------------------ + # Public API + # ------------------------------------------------------------------ + + def sort_simple( + self, + sort_keys: wp.array, + contact_count: wp.array, + *, + contact_pair: wp.array, + contact_position: wp.array, + contact_normal: wp.array, + contact_penetration: wp.array, + contact_tangent: wp.array | None = None, + device: Devicelike = None, + ) -> None: + """Sort contacts written through the simplified narrow-phase writer. + + Fully graph-capturable — no host synchronization. + + Args: + sort_keys: Per-contact int64 sort keys (filled by the writer). + contact_count: Single-element int array with the active contact count. + contact_pair: vec2i shape pair array. + contact_position: vec3 contact positions. + contact_normal: vec3 contact normals. + contact_penetration: float penetration depths. + contact_tangent: Optional vec3 tangent array. + device: Device to launch on. + """ + n = self._capacity + self._sort_and_permute(sort_keys, contact_count, device=device) + + has_tangent = contact_tangent is not None and contact_tangent.shape[0] > 0 + + data = _SimpleContactArrays() + data.pair = contact_pair + data.position = contact_position + data.normal = contact_normal + data.penetration = contact_penetration + data.tangent = contact_tangent if has_tangent else self._simple_tangent_buf + data.pair_buf = self._simple_pair_buf + data.position_buf = self._simple_position_buf + data.normal_buf = self._simple_normal_buf + data.penetration_buf = self._simple_penetration_buf + data.tangent_buf = self._simple_tangent_buf + data.has_tangent = 1 if has_tangent else 0 + + wp.launch(_backup_simple_kernel, dim=n, inputs=[data, contact_count], device=device) + wp.launch(_gather_simple_kernel, dim=n, inputs=[data, self._sort_indices, contact_count], device=device) + + def sort_full( + self, + sort_keys: wp.array, + contact_count: wp.array, + *, + shape0: wp.array, + shape1: wp.array, + point0: wp.array, + point1: wp.array, + offset0: wp.array, + offset1: wp.array, + normal: wp.array, + margin0: wp.array, + margin1: wp.array, + tids: wp.array, + stiffness: wp.array | None = None, + damping: wp.array | None = None, + friction: wp.array | None = None, + device: Devicelike = None, + ) -> None: + """Sort contacts written through the full collide.py writer. + + Fully graph-capturable — no host synchronization. + + Args: + sort_keys: Per-contact int64 sort keys (filled by the writer). + contact_count: Single-element int array with the active contact count. + shape0: int array of first shape indices. + shape1: int array of second shape indices. + point0: vec3 body-frame contact points on shape 0. + point1: vec3 body-frame contact points on shape 1. + offset0: vec3 body-frame friction anchor offsets for shape 0. + offset1: vec3 body-frame friction anchor offsets for shape 1. + normal: vec3 contact normals. + margin0: float surface thickness for shape 0. + margin1: float surface thickness for shape 1. + tids: int tid array. + stiffness: Optional float per-contact stiffness. + damping: Optional float per-contact damping. + friction: Optional float per-contact friction. + device: Device to launch on. + """ + n = self._capacity + self._sort_and_permute(sort_keys, contact_count, device=device) + + has_props = self._has_shape_props + + data = _FullContactArrays() + data.shape0 = shape0 + data.shape1 = shape1 + data.point0 = point0 + data.point1 = point1 + data.offset0 = offset0 + data.offset1 = offset1 + data.normal = normal + data.margin0 = margin0 + data.margin1 = margin1 + data.tids = tids + data.stiffness = ( + stiffness if has_props and stiffness is not None and stiffness.shape[0] > 0 else self._full_stiffness_buf + ) + data.damping = damping if has_props and damping is not None and damping.shape[0] > 0 else self._full_damping_buf + data.friction = ( + friction if has_props and friction is not None and friction.shape[0] > 0 else self._full_friction_buf + ) + data.shape0_buf = self._full_shape0_buf + data.shape1_buf = self._full_shape1_buf + data.point0_buf = self._full_point0_buf + data.point1_buf = self._full_point1_buf + data.offset0_buf = self._full_offset0_buf + data.offset1_buf = self._full_offset1_buf + data.normal_buf = self._full_normal_buf + data.margin0_buf = self._full_margin0_buf + data.margin1_buf = self._full_margin1_buf + data.tids_buf = self._full_tids_buf + data.stiffness_buf = self._full_stiffness_buf + data.damping_buf = self._full_damping_buf + data.friction_buf = self._full_friction_buf + data.has_shape_props = 1 if has_props else 0 + + wp.launch(_backup_full_kernel, dim=n, inputs=[data, contact_count], device=device) + wp.launch(_gather_full_kernel, dim=n, inputs=[data, self._sort_indices, contact_count], device=device) + + # ------------------------------------------------------------------ + # Internal helpers + # ------------------------------------------------------------------ + + def _sort_and_permute(self, sort_keys: wp.array, contact_count: wp.array, *, device: Devicelike = None) -> None: + """Prepare keys (sentinel-fill unused slots), then radix-sort over the full buffer.""" + n = self._capacity + wp.launch( + _prepare_sort, + dim=n, + inputs=[contact_count, sort_keys, self._sort_keys_copy, self._sort_indices], + device=device, + ) + wp.utils.radix_sort_pairs(self._sort_keys_copy, self._sort_indices, n) diff --git a/newton/_src/geometry/multicontact.py b/newton/_src/geometry/multicontact.py index 35eb275873..8e1a5611e0 100644 --- a/newton/_src/geometry/multicontact.py +++ b/newton/_src/geometry/multicontact.py @@ -766,6 +766,7 @@ def extract_4_point_contact_manifolds( contact_data.contact_point_center = contact_point_world contact_data.contact_normal_a_to_b = normal_world contact_data.contact_distance = signed_distance + contact_data.sort_sub_key = (contact_template.sort_sub_key << 3) | i contact_data = post_process_contact( contact_data, geom_a, position_a, quaternion_a, geom_b, position_b, quaternion_b @@ -946,6 +947,7 @@ def build_manifold( contact_data.contact_point_center = deepest_center_world contact_data.contact_normal_a_to_b = normal_world contact_data.contact_distance = deepest_signed_distance + contact_data.sort_sub_key = (contact_template.sort_sub_key << 3) | count_out contact_data = post_process_contact( contact_data, geom_a, position_a_ws, quaternion_a_ws, geom_b, position_b_ws, quaternion_b_ws diff --git a/newton/_src/geometry/narrow_phase.py b/newton/_src/geometry/narrow_phase.py index d577f05ac4..1575bb29e2 100644 --- a/newton/_src/geometry/narrow_phase.py +++ b/newton/_src/geometry/narrow_phase.py @@ -32,7 +32,7 @@ collide_sphere_cylinder, collide_sphere_sphere, ) -from ..geometry.contact_data import SHAPE_PAIR_HFIELD_BIT, ContactData, contact_passes_gap_check +from ..geometry.contact_data import SHAPE_PAIR_HFIELD_BIT, ContactData, contact_passes_gap_check, make_contact_sort_key from ..geometry.contact_reduction_global import ( GlobalContactReducer, create_export_reduced_contacts_kernel, @@ -40,6 +40,7 @@ reduce_buffered_contacts_kernel, write_contact_to_reducer, ) +from ..geometry.contact_sort import ContactSorter from ..geometry.flags import ShapeFlags from ..geometry.sdf_contact import ( compute_block_counts_from_weights, @@ -71,6 +72,7 @@ class ContactWriterData: contact_normal: wp.array[wp.vec3] contact_penetration: wp.array[float] contact_tangent: wp.array[wp.vec3] + contact_sort_key: wp.array[wp.int64] @wp.func @@ -125,6 +127,11 @@ def write_contact_simple( world_x = wp.vec3(0.0, 1.0, 0.0) writer_data.contact_tangent[index] = wp.normalize(world_x - wp.dot(world_x, normal) * normal) + if writer_data.contact_sort_key.shape[0] > 0: + writer_data.contact_sort_key[index] = make_contact_sort_key( + contact_data.shape_a, contact_data.shape_b, contact_data.sort_sub_key + ) + def create_narrow_phase_primitive_kernel(writer_func: Any, speculative: bool = False): """ @@ -143,8 +150,9 @@ def create_narrow_phase_primitive_kernel(writer_func: Any, speculative: bool = F Returns: A warp kernel for primitive collision detection """ + _module = f"narrow_phase_primitive_{writer_func.__name__}" - @wp.kernel(enable_backward=False, module="unique") + @wp.kernel(enable_backward=False, module=_module) def narrow_phase_primitive_kernel( candidate_pair: wp.array[wp.vec2i], candidate_pair_count: wp.array[int], @@ -585,6 +593,7 @@ def narrow_phase_primitive_kernel( if contact_0_valid: contact_data.contact_point_center = contact_pos_0 contact_data.contact_distance = contact_dist_0 + contact_data.sort_sub_key = 0 writer_func(contact_data, writer_data, base_index) base_index += 1 @@ -592,6 +601,7 @@ def narrow_phase_primitive_kernel( if contact_1_valid: contact_data.contact_point_center = contact_pos_1 contact_data.contact_distance = contact_dist_1 + contact_data.sort_sub_key = 1 writer_func(contact_data, writer_data, base_index) base_index += 1 @@ -599,6 +609,7 @@ def narrow_phase_primitive_kernel( if contact_2_valid: contact_data.contact_point_center = contact_pos_2 contact_data.contact_distance = contact_dist_2 + contact_data.sort_sub_key = 2 writer_func(contact_data, writer_data, base_index) base_index += 1 @@ -606,6 +617,7 @@ def narrow_phase_primitive_kernel( if contact_3_valid: contact_data.contact_point_center = contact_pos_3 contact_data.contact_distance = contact_dist_3 + contact_data.sort_sub_key = 3 writer_func(contact_data, writer_data, base_index) continue @@ -643,8 +655,11 @@ def create_narrow_phase_kernel_gjk_mpr( speculative: When True, extends ``gap_sum`` by a scalar speculative margin derived from per-shape velocity arrays. """ + _sf = support_func.__name__ if support_func is not None else "default" + _ppc = post_process_contact.__name__ if post_process_contact is not None else "default" + _module = f"narrow_phase_gjk_mpr_{external_aabb}_{writer_func.__name__}_{_sf}_{_ppc}" - @wp.kernel(enable_backward=False, module="unique") + @wp.kernel(enable_backward=False, module=_module) def narrow_phase_kernel_gjk_mpr( candidate_pair: wp.array[wp.vec2i], candidate_pair_count: wp.array[int], @@ -941,7 +956,9 @@ def narrow_phase_find_mesh_triangle_overlaps_kernel( def create_narrow_phase_process_mesh_triangle_contacts_kernel(writer_func: Any, speculative: bool = False): - @wp.kernel(enable_backward=False, module="unique") + _module = f"narrow_phase_mesh_tri_{writer_func.__name__}" + + @wp.kernel(enable_backward=False, module=_module) def narrow_phase_process_mesh_triangle_contacts_kernel( shape_types: wp.array[int], shape_data: wp.array[wp.vec4], @@ -1049,6 +1066,7 @@ def narrow_phase_process_mesh_triangle_contacts_kernel( margin_offset_a, margin_offset_b, writer_data, + (tri_idx << 1) | 1, ) return narrow_phase_process_mesh_triangle_contacts_kernel @@ -1144,8 +1162,9 @@ def create_narrow_phase_process_mesh_plane_contacts_kernel( Returns: A warp kernel that processes mesh-plane collisions """ + _module = f"narrow_phase_mesh_plane_{writer_func.__name__}_{reduce_contacts}" - @wp.kernel(enable_backward=False, module="unique") + @wp.kernel(enable_backward=False, module=_module) def narrow_phase_process_mesh_plane_contacts_kernel( shape_data: wp.array[wp.vec4], shape_transform: wp.array[wp.transform], @@ -1253,6 +1272,7 @@ def narrow_phase_process_mesh_plane_contacts_kernel( contact_data.shape_a = mesh_shape contact_data.shape_b = plane_shape contact_data.gap_sum = gap_sum + contact_data.sort_sub_key = vertex_idx if writer_data.contact_count[0] < writer_data.contact_max: writer_func(contact_data, writer_data, -1) @@ -1261,7 +1281,7 @@ def narrow_phase_process_mesh_plane_contacts_kernel( if not reduce_contacts: return narrow_phase_process_mesh_plane_contacts_kernel - @wp.kernel(enable_backward=False, module="unique") + @wp.kernel(enable_backward=False, module=_module) def narrow_phase_process_mesh_plane_contacts_reduce_kernel( shape_data: wp.array[wp.vec4], shape_transform: wp.array[wp.transform], @@ -1399,6 +1419,7 @@ def narrow_phase_process_mesh_plane_contacts_reduce_kernel( contact_data.shape_a = mesh_shape contact_data.shape_b = plane_shape contact_data.gap_sum = gap_sum + contact_data.sort_sub_key = vertex_idx writer_func(contact_data, writer_data, -1) @@ -1511,6 +1532,8 @@ def __init__( has_heightfields: bool = False, use_lean_gjk_mpr: bool = False, speculative: bool = False, + deterministic: bool = False, + contact_max: int | None = None, ) -> None: """ Initialize NarrowPhase with pre-allocated buffers. @@ -1538,6 +1561,14 @@ def __init__( When True, kernel variants that read per-shape velocity arrays and extend gap thresholds are compiled. When False (default), the speculative code paths are eliminated at compile time. + deterministic: Sort contacts after the narrow phase so that results are + independent of GPU thread scheduling. Adds a radix sort + gather + pass. Hydroelastic contacts are not yet covered. + contact_max: Maximum number of contacts for the deterministic sort buffer. + Must match the ``contact_pair`` array size passed to :meth:`launch`. + Defaults to ``max_candidate_pairs``. Set this to a larger value when + a single candidate pair can emit multiple contacts (e.g. up to 4 for + primitive multi-contact paths). """ self.max_candidate_pairs = max_candidate_pairs self.max_triangle_pairs = max_triangle_pairs @@ -1545,6 +1576,7 @@ def __init__( self.reduce_contacts = reduce_contacts self.has_meshes = has_meshes self.has_heightfields = has_heightfields + self.deterministic = deterministic # Warn when running on CPU with meshes: mesh-mesh SDF contacts require CUDA is_gpu_device = wp.get_device(device).is_cuda @@ -1663,7 +1695,9 @@ def __init__( speculative=speculative ) # Global contact reducer for all mesh contact types - self.global_contact_reducer = GlobalContactReducer(max_triangle_pairs, device=device) + self.global_contact_reducer = GlobalContactReducer( + max_triangle_pairs, device=device, deterministic=deterministic + ) else: self.export_reduced_contacts_kernel = None self.mesh_triangle_to_reducer_kernel = None @@ -1715,6 +1749,14 @@ def __init__( ) self.empty_tangent = None + self._empty_sort_key = wp.zeros(0, dtype=wp.int64, device=device) + det_capacity = contact_max if contact_max is not None else max_candidate_pairs + if deterministic: + self._sort_key_array = wp.zeros(det_capacity, dtype=wp.int64, device=device) + self._contact_sorter = ContactSorter(det_capacity, device=device) + else: + self._sort_key_array = wp.zeros(0, dtype=wp.int64, device=device) + self._contact_sorter = None # Sentinel edge buffers used when no edge data is provided. # _empty_edge_range is indexed by shape id, so it must have one # slot per shape (not per candidate pair). @@ -2200,12 +2242,14 @@ def launch_custom_write( self.global_contact_reducer.position_depth, self.global_contact_reducer.normal, self.global_contact_reducer.shape_pairs, + self.global_contact_reducer.contact_fingerprints, self.global_contact_reducer.exported_flags, shape_types, shape_data, shape_gap, writer_data, self.total_num_threads, + int(self.global_contact_reducer.deterministic), ], device=device, block_dim=self.block_dim, @@ -2343,7 +2387,20 @@ def launch( # Clear external contact count (internal counters are cleared in launch_custom_write) contact_count.zero_() + # Verify sort-key buffer and sorter match the contact output capacity. + # Raising instead of silently reallocating keeps this path + # CUDA-graph-capturable and consistent with CollisionPipeline.collide(). + if self.deterministic and self._sort_key_array.shape[0] != contact_max: + raise ValueError( + f"Contact output capacity ({contact_max}) does not match the " + f"deterministic sort buffer size ({self._sort_key_array.shape[0]}). " + f"The sorter operates over fixed-capacity buffers for CUDA graph capture " + f"compatibility, so the sizes must match exactly." + ) + # Create ContactWriterData struct + sort_key_arr = self._sort_key_array if self.deterministic else self._empty_sort_key + writer_data = ContactWriterData() writer_data.contact_max = contact_max writer_data.contact_count = contact_count @@ -2352,6 +2409,7 @@ def launch( writer_data.contact_normal = contact_normal writer_data.contact_penetration = contact_penetration writer_data.contact_tangent = contact_tangent + writer_data.contact_sort_key = sort_key_arr # Delegate to launch_custom_write self.launch_custom_write( @@ -2374,3 +2432,15 @@ def launch( writer_data=writer_data, device=device, ) + + if self.deterministic: + self._contact_sorter.sort_simple( + sort_key_arr, + contact_count, + contact_pair=contact_pair, + contact_position=contact_position, + contact_normal=contact_normal, + contact_penetration=contact_penetration, + contact_tangent=contact_tangent, + device=device, + ) diff --git a/newton/_src/geometry/raycast.py b/newton/_src/geometry/raycast.py index 7ed0f1b96c..6a11a61771 100644 --- a/newton/_src/geometry/raycast.py +++ b/newton/_src/geometry/raycast.py @@ -11,6 +11,8 @@ # A small constant to avoid division by zero and other numerical issues MINVAL = 1e-15 +# Tolerance for near-parallel ray rejection (e.g. ray vs plane) +PARALLEL_TOL = 1e-6 @wp.func @@ -516,6 +518,51 @@ def ray_intersect_mesh( return t_hit +@wp.func +def ray_intersect_plane(geom_to_world: wp.transform, ray_origin: wp.vec3, ray_direction: wp.vec3, size: wp.vec3): + """Computes ray-plane intersection. + + The plane lies at z = 0 in local space with normal along +Z. ``size`` holds ``(width, length, 0)``: + the full extents along local X and Y. A value of ``0`` means infinite in that axis. The plane is double-sided: + rays approaching from either side register intersections. + + Args: + geom_to_world: The world transform of the plane. + ray_origin: The origin of the ray in world space. + ray_direction: The direction of the ray in world space. + size: ``(width, length, 0)`` -- full extents; ``0`` = infinite. + + Returns: + The distance along the ray to the intersection point, or -1.0 if there is no intersection. + """ + # transform ray to local frame + world_to_geom = wp.transform_inverse(geom_to_world) + ro = wp.transform_point(world_to_geom, ray_origin) + rd = wp.transform_vector(world_to_geom, ray_direction) + + # Ray parallel to the plane (or degenerate) + if wp.abs(rd[2]) < PARALLEL_TOL: + return -1.0 + + # t where the ray crosses z = 0 + t = -ro[2] / rd[2] + if t < 0.0: + return -1.0 + + hit_x = ro[0] + t * rd[0] + hit_y = ro[1] + t * rd[1] + + half_w = size[0] * 0.5 + half_l = size[1] * 0.5 + + if half_w > 0.0 and wp.abs(hit_x) > half_w: + return -1.0 + if half_l > 0.0 and wp.abs(hit_y) > half_l: + return -1.0 + + return t + + @wp.func def ray_intersect_geom( geom_to_world: wp.transform, @@ -529,7 +576,7 @@ def ray_intersect_geom( Computes the intersection of a ray with a geometry. Args: - geom_to_world: The world-to-shape transform. + geom_to_world: The world transform of the shape. size: The size of the geometry. geomtype: The type of the geometry. ray_origin: The origin of the ray. @@ -541,7 +588,10 @@ def ray_intersect_geom( """ t_hit = -1.0 - if geomtype == GeoType.SPHERE: + if geomtype == GeoType.PLANE: + t_hit = ray_intersect_plane(geom_to_world, ray_origin, ray_direction, size) + + elif geomtype == GeoType.SPHERE: r = size[0] t_hit = ray_intersect_sphere(geom_to_world, ray_origin, ray_direction, r) diff --git a/newton/_src/geometry/sdf_contact.py b/newton/_src/geometry/sdf_contact.py index b78f9c7c49..825206e836 100644 --- a/newton/_src/geometry/sdf_contact.py +++ b/newton/_src/geometry/sdf_contact.py @@ -1027,7 +1027,16 @@ def create_narrow_phase_process_mesh_mesh_contacts_kernel( ): find_interesting_edges, do_edge_sdf_collision = _create_sdf_contact_funcs(enable_heightfields) - @wp.kernel(enable_backward=False, module="unique") + # Derive a stable module name from the factory arguments so that + # identical configurations share the compiled CUDA kernel. This is + # critical for deterministic contact generation: two CollisionPipeline + # instances with the same writer_func must execute the exact same + # compiled code, otherwise FMA-fusion or register-allocation + # differences between independent JIT compilations can produce subtly + # different floating-point results, breaking bit-exact reproducibility. + _module = f"sdf_contact_{writer_func.__name__}_{enable_heightfields}_{reduce_contacts}" + + @wp.kernel(enable_backward=False, module=_module) def mesh_sdf_collision_kernel( shape_data: wp.array[wp.vec4], shape_transform: wp.array[wp.transform], @@ -1303,6 +1312,7 @@ def mesh_sdf_collision_kernel( contact_data.shape_a = pair[0] contact_data.shape_b = pair[1] contact_data.gap_sum = gap_sum + contact_data.sort_sub_key = (edge_idx << 2) | (mode << 1) writer_func(contact_data, writer_data, -1) @@ -1321,7 +1331,7 @@ def mesh_sdf_collision_kernel( # but contacts are written directly to global buffer + hashtable. # ========================================================================= - @wp.kernel(enable_backward=False, module="unique") + @wp.kernel(enable_backward=False, module=_module) def mesh_sdf_collision_global_reduce_kernel( shape_data: wp.array[wp.vec4], shape_transform: wp.array[wp.transform], @@ -1617,6 +1627,7 @@ def mesh_sdf_collision_global_reduce_kernel( point_world, contact_normal, dist, + (edge_idx << 2) | (mode << 1), point_world - midpoint, X_ws_tri, aabb_lower_tri, diff --git a/newton/_src/geometry/sdf_hydroelastic.py b/newton/_src/geometry/sdf_hydroelastic.py index 80700eae4c..386ed1b52e 100644 --- a/newton/_src/geometry/sdf_hydroelastic.py +++ b/newton/_src/geometry/sdf_hydroelastic.py @@ -658,13 +658,14 @@ def _broadphase_sdfs( wp.launch( kernel=broadphase_collision_pairs_scatter, - dim=[self.max_num_shape_pairs], + dim=[self.grid_size], inputs=[ - self.num_blocks_per_pair, - shape_sdf_data, + self.grid_size, + self.block_broad_collide_count, self.block_start_prefix, shape_pairs_sdf_sdf, shape_pairs_sdf_sdf_count, + shape_sdf_data, self.shape_sdf_shape2blocks, self.max_num_blocks_broad, ], @@ -928,51 +929,52 @@ def broadphase_collision_pairs_count( @wp.kernel(enable_backward=False) def broadphase_collision_pairs_scatter( - thread_num_blocks: wp.array[wp.int32], - shape_sdf_data: wp.array[TextureSDFData], + grid_size: int, + block_broad_collide_count: wp.array[wp.int32], block_start_prefix: wp.array[wp.int32], shape_pairs_sdf_sdf: wp.array[wp.vec2i], shape_pairs_sdf_sdf_count: wp.array[wp.int32], + shape_sdf_data: wp.array[TextureSDFData], shape2blocks: wp.array[wp.vec2i], max_num_blocks_broad: int, # outputs block_broad_collide_shape_pair: wp.array[wp.vec2i], block_broad_idx: wp.array[wp.int32], ): - tid = wp.tid() - if tid >= shape_pairs_sdf_sdf_count[0]: - return - - num_blocks = thread_num_blocks[tid] - if num_blocks == 0: + offset = wp.tid() + total_blocks = wp.min(block_broad_collide_count[0], max_num_blocks_broad) + pair_count = wp.min(shape_pairs_sdf_sdf_count[0], block_start_prefix.shape[0]) + if pair_count == 0: return - pair = shape_pairs_sdf_sdf[tid] - shape_a = pair[0] - shape_b = pair[1] - - # sort shapes such that the shape with the smaller voxel size is in second place - # NOTE: Confirm that this is OK to do for downstream code - voxel_radius_a = shape_sdf_data[shape_a].voxel_radius - voxel_radius_b = shape_sdf_data[shape_b].voxel_radius - - if voxel_radius_b > voxel_radius_a: - shape_b, shape_a = shape_a, shape_b + for block_tid in range(offset, total_blocks, grid_size): + # Binary search: find rightmost pair_idx where prefix[pair_idx] <= block_tid + lo = int(0) + hi = int(pair_count - 1) + while lo < hi: + mid = (lo + hi + 1) // 2 + if block_start_prefix[mid] <= block_tid: + lo = mid + else: + hi = mid - 1 + pair_idx = lo - shape_b_idx = shape2blocks[shape_b] - shape_b_block_start = shape_b_idx[0] + pair = shape_pairs_sdf_sdf[pair_idx] + shape_a = pair[0] + shape_b = pair[1] - block_start = block_start_prefix[tid] + # Sort shapes so the one with smaller voxel size is shape_b + voxel_radius_a = shape_sdf_data[shape_a].voxel_radius + voxel_radius_b = shape_sdf_data[shape_b].voxel_radius + if voxel_radius_b > voxel_radius_a: + shape_b, shape_a = shape_a, shape_b - remaining = max_num_blocks_broad - block_start - if remaining <= 0: - return - num_blocks = wp.min(num_blocks, remaining) + shape_b_idx = shape2blocks[shape_b] + shape_b_block_start = shape_b_idx[0] + block_in_pair = block_tid - block_start_prefix[pair_idx] - pair = wp.vec2i(shape_a, shape_b) - for i in range(num_blocks): - block_broad_collide_shape_pair[block_start + i] = pair - block_broad_idx[block_start + i] = shape_b_block_start + i + block_broad_collide_shape_pair[block_tid] = wp.vec2i(shape_a, shape_b) + block_broad_idx[block_tid] = shape_b_block_start + block_in_pair @wp.kernel(enable_backward=False) diff --git a/newton/_src/geometry/support_function.py b/newton/_src/geometry/support_function.py index 5cda694e32..8c97ec5dc8 100644 --- a/newton/_src/geometry/support_function.py +++ b/newton/_src/geometry/support_function.py @@ -33,6 +33,11 @@ from .types import GeoType +# Relative deadband factor for box support-map sign decisions. +# Near-zero direction components (e.g. from quaternion rotation noise ~1e-14) +# are treated as non-negative, biasing toward the +1 vertex. +BOX_SUPPORT_DEADBAND = 1.0e-10 + # Is not allowed to share values with GeoType class GeoTypeEx(enum.IntEnum): @@ -168,9 +173,16 @@ def support_map(geom: GenericShapeData, direction: wp.vec3, data_provider: Suppo if direction[2] < 0.0: result = result + wp.vec3(0.0, 0.0, -1.0) elif geom.shape_type == GeoType.BOX: - sx = 1.0 if direction[0] >= 0.0 else -1.0 - sy = 1.0 if direction[1] >= 0.0 else -1.0 - sz = 1.0 if direction[2] >= 0.0 else -1.0 + # Use a relative deadband so near-zero direction components + # (from quaternion rotation noise ~1e-14) cannot flip the sign + # and select a different box vertex. For face-aligned queries + # the non-primary components are zero; any vertex on that face + # is an equally valid support point, so biasing toward +1 is + # correct and keeps MPR's initial portal construction stable. + threshold = BOX_SUPPORT_DEADBAND * wp.length(direction) + sx = 1.0 if direction[0] >= -threshold else -1.0 + sy = 1.0 if direction[1] >= -threshold else -1.0 + sz = 1.0 if direction[2] >= -threshold else -1.0 result = wp.vec3(sx * geom.scale[0], sy * geom.scale[1], sz * geom.scale[2]) @@ -317,9 +329,10 @@ def support_map_lean(geom: GenericShapeData, direction: wp.vec3, data_provider: result = wp.cw_mul(mesh.points[best_idx], geom.scale) elif geom.shape_type == GeoType.BOX: - sx = 1.0 if direction[0] >= 0.0 else -1.0 - sy = 1.0 if direction[1] >= 0.0 else -1.0 - sz = 1.0 if direction[2] >= 0.0 else -1.0 + threshold = BOX_SUPPORT_DEADBAND * wp.length(direction) + sx = 1.0 if direction[0] >= -threshold else -1.0 + sy = 1.0 if direction[1] >= -threshold else -1.0 + sz = 1.0 if direction[2] >= -threshold else -1.0 result = wp.vec3(sx * geom.scale[0], sy * geom.scale[1], sz * geom.scale[2]) elif geom.shape_type == GeoType.SPHERE: diff --git a/newton/_src/geometry/types.py b/newton/_src/geometry/types.py index 921822a4f3..5c60b0ff62 100644 --- a/newton/_src/geometry/types.py +++ b/newton/_src/geometry/types.py @@ -79,6 +79,24 @@ class GeoType(enum.IntEnum): GAUSSIAN = 11 """Gaussian splat.""" + @property + def is_primitive(self) -> bool: + """Return whether this is a primitive (analytically defined) shape type.""" + return self in { + GeoType.SPHERE, + GeoType.CYLINDER, + GeoType.CONE, + GeoType.CAPSULE, + GeoType.BOX, + GeoType.ELLIPSOID, + GeoType.PLANE, + } + + @property + def is_explicit(self) -> bool: + """Return whether this is an explicit (data-driven) shape type.""" + return self in {GeoType.MESH, GeoType.CONVEX_MESH, GeoType.HFIELD} + class Mesh: """ diff --git a/newton/_src/sim/builder.py b/newton/_src/sim/builder.py index 79807e853c..c9d3de5bad 100644 --- a/newton/_src/sim/builder.py +++ b/newton/_src/sim/builder.py @@ -2243,7 +2243,7 @@ def add_usd( force_position_velocity_actuation: bool = False, override_root_xform: bool = False, ) -> dict[str, Any]: - """Parses a Universal Scene Description (USD) stage containing UsdPhysics schema definitions for rigid-body articulations and adds the bodies, shapes and joints to the given ModelBuilder. + """Parses a Universal Scene Description (USD) stage and adds rigid bodies, soft bodies, shapes, and joints to the given ModelBuilder. The USD description has to be either a path (file name or URL), or an existing USD stage instance that implements the `Stage `_ interface. diff --git a/newton/_src/sim/collide.py b/newton/_src/sim/collide.py index b5404e03d5..1f5aa9e5e4 100644 --- a/newton/_src/sim/collide.py +++ b/newton/_src/sim/collide.py @@ -12,7 +12,8 @@ from ..geometry.broad_phase_nxn import BroadPhaseAllPairs, BroadPhaseExplicit from ..geometry.broad_phase_sap import BroadPhaseSAP from ..geometry.collision_core import compute_tight_aabb_from_support -from ..geometry.contact_data import ContactData +from ..geometry.contact_data import ContactData, make_contact_sort_key +from ..geometry.contact_sort import ContactSorter from ..geometry.differentiable_contacts import launch_differentiable_contact_augment from ..geometry.flags import ShapeFlags from ..geometry.kernels import create_soft_contacts @@ -83,6 +84,7 @@ class ContactWriterData: out_stiffness: wp.array[float] out_damping: wp.array[float] out_friction: wp.array[float] + out_sort_key: wp.array[wp.int64] # Speculative contact fields (empty arrays / 0.0 when disabled) shape_lin_vel: wp.array[wp.vec3] shape_ang_speed_bound: wp.array[float] @@ -189,6 +191,11 @@ def write_contact( writer_data.out_damping[index] = contact_data.contact_damping writer_data.out_friction[index] = contact_data.contact_friction_scale + if writer_data.out_sort_key.shape[0] > 0: + writer_data.out_sort_key[index] = make_contact_sort_key( + contact_data.shape_a, contact_data.shape_b, contact_data.sort_sub_key + ) + def _create_compute_shape_aabbs(speculative: bool): """Factory for the AABB kernel. When *speculative* is True the kernel reads @@ -388,18 +395,16 @@ def prepare_geom_data_kernel( shape_margin: wp.array[float], body_q: wp.array[wp.transform], # Outputs - geom_data: wp.array[wp.vec4], # scale xyz, margin w - geom_transform: wp.array[wp.transform], # world space transform + geom_data: wp.array[wp.vec4], + geom_transform: wp.array[wp.transform], ): """Prepare geometry data arrays for NarrowPhase API.""" idx = wp.tid() - # Pack scale and margin into geom_data scale = shape_scale[idx] margin = shape_margin[idx] geom_data[idx] = wp.vec4(scale[0], scale[1], scale[2], margin) - # Compute world space transform body_idx = shape_body[idx] if body_idx >= 0: geom_transform[idx] = wp.transform_multiply(body_q[body_idx], shape_transform[idx]) @@ -610,6 +615,7 @@ def __init__( narrow_phase: NarrowPhase | None = None, sdf_hydroelastic_config: HydroelasticSDF.Config | None = None, speculative_config: SpeculativeContactConfig | None = None, + deterministic: bool = False, ): """ Initialize the CollisionPipeline (expert API). @@ -647,6 +653,9 @@ def __init__( within the next collision update interval are detected early. ``None`` (default) disables speculative contacts with zero runtime overhead via compile-time elimination. + deterministic: Sort contacts after the narrow phase so that results + are independent of GPU thread scheduling. Adds a radix sort + + gather pass. Hydroelastic contacts are not yet covered. .. note:: When ``requires_grad`` is true (explicitly or via ``model.requires_grad``), @@ -728,6 +737,12 @@ def __init__( self.shape_pairs_excluded.shape[0] if self.shape_pairs_excluded is not None else 0 ) + if deterministic and not narrow_phase.deterministic: + raise ValueError( + "CollisionPipeline(deterministic=True) requires a deterministic " + "NarrowPhase. Either omit narrow_phase or construct it with " + "deterministic=True." + ) if narrow_phase.max_candidate_pairs < self.shape_pairs_max: raise ValueError( "Provided narrow_phase.max_candidate_pairs is too small for this model and broad phase mode " @@ -819,6 +834,7 @@ def __init__( has_heightfields=has_heightfields, use_lean_gjk_mpr=use_lean_gjk_mpr, speculative=self._speculative_enabled, + deterministic=deterministic, ) self.hydroelastic_sdf = self.narrow_phase.hydroelastic_sdf @@ -850,6 +866,17 @@ def __init__( self.soft_contact_margin = soft_contact_margin self._soft_contact_max = soft_contact_max self.requires_grad = requires_grad + self.deterministic = deterministic + if deterministic: + per_contact_props = self.narrow_phase.hydroelastic_sdf is not None + with wp.ScopedDevice(device): + self._sort_key_array = wp.zeros(rigid_contact_max, dtype=wp.int64, device=device) + self._contact_sorter = ContactSorter( + rigid_contact_max, per_contact_shape_properties=per_contact_props, device=device + ) + else: + self._sort_key_array = wp.zeros(0, dtype=wp.int64, device=device) + self._contact_sorter = None if self._speculative_enabled: with wp.ScopedDevice(device): @@ -1106,6 +1133,15 @@ def collide( writer_data.out_stiffness = contacts.rigid_contact_stiffness writer_data.out_damping = contacts.rigid_contact_damping writer_data.out_friction = contacts.rigid_contact_friction + if self.deterministic and contacts.rigid_contact_max != self._sort_key_array.shape[0]: + raise ValueError( + f"Contacts buffer capacity ({contacts.rigid_contact_max}) does not match the " + f"deterministic sort buffer size ({self._sort_key_array.shape[0]}). " + f"The sorter operates over fixed-capacity buffers for CUDA graph capture " + f"compatibility, so the sizes must match exactly. Use CollisionPipeline.contacts() " + f"or pass matching rigid_contact_max." + ) + writer_data.out_sort_key = self._sort_key_array writer_data.shape_lin_vel = self._shape_lin_vel writer_data.shape_ang_speed_bound = self._shape_ang_speed_bound @@ -1141,6 +1177,26 @@ def collide( max_speculative_extension=max_speculative_extension, ) + if self.deterministic and self._contact_sorter is not None: + self._contact_sorter.sort_full( + self._sort_key_array, + contacts.rigid_contact_count, + shape0=contacts.rigid_contact_shape0, + shape1=contacts.rigid_contact_shape1, + point0=contacts.rigid_contact_point0, + point1=contacts.rigid_contact_point1, + offset0=contacts.rigid_contact_offset0, + offset1=contacts.rigid_contact_offset1, + normal=contacts.rigid_contact_normal, + margin0=contacts.rigid_contact_margin0, + margin1=contacts.rigid_contact_margin1, + tids=contacts.rigid_contact_tids, + stiffness=contacts.rigid_contact_stiffness, + damping=contacts.rigid_contact_damping, + friction=contacts.rigid_contact_friction, + device=self.device, + ) + # Differentiable contact augmentation: reconstruct world-space contact # quantities through body_q so that gradients flow via wp.Tape. if self.requires_grad and contacts.rigid_contact_diff_distance is not None: diff --git a/newton/_src/sim/contacts.py b/newton/_src/sim/contacts.py index 707461db25..ce3be15935 100644 --- a/newton/_src/sim/contacts.py +++ b/newton/_src/sim/contacts.py @@ -6,6 +6,19 @@ import warp as wp from warp import DeviceLike as Devicelike +GENERATION_SENTINEL = -1 +"""Value reserved as an impossible generation; the increment kernel skips it.""" + + +@wp.kernel(enable_backward=False) +def _increment_contact_generation(generation: wp.array[wp.int32]): + g = generation[0] + if g == 2147483647: + g = 0 + else: + g = g + 1 + generation[0] = g + class Contacts: """ @@ -96,6 +109,12 @@ def __init__( # Create sliced views for individual counters (no additional allocation) self.rigid_contact_count = self._counter_array[0:1] + self.contact_generation = wp.zeros(1, dtype=wp.int32) + """Device-side generation counter, incremented each time :meth:`clear` is called. + + Solvers can compare this against a cached value to detect whether the + contact set changed since the last conversion pass.""" + # rigid contacts — never requires_grad (narrow phase has enable_backward=False) self.rigid_contact_point_id = wp.zeros(rigid_contact_max, dtype=wp.int32) self.rigid_contact_shape0 = wp.full(rigid_contact_max, -1, dtype=wp.int32) @@ -204,7 +223,7 @@ def clear(self): Clear contact data, resetting counts and optionally clearing all buffers. By default (clear_buffers=False), only resets contact counts. This is highly optimized, - requiring just 1 kernel launch. Collision detection overwrites all data up to the new + requiring just 2 kernel launches. Collision detection overwrites all data up to the new contact_count, and solvers only read up to count, so clearing stale data is unnecessary. If clear_buffers=True (conservative mode), performs full buffer clearing with sentinel @@ -213,6 +232,15 @@ def clear(self): # Clear all counters with a single kernel launch (consolidated counter array) self._counter_array.zero_() + # Bump generation so solvers know the contact set changed (graph-capture safe) + wp.launch( + _increment_contact_generation, + dim=1, + inputs=[self.contact_generation], + device=self.contact_generation.device, + record_tape=False, + ) + if self.clear_buffers: # Conservative path: clear all buffers (7-10 kernel launches) # This is slower but may be useful for debugging or special cases diff --git a/newton/_src/solvers/kamino/_src/core/builder.py b/newton/_src/solvers/kamino/_src/core/builder.py index 6576236490..0bef7d432e 100644 --- a/newton/_src/solvers/kamino/_src/core/builder.py +++ b/newton/_src/solvers/kamino/_src/core/builder.py @@ -25,7 +25,7 @@ from .materials import MaterialDescriptor, MaterialManager, MaterialPairProperties, MaterialPairsModel, MaterialsModel from .math import FLOAT32_EPS from .model import ModelKamino, ModelKaminoInfo -from .shapes import ShapeDescriptorType, is_explicit_geo_type, max_contacts_for_shape_pair +from .shapes import ShapeDescriptorType, max_contacts_for_shape_pair from .size import SizeKamino from .time import TimeModel from .types import Axis, float32, int32, mat33f, transformf, vec2i, vec3f, vec4f, vec6f @@ -1130,7 +1130,7 @@ def collect_joint_model_data(): # NOTE: This also finalizes the mesh/SDF/HField data on the device def make_geometry_source_pointer(geom: GeometryDescriptor, mesh_geoms: dict, device) -> int: # Append to data pointers array of the shape has a Mesh, SDF or HField source - if is_explicit_geo_type(geom.shape.type): + if geom.shape.type.is_explicit: geom_uid = geom.uid # If the geometry has a Mesh, SDF or HField source, # finalize it and retrieve the mesh pointer/index diff --git a/newton/_src/solvers/kamino/_src/core/geometry.py b/newton/_src/solvers/kamino/_src/core/geometry.py index 87adcb5288..b9c7ea5075 100644 --- a/newton/_src/solvers/kamino/_src/core/geometry.py +++ b/newton/_src/solvers/kamino/_src/core/geometry.py @@ -331,6 +331,31 @@ class GeometriesModel: Shape of ``(num_excluded_geom_pairs,)`` and type :class:`vec2i`. """ + ### + # Mesh / Heightfield Data (pass-through from Newton Model) + ### + + heightfield_index: wp.array | None = None + """Per-shape heightfield index (``-1`` for non-heightfield shapes).""" + + heightfield_data: wp.array | None = None + """Concatenated :class:`HeightfieldData` structs for all heightfields.""" + + heightfield_elevations: wp.array | None = None + """Concatenated elevation samples for all heightfields.""" + + collision_aabb_lower: wp.array | None = None + """Per-shape local-space collision AABB lower bounds.""" + + collision_aabb_upper: wp.array | None = None + """Per-shape local-space collision AABB upper bounds.""" + + voxel_resolution: wp.array | None = None + """Per-shape voxel resolution for mesh contact reduction.""" + + collision_radius: wp.array | None = None + """Per-shape bounding-sphere radius for broadphase AABB computation.""" + @dataclass class GeometriesData: diff --git a/newton/_src/solvers/kamino/_src/core/model.py b/newton/_src/solvers/kamino/_src/core/model.py index fedc3c6199..5f48f2e3ba 100644 --- a/newton/_src/solvers/kamino/_src/core/model.py +++ b/newton/_src/solvers/kamino/_src/core/model.py @@ -975,7 +975,6 @@ def _compute_num_entities_per_world(entity_world: wp.array, num_worlds: int) -> shape_scale_np = model.shape_scale.numpy() shape_flags_np = model.shape_flags.numpy() geom_shape_collision_group_np = model.shape_collision_group.numpy() - geom_shape_type_np = np.array(shape_type_np, dtype=int) geom_shape_params_np = np.zeros((model.shape_count, 4), dtype=float) model_num_collidable_geoms = 0 for s in range(model.shape_count): @@ -1311,7 +1310,7 @@ def _compute_num_entities_per_world(entity_world: wp.array, num_worlds: int) -> wid=model.shape_world, gid=wp.array(shape_sid_np, dtype=int32), # TODO: Remove bid=model.shape_body, - type=wp.array(geom_shape_type_np, dtype=int32), + type=wp.array(shape_type_np, dtype=int32), flags=model.shape_flags, ptr=model.shape_source_ptr, params=wp.array(geom_shape_params_np, dtype=vec4f), @@ -1322,6 +1321,14 @@ def _compute_num_entities_per_world(entity_world: wp.array, num_worlds: int) -> margin=model.shape_margin, collidable_pairs=model.shape_contact_pairs, excluded_pairs=wp.array(sorted(model.shape_collision_filter_pairs), dtype=vec2i), + # Mesh / heightfield data pass-through from Newton model + heightfield_index=model.shape_heightfield_index, + heightfield_data=model.heightfield_data, + heightfield_elevations=model.heightfield_elevations, + collision_aabb_lower=model.shape_collision_aabb_lower, + collision_aabb_upper=model.shape_collision_aabb_upper, + voxel_resolution=model._shape_voxel_resolution, + collision_radius=model.shape_collision_radius, ) # Per-material properties diff --git a/newton/_src/solvers/kamino/_src/core/shapes.py b/newton/_src/solvers/kamino/_src/core/shapes.py index f9c67dd069..5c534fb32a 100644 --- a/newton/_src/solvers/kamino/_src/core/shapes.py +++ b/newton/_src/solvers/kamino/_src/core/shapes.py @@ -51,25 +51,21 @@ def is_primitive_geo_type(geo_type: GeoType) -> bool: - """Returns whether the geo type is a primitive shape.""" - return geo_type in { - GeoType.SPHERE, - GeoType.CYLINDER, - GeoType.CONE, - GeoType.CAPSULE, - GeoType.BOX, - GeoType.ELLIPSOID, - GeoType.PLANE, - } + """Return whether the geo type is a primitive shape. + + .. deprecated:: + Use :attr:`GeoType.is_primitive` instead. + """ + return geo_type.is_primitive def is_explicit_geo_type(geo_type: GeoType) -> bool: - """Returns whether the geo type is an explicit shape (mesh, convex, heightfield).""" - return geo_type in { - GeoType.MESH, - GeoType.CONVEX_MESH, - GeoType.HFIELD, - } + """Return whether the geo type is an explicit shape (mesh, convex, heightfield). + + .. deprecated:: + Use :attr:`GeoType.is_explicit` instead. + """ + return geo_type.is_explicit class ShapeDescriptor(ABC, Descriptor): @@ -546,16 +542,22 @@ def color(self) -> Vec3 | None: class HFieldShape(ShapeDescriptor): - """ - A shape descriptor for height-field shapes. + """A shape descriptor for height-field (terrain) shapes. - WARNING: This class is not yet implemented. + Attributes: + heightfield: The underlying :class:`Heightfield` data. """ - def __init__(self, name: str = "hfield", uid: str | None = None): + def __init__(self, heightfield: Heightfield, name: str = "hfield", uid: str | None = None): + """Initialize the height-field shape descriptor. + + Args: + heightfield: A :class:`Heightfield` instance containing elevation data. + name: The name of the shape descriptor. + uid: Optional unique identifier of the shape descriptor. + """ super().__init__(GeoType.HFIELD, name, uid) - # TODO: Remove this when HFieldShape is implemented - raise NotImplementedError("HFieldShape is not yet implemented.") + self._data: Heightfield = heightfield @override def __repr__(self): @@ -572,6 +574,11 @@ def params(self) -> tuple[float, float, float]: """Returns the XYZ scaling of the height-field.""" return 1.0, 1.0, 1.0 + @property + @override + def data(self) -> Heightfield: + return self._data + ### # Aliases @@ -616,6 +623,12 @@ def max_contacts_for_shape_pair(type_a: int, type_b: int) -> tuple[int, int]: if type_a > type_b: type_a, type_b = type_b, type_a + # Contact counts for mesh/heightfield pairs are dynamic (bounded by the + # pipeline's max_contacts_per_pair setting). The values below are + # conservative upper-bound estimates used for capacity allocation. + _MESH_CONVEX_MAX = 32 + _MESH_MESH_MAX = 64 + if type_a == GeoType.SPHERE: return 1, 0 @@ -629,7 +642,7 @@ def max_contacts_for_shape_pair(type_a: int, type_b: int) -> tuple[int, int]: elif type_b == GeoType.BOX: return 8, 8 elif type_b == GeoType.MESH or type_b == GeoType.CONVEX_MESH: - pass # TODO: WHAT TO RETURN WHEN MESH SUPPORT IS ADDED? + return _MESH_CONVEX_MAX, 0 elif type_b == GeoType.CONE: return 4, 4 elif type_b == GeoType.PLANE: @@ -643,7 +656,7 @@ def max_contacts_for_shape_pair(type_a: int, type_b: int) -> tuple[int, int]: elif type_b == GeoType.BOX: return 8, 8 elif type_b == GeoType.MESH or type_b == GeoType.CONVEX_MESH: - pass # TODO: WHAT TO RETURN WHEN MESH SUPPORT IS ADDED? + return _MESH_CONVEX_MAX, 0 elif type_b == GeoType.CONE: return 8, 8 elif type_b == GeoType.PLANE: @@ -655,7 +668,7 @@ def max_contacts_for_shape_pair(type_a: int, type_b: int) -> tuple[int, int]: elif type_b == GeoType.BOX: return 8, 8 elif type_b == GeoType.MESH or type_b == GeoType.CONVEX_MESH: - pass # TODO: WHAT TO RETURN WHEN MESH SUPPORT IS ADDED? + return _MESH_CONVEX_MAX, 0 elif type_b == GeoType.CONE: return 4, 4 elif type_b == GeoType.PLANE: @@ -665,7 +678,7 @@ def max_contacts_for_shape_pair(type_a: int, type_b: int) -> tuple[int, int]: if type_b == GeoType.BOX: return 12, 12 elif type_b == GeoType.MESH or type_b == GeoType.CONVEX_MESH: - pass # TODO: WHAT TO RETURN WHEN MESH SUPPORT IS ADDED? + return _MESH_CONVEX_MAX, 0 elif type_b == GeoType.CONE: return 8, 8 elif type_b == GeoType.PLANE: @@ -673,13 +686,17 @@ def max_contacts_for_shape_pair(type_a: int, type_b: int) -> tuple[int, int]: elif type_a == GeoType.MESH or type_a == GeoType.CONVEX_MESH: if type_b == GeoType.HFIELD: - pass # TODO: WHAT TO RETURN WHEN MESH SUPPORT IS ADDED? + return _MESH_MESH_MAX, 0 elif type_b == GeoType.CONE: - pass # TODO: WHAT TO RETURN WHEN MESH SUPPORT IS ADDED? + return _MESH_CONVEX_MAX, 0 elif type_b == GeoType.PLANE: - pass # TODO: WHAT TO RETURN WHEN MESH SUPPORT IS ADDED? + return _MESH_CONVEX_MAX, 0 else: - pass # TODO: WHAT TO RETURN WHEN MESH SUPPORT IS ADDED? + return _MESH_MESH_MAX, 0 + + elif type_a == GeoType.HFIELD: + # Heightfield vs convex primitives + return _MESH_CONVEX_MAX, 0 elif type_a == GeoType.CONE: if type_b == GeoType.CONE: diff --git a/newton/_src/solvers/kamino/_src/geometry/unified.py b/newton/_src/solvers/kamino/_src/geometry/unified.py index b2643fb35b..a46d18c145 100644 --- a/newton/_src/solvers/kamino/_src/geometry/unified.py +++ b/newton/_src/solvers/kamino/_src/geometry/unified.py @@ -273,6 +273,9 @@ def _compute_collision_radius(geo_type: int32, scale: vec3f) -> float32: radius = wp.length(scale) else: radius = float32(1.0e6) + elif geo_type == GeoType.MESH or geo_type == GeoType.CONVEX_MESH or geo_type == GeoType.HFIELD: + # Large bounding sphere; the AABB kernel computes a tighter bound from mesh data + radius = float32(1.0e6) return radius @@ -518,30 +521,48 @@ def __init__( | ShapeFlags.COLLIDE_PARTICLES # Enable shape-particle collision ) + # Detect whether the model contains mesh, convex mesh, or heightfield shapes. + # Keep mesh and heightfield flags separate: heightfield-only scenes should not + # trigger mesh-only kernel setup (mesh-mesh SDF contacts require CUDA). + geom_type_np = self._model.geoms.type.numpy() + _has_meshes = any(int(t) in (GeoType.MESH, GeoType.CONVEX_MESH) for t in geom_type_np) + _has_heightfields = any(int(t) == GeoType.HFIELD for t in geom_type_np) + _has_explicit = _has_meshes or _has_heightfields + # Allocate internal data needed by the pipeline that # the Kamino model and data do not yet provide with wp.ScopedDevice(self._device): self.geom_type = wp.zeros(self._num_geoms, dtype=int32) self.geom_data = wp.zeros(self._num_geoms, dtype=vec4f) self.geom_collision_group = wp.array(geom_collision_group_list, dtype=int32) - self.shape_collision_radius = wp.zeros(self._num_geoms, dtype=float32) + self.collision_radius = wp.zeros(self._num_geoms, dtype=float32) self.shape_flags = wp.full(self._num_geoms, default_shape_flag, dtype=int32) self.shape_aabb_lower = wp.zeros(self._num_geoms, dtype=wp.vec3) self.shape_aabb_upper = wp.zeros(self._num_geoms, dtype=wp.vec3) self.broad_phase_pairs = wp.zeros(self._max_shape_pairs, dtype=wp.vec2i) self.broad_phase_pair_count = wp.zeros(1, dtype=wp.int32) self.narrow_phase_contact_count = wp.zeros(1, dtype=int32) - # TODO: These are currently left empty just to satisfy the narrow phase interface - # but we need to implement SDF/mesh/heightfield support in Kamino to make use of them. - # With has_meshes=False, these arrays are never accessed. self.shape_sdf_data = wp.empty(shape=(0,), dtype=TextureSDFData) self.shape_sdf_index = wp.full_like(self.geom_type, -1) - self.shape_collision_aabb_lower = wp.empty(shape=(0,), dtype=wp.vec3) - self.shape_collision_aabb_upper = wp.empty(shape=(0,), dtype=wp.vec3) - self.shape_voxel_resolution = wp.empty(shape=(0,), dtype=wp.vec3i) - self.shape_heightfield_index = None # TODO - self.heightfield_data = None # TODO - self.heightfield_elevations = None # TODO + + # Wire mesh / heightfield data from the model when explicit shapes exist; + # otherwise use empty placeholder arrays that satisfy the narrow-phase interface. + geoms = self._model.geoms + if _has_explicit: + self.collision_aabb_lower = geoms.collision_aabb_lower + self.collision_aabb_upper = geoms.collision_aabb_upper + self.voxel_resolution = geoms.voxel_resolution + self.heightfield_index = geoms.heightfield_index + self.heightfield_data = geoms.heightfield_data + self.heightfield_elevations = geoms.heightfield_elevations + else: + with wp.ScopedDevice(self._device): + self.collision_aabb_lower = wp.empty(shape=(0,), dtype=wp.vec3) + self.collision_aabb_upper = wp.empty(shape=(0,), dtype=wp.vec3) + self.voxel_resolution = wp.empty(shape=(0,), dtype=wp.vec3i) + self.heightfield_index = None + self.heightfield_data = None + self.heightfield_elevations = None # Initialize the broad-phase backend depending on the selected mode match self._broadphase: @@ -555,7 +576,6 @@ def __init__( raise ValueError(f"Unsupported broad phase mode: {self._broadphase}") # Initialize narrow-phase backend with the contact writer customized for Kamino - # Note: has_meshes=False since Kamino doesn't support mesh collisions yet self.narrow_phase = NarrowPhase( max_candidate_pairs=self._max_shape_pairs, max_triangle_pairs=self._max_triangle_pairs, @@ -563,7 +583,8 @@ def __init__( shape_aabb_lower=self.shape_aabb_lower, shape_aabb_upper=self.shape_aabb_upper, contact_writer_warp_func=write_contact_unified_kamino, - has_meshes=False, + has_meshes=_has_meshes, + has_heightfields=_has_heightfields, ) # Convert geometry data from Kamino to Newton format @@ -657,11 +678,16 @@ def _convert_geometry_data(self): self._model.geoms.gap, self.geom_type, self.geom_data, - self.shape_collision_radius, + self.collision_radius, ], device=self._device, ) + # Use Newton's precomputed collision radius when available (gives + # tighter AABBs for meshes and heightfields than the 1e6 fallback). + if self._model.geoms.collision_radius is not None: + self.collision_radius.assign(self._model.geoms.collision_radius) + def _update_geom_data(self, data: DataKamino, state: StateKamino): """ Updates geometry poses from corresponding body states and computes respective AABBs. @@ -683,7 +709,7 @@ def _update_geom_data(self, data: DataKamino, state: StateKamino): self._model.geoms.offset, self._model.geoms.margin, self._model.geoms.gap, - self.shape_collision_radius, + self.collision_radius, state.q_i, ], outputs=[ @@ -798,12 +824,12 @@ def _run_narrowphase(self, data: DataKamino, contacts: ContactsKamino): texture_sdf_data=self.shape_sdf_data, shape_sdf_index=self.shape_sdf_index, shape_gap=self._model.geoms.gap, - shape_collision_radius=self.shape_collision_radius, + shape_collision_radius=self.collision_radius, shape_flags=self.shape_flags, - shape_collision_aabb_lower=self.shape_collision_aabb_lower, - shape_collision_aabb_upper=self.shape_collision_aabb_upper, - shape_voxel_resolution=self.shape_voxel_resolution, - shape_heightfield_index=self.shape_heightfield_index, + shape_collision_aabb_lower=self.collision_aabb_lower, + shape_collision_aabb_upper=self.collision_aabb_upper, + shape_voxel_resolution=self.voxel_resolution, + shape_heightfield_index=self.heightfield_index, heightfield_data=self.heightfield_data, heightfield_elevations=self.heightfield_elevations, writer_data=writer_data, diff --git a/newton/_src/solvers/kamino/examples/rl/example_rl_bipedal.py b/newton/_src/solvers/kamino/examples/rl/example_rl_bipedal.py index 25637e2b42..671f601005 100644 --- a/newton/_src/solvers/kamino/examples/rl/example_rl_bipedal.py +++ b/newton/_src/solvers/kamino/examples/rl/example_rl_bipedal.py @@ -22,6 +22,9 @@ import torch # noqa: TID253 import warp as wp +# Newton +import newton + # Kamino from newton._src.solvers.kamino._src.utils import logger as msg from newton._src.solvers.kamino._src.utils.viewer import ViewerConfig @@ -93,6 +96,95 @@ def _build_normalization(joint_names: list[str]): return offsets, scales +########################################################################### +# Terrain callback - adds a smooth heightfield +########################################################################### + + +def _make_terrain_fn( + nrow: int = 40, + ncol: int = 40, + hx: float = 10.0, + hy: float = 10.0, + amplitude: float = 0.35, + seed: int = 42, +): + """Return a callback that adds a smooth heightfield terrain to a builder. + + The elevation is a sum of low-frequency sine waves — gentle enough for + a bipedal robot to walk on yet clearly non-flat. + + Args: + nrow: Grid rows. + ncol: Grid columns. + hx: Half-extent in X [m]. + hy: Half-extent in Y [m]. + amplitude: Peak-to-peak height variation [m]. + seed: RNG seed for random phase offsets. + """ + rng = np.random.default_rng(seed) + x = np.linspace(-hx, hx, ncol) + y = np.linspace(-hy, hy, nrow) + xx, yy = np.meshgrid(x, y) + + elevation = np.zeros_like(xx) + for freq in (0.4, 0.7, 1.1): + px, py = rng.uniform(0, 2 * np.pi, size=2) + elevation += np.sin(freq * xx + px) * np.cos(freq * yy + py) + elevation *= amplitude / np.ptp(elevation) + center_r, center_c = nrow // 2, ncol // 2 + elevation -= elevation[center_r, center_c] # surface at origin == z=0 (robot feet) + + hfield = newton.Heightfield( + data=elevation.astype(np.float32), + nrow=nrow, + ncol=ncol, + hx=hx, + hy=hy, + ) + + def _add_terrain(builder): + cfg = newton.ModelBuilder.ShapeConfig() + cfg.margin = 0.01 + cfg.gap = 0.02 + builder.add_shape_heightfield(heightfield=hfield, cfg=cfg) + + return _add_terrain + + +########################################################################### +# Scene callback - adds pushable balls +########################################################################### + +BALL_RADIUS = 0.2 +BALL_POSITIONS = [ + wp.vec3(0.5, 0.0, BALL_RADIUS + 0.01), + wp.vec3(-0.6, 0.4, BALL_RADIUS + 0.01), + wp.vec3(0.3, -0.5, BALL_RADIUS + 0.01), + wp.vec3(-0.4, -0.3, BALL_RADIUS + 0.01), + wp.vec3(0.7, 0.6, BALL_RADIUS + 0.01), +] + + +def _make_balls_fn(num_balls: int = 1): + """Return a callback that adds *num_balls* pushable spheres.""" + num_balls = max(0, min(num_balls, len(BALL_POSITIONS))) + positions = BALL_POSITIONS[:num_balls] + + def _add_balls(robot_builder): + ball_cfg = newton.ModelBuilder.ShapeConfig() + ball_cfg.density = 50.0 + ball_cfg.mu = 0.5 + for i, pos in enumerate(positions): + ball_body = robot_builder.add_body( + xform=wp.transform(p=pos, q=wp.quat_identity()), + label=f"ball_{i}", + ) + robot_builder.add_shape_sphere(ball_body, radius=BALL_RADIUS, cfg=ball_cfg) + + return _add_balls + + ########################################################################### # Example class ########################################################################### @@ -104,6 +196,7 @@ def __init__( device: wp.DeviceLike = None, policy=None, headless: bool = False, + num_balls: int = 1, ): # Timing self.sim_dt = 0.02 @@ -114,7 +207,7 @@ def __init__( # USD model path USD_MODEL_PATH = os.path.join(_ASSETS_DIR, "bipedal", "bipedal_with_textures.usda") - # Create generic articulated body simulator + # Create generic articulated body simulator with rolling terrain self.sim_wrapper = RigidBodySim( usd_model_path=USD_MODEL_PATH, num_worlds=1, @@ -128,6 +221,8 @@ def __init__( specular_scale=0.3, shadow_radius=10.0, ), + terrain_fn=_make_terrain_fn(), + scene_callback=_make_balls_fn(num_balls), ) # Override PD gains @@ -136,10 +231,12 @@ def __init__( self.sim_wrapper.sim.model.joints.a_j.fill_(0.004) self.sim_wrapper.sim.model.joints.b_j.fill_(0.0) - # Build normalization from simulator joint order - joint_pos_offset, joint_pos_scale = _build_normalization(self.sim_wrapper.joint_names) + # Build normalization from actuated joints only (excludes passive free joints + # such as the ball, which should not feed into the RL policy). + joint_pos_offset, joint_pos_scale = _build_normalization(self.sim_wrapper.actuated_joint_names) self.joint_pos_offset = torch.tensor(joint_pos_offset, device=self.torch_device) self.joint_pos_scale = torch.tensor(joint_pos_scale, device=self.torch_device) + self._act_idx = self.sim_wrapper.actuated_dof_indices_tensor # Observation builder self.obs = BipedalObservation( @@ -167,8 +264,8 @@ def __init__( root_yaw = quat_to_projected_yaw(self.sim_wrapper.q_i[:, 0, 3:]) self.joystick.reset(root_pos_2d=root_pos_2d, root_yaw=root_yaw) - # Action buffer - self.actions = self.sim_wrapper.q_j.clone() + # Action buffer (actuated joints only) + self.actions = self.sim_wrapper.q_j[:, self._act_idx].clone() # Pre-allocated command buffers (eliminates per-step torch.tensor()) self._cmd_vel_buf = torch.zeros(1, 2, device=self.torch_device) @@ -193,7 +290,7 @@ def reset(self): root_pos_2d = self.sim_wrapper.q_i[:, 0, :2] root_yaw = quat_to_projected_yaw(self.sim_wrapper.q_i[:, 0, 3:]) self.joystick.reset(root_pos_2d=root_pos_2d, root_yaw=root_yaw) - self.actions[:] = self.sim_wrapper.q_j + self.actions[:] = self.sim_wrapper.q_j[:, self._act_idx] def step_once(self): """Single physics step (used by run_headless warm-up).""" @@ -234,8 +331,8 @@ def sim_step(self): torch.mul(raw, self.joint_pos_scale, out=self.actions) self.actions.add_(self.joint_pos_offset) - # Write action targets to implicit PD controller - self.sim_wrapper.q_j_ref[:] = self.actions + # Write action targets to actuated joints only + self.sim_wrapper.q_j_ref[:, self._act_idx] = self.actions # Step physics for _ in range(self.control_decimation): @@ -273,6 +370,12 @@ def render(self): default="sync", help="Sim loop mode: sync (default) or async", ) + parser.add_argument( + "--num-balls", + type=int, + default=1, + help="Number of balls to add to the scene (max 5, default: 1)", + ) parser.add_argument( "--render-fps", type=float, @@ -305,6 +408,7 @@ def render(self): device=device, policy=policy, headless=args.headless, + num_balls=args.num_balls, ) try: diff --git a/newton/_src/solvers/kamino/examples/rl/simulation.py b/newton/_src/solvers/kamino/examples/rl/simulation.py index 1de6ee4613..10659ef210 100644 --- a/newton/_src/solvers/kamino/examples/rl/simulation.py +++ b/newton/_src/solvers/kamino/examples/rl/simulation.py @@ -30,6 +30,7 @@ from newton._src.solvers.kamino._src.core.types import transformf, vec6f from newton._src.solvers.kamino._src.geometry import CollisionDetector from newton._src.solvers.kamino._src.geometry.aggregation import ContactAggregation +from newton._src.solvers.kamino._src.geometry.contacts import ContactsKamino, convert_contacts_newton_to_kamino from newton._src.solvers.kamino._src.solver_kamino_impl import SolverKaminoImpl from newton._src.solvers.kamino._src.utils import logger as msg from newton._src.solvers.kamino._src.utils.sim import Simulator @@ -44,6 +45,11 @@ class SimulatorFromNewton: already-finalized :class:`newton.Model` instead of a ``ModelBuilderKamino``. Internally uses :meth:`ModelKamino.from_newton` to obtain Kamino-native model, state, control, and solver objects. + + When *use_newton_collisions* is ``True`` (required for heightfield / + mesh terrain), Newton's own :meth:`~newton.Model.collide` pipeline + runs each step and the resulting contacts are converted to Kamino + format via :func:`convert_contacts_newton_to_kamino`. """ def __init__( @@ -51,6 +57,7 @@ def __init__( newton_model: newton.Model, config: Simulator.Config | None = None, device: wp.DeviceLike = None, + use_newton_collisions: bool = False, ): self._device = wp.get_device(device) @@ -69,11 +76,27 @@ def __init__( self._control: ControlKamino = self._model.control(device=self._device) # Collision detection - self._collision_detector = CollisionDetector( - model=self._model, - config=config.collision_detector, - ) - self._contacts = self._collision_detector.contacts + self._use_newton_collisions = use_newton_collisions + self._collision_detector: CollisionDetector | None = None + + if use_newton_collisions: + self._newton_model = newton_model + self._newton_state = newton_model.state() + self._newton_contacts = newton_model.contacts() + per_world = max(1024, newton_model.rigid_contact_max // max(newton_model.world_count, 1)) + if config.collision_detector.max_contacts_per_world is not None: + per_world = min(per_world, config.collision_detector.max_contacts_per_world) + world_max = [per_world] * newton_model.world_count + self._contacts = ContactsKamino(capacity=world_max, device=self._device) + else: + self._newton_model = None + self._newton_state = None + self._newton_contacts = None + self._collision_detector = CollisionDetector( + model=self._model, + config=config.collision_detector, + ) + self._contacts = self._collision_detector.contacts # Solver self._solver = SolverKaminoImpl( @@ -109,13 +132,28 @@ def contacts(self): return self._contacts @property - def collision_detector(self) -> CollisionDetector: + def collision_detector(self) -> CollisionDetector | None: return self._collision_detector @property def solver(self) -> SolverKaminoImpl: return self._solver + def _run_newton_collision(self, state_kamino: StateKamino): + """Convert COM poses to body-origin frame, run Newton collision, convert contacts.""" + convert_body_com_to_origin( + body_com=self._model.bodies.i_r_com_i, + body_q_com=state_kamino.q_i, + body_q=self._newton_state.body_q, + ) + self._newton_model.collide(self._newton_state, self._newton_contacts) + convert_contacts_newton_to_kamino( + self._newton_model, + self._newton_state, + self._newton_contacts, + self._contacts, + ) + def step(self): """Advance the simulation by one timestep. @@ -124,13 +162,24 @@ def step(self): only for rendering via :meth:`RigidBodySim.render`. """ self._state_p.copy_from(self._state_n) - self._solver.step( - state_in=self._state_p, - state_out=self._state_n, - control=self._control, - contacts=self._contacts, - detector=self._collision_detector, - ) + + if self._use_newton_collisions: + self._run_newton_collision(self._state_p) + self._solver.step( + state_in=self._state_p, + state_out=self._state_n, + control=self._control, + contacts=self._contacts, + detector=None, + ) + else: + self._solver.step( + state_in=self._state_p, + state_out=self._state_n, + control=self._control, + contacts=self._contacts, + detector=self._collision_detector, + ) def reset(self, **kwargs): """Reset the simulation state. @@ -170,6 +219,12 @@ class RigidBodySim: use_cuda_graph: Capture CUDA graphs for step and reset (requires CUDA device with memory pool enabled). render_config: Viewer appearance settings. ``None`` uses defaults. + terrain_fn: Optional callable ``fn(builder)`` that adds terrain + shapes to the multi-world :class:`~newton.ModelBuilder`. + When provided, replaces the default ground plane. + scene_callback: Optional callable ``fn(robot_builder)`` that adds + extra shapes (e.g. pushable objects) to the robot builder + before multi-world duplication. """ def __init__( @@ -188,8 +243,11 @@ def __init__( video_folder: str | None = None, async_save: bool = True, max_contacts_per_pair: int | None = None, + max_contacts_per_world: int | None = None, render_config: ViewerConfig | None = None, collapse_fixed_joints: bool = False, + terrain_fn: callable | None = None, + scene_callback: callable | None = None, ): # ----- Device setup ----- self._device = wp.get_device(device) @@ -227,36 +285,43 @@ def __init__( hide_collision_shapes=True, ) + if scene_callback is not None: + scene_callback(robot_builder) + # Create the multi-world model by duplicating the single-robot # builder for the specified number of worlds builder = newton.ModelBuilder(up_axis=newton.Axis.Z) for _ in range(num_worlds): builder.add_world(robot_builder) - # Add a global ground plane applied to all worlds - builder.add_ground_plane() + if terrain_fn is not None: + terrain_fn(builder) + elif add_ground: + builder.add_ground_plane() # Create the model from the builder self._newton_model = builder.finalize(skip_validation_joints=True) - # TODO remove after fixing bug - self._newton_model.shape_margin.fill_(0.0) - self._newton_model.shape_gap.fill_(1e-5) - if enable_gravity: self._newton_model.set_gravity((0.0, 0.0, -9.81)) # ----- Create Kamino simulator from Newton model ----- msg.notif("Building Kamino simulator ...") - # Cap per-pair contact count to limit Delassus matrix size + # Cap contact counts to limit Delassus matrix size if max_contacts_per_pair is not None: settings.collision_detector.max_contacts_per_pair = max_contacts_per_pair + if max_contacts_per_world is not None: + settings.collision_detector.max_contacts_per_world = max_contacts_per_world + # Use Newton's collision pipeline when terrain_fn adds non-primitive + # shapes (heightfields, meshes) that Kamino's detector cannot handle. + use_newton_cd = terrain_fn is not None self.sim = SimulatorFromNewton( newton_model=self._newton_model, config=settings, device=self._device, + use_newton_collisions=use_newton_cd, ) self.model: ModelKamino = self.sim.model msg.info(f"Model size: {self.sim.model.size}") @@ -367,16 +432,18 @@ def apply_shape_colors(shape_colors: dict[int, Color3]): def _make_rl_interface(self): """Create zero-copy PyTorch views of simulator state, control and contact arrays.""" nw = self.sim.model.size.num_worlds + njc = self.sim.model.size.max_of_num_joint_coords njd = self.sim.model.size.max_of_num_joint_dofs nb = self.sim.model.size.max_of_num_bodies # State tensors (read-only views into simulator) - self._q_j = wp.to_torch(self.sim.state.q_j).reshape(nw, njd) + # q_j uses generalized coordinates (njc), dq_j uses DOFs (njd) + self._q_j = wp.to_torch(self.sim.state.q_j).reshape(nw, njc) self._dq_j = wp.to_torch(self.sim.state.dq_j).reshape(nw, njd) self._q_i = wp.to_torch(self.sim.state.q_i).reshape(nw, nb, 7) self._u_i = wp.to_torch(self.sim.state.u_i).reshape(nw, nb, 6) - # Control tensors (writable views) + # Control tensors (writable views — all use DOF space) self._q_j_ref = wp.to_torch(self.sim.control.q_j_ref).reshape(nw, njd) self._dq_j_ref = wp.to_torch(self.sim.control.dq_j_ref).reshape(nw, njd) self._tau_j_ref = wp.to_torch(self.sim.control.tau_j_ref).reshape(nw, njd) diff --git a/newton/_src/solvers/kamino/tests/test_geometry_mesh_heightfield.py b/newton/_src/solvers/kamino/tests/test_geometry_mesh_heightfield.py new file mode 100644 index 0000000000..453e5f6513 --- /dev/null +++ b/newton/_src/solvers/kamino/tests/test_geometry_mesh_heightfield.py @@ -0,0 +1,604 @@ +# SPDX-FileCopyrightText: Copyright (c) 2025 The Newton Developers +# SPDX-License-Identifier: Apache-2.0 + +"""Unit tests for mesh and heightfield collision support in Kamino. + +Tests the unified collision pipeline, Newton-to-Kamino contact conversion, +and solver integration with mesh and heightfield shapes via the +``ModelKamino.from_newton()`` path. +""" + +import unittest + +import numpy as np +import warp as wp + +import newton +from newton._src.solvers.kamino._src.core.bodies import convert_body_com_to_origin +from newton._src.solvers.kamino._src.core.model import ModelKamino +from newton._src.solvers.kamino._src.geometry.contacts import ContactsKamino, convert_contacts_newton_to_kamino +from newton._src.solvers.kamino._src.geometry.unified import CollisionPipelineUnifiedKamino +from newton._src.solvers.kamino._src.solver_kamino_impl import SolverKaminoImpl +from newton._src.solvers.kamino._src.utils import logger as msg +from newton._src.solvers.kamino.tests import setup_tests, test_context + +_cuda_available = wp.is_cuda_available() + +### +# Scene Builders +### + +SPHERE_RADIUS = 0.25 +BOX_HALF = 0.5 + + +def _build_sphere_on_heightfield(sphere_z=None) -> newton.ModelBuilder: + """Sphere resting on a flat heightfield (elevation = 0 everywhere).""" + builder = newton.ModelBuilder(up_axis=newton.Axis.Z) + + nrow, ncol = 8, 8 + elevation = np.zeros((nrow, ncol), dtype=np.float32) + hfield = newton.Heightfield(data=elevation, nrow=nrow, ncol=ncol, hx=4.0, hy=4.0) + + cfg = newton.ModelBuilder.ShapeConfig() + cfg.margin = 0.0 + cfg.gap = 1e-3 + + builder.add_shape_heightfield(heightfield=hfield, cfg=cfg) + + z = sphere_z if sphere_z is not None else SPHERE_RADIUS + body = builder.add_body(xform=wp.transform(p=(0.0, 0.0, z), q=wp.quat_identity())) + builder.add_shape_sphere(body, radius=SPHERE_RADIUS, cfg=cfg) + + return builder + + +def _build_sphere_on_mesh_box(sphere_z=None) -> newton.ModelBuilder: + """Sphere resting on a box-shaped triangle mesh.""" + builder = newton.ModelBuilder(up_axis=newton.Axis.Z) + + mesh = newton.Mesh.create_box(BOX_HALF, BOX_HALF, BOX_HALF) + cfg = newton.ModelBuilder.ShapeConfig() + cfg.margin = 0.0 + cfg.gap = 0.02 + + # Static mesh box centered at origin (top face at z = 0.5) + builder.add_shape_mesh(body=-1, mesh=mesh, cfg=cfg) + + # Sphere slightly penetrating the mesh box top face + z = sphere_z if sphere_z is not None else (BOX_HALF + SPHERE_RADIUS - 0.005) + body = builder.add_body(xform=wp.transform(p=(0.0, 0.0, z), q=wp.quat_identity())) + builder.add_shape_sphere(body, radius=SPHERE_RADIUS, cfg=cfg) + + return builder + + +def _build_box_on_heightfield() -> newton.ModelBuilder: + """Box resting on a flat heightfield.""" + builder = newton.ModelBuilder(up_axis=newton.Axis.Z) + + nrow, ncol = 8, 8 + elevation = np.zeros((nrow, ncol), dtype=np.float32) + hfield = newton.Heightfield(data=elevation, nrow=nrow, ncol=ncol, hx=4.0, hy=4.0) + + cfg = newton.ModelBuilder.ShapeConfig() + cfg.margin = 0.0 + cfg.gap = 1e-3 + + builder.add_shape_heightfield(heightfield=hfield, cfg=cfg) + + body = builder.add_body(xform=wp.transform(p=(0.0, 0.0, BOX_HALF), q=wp.quat_identity())) + builder.add_shape_box(body, hx=BOX_HALF, hy=BOX_HALF, hz=BOX_HALF, cfg=cfg) + + return builder + + +def _build_mixed_scene() -> newton.ModelBuilder: + """Scene with both primitive shapes and a mesh — sphere on mesh box + sphere on ground plane.""" + builder = newton.ModelBuilder(up_axis=newton.Axis.Z) + + mesh = newton.Mesh.create_box(BOX_HALF, BOX_HALF, BOX_HALF) + cfg = newton.ModelBuilder.ShapeConfig() + cfg.margin = 0.0 + cfg.gap = 0.02 + + # Static mesh box at x=2 + builder.add_shape_mesh( + body=-1, + mesh=mesh, + xform=wp.transform(p=(2.0, 0.0, 0.0), q=wp.quat_identity()), + cfg=cfg, + ) + + # Ground plane + builder.add_ground_plane(cfg=cfg) + + # Sphere on ground plane at origin (touching) + body_a = builder.add_body(xform=wp.transform(p=(0.0, 0.0, SPHERE_RADIUS), q=wp.quat_identity())) + builder.add_shape_sphere(body_a, radius=SPHERE_RADIUS, cfg=cfg) + + # Sphere on mesh box at x=2 (slightly penetrating) + body_b = builder.add_body( + xform=wp.transform(p=(2.0, 0.0, BOX_HALF + SPHERE_RADIUS - 0.005), q=wp.quat_identity()), + ) + builder.add_shape_sphere(body_b, radius=SPHERE_RADIUS, cfg=cfg) + + return builder + + +def _build_heightfield_terrain() -> newton.ModelBuilder: + """Sphere on a non-flat heightfield with sine-wave terrain.""" + builder = newton.ModelBuilder(up_axis=newton.Axis.Z) + + nrow, ncol = 20, 20 + x = np.linspace(-2.0, 2.0, ncol) + y = np.linspace(-2.0, 2.0, nrow) + xx, yy = np.meshgrid(x, y) + elevation = (0.1 * np.sin(xx) * np.cos(yy)).astype(np.float32) + # Elevation at center (0,0) ≈ 0 + hfield = newton.Heightfield(data=elevation, nrow=nrow, ncol=ncol, hx=2.0, hy=2.0) + + cfg = newton.ModelBuilder.ShapeConfig() + cfg.margin = 0.0 + cfg.gap = 1e-3 + + builder.add_shape_heightfield(heightfield=hfield, cfg=cfg) + + # Sphere at the center, slightly above terrain surface (elevation ≈ 0) + body = builder.add_body(xform=wp.transform(p=(0.0, 0.0, SPHERE_RADIUS), q=wp.quat_identity())) + builder.add_shape_sphere(body, radius=SPHERE_RADIUS, cfg=cfg) + + return builder + + +def _build_multi_world_heightfield(num_worlds: int = 3) -> newton.ModelBuilder: + """Multi-world scene, each with sphere-on-flat-heightfield.""" + single = newton.ModelBuilder(up_axis=newton.Axis.Z) + + nrow, ncol = 8, 8 + elevation = np.zeros((nrow, ncol), dtype=np.float32) + hfield = newton.Heightfield(data=elevation, nrow=nrow, ncol=ncol, hx=4.0, hy=4.0) + + cfg = newton.ModelBuilder.ShapeConfig() + cfg.margin = 0.0 + cfg.gap = 1e-3 + + body = single.add_body(xform=wp.transform(p=(0.0, 0.0, SPHERE_RADIUS), q=wp.quat_identity())) + single.add_shape_sphere(body, radius=SPHERE_RADIUS, cfg=cfg) + + multi = newton.ModelBuilder(up_axis=newton.Axis.Z) + for _ in range(num_worlds): + multi.add_world(single) + + multi.add_shape_heightfield(heightfield=hfield, cfg=cfg) + + return multi + + +### +# Helpers +### + + +def _finalize_and_get_kamino(builder, device): + """Finalize Newton model, create Kamino model, data, and state.""" + newton_model = builder.finalize(device=device) + model = ModelKamino.from_newton(newton_model) + data = model.data(device=device) + state = model.state(device=device) + return newton_model, model, data, state + + +def _run_unified_pipeline(model, data, state, device): + """Create unified pipeline, allocate contacts, run collision detection.""" + num_worlds = model.size.num_worlds + pipeline = CollisionPipelineUnifiedKamino( + model=model, + broadphase="nxn", + device=device, + ) + contacts = ContactsKamino(capacity=[4096] * num_worlds, device=device) + contacts.clear() + pipeline.collide(data, state, contacts) + return contacts + + +def _run_newton_cd_and_convert(newton_model, device): + """Run Newton's CD pipeline and convert contacts to Kamino format.""" + # Normalize shape_world for single-world models + if newton_model.world_count == 1: + sw = newton_model.shape_world.numpy() + if np.any(sw < 0): + sw[sw < 0] = 0 + newton_model.shape_world.assign(sw) + + state = newton_model.state() + newton.eval_fk(newton_model, newton_model.joint_q, newton_model.joint_qd, state) + newton_contacts = newton_model.collide(state) + + nc = int(newton_contacts.rigid_contact_count.numpy()[0]) + kamino_contacts = ContactsKamino(capacity=[max(nc + 64, 256)], device=device) + convert_contacts_newton_to_kamino(newton_model, state, newton_contacts, kamino_contacts) + wp.synchronize() + + return kamino_contacts, nc + + +def _step_with_newton_cd(builder, device, num_steps=200, dt=0.005): + """Build scene, step solver with Newton CD, return final body positions (COM frame).""" + newton_model = builder.finalize(device=device) + + # Normalize shape_world + if newton_model.world_count == 1: + sw = newton_model.shape_world.numpy() + if np.any(sw < 0): + sw[sw < 0] = 0 + newton_model.shape_world.assign(sw) + + newton_model.set_gravity((0.0, 0.0, -9.81)) + + model = ModelKamino.from_newton(newton_model) + model.time.set_uniform_timestep(dt) + + state_p = model.state(device=device) + state_n = model.state(device=device) + control = model.control(device=device) + + per_world = max(1024, newton_model.rigid_contact_max // max(newton_model.world_count, 1)) + contacts = ContactsKamino(capacity=[per_world], device=device) + + solver = SolverKaminoImpl(model=model, contacts=contacts) + solver.reset(state_out=state_n) + state_p.copy_from(state_n) + + newton_state = newton_model.state() + newton_contacts = newton_model.contacts() + + for _ in range(num_steps): + state_p.copy_from(state_n) + + convert_body_com_to_origin( + body_com=model.bodies.i_r_com_i, + body_q_com=state_p.q_i, + body_q=newton_state.body_q, + ) + newton_model.collide(newton_state, newton_contacts) + convert_contacts_newton_to_kamino(newton_model, newton_state, newton_contacts, contacts) + + solver.step( + state_in=state_p, + state_out=state_n, + control=control, + contacts=contacts, + detector=None, + ) + + return state_n.q_i.numpy() + + +### +# Test Classes +### + + +class TestUnifiedPipelineMeshHeightfield(unittest.TestCase): + """Tests Kamino unified collision pipeline with heightfield shapes via from_newton(). + + The unified pipeline handles heightfield-vs-convex contacts directly. + Each test verifies exact contact counts, contact positions, normals, + and signed distances against analytically known values. + """ + + def setUp(self): + if not test_context.setup_done: + setup_tests(clear_cache=False) + self.default_device = wp.get_device(test_context.device) + self.verbose = test_context.verbose + if self.verbose: + msg.set_log_level(msg.LogLevel.DEBUG) + else: + msg.reset_log_level() + + def tearDown(self): + self.default_device = None + if self.verbose: + msg.reset_log_level() + + def test_01_sphere_on_flat_heightfield(self): + """Sphere touching flat heightfield: 2 contacts (one per cell triangle), normal=(0,0,1), position at z=0.""" + _, model, data, state = _finalize_and_get_kamino(_build_sphere_on_heightfield(), self.default_device) + contacts = _run_unified_pipeline(model, data, state, self.default_device) + + nc = int(contacts.model_active_contacts.numpy()[0]) + # A sphere centered over a heightfield cell touches both triangles in that cell, + # producing 2 contacts on a flat surface. + self.assertEqual(nc, 2, f"Sphere-on-flat-heightfield should produce 2 contacts (1 per triangle), got {nc}") + + gapfunc = contacts.gapfunc.numpy()[:nc] + pos_a = contacts.position_A.numpy()[:nc] + + for i in range(nc): + normal = gapfunc[i, :3] + signed_dist = gapfunc[i, 3] + + # Normal must be (0, 0, 1) for a flat heightfield + np.testing.assert_allclose(normal, [0.0, 0.0, 1.0], atol=0.05, err_msg=f"Contact {i}: normal must point up") + + # Signed distance: sphere center is at z=R, surface at z=0, so distance ≈ 0 + self.assertLessEqual( + signed_dist, 0.01, f"Contact {i}: signed distance should be near zero, got {signed_dist}" + ) + self.assertGreaterEqual( + signed_dist, -0.01, f"Contact {i}: signed distance should be near zero, got {signed_dist}" + ) + + # Contact point on the heightfield side (position_A) should be near (0, 0, 0) + np.testing.assert_allclose( + pos_a[i, 2], + 0.0, + atol=0.02, + err_msg=f"Contact {i}: heightfield contact z should be ≈ 0, got {pos_a[i, 2]}", + ) + + def test_02_box_on_flat_heightfield(self): + """Box resting on flat heightfield: >=4 contacts, all at z ≈ 0.""" + _, model, data, state = _finalize_and_get_kamino(_build_box_on_heightfield(), self.default_device) + contacts = _run_unified_pipeline(model, data, state, self.default_device) + + nc = int(contacts.model_active_contacts.numpy()[0]) + self.assertGreaterEqual(nc, 4, f"Box face on heightfield should produce >=4 contacts, got {nc}") + + gapfunc = contacts.gapfunc.numpy()[:nc] + for i in range(nc): + normal = gapfunc[i, :3] + signed_dist = gapfunc[i, 3] + + # All normals should point up + np.testing.assert_allclose( + normal, [0.0, 0.0, 1.0], atol=0.1, err_msg=f"Contact {i}: normal should point up" + ) + # Signed distance near zero (touching) + self.assertLessEqual( + abs(signed_dist), 0.02, f"Contact {i}: distance should be near zero, got {signed_dist}" + ) + + # All contact positions should be at z ≈ 0 and within the box footprint + pos_a = contacts.position_A.numpy()[:nc] + for i in range(nc): + self.assertAlmostEqual(pos_a[i, 2], 0.0, places=1, msg=f"Contact {i}: z should be ≈ 0") + self.assertLessEqual(abs(pos_a[i, 0]), BOX_HALF + 0.01, f"Contact {i}: x out of box bounds") + self.assertLessEqual(abs(pos_a[i, 1]), BOX_HALF + 0.01, f"Contact {i}: y out of box bounds") + + def test_03_heightfield_terrain(self): + """Sphere on sine-wave terrain: contacts generated, normal has upward component.""" + _, model, data, state = _finalize_and_get_kamino(_build_heightfield_terrain(), self.default_device) + contacts = _run_unified_pipeline(model, data, state, self.default_device) + + nc = int(contacts.model_active_contacts.numpy()[0]) + self.assertGreaterEqual(nc, 1, "Sphere on terrain must produce contacts") + + gapfunc = contacts.gapfunc.numpy()[:nc] + for i in range(nc): + normal = gapfunc[i, :3] + norm_len = np.linalg.norm(normal) + self.assertTrue(np.isclose(norm_len, 1.0, atol=1e-4), f"Contact {i}: normal not unit") + # On gently undulating terrain near the center, normal should still be mostly upward + self.assertGreater(normal[2], 0.7, f"Contact {i}: normal z={normal[2]}, expected mostly up") + + def test_04_multi_world_heightfield(self): + """Multi-world sphere-on-heightfield: each world gets exactly 2 contacts (1 per triangle).""" + num_worlds = 3 + _, model, data, state = _finalize_and_get_kamino( + _build_multi_world_heightfield(num_worlds), self.default_device + ) + contacts = _run_unified_pipeline(model, data, state, self.default_device) + + nc = int(contacts.model_active_contacts.numpy()[0]) + expected_total = 2 * num_worlds # 2 contacts per sphere (one per cell triangle) + self.assertEqual(nc, expected_total, f"Expected {expected_total} contacts (2 per world), got {nc}") + + world_counts = contacts.world_active_contacts.numpy()[:num_worlds] + for w in range(num_worlds): + self.assertEqual(int(world_counts[w]), 2, f"World {w}: expected 2 contacts, got {world_counts[w]}") + + def test_05_no_contacts_when_separated(self): + """Sphere far above heightfield must produce zero contacts.""" + _, model, data, state = _finalize_and_get_kamino( + _build_sphere_on_heightfield(sphere_z=SPHERE_RADIUS + 1.0), self.default_device + ) + contacts = _run_unified_pipeline(model, data, state, self.default_device) + + nc = int(contacts.model_active_contacts.numpy()[0]) + self.assertEqual(nc, 0, f"Separated sphere should produce 0 contacts, got {nc}") + + +class TestNewtonCollisionPathMeshHeightfield(unittest.TestCase): + """Tests Newton model.collide() -> convert_contacts_newton_to_kamino() path. + + This is the primary path for mesh collisions in Kamino. Tests verify + that contact data survives conversion with correct body indices, + physically plausible normals, positions, and signed distances. + """ + + def setUp(self): + if not test_context.setup_done: + setup_tests(clear_cache=False) + self.default_device = wp.get_device(test_context.device) + self.verbose = test_context.verbose + if self.verbose: + msg.set_log_level(msg.LogLevel.DEBUG) + else: + msg.reset_log_level() + + def tearDown(self): + self.default_device = None + if self.verbose: + msg.reset_log_level() + + def test_01_newton_to_kamino_heightfield(self): + """Heightfield contacts survive Newton->Kamino conversion with correct geometry.""" + builder = _build_sphere_on_heightfield() + newton_model = builder.finalize(device=self.default_device) + + kamino_contacts, newton_count = _run_newton_cd_and_convert(newton_model, self.default_device) + self.assertGreater(newton_count, 0, "Newton must produce contacts for sphere on heightfield") + + nc = int(kamino_contacts.model_active_contacts.numpy()[0]) + self.assertGreater(nc, 0, "Conversion must preserve contacts") + + gapfunc = kamino_contacts.gapfunc.numpy()[:nc] + bid_AB = kamino_contacts.bid_AB.numpy()[:nc] + pos_a = kamino_contacts.position_A.numpy()[:nc] + + for i in range(nc): + # A/B convention: bid_B must be dynamic (>= 0) + self.assertGreaterEqual(int(bid_AB[i, 1]), 0, f"Contact {i}: bid_B must be >= 0") + + # Normal must be approximately upward + normal = gapfunc[i, :3] + np.testing.assert_allclose( + normal, [0.0, 0.0, 1.0], atol=0.1, err_msg=f"Contact {i}: normal should point up" + ) + + # Contact position on heightfield should be near z=0 + self.assertAlmostEqual(pos_a[i, 2], 0.0, places=1, msg=f"Contact {i}: position z should be ≈ 0") + + # Signed distance should be non-positive (penetrating or touching) + self.assertLessEqual(gapfunc[i, 3], 0.01, f"Contact {i}: distance should be <= 0") + + @unittest.skipUnless(_cuda_available, "mesh collision requires CUDA") + def test_02_newton_to_kamino_mesh(self): + """Mesh box contacts survive Newton->Kamino conversion with correct geometry.""" + builder = _build_sphere_on_mesh_box() + newton_model = builder.finalize(device=self.default_device) + + kamino_contacts, newton_count = _run_newton_cd_and_convert(newton_model, self.default_device) + self.assertGreater(newton_count, 0, "Newton must produce contacts for sphere on mesh") + + nc = int(kamino_contacts.model_active_contacts.numpy()[0]) + self.assertGreater(nc, 0, "Conversion must preserve contacts") + + gapfunc = kamino_contacts.gapfunc.numpy()[:nc] + bid_AB = kamino_contacts.bid_AB.numpy()[:nc] + pos_a = kamino_contacts.position_A.numpy()[:nc] + + for i in range(nc): + self.assertGreaterEqual(int(bid_AB[i, 1]), 0, f"Contact {i}: bid_B must be >= 0") + + normal = gapfunc[i, :3] + # Normal should point mostly upward (sphere on top of mesh box) + self.assertGreater(normal[2], 0.5, f"Contact {i}: normal z={normal[2]}, expected upward") + + # Contact on mesh top face should be near z = BOX_HALF = 0.5 + self.assertAlmostEqual(pos_a[i, 2], BOX_HALF, delta=0.1, msg=f"Contact {i}: z should be near mesh top face") + + @unittest.skipUnless(_cuda_available, "mesh collision requires CUDA") + def test_03_newton_to_kamino_mixed(self): + """Mixed scene: both primitive-plane and mesh contacts converted correctly.""" + builder = _build_mixed_scene() + newton_model = builder.finalize(device=self.default_device) + + kamino_contacts, newton_count = _run_newton_cd_and_convert(newton_model, self.default_device) + self.assertGreater(newton_count, 0, "Newton must produce contacts") + + nc = int(kamino_contacts.model_active_contacts.numpy()[0]) + # Must have contacts for both spheres (one on plane, one on mesh) + self.assertGreaterEqual(nc, 2, f"Mixed scene should have >=2 contacts, got {nc}") + + # Verify we got contacts involving different bodies + bid_AB = kamino_contacts.bid_AB.numpy()[:nc] + dynamic_bodies = {int(bid_AB[i, 1]) for i in range(nc)} + self.assertGreaterEqual( + len(dynamic_bodies), 2, f"Should have contacts for >=2 different bodies, got {dynamic_bodies}" + ) + + @unittest.skipUnless(_cuda_available, "mesh collision requires CUDA") + def test_04_no_contacts_when_separated(self): + """Sphere far above mesh box must produce zero contacts after conversion.""" + builder = _build_sphere_on_mesh_box(sphere_z=BOX_HALF + SPHERE_RADIUS + 2.0) + newton_model = builder.finalize(device=self.default_device) + + kamino_contacts, newton_count = _run_newton_cd_and_convert(newton_model, self.default_device) + self.assertEqual(newton_count, 0, "Separated shapes should produce 0 Newton contacts") + + nc = int(kamino_contacts.model_active_contacts.numpy()[0]) + self.assertEqual(nc, 0, "Separated shapes should produce 0 Kamino contacts") + + +@unittest.skipUnless(_cuda_available, "Kamino solver requires CUDA") +class TestSolverWithMeshHeightfield(unittest.TestCase): + """Tests Kamino solver produces physically correct behavior with mesh/heightfield contacts. + + Drops objects onto surfaces and verifies they come to rest at the + analytically expected height rather than falling through or floating. + """ + + def setUp(self): + if not test_context.setup_done: + setup_tests(clear_cache=False) + self.default_device = wp.get_device(test_context.device) + self.verbose = test_context.verbose + if self.verbose: + msg.set_log_level(msg.LogLevel.DEBUG) + else: + msg.reset_log_level() + + def tearDown(self): + self.default_device = None + if self.verbose: + msg.reset_log_level() + + def test_01_sphere_falls_onto_heightfield(self): + """Sphere dropped from 0.5m above flat heightfield must rest at z ≈ SPHERE_RADIUS.""" + drop_height = SPHERE_RADIUS + 0.5 + builder = _build_sphere_on_heightfield(sphere_z=drop_height) + + q_i = _step_with_newton_cd(builder, self.default_device, num_steps=500, dt=0.005) + + # Sphere COM should be near SPHERE_RADIUS (resting on z=0 surface) + sphere_z = float(q_i[0, 2]) + expected_z = SPHERE_RADIUS # 0.25 + + # Tight tolerance: must be within 5cm of expected rest height + self.assertAlmostEqual( + sphere_z, + expected_z, + delta=0.05, + msg=f"Sphere should rest at z≈{expected_z}, got z={sphere_z:.4f}", + ) + + def test_02_sphere_falls_onto_mesh_box(self): + """Sphere dropped from 0.5m above mesh box must rest at z ≈ BOX_HALF + SPHERE_RADIUS.""" + drop_height = BOX_HALF + SPHERE_RADIUS + 0.5 + builder = _build_sphere_on_mesh_box(sphere_z=drop_height) + + q_i = _step_with_newton_cd(builder, self.default_device, num_steps=500, dt=0.005) + + sphere_z = float(q_i[0, 2]) + expected_z = BOX_HALF + SPHERE_RADIUS # 0.75 + + self.assertAlmostEqual( + sphere_z, + expected_z, + delta=0.05, + msg=f"Sphere should rest at z≈{expected_z}, got z={sphere_z:.4f}", + ) + + def test_03_sphere_does_not_fall_through_heightfield(self): + """Sphere placed at contact boundary must not fall below the surface after stepping.""" + builder = _build_sphere_on_heightfield(sphere_z=SPHERE_RADIUS) + + q_i = _step_with_newton_cd(builder, self.default_device, num_steps=200, dt=0.005) + + sphere_z = float(q_i[0, 2]) + # With gravity pulling down, if contacts aren't working the sphere goes negative. + # Allow a small margin for numerical settling but it must stay above the surface. + self.assertGreater( + sphere_z, + SPHERE_RADIUS - 0.02, + f"Sphere fell through heightfield: z={sphere_z:.4f}, min allowed={SPHERE_RADIUS - 0.02}", + ) + + +if __name__ == "__main__": + unittest.main() diff --git a/newton/_src/solvers/kamino/tests/test_geometry_unified.py b/newton/_src/solvers/kamino/tests/test_geometry_unified.py index 2d4fb56db0..e04ab1dcc2 100644 --- a/newton/_src/solvers/kamino/tests/test_geometry_unified.py +++ b/newton/_src/solvers/kamino/tests/test_geometry_unified.py @@ -629,7 +629,7 @@ def _make_two_sphere_builder(self, group_a=1, collides_a=1, group_b=1, collides_ def test_00_nxn_sphere_on_plane_generates_contacts(self): """Sphere resting on a plane via NXN broadphase must produce contacts. - Validates that shape_collision_radius is populated correctly for + Validates that collision_radius is populated correctly for infinite planes (which need a large bounding-sphere radius for AABB-based broadphase modes to detect them). """ diff --git a/newton/_src/solvers/mujoco/kernels.py b/newton/_src/solvers/mujoco/kernels.py index 375923f859..98af3a8188 100644 --- a/newton/_src/solvers/mujoco/kernels.py +++ b/newton/_src/solvers/mujoco/kernels.py @@ -27,9 +27,15 @@ def _import_contact_force_fn(): # Constants MJ_MINVAL = 2.220446049250313e-16 +MJ_MINMU = 1e-5 # Utility functions +@wp.func +def safe_div(x: float, y: float) -> float: + return x / wp.where(y != 0.0, y, MJ_MINVAL) + + @wp.func def orthogonals(a: wp.vec3): y = wp.vec3(0.0, 1.0, 0.0) @@ -122,7 +128,7 @@ def contact_params( geoms: wp.vec2i, worldid: int, ): - # See function contact_params in mujoco_warp, file collision_primitive.py + # See function contact_params in mujoco_warp, file collision_core.py g1 = geoms[0] g2 = geoms[1] @@ -130,32 +136,39 @@ def contact_params( p1 = geom_priority[g1] p2 = geom_priority[g2] - solmix1 = geom_solmix[worldid, g1] - solmix2 = geom_solmix[worldid, g2] - - mix = solmix1 / (solmix1 + solmix2) - mix = wp.where((solmix1 < MJ_MINVAL) and (solmix2 < MJ_MINVAL), 0.5, mix) - mix = wp.where((solmix1 < MJ_MINVAL) and (solmix2 >= MJ_MINVAL), 0.0, mix) - mix = wp.where((solmix1 >= MJ_MINVAL) and (solmix2 < MJ_MINVAL), 1.0, mix) - mix = wp.where(p1 == p2, mix, wp.where(p1 > p2, 1.0, 0.0)) - - # Sum margins for consistency with thickness summing - margin = geom_margin[worldid, g1] + geom_margin[worldid, g2] - gap = geom_gap[worldid, g1] + geom_gap[worldid, g2] - condim1 = geom_condim[g1] condim2 = geom_condim[g2] - condim = wp.where(p1 == p2, wp.max(condim1, condim2), wp.where(p1 > p2, condim1, condim2)) - max_geom_friction = wp.max(geom_friction[worldid, g1], geom_friction[worldid, g2]) + if p1 > p2: + mix = 1.0 + condim = condim1 + resolved_friction = geom_friction[worldid, g1] + elif p2 > p1: + mix = 0.0 + condim = condim2 + resolved_friction = geom_friction[worldid, g2] + else: + solmix1 = geom_solmix[worldid, g1] + solmix2 = geom_solmix[worldid, g2] + mix = safe_div(solmix1, solmix1 + solmix2) + mix = wp.where((solmix1 < MJ_MINVAL) and (solmix2 < MJ_MINVAL), 0.5, mix) + mix = wp.where((solmix1 < MJ_MINVAL) and (solmix2 >= MJ_MINVAL), 0.0, mix) + mix = wp.where((solmix1 >= MJ_MINVAL) and (solmix2 < MJ_MINVAL), 1.0, mix) + condim = wp.max(condim1, condim2) + resolved_friction = wp.max(geom_friction[worldid, g1], geom_friction[worldid, g2]) + friction = vec5( - max_geom_friction[0], - max_geom_friction[0], - max_geom_friction[1], - max_geom_friction[2], - max_geom_friction[2], + wp.max(MJ_MINMU, resolved_friction[0]), + wp.max(MJ_MINMU, resolved_friction[0]), + wp.max(MJ_MINMU, resolved_friction[1]), + wp.max(MJ_MINMU, resolved_friction[2]), + wp.max(MJ_MINMU, resolved_friction[2]), ) + # Sum margins for consistency with thickness summing + margin = geom_margin[worldid, g1] + geom_margin[worldid, g2] + gap = geom_gap[worldid, g1] + geom_gap[worldid, g2] + if geom_solref[worldid, g1].x > 0.0 and geom_solref[worldid, g2].x > 0.0: solref = mix * geom_solref[worldid, g1] + (1.0 - mix) * geom_solref[worldid, g2] else: @@ -252,179 +265,240 @@ def convert_newton_contacts_to_mjwarp_kernel( # Values to clear - see _zero_collision_arrays kernel from mujoco_warp nworld_in: int, ncollision_out: wp.array[int], + # Fast-path generation tracking + contact_generation: wp.array[wp.int32], + last_contact_generation: wp.array[wp.int32], + tid_to_cid: wp.array[wp.int32], + last_nacon_count: wp.array[wp.int32], ): - # See kernel solve_body_contact_positions for reference # nacon_out must be zeroed before this kernel is launched so that # wp.atomic_add below produces the correct compacted count. + # + # When the contact set hasn't changed since the last full pass + # (contact_generation == last_contact_generation), the kernel takes a + # fast path that only recomputes the body-q-dependent fields (dist, pos) + # and resets efc_address. All other MJWarp contact fields (frame, + # friction, solref, solimp, condim, geom, worldid, includemargin) are + # still valid from the previous full pass. tid = wp.tid() count = rigid_contact_count[0] - if tid == 0: + gen = contact_generation[0] + last_gen = last_contact_generation[0] + needs_full = gen != last_gen + + if needs_full: + # ── FULL PATH ──────────────────────────────────────────────────── + # Runs on the first substep after collision detection. Identical to + # the original kernel plus recording the tid→cid mapping. + + if tid == 0: + if count > naconmax: + wp.printf( + "Number of Newton contacts (%d) exceeded MJWarp limit (%d). Increase nconmax.\n", + count, + naconmax, + ) + ncollision_out[0] = 0 + if count > naconmax: - wp.printf( - "Number of Newton contacts (%d) exceeded MJWarp limit (%d). Increase nconmax.\n", - count, - naconmax, - ) - ncollision_out[0] = 0 + count = naconmax - if count > naconmax: - count = naconmax + if tid >= count: + tid_to_cid[tid] = -1 + return - if tid >= count: - return + shape_a = rigid_contact_shape0[tid] + shape_b = rigid_contact_shape1[tid] - shape_a = rigid_contact_shape0[tid] - shape_b = rigid_contact_shape1[tid] + if shape_a < 0 or shape_b < 0: + tid_to_cid[tid] = -1 + return - # Skip invalid contacts - both shapes must be specified - if shape_a < 0 or shape_b < 0: - return + geom_a = newton_shape_to_mjc_geom[shape_a] + geom_b = newton_shape_to_mjc_geom[shape_b] - # --- Filter contacts that would produce degenerate efc_D values ---------- - # A body is "immovable" from the MuJoCo solver's perspective when it - # contributes zero (or near-zero) invweight. Three cases: - # - # 1. Static shapes (body < 0) — no MuJoCo body at all. - # 2. Kinematic bodies (BodyFlags.KINEMATIC) — Newton sets armature=1e10 - # on their DOFs, giving near-zero invweight even though MuJoCo still - # sees DOFs (body_weldid != 0). - # 3. Fixed-root bodies welded to the world body (body_weldid == 0) — - # MuJoCo merges them into weld group 0, giving zero invweight. - # - # Each body is classified independently; a contact is skipped when both - # sides are immovable. + body_a = shape_body[shape_a] + body_b = shape_body[shape_b] - geom_a = newton_shape_to_mjc_geom[shape_a] - geom_b = newton_shape_to_mjc_geom[shape_b] + mj_body_a = geom_bodyid[geom_a] + mj_body_b = geom_bodyid[geom_b] - body_a = shape_body[shape_a] - body_b = shape_body[shape_b] + # A body is "immovable" in three cases: + # 1. body < 0 → static shape (no body) + # 2. BodyFlags.KINEMATIC → kinematic body (e.g. armature=1e10) + # 3. body_weldid == 0 → fixed root body (worldbody) + # Pairs where both sides are immovable produce degenerate efc_D values + # in MuJoCo's solver, so we skip them. + a_immovable = body_a < 0 or (body_flags[body_a] & BodyFlags.KINEMATIC) != 0 or body_weldid[mj_body_a] == 0 + b_immovable = body_b < 0 or (body_flags[body_b] & BodyFlags.KINEMATIC) != 0 or body_weldid[mj_body_b] == 0 - mj_body_a = geom_bodyid[geom_a] - mj_body_b = geom_bodyid[geom_b] + if a_immovable and b_immovable: + tid_to_cid[tid] = -1 + return - a_immovable = body_a < 0 or (body_flags[body_a] & BodyFlags.KINEMATIC) != 0 or body_weldid[mj_body_a] == 0 - b_immovable = body_b < 0 or (body_flags[body_b] & BodyFlags.KINEMATIC) != 0 or body_weldid[mj_body_b] == 0 + X_wb_a = wp.transform_identity() + X_wb_b = wp.transform_identity() + if body_a >= 0: + X_wb_a = body_q[body_a] + if body_b >= 0: + X_wb_b = body_q[body_b] + + bx_a = wp.transform_point(X_wb_a, rigid_contact_point0[tid]) + bx_b = wp.transform_point(X_wb_b, rigid_contact_point1[tid]) + + # rigid_contact_margin0/1 = radius_eff + shape_margin per shape. + # Subtract shape_margin so dist is the surface-to-surface distance; + # shape_margin is handled by geom_margin (MuJoCo's includemargin). + radius_eff = (rigid_contact_margin0[tid] - shape_margin[shape_a]) + ( + rigid_contact_margin1[tid] - shape_margin[shape_b] + ) - if a_immovable and b_immovable: - return + n = rigid_contact_normal[tid] + dist = wp.dot(n, bx_b - bx_a) - radius_eff + pos = 0.5 * (bx_a + bx_b) + + frame = make_frame(n) + + geoms = wp.vec2i(geom_a, geom_b) + + worldid = body_a // bodies_per_world + if body_a < 0: + worldid = body_b // bodies_per_world + + margin, gap, condim, friction, solref, solreffriction, solimp = contact_params( + geom_condim, + geom_priority, + geom_solmix, + geom_solref, + geom_solimp, + geom_friction, + geom_margin, + geom_gap, + geoms, + worldid, + ) - X_wb_a = wp.transform_identity() - X_wb_b = wp.transform_identity() - if body_a >= 0: - X_wb_a = body_q[body_a] + # Convert Newton per-contact stiffness/damping to MuJoCo solref + # (timeconst, dampratio). solimp is set to approximate a linear + # force-displacement relationship at rest, compensating for impedance + # scaling. See https://mujoco.readthedocs.io/en/latest/modeling.html#solver-parameters + if rigid_contact_stiffness: + contact_ke = rigid_contact_stiffness[tid] + if contact_ke > 0.0: + imp = solimp[1] + solimp = vec5(imp, imp, 0.001, 1.0, 0.5) + contact_ke = contact_ke * (1.0 - imp) + kd = rigid_contact_damping[tid] + if kd > 0.0: + timeconst = 2.0 / kd + dampratio = wp.sqrt(1.0 / (timeconst * timeconst * contact_ke)) + else: + timeconst = wp.sqrt(1.0 / contact_ke) + dampratio = 1.0 + solref = wp.vec2(timeconst, dampratio) + + friction_scale = rigid_contact_friction[tid] + if friction_scale > 0.0: + friction = vec5( + friction[0] * friction_scale, + friction[1] * friction_scale, + friction[2], + friction[3], + friction[4], + ) + + cid = wp.atomic_add(nacon_out, 0, 1) + if cid >= naconmax: + tid_to_cid[tid] = -1 + return - if body_b >= 0: - X_wb_b = body_q[body_b] + tid_to_cid[tid] = cid + + write_contact( + dist_in=dist, + pos_in=pos, + frame_in=frame, + margin_in=margin, + gap_in=gap, + condim_in=condim, + friction_in=friction, + solref_in=solref, + solreffriction_in=solreffriction, + solimp_in=solimp, + geoms_in=geoms, + worldid_in=worldid, + contact_id_in=cid, + contact_dist_out=contact_dist_out, + contact_pos_out=contact_pos_out, + contact_frame_out=contact_frame_out, + contact_includemargin_out=contact_includemargin_out, + contact_friction_out=contact_friction_out, + contact_solref_out=contact_solref_out, + contact_solreffriction_out=contact_solreffriction_out, + contact_solimp_out=contact_solimp_out, + contact_dim_out=contact_dim_out, + contact_geom_out=contact_geom_out, + contact_efc_address_out=contact_efc_address_out, + contact_worldid_out=contact_worldid_out, + ) + else: + # ── FAST PATH ──────────────────────────────────────────────────── + # Subsequent substeps with the same contact set. Only dist, pos, + # and efc_address need updating; all other MJWarp fields are still + # valid from the full pass. + # + # NOTE: rigid_contact_normal is computed once by the narrow phase + # and is invariant across substeps. The fast path is only correct + # when collide() has not been called since the last full pass. - bx_a = wp.transform_point(X_wb_a, rigid_contact_point0[tid]) - bx_b = wp.transform_point(X_wb_b, rigid_contact_point1[tid]) + if tid == 0: + ncollision_out[0] = 0 + # Restore the compacted contact count from the full pass + nacon_out[0] = last_nacon_count[0] - # rigid_contact_margin0/1 = radius_eff + shape_margin per shape. - # Subtract only radius_eff so dist is the surface-to-surface distance. - # shape_margin is handled by geom_margin (MuJoCo's includemargin threshold). - radius_eff = (rigid_contact_margin0[tid] - shape_margin[shape_a]) + ( - rigid_contact_margin1[tid] - shape_margin[shape_b] - ) + cid = tid_to_cid[tid] + if cid < 0: + return - n = rigid_contact_normal[tid] - dist = wp.dot(n, bx_b - bx_a) - radius_eff - - # Contact position: use midpoint between contact points (as in XPBD kernel) - pos = 0.5 * (bx_a + bx_b) - - # Build contact frame - frame = make_frame(n) - - geoms = wp.vec2i(geom_a, geom_b) - - # Compute world ID from body indices (more reliable than shape mapping for static shapes) - # Static shapes like ground planes share the same Newton shape index across all worlds, - # so the inverse shape mapping may have the wrong world ID for them. - # Using body indices: body_index = world * bodies_per_world + body_in_world - worldid = body_a // bodies_per_world - if body_a < 0: - worldid = body_b // bodies_per_world - - margin, gap, condim, friction, solref, solreffriction, solimp = contact_params( - geom_condim, - geom_priority, - geom_solmix, - geom_solref, - geom_solimp, - geom_friction, - geom_margin, - geom_gap, - geoms, - worldid, - ) + shape_a = rigid_contact_shape0[tid] + shape_b = rigid_contact_shape1[tid] + body_a = shape_body[shape_a] + body_b = shape_body[shape_b] - if rigid_contact_stiffness: - # Use per-contact stiffness/damping parameters - contact_ke = rigid_contact_stiffness[tid] - if contact_ke > 0.0: - # set solimp to approximate linear force-to-displacement relationship at rest - # see https://mujoco.readthedocs.io/en/latest/modeling.html#solver-parameters - imp = solimp[1] - solimp = vec5(imp, imp, 0.001, 1.0, 0.5) - contact_ke = contact_ke * (1.0 - imp) # compensate for impedance scaling - kd = rigid_contact_damping[tid] - # convert from stiffness/damping to MuJoCo's solref timeconst and dampratio - if kd > 0.0: - timeconst = 2.0 / kd - dampratio = wp.sqrt(1.0 / (timeconst * timeconst * contact_ke)) - else: - # if no damping was set, use default damping ratio - timeconst = wp.sqrt(1.0 / contact_ke) - dampratio = 1.0 - - solref = wp.vec2(timeconst, dampratio) - - friction_scale = rigid_contact_friction[tid] - if friction_scale > 0.0: - friction = vec5( - friction[0] * friction_scale, - friction[1] * friction_scale, - friction[2], - friction[3], - friction[4], - ) + X_wb_a = wp.transform_identity() + X_wb_b = wp.transform_identity() + if body_a >= 0: + X_wb_a = body_q[body_a] + if body_b >= 0: + X_wb_b = body_q[body_b] - # Atomically claim a compacted output slot (contacts may be filtered above) - cid = wp.atomic_add(nacon_out, 0, 1) - if cid >= naconmax: - return + bx_a = wp.transform_point(X_wb_a, rigid_contact_point0[tid]) + bx_b = wp.transform_point(X_wb_b, rigid_contact_point1[tid]) - write_contact( - dist_in=dist, - pos_in=pos, - frame_in=frame, - margin_in=margin, - gap_in=gap, - condim_in=condim, - friction_in=friction, - solref_in=solref, - solreffriction_in=solreffriction, - solimp_in=solimp, - geoms_in=geoms, - worldid_in=worldid, - contact_id_in=cid, - contact_dist_out=contact_dist_out, - contact_pos_out=contact_pos_out, - contact_frame_out=contact_frame_out, - contact_includemargin_out=contact_includemargin_out, - contact_friction_out=contact_friction_out, - contact_solref_out=contact_solref_out, - contact_solreffriction_out=contact_solreffriction_out, - contact_solimp_out=contact_solimp_out, - contact_dim_out=contact_dim_out, - contact_geom_out=contact_geom_out, - contact_efc_address_out=contact_efc_address_out, - contact_worldid_out=contact_worldid_out, - ) + radius_eff = (rigid_contact_margin0[tid] - shape_margin[shape_a]) + ( + rigid_contact_margin1[tid] - shape_margin[shape_b] + ) + + n = rigid_contact_normal[tid] + contact_dist_out[cid] = wp.dot(n, bx_b - bx_a) - radius_eff + contact_pos_out[cid] = 0.5 * (bx_a + bx_b) + + for i in range(contact_efc_address_out.shape[1]): + contact_efc_address_out[cid, i] = -1 + + +@wp.kernel(enable_backward=False) +def _snapshot_nacon_count( + nacon: wp.array[wp.int32], + last_nacon_count: wp.array[wp.int32], + contact_generation: wp.array[wp.int32], + last_contact_generation: wp.array[wp.int32], +): + last_nacon_count[0] = nacon[0] + last_contact_generation[0] = contact_generation[0] @wp.kernel diff --git a/newton/_src/solvers/mujoco/solver_mujoco.py b/newton/_src/solvers/mujoco/solver_mujoco.py index eb5d92804c..fc5e11d6ae 100644 --- a/newton/_src/solvers/mujoco/solver_mujoco.py +++ b/newton/_src/solvers/mujoco/solver_mujoco.py @@ -25,6 +25,7 @@ ModelBuilder, State, ) +from ...sim.contacts import GENERATION_SENTINEL as _GENERATION_SENTINEL from ...sim.graph_coloring import color_graph, plot_graph from ...utils import topological_sort from ...utils.benchmark import event_scope @@ -32,6 +33,7 @@ from ..flags import SolverNotifyFlags from ..solver import SolverBase from .kernels import ( + _snapshot_nacon_count, apply_mjc_body_f_kernel, apply_mjc_control_kernel, apply_mjc_free_joint_f_to_body_f_kernel, @@ -2777,6 +2779,7 @@ def __init__( wind: tuple | None = None, magnetic: tuple | None = None, use_mujoco_cpu: bool = False, + enable_multiccd: bool = False, disable_contacts: bool = False, update_data_interval: int = 1, save_to_mjcf: str | None = None, @@ -2815,6 +2818,7 @@ def __init__( wind: Wind velocity vector (x, y, z) for lift and drag forces. If None, uses model custom attribute or MuJoCo's default (0, 0, 0). magnetic: Global magnetic flux vector (x, y, z). If None, uses model custom attribute or MuJoCo's default (0, -0.5, 0). use_mujoco_cpu: If True, use the MuJoCo-C CPU backend instead of `mujoco_warp`. + enable_multiccd: If True, enable multi-CCD contact generation (up to 4 contact points per geom pair instead of 1). Note: geom pairs where either geom has ``margin > 0`` always produce a single contact regardless of this flag. disable_contacts: If True, disable contact computation in MuJoCo. update_data_interval: Frequency (in simulation steps) at which to update the MuJoCo Data object from the Newton state. If 0, Data is never updated after initialization. save_to_mjcf: Optional path to save the generated MJCF model file. @@ -2913,15 +2917,28 @@ def __init__( self._viewer = None """Instance of the MuJoCo viewer for debugging.""" + enableflags = 0 + if enable_multiccd: + enableflags |= mujoco.mjtEnableBit.mjENBL_MULTICCD disableflags = 0 if disable_contacts: disableflags |= mujoco.mjtDisableBit.mjDSBL_CONTACT self.use_mujoco_cpu = use_mujoco_cpu if separate_worlds is None: separate_worlds = not use_mujoco_cpu and model.world_count > 1 + # Lazy-allocated buffers for the fast-path contact conversion optimisation. + # See _convert_contacts_to_mjwarp / convert_newton_contacts_to_mjwarp_kernel. + # Initialised before _convert_to_mjc because notify_model_changed (called + # during conversion) may call _invalidate_contact_fast_path. + self._contact_tid_to_cid: wp.array[wp.int32] | None = None + self._last_contact_generation: wp.array[wp.int32] | None = None + self._last_nacon_count: wp.array[wp.int32] | None = None + self._last_contacts_id: int | None = None + with wp.ScopedTimer("convert_model_to_mujoco", active=False): self._convert_to_mjc( model, + enableflags=enableflags, disableflags=disableflags, disable_contacts=disable_contacts, separate_worlds=separate_worlds, @@ -2999,19 +3016,51 @@ def _enable_rne_postconstraint(self, state_out: State): print("Setting model.sensor_rne_postconstraint True") m.sensor_rne_postconstraint = True + def _invalidate_contact_fast_path(self): + """Force the next contact conversion to take the full path. + + Called when cached MJWarp contact fields (friction, solref, solimp, + etc.) may be stale — e.g. after :meth:`notify_model_changed` updates + geom properties. + """ + if self._last_contact_generation is not None: + self._last_contact_generation.fill_(_GENERATION_SENTINEL) + self._last_nacon_count.zero_() + def _convert_contacts_to_mjwarp(self, model: Model, state_in: State, contacts: Contacts): # Ensure the inverse shape mapping exists (lazy creation) if self.newton_shape_to_mjc_geom is None: self._create_inverse_shape_mapping() - # Zero nacon before the kernel — the kernel uses atomic_add to count - # only the contacts that survive immovable-pair filtering. + # The kernel only produces valid output for tid < naconmax (the full + # path clamps count and rejects cid >= naconmax). Launching more + # threads than naconmax wastes GPU resources, so cap the grid size. + launch_dim = min(contacts.rigid_contact_max, self.mjw_data.naconmax) + + # Lazy-allocate fast-path buffers; reallocate if launch_dim grew + # (e.g. a different Contacts object with a larger rigid_contact_max). + # Also invalidate when the Contacts instance changes — a different + # object's contact_generation could coincidentally match our cached + # last_contact_generation while containing entirely different data. + contacts_id = id(contacts.contact_generation) + needs_realloc = self._contact_tid_to_cid is None or self._contact_tid_to_cid.shape[0] < launch_dim + contacts_changed = self._last_contacts_id != contacts_id + + if needs_realloc or contacts_changed: + if needs_realloc: + self._contact_tid_to_cid = wp.full(launch_dim, -1, dtype=wp.int32, device=model.device) + self._last_contact_generation = wp.full(1, _GENERATION_SENTINEL, dtype=wp.int32, device=model.device) + self._last_nacon_count = wp.zeros(1, dtype=wp.int32, device=model.device) + self._last_contacts_id = contacts_id + + # Zero nacon before the kernel — the full path uses atomic_add to count + # contacts; the fast path restores the count from last_nacon_count. self.mjw_data.nacon.zero_() bodies_per_world = self.model.body_count // self.model.world_count wp.launch( convert_newton_contacts_to_mjwarp_kernel, - dim=(contacts.rigid_contact_max,), + dim=(launch_dim,), inputs=[ state_in.body_q, model.shape_body, @@ -3059,6 +3108,30 @@ def _convert_contacts_to_mjwarp(self, model: Model, state_in: State, contacts: C # Data to clear self.mjw_data.nworld, self.mjw_data.ncollision, + # Fast-path generation tracking + contacts.contact_generation, + self._last_contact_generation, + self._contact_tid_to_cid, + self._last_nacon_count, + ], + device=model.device, + ) + + # Snapshot the final nacon count and generation so the fast path can + # restore them on subsequent substeps. Runs as a separate dim=1 + # kernel AFTER the main kernel completes so that: + # - nacon_out has its final value (from atomic_add on full path, or + # restored from last_nacon_count on fast path) + # - last_contact_generation is only updated after ALL threads in the + # main kernel have read it (avoids a cross-block race) + wp.launch( + _snapshot_nacon_count, + dim=1, + inputs=[ + self.mjw_data.nacon, + self._last_nacon_count, + contacts.contact_generation, + self._last_contact_generation, ], device=model.device, ) @@ -3077,6 +3150,7 @@ def notify_model_changed(self, flags: int) -> None: self._update_joint_properties() if flags & SolverNotifyFlags.BODY_PROPERTIES: self._update_body_properties() + self._invalidate_contact_fast_path() need_const_0 = True if flags & SolverNotifyFlags.JOINT_DOF_PROPERTIES: self._update_joint_dof_properties() @@ -3085,6 +3159,7 @@ def notify_model_changed(self, flags: int) -> None: if flags & SolverNotifyFlags.SHAPE_PROPERTIES: self._update_geom_properties() self._update_pair_properties() + self._invalidate_contact_fast_path() if flags & SolverNotifyFlags.MODEL_PROPERTIES: self._update_model_properties() if flags & SolverNotifyFlags.CONSTRAINT_PROPERTIES: @@ -3646,6 +3721,7 @@ def _convert_to_mjc( nconmax: int | None = None, solver: int | str | None = None, integrator: int | str | None = None, + enableflags: int = 0, disableflags: int = 0, disable_contacts: bool = False, impratio: float | None = None, @@ -3686,6 +3762,7 @@ def _convert_to_mjc( nconmax: Maximum number of contacts. solver: Constraint solver type ("cg" or "newton"). If None, uses model custom attribute or Newton's default ("newton"). integrator: Integration method ("euler", "rk4", "implicit", "implicitfast"). If None, uses model custom attribute or Newton's default ("implicitfast"). + enableflags: MuJoCo enable flags bitmask. disableflags: MuJoCo disable flags bitmask. disable_contacts: If True, disable contact computation. impratio: Impedance ratio for contacts. If None, uses model custom attribute or MuJoCo default (1.0). @@ -3857,6 +3934,7 @@ def resolve_vector_option(name: str, constructor_value): jacobian = mujoco.mjtJacobian.mjJAC_AUTO spec = mujoco.MjSpec() + spec.option.enableflags = enableflags spec.option.disableflags = disableflags spec.option.gravity = np.array([*model.gravity.numpy()[0]]) spec.option.solver = solver diff --git a/newton/_src/solvers/xpbd/kernels.py b/newton/_src/solvers/xpbd/kernels.py index adffb8d892..0f1ae3f482 100644 --- a/newton/_src/solvers/xpbd/kernels.py +++ b/newton/_src/solvers/xpbd/kernels.py @@ -2078,6 +2078,7 @@ def solve_body_contact_positions( # outputs deltas: wp.array[wp.spatial_vector], contact_inv_weight: wp.array[float], + contact_impulse: wp.array[wp.spatial_vector], ): tid = wp.tid() @@ -2285,6 +2286,104 @@ def solve_body_contact_positions( if body_b >= 0: wp.atomic_add(deltas, body_b, wp.spatial_vector(lin_delta_b, ang_delta_b)) + if contact_impulse: + wp.atomic_add(contact_impulse, tid, wp.spatial_vector(lin_delta_a, ang_delta_a)) + + +@wp.kernel +def accumulate_weighted_contact_impulse( + contact_count: wp.array[int], + contact_impulse_iter: wp.array[wp.spatial_vector], + contact_shape0: wp.array[int], + contact_shape1: wp.array[int], + shape_body: wp.array[int], + constraint_inv_weight: wp.array[float], + # output (accumulated across iterations) + contact_impulse: wp.array[wp.spatial_vector], +): + """Scale per-contact impulse from one iteration by 1/N and accumulate. + + ``constraint_inv_weight[body]`` holds the number of active contacts on + each body for the current iteration. ``apply_body_deltas`` divides the + positional correction by that count, so the raw impulse stored per contact + is N times too large relative to what was actually applied. + + When only one body is dynamic (the other is kinematic / ground), the + weight is simply ``1/N_dynamic``. When both bodies are dynamic the + solver applies ``1/N_a`` to body A and ``1/N_b`` to body B, so there is + no single exact scalar. We use the harmonic mean ``2/(N_a + N_b)`` which + is symmetric with respect to body ordering and reduces to ``1/N`` when + both counts are equal. + """ + tid = wp.tid() + count = contact_count[0] + if tid >= count: + return + + impulse = contact_impulse_iter[tid] + + weight = 1.0 + if constraint_inv_weight: + n_a = 0.0 + n_b = 0.0 + shape_a = contact_shape0[tid] + if shape_a >= 0: + body_a = shape_body[shape_a] + if body_a >= 0: + n_a = constraint_inv_weight[body_a] + shape_b = contact_shape1[tid] + if shape_b >= 0: + body_b = shape_body[shape_b] + if body_b >= 0: + n_b = constraint_inv_weight[body_b] + n_sum = n_a + n_b + if n_sum > 0.0: + if n_a == 0.0: + weight = 1.0 / n_b + elif n_b == 0.0: + weight = 1.0 / n_a + else: + weight = 2.0 / n_sum + + scaled = wp.spatial_vector( + wp.spatial_top(impulse) * weight, + wp.spatial_bottom(impulse) * weight, + ) + wp.atomic_add(contact_impulse, tid, scaled) + + +@wp.kernel +def convert_contact_impulse_to_force( + contact_count: wp.array[int], + contact_impulse: wp.array[wp.spatial_vector], + dt: float, + # output + contact_force: wp.array[wp.spatial_vector], +): + """Convert accumulated per-contact spatial impulse to ``contacts.force`` spatial vectors. + + The XPBD lambda convention used in this solver already absorbs one power + of ``dt`` (see ``compute_contact_constraint_delta``), so dividing the + accumulated impulse by the substep ``dt`` yields force [N] and torque [N·m]. + The linear component includes normal and friction forces; the angular + component includes torsional and rolling friction torques. + + The impulse is expected to already include the 1/N contact-weighting + correction (applied by ``accumulate_weighted_contact_impulse`` each + iteration). + """ + tid = wp.tid() + count = contact_count[0] + if tid >= count: + contact_force[tid] = wp.spatial_vector() + return + + inv_dt = 1.0 / dt + impulse = contact_impulse[tid] + f = wp.spatial_top(impulse) * inv_dt + tau = wp.spatial_bottom(impulse) * inv_dt + contact_force[tid] = wp.spatial_vector(f, tau) + @wp.kernel def update_body_velocities( diff --git a/newton/_src/solvers/xpbd/solver_xpbd.py b/newton/_src/solvers/xpbd/solver_xpbd.py index a921c1a25b..29121888a4 100644 --- a/newton/_src/solvers/xpbd/solver_xpbd.py +++ b/newton/_src/solvers/xpbd/solver_xpbd.py @@ -8,6 +8,7 @@ from ..flags import SolverNotifyFlags from ..solver import SolverBase from .kernels import ( + accumulate_weighted_contact_impulse, apply_body_delta_velocities, apply_body_deltas, apply_joint_forces, @@ -15,6 +16,7 @@ apply_particle_shape_restitution, apply_rigid_restitution, bending_constraint, + convert_contact_impulse_to_force, copy_kinematic_body_state_kernel, solve_body_contact_positions, solve_body_joints, @@ -37,6 +39,16 @@ class SolverXPBD(SolverBase): After constructing :class:`Model`, :class:`State`, and :class:`Control` (optional) objects, this time-integrator may be used to advance the simulation state forward in time. + Limitations: + **Momentum conservation** -- When ``rigid_contact_con_weighting`` is + enabled (the default), each body's positional correction is divided by + its number of active contacts. This improves convergence for stacking + scenarios but means the solver does not conserve momentum at contacts. + Reported per-contact forces (see :meth:`update_contacts`) are + approximate: for contacts between two dynamic bodies the force is + computed using the harmonic mean of the two bodies' contact counts, + which is symmetric but not exact. + Joint limitations: - Supported joint types: PRISMATIC, REVOLUTE, BALL, FIXED, FREE, DISTANCE, D6. CABLE joints are not supported. @@ -249,11 +261,20 @@ def step(self, state_in: State, state_out: State, control: Control, contacts: Co rigid_contact_inv_weight = None + contact_impulse = None + contact_impulse_iter = None + if contacts: if self.rigid_contact_con_weighting: rigid_contact_inv_weight = wp.zeros(model.body_count, dtype=float, device=model.device) rigid_contact_inv_weight_init = None + if contacts.force is not None: + contact_impulse = wp.zeros(contacts.rigid_contact_max, dtype=wp.spatial_vector, device=model.device) + contact_impulse_iter = wp.zeros( + contacts.rigid_contact_max, dtype=wp.spatial_vector, device=model.device + ) + if control is None: control = model.control(clone_variables=False) @@ -471,6 +492,9 @@ def step(self, state_in: State, state_out: State, control: Control, contacts: Co if self.rigid_contact_con_weighting: rigid_contact_inv_weight.zero_() + if contact_impulse_iter is not None: + contact_impulse_iter.zero_() + wp.launch( kernel=solve_body_contact_positions, dim=contacts.rigid_contact_max, @@ -501,10 +525,27 @@ def step(self, state_in: State, state_out: State, control: Control, contacts: Co outputs=[ body_deltas, rigid_contact_inv_weight, + contact_impulse_iter, ], device=model.device, ) + if contact_impulse_iter is not None: + wp.launch( + kernel=accumulate_weighted_contact_impulse, + dim=contacts.rigid_contact_max, + inputs=[ + contacts.rigid_contact_count, + contact_impulse_iter, + contacts.rigid_contact_shape0, + contacts.rigid_contact_shape1, + model.shape_body, + rigid_contact_inv_weight, + ], + outputs=[contact_impulse], + device=model.device, + ) + # if model.rigid_contact_count.numpy()[0] > 0: # print("rigid_contact_count:", model.rigid_contact_count.numpy().flatten()) # # print("rigid_active_contact_distance:", rigid_active_contact_distance.numpy().flatten()) @@ -567,6 +608,10 @@ def step(self, state_in: State, state_out: State, control: Control, contacts: Co body_q, body_qd = self._apply_body_deltas(model, state_in, state_out, body_deltas, dt) + self._contact_impulse = contact_impulse + self._contact_impulse_capacity = contacts.rigid_contact_max if contacts is not None else 0 + self._last_dt = dt + if model.particle_count: if particle_q.ptr != state_out.particle_q.ptr: state_out.particle_q.assign(particle_q) @@ -675,3 +720,60 @@ def step(self, state_in: State, state_out: State, control: Control, contacts: Co if model.body_count: self.copy_kinematic_body_state(model, state_in, state_out) + + @override + def update_contacts(self, contacts: Contacts, state: State | None = None) -> None: + """Populate ``contacts.force`` from XPBD contact impulses accumulated during the last :meth:`step`. + + Both force [N] and torque [N·m] components are written. The torque + includes torsional and rolling friction contributions that cannot be + reconstructed from the linear force alone. + + When ``rigid_contact_con_weighting`` is enabled, the raw per-contact + impulse is scaled to reflect the ``1/N`` correction that + ``apply_body_deltas`` applies. For contacts between a dynamic and a + kinematic body, ``N`` is the dynamic body's contact count. For + contacts between two dynamic bodies, the harmonic mean + ``2/(N_a + N_b)`` is used so that the reported force is symmetric with + respect to body ordering. This is an approximation -- the solver + applies ``1/N_a`` and ``1/N_b`` independently to each side, so no + single scalar can exactly represent both. + + Args: + contacts: :class:`Contacts` object whose :attr:`~Contacts.force` buffer will be written. + Must have been created with ``"force"`` in its requested attributes and must + match the :class:`Contacts` instance (same ``rigid_contact_max``) passed to + the preceding :meth:`step`. + state: Unused (accepted for API compatibility with :class:`SolverBase`). + + Raises: + ValueError: If ``contacts.force`` is ``None`` (not requested), if no step has been run yet, + or if the contacts capacity does not match the one used in the last :meth:`step`. + """ + if contacts.force is None: + raise ValueError( + "contacts.force is not allocated. Call model.request_contact_attributes('force') " + "before creating the Contacts object." + ) + if not hasattr(self, "_contact_impulse") or self._contact_impulse is None: + raise ValueError("No contact impulse data available. Call step() before update_contacts().") + if contacts.rigid_contact_max != self._contact_impulse_capacity: + raise ValueError( + f"Contacts capacity mismatch: update_contacts() received rigid_contact_max=" + f"{contacts.rigid_contact_max}, but step() used {self._contact_impulse_capacity}. " + f"Pass the same Contacts instance to both step() and update_contacts()." + ) + + contacts.force.zero_() + + wp.launch( + kernel=convert_contact_impulse_to_force, + dim=contacts.rigid_contact_max, + inputs=[ + contacts.rigid_contact_count, + self._contact_impulse, + self._last_dt, + ], + outputs=[contacts.force], + device=self.model.device, + ) diff --git a/newton/_src/utils/import_usd.py b/newton/_src/utils/import_usd.py index 2e0eae9355..3e9c47c242 100644 --- a/newton/_src/utils/import_usd.py +++ b/newton/_src/utils/import_usd.py @@ -4,6 +4,7 @@ from __future__ import annotations import collections +import copy import datetime import inspect import itertools @@ -18,6 +19,8 @@ if TYPE_CHECKING: from pxr import Usd + from ..geometry.types import TetMesh + UsdStage = Usd.Stage else: UsdStage = Any @@ -87,7 +90,7 @@ def parse_usd( force_position_velocity_actuation: bool = False, override_root_xform: bool = False, ) -> dict[str, Any]: - """Parses a Universal Scene Description (USD) stage containing UsdPhysics schema definitions for rigid-body articulations and adds the bodies, shapes and joints to the given ModelBuilder. + """Parses a Universal Scene Description (USD) stage and adds rigid bodies, soft bodies, shapes, and joints to the given ModelBuilder. The USD description has to be either a path (file name or URL), or an existing USD stage instance that implements the `Stage `_ interface. @@ -349,10 +352,14 @@ class PhysicsMaterial: path_shape_scale: dict[str, wp.vec3] = {} # mapping from prim path to joint index in ModelBuilder path_joint_map: dict[str, int] = {} + # DOF offset within a merged D6 joint for each original prim path (only populated for merged joints) + merged_dof_offset: dict[str, int] = {} # cache for resolved material properties (keyed by prim path) material_props_cache: dict[str, dict[str, Any]] = {} # cache for mesh data loaded from USD prims mesh_cache: dict[tuple[str, bool, bool], Mesh] = {} + # cache for TetMesh data loaded from USD prims + tetmesh_cache: dict[str, TetMesh] = {} physics_scene_prim = None physics_dt = None @@ -443,6 +450,18 @@ def _get_mesh_with_visual_material(prim: Usd.Prim, *, path_name: str) -> Mesh: mesh.metallic = material_props["metallic"] return mesh + def _get_tetmesh_cached(prim: Usd.Prim) -> TetMesh: + """Load and cache TetMesh data to avoid repeated USD extraction.""" + prim_path = str(prim.GetPath()) + if prim_path not in tetmesh_cache: + tetmesh_cache[prim_path] = usd.get_tetmesh(prim) + return tetmesh_cache[prim_path] + + def _is_uniform_scale(scale: wp.vec3) -> bool: + """Return whether a decomposed scale vector is effectively uniform.""" + scale_np = np.array(scale, dtype=np.float32) + return bool(np.allclose(scale_np, scale_np[0], rtol=1e-6, atol=1e-6)) + def _has_visual_material_properties(material_props: dict[str, Any]) -> bool: # Require PBR-like material cues to avoid promoting generic displayColor-only colliders. return any(material_props.get(key) is not None for key in ("texture", "roughness", "metallic")) @@ -629,7 +648,7 @@ def _load_visual_shapes_impl( cfg=visual_shape_cfg, label=path_name, ) - elif len(type_name) > 0 and type_name != "xform" and verbose: + elif len(type_name) > 0 and type_name not in {"xform", "tetmesh"} and verbose: print(f"Warning: Unsupported geometry type {type_name} at {path_name} while loading visual shapes.") if shape_id >= 0: @@ -1174,6 +1193,322 @@ def define_joint_targets(dof, joint_desc): return joint_index + def parse_merged_joints( + joint_paths: list[str], + incoming_xform: wp.transform | None = None, + ) -> int | None: + """Combine multiple single-DOF joints between the same two bodies into one D6 joint. + + This handles USD files where multi-DOF MuJoCo joints are represented as + separate PhysicsRevoluteJoint / PhysicsPrismaticJoint prims connecting the + same parent and child bodies. The individual joints are merged into a + single :func:`~newton.ModelBuilder.add_joint_d6` call, following the same + pattern used by the MJCF importer. + + Args: + joint_paths: Prim paths of the joints to merge (all must share the + same body pair). + incoming_xform: Optional world-space transform applied to the parent + frame of the first joint. + + Returns: + The builder joint index of the newly created D6 joint, or ``None`` if + all joints in the group are disabled. + """ + linear_axes: list[ModelBuilder.JointDofConfig] = [] + angular_axes: list[ModelBuilder.JointDofConfig] = [] + # Track prim paths and initial state separately for linear/angular DOFs + # because add_joint_d6 orders linear DOFs first, then angular + linear_prim_paths: list[str] = [] + angular_prim_paths: list[str] = [] + linear_initial_pos: list[float | None] = [] + linear_initial_vel: list[float | None] = [] + angular_initial_pos: list[float | None] = [] + angular_initial_vel: list[float | None] = [] + enabled_count = 0 + + # Find the first enabled joint to use as representative for transforms and metadata + first_desc = None + first_prim = None + for jp in joint_paths: + jd = joint_descriptions[jp] + if not jd.jointEnabled and only_load_enabled_joints: + continue + first_desc = jd + first_prim = stage.GetPrimAtPath(jd.primPath) + break + if first_desc is None: + return None # all joints disabled + + parent_id, child_id, parent_tf, child_tf = resolve_joint_parent_child( # pyright: ignore[reportAssignmentType] + first_desc, path_body_map, get_transforms=True + ) + if incoming_xform is not None: + parent_tf = incoming_xform * parent_tf + + # Warn if any sibling joint has a different anchor position. + # Different local rotations are expected (they encode different DOF axis directions) + # and are handled by remapping axes into the representative frame. + for jp in joint_paths: + jd = joint_descriptions[jp] + if jd is first_desc: + continue + _, _, other_parent_tf, other_child_tf = resolve_joint_parent_child( # pyright: ignore[reportAssignmentType] + jd, path_body_map, get_transforms=True + ) + parent_pos_match = np.allclose(parent_tf.p, other_parent_tf.p, atol=1e-6) + child_pos_match = np.allclose(child_tf.p, other_child_tf.p, atol=1e-6) + if not (parent_pos_match and child_pos_match): + warnings.warn( + f"Merged joint {jp} has different anchor positions than representative " + f"{first_desc.primPath}; using representative positions for the D6 joint.", + stacklevel=2, + ) + break + + # Split custom attributes into joint-level (one value per joint) and + # per-DOF (one value per DOF). Joint-level attrs come from the + # representative prim; per-DOF attrs are collected from each sibling. + joint_freq_attrs = [a for a in builder_custom_attr_joint if a.frequency == AttributeFrequency.JOINT] + dof_freq_attrs = [ + a + for a in builder_custom_attr_joint + if a.frequency in (AttributeFrequency.JOINT_DOF, AttributeFrequency.JOINT_COORD) + ] + joint_custom_attrs = usd.get_custom_attribute_values(first_prim, joint_freq_attrs, context={"builder": builder}) + # Per-DOF custom attributes accumulated separately for linear / angular + # so we can reorder to D6 DOF order (linear first, then angular). + linear_dof_custom: list[dict[str, Any]] = [] + angular_dof_custom: list[dict[str, Any]] = [] + + # Cache the representative parent-side rotation for axis remapping + rep_parent_rot = np.array(parent_tf.q, dtype=float) + + for jp in joint_paths: + jd = joint_descriptions[jp] + if not jd.jointEnabled and only_load_enabled_joints: + continue + jp_prim = stage.GetPrimAtPath(jd.primPath) + if collect_schema_attrs: + R.collect_prim_attrs(jp_prim) + + key = jd.type + if key not in (UsdPhysics.ObjectType.RevoluteJoint, UsdPhysics.ObjectType.PrismaticJoint): + raise ValueError( + f"Cannot merge joint {jp} of type {key} into a D6 joint. " + "Only RevoluteJoint and PrismaticJoint are supported for merging." + ) + + is_revolute = key == UsdPhysics.ObjectType.RevoluteJoint + if is_revolute: + limit_gains_scaling = DegreesToRadian + else: + limit_gains_scaling = 1.0 + + j_armature = R.get_value( + jp_prim, prim_type=PrimType.JOINT, key="armature", default=default_joint_armature, verbose=verbose + ) + j_friction = R.get_value( + jp_prim, prim_type=PrimType.JOINT, key="friction", default=default_joint_friction, verbose=verbose + ) + j_velocity_limit = R.get_value( + jp_prim, prim_type=PrimType.JOINT, key="velocity_limit", default=None, verbose=verbose + ) + + limit_ke = R.get_value( + jp_prim, + prim_type=PrimType.JOINT, + key="limit_angular_ke" if is_revolute else "limit_linear_ke", + default=default_joint_limit_ke * limit_gains_scaling, + verbose=verbose, + ) + limit_kd = R.get_value( + jp_prim, + prim_type=PrimType.JOINT, + key="limit_angular_kd" if is_revolute else "limit_linear_kd", + default=default_joint_limit_kd * limit_gains_scaling, + verbose=verbose, + ) + + limit_lower = jd.limit.lower + limit_upper = jd.limit.upper + + # Build drive params + target_pos = 0.0 + target_vel = 0.0 + target_ke = 0.0 + target_kd = 0.0 + effort_limit = np.inf + actuator_mode = JointTargetMode.NONE + if jd.drive.enabled: + target_vel = jd.drive.targetVelocity + target_pos = jd.drive.targetPosition + target_ke = jd.drive.stiffness + target_kd = jd.drive.damping + effort_limit = jd.drive.forceLimit + actuator_mode = JointTargetMode.from_gains( + target_ke, target_kd, force_position_velocity_actuation, has_drive=True + ) + + # Read initial joint state + initial_position = None + initial_velocity = None + if is_revolute: + initial_position = R.get_value( + jp_prim, PrimType.JOINT, "angular_position", default=None, verbose=verbose + ) + initial_velocity = R.get_value( + jp_prim, PrimType.JOINT, "angular_velocity", default=None, verbose=verbose + ) + else: + initial_position = R.get_value( + jp_prim, PrimType.JOINT, "linear_position", default=None, verbose=verbose + ) + initial_velocity = R.get_value( + jp_prim, PrimType.JOINT, "linear_velocity", default=None, verbose=verbose + ) + + # Unit conversion for revolute joints + if is_revolute: + limit_lower *= DegreesToRadian + limit_upper *= DegreesToRadian + limit_ke /= DegreesToRadian + limit_kd /= DegreesToRadian + if jd.drive.enabled: + target_pos *= DegreesToRadian + target_vel *= DegreesToRadian + target_kd /= DegreesToRadian / joint_drive_gains_scaling + target_ke /= DegreesToRadian / joint_drive_gains_scaling + if j_velocity_limit is not None: + j_velocity_limit *= DegreesToRadian + if initial_position is not None: + initial_position *= DegreesToRadian + + # Compute the DOF axis in the representative joint's frame. + # Each USD joint may have a different localRot that orients its fixed axis + # (X, Y, or Z) to the physical DOF direction. We remap into the rep frame. + _, _, jp_parent_tf, _ = resolve_joint_parent_child( # pyright: ignore[reportAssignmentType] + jd, path_body_map, get_transforms=True + ) + jp_parent_rot = np.array(jp_parent_tf.q, dtype=float) + # q and -q represent the same rotation + if abs(np.dot(rep_parent_rot, jp_parent_rot)) > 1.0 - 1e-6: + # Same rotation — use the original axis directly + dof_axis = usd_axis_to_axis[jd.axis] + else: + # Different rotation — transform axis into rep frame + rep_q_inv = wp.quat_inverse(wp.quat(*rep_parent_rot.tolist())) + jp_q = wp.quat(*jp_parent_rot.tolist()) + relative_q = wp.mul(rep_q_inv, jp_q) + # Axis enum value: 0=X, 1=Y, 2=Z → unit vector + axis_idx = int(usd_axis_to_axis[jd.axis]) + axis_unit = [0.0, 0.0, 0.0] + axis_unit[axis_idx] = 1.0 + rotated = wp.quat_rotate(relative_q, wp.vec3(axis_unit[0], axis_unit[1], axis_unit[2])) + dof_axis = (float(rotated[0]), float(rotated[1]), float(rotated[2])) + + ax = ModelBuilder.JointDofConfig( + axis=dof_axis, + limit_lower=limit_lower, + limit_upper=limit_upper, + limit_ke=limit_ke, + limit_kd=limit_kd, + target_pos=target_pos, + target_vel=target_vel, + target_ke=target_ke, + target_kd=target_kd, + armature=j_armature, + friction=j_friction, + effort_limit=effort_limit, + velocity_limit=j_velocity_limit if j_velocity_limit is not None else default_joint_velocity_limit, + actuator_mode=actuator_mode, + ) + + # Collect per-DOF custom attributes from this sibling prim + sibling_dof_attrs = usd.get_custom_attribute_values(jp_prim, dof_freq_attrs, context={"builder": builder}) + + if is_revolute: + angular_axes.append(ax) + angular_prim_paths.append(jp) + angular_initial_pos.append(initial_position) + angular_initial_vel.append(initial_velocity) + angular_dof_custom.append(sibling_dof_attrs) + else: + linear_axes.append(ax) + linear_prim_paths.append(jp) + linear_initial_pos.append(initial_position) + linear_initial_vel.append(initial_velocity) + linear_dof_custom.append(sibling_dof_attrs) + + enabled_count += 1 + + if enabled_count == 0: + return None + + # D6 DOF order: linear first, then angular + dof_prim_paths = linear_prim_paths + angular_prim_paths + dof_initial_pos = linear_initial_pos + angular_initial_pos + dof_initial_vel = linear_initial_vel + angular_initial_vel + ordered_dof_custom = linear_dof_custom + angular_dof_custom + + # Merge per-DOF custom attributes into DOF-indexed dicts for add_joint_d6. + # Each entry in ordered_dof_custom is a dict of {attr_key: value} from one sibling prim. + # We assemble {attr_key: {dof_index: value}} so _process_joint_custom_attributes + # assigns each DOF its own value instead of broadcasting from the representative. + for dof_idx, dof_attrs in enumerate(ordered_dof_custom): + for attr_key, value in dof_attrs.items(): + if attr_key not in joint_custom_attrs: + joint_custom_attrs[attr_key] = {} + existing = joint_custom_attrs[attr_key] + if not isinstance(existing, dict): + # First per-DOF value for an attr that was already set as a scalar + # from the representative — convert to a dict to allow per-DOF override. + joint_custom_attrs[attr_key] = {dof_idx: value} + else: + existing[dof_idx] = value + + # Use the representative (first enabled) joint path as the D6 joint label + label = str(first_desc.primPath) + + # Register original prim paths as DOF labels so MjcActuator targets resolve correctly + if "mujoco:joint_dof_label" in builder.custom_attributes: + joint_custom_attrs["mujoco:joint_dof_label"] = dof_prim_paths + + joint_index = builder.add_joint_d6( + parent=parent_id, + child=child_id, + linear_axes=linear_axes if linear_axes else None, + angular_axes=angular_axes if angular_axes else None, + parent_xform=parent_tf, + child_xform=child_tf, + label=label, + enabled=first_desc.jointEnabled, + custom_attributes=joint_custom_attrs, + ) + + # Register all original joint prim paths in path_joint_map and track per-path DOF offsets + for jp in joint_paths: + path_joint_map[jp] = joint_index + for dof_idx, dof_path in enumerate(dof_prim_paths): + merged_dof_offset[dof_path] = dof_idx + + # Apply initial positions/velocities + q_start = builder.joint_q_start[joint_index] + qd_start = builder.joint_qd_start[joint_index] + for dof_idx, (pos, vel) in enumerate(zip(dof_initial_pos, dof_initial_vel, strict=True)): + if pos is not None: + builder.joint_q[q_start + dof_idx] = pos + if vel is not None: + builder.joint_qd[qd_start + dof_idx] = vel + + if verbose: + print( + f"Merged {len(joint_paths)} joints into D6 joint {joint_index}: " + f"{len(linear_axes)} linear + {len(angular_axes)} angular DOFs" + ) + + return joint_index + # Looking for and parsing the attributes on PhysicsScene prims scene_attributes = {} physics_scene_prim = None @@ -1518,6 +1853,11 @@ def warn_invalid_desc(path, descriptor) -> bool: joint_edges: list[tuple[int, int]] = [] # keys of joints that are excluded from the articulation (loop joints) joint_excluded: set[str] = set() + # Groups of joints that share the same body pair (multi-DOF joints from MuJoCo USD). + # Maps the representative joint path (first encountered) to all joint paths in the group. + merged_joint_groups: dict[str, list[str]] = {} + # Track which body pair maps to which representative joint path + body_pair_to_representative: dict[tuple[int, int], str] = {} for p in desc.articulatedJoints: joint_path = str(p) joint_desc = joint_descriptions[joint_path] @@ -1534,8 +1874,17 @@ def warn_invalid_desc(path, descriptor) -> bool: if joint_desc.excludeFromArticulation: joint_excluded.add(joint_path) else: - joint_edges.append((parent_id, child_id)) - joint_names.append(joint_path) + body_pair = (parent_id, child_id) + if body_pair in body_pair_to_representative: + # Another joint between the same bodies — merge into existing group + rep = body_pair_to_representative[body_pair] + merged_joint_groups[rep].append(joint_path) + else: + # First joint for this body pair + body_pair_to_representative[body_pair] = joint_path + merged_joint_groups[joint_path] = [joint_path] + joint_edges.append(body_pair) + joint_names.append(joint_path) articulation_joint_indices = [] @@ -1758,17 +2107,30 @@ def warn_invalid_desc(path, descriptor) -> bool: else wp.transform_identity() ) root_incoming_xform = incoming_world_xform * root_frame_xform * world_body_xform - joint = parse_joint( - joint_descriptions[joint_names[i]], - incoming_xform=root_incoming_xform, - ) + group = merged_joint_groups.get(joint_names[i]) + if group is not None and len(group) > 1: + joint = parse_merged_joints(group, incoming_xform=root_incoming_xform) + else: + joint = parse_joint( + joint_descriptions[joint_names[i]], + incoming_xform=root_incoming_xform, + ) else: - joint = parse_joint( - joint_descriptions[joint_names[i]], - ) + group = merged_joint_groups.get(joint_names[i]) + if group is not None and len(group) > 1: + joint = parse_merged_joints(group) + else: + joint = parse_joint( + joint_descriptions[joint_names[i]], + ) if joint is not None: articulation_joint_indices.append(joint) processed_joints.add(joint_names[i]) + # Mark all paths in the group as processed + group = merged_joint_groups.get(joint_names[i]) + if group is not None: + for gp in group: + processed_joints.add(gp) # insert loop joints for joint_path in joint_excluded: @@ -2368,6 +2730,57 @@ def _build_mass_info_from_shape_geometry( for shape2 in builder.body_shapes[body2]: builder.add_shape_collision_filter_pair(shape1, shape2) + root_prim = stage.GetPrimAtPath(root_path) + if root_prim and root_prim.IsValid(): + for prim in Usd.PrimRange(root_prim, Usd.TraverseInstanceProxies()): + if not prim.IsA(UsdGeom.TetMesh): + continue + + path = str(prim.GetPath()) + if path.startswith("/Prototypes/"): + continue + if any(re.match(pattern, path) for pattern in ignore_paths): + continue + + if collect_schema_attrs: + R.collect_prim_attrs(prim) + + tetmesh = _get_tetmesh_cached(prim) + tetmesh_for_builder = tetmesh + if tetmesh.custom_attributes: + filtered_custom_attributes = { + k: v for k, v in tetmesh.custom_attributes.items() if k in builder.custom_attributes + } + if len(filtered_custom_attributes) != len(tetmesh.custom_attributes): + # Preserve the cached TetMesh while keeping add_usd's + # current behavior of dropping unregistered import attrs. + tetmesh_for_builder = copy.copy(tetmesh) + tetmesh_for_builder.custom_attributes = filtered_custom_attributes + + soft_mesh_mat = _get_prim_world_mat(prim, None, incoming_world_xform) + soft_mesh_pos, soft_mesh_rot, soft_mesh_scale = wp.transform_decompose(soft_mesh_mat) + + add_soft_mesh_kwargs = { + "pos": soft_mesh_pos, + "rot": soft_mesh_rot, + "scale": 1.0, + "vel": wp.vec3(0.0, 0.0, 0.0), + "mesh": tetmesh_for_builder, + } + if _is_uniform_scale(soft_mesh_scale): + add_soft_mesh_kwargs["scale"] = float(np.array(soft_mesh_scale, dtype=np.float32)[0]) + else: + add_soft_mesh_kwargs["vertices"] = tetmesh_for_builder.vertices * np.array( + soft_mesh_scale, dtype=np.float32 + ) + + builder.add_soft_mesh(**add_soft_mesh_kwargs) + + if verbose: + print( + f"Added soft mesh {path} with {tetmesh.vertex_count} vertices and {tetmesh.tet_count} tetrahedra." + ) + # Load Gaussian splat prims that weren't already captured as children of rigid bodies. if load_visual_shapes: prims = iter(Usd.PrimRange(stage.GetPrimAtPath(root_path), Usd.TraverseInstanceProxies())) @@ -2609,6 +3022,7 @@ def _get_collision_mass_information(collider_prim: Usd.Prim): # collapsing fixed joints to reduce the number of simulated bodies connected by fixed joints. collapse_results = None path_body_relative_transform = {} + builder_joint_labels_before_collapse = list(builder.joint_label) if scene_attributes.get("newton:collapse_fixed_joints", collapse_fixed_joints): collapse_results = builder.collapse_fixed_joints() body_merged_parent = collapse_results["body_merged_parent"] @@ -2632,7 +3046,21 @@ def _get_collision_mass_information(collider_prim: Usd.Prim): path_body_map[path] = new_id # Joint indices may have shifted after collapsing fixed joints; refresh the joint path map accordingly. - path_joint_map = {label: idx for idx, label in enumerate(builder.joint_label)} + # First rebuild the canonical label→index map, then re-add merged joint aliases. + new_label_to_idx = {label: idx for idx, label in enumerate(builder.joint_label)} + old_path_joint_map = path_joint_map + path_joint_map = dict(new_label_to_idx) + for path, old_idx in old_path_joint_map.items(): + if path in path_joint_map: + continue # already mapped via joint_label + # Find the new index for this merged alias via the representative label + old_label = ( + builder_joint_labels_before_collapse[old_idx] + if old_idx < len(builder_joint_labels_before_collapse) + else None + ) + if old_label is not None and old_label in new_label_to_idx: + path_joint_map[path] = new_label_to_idx[old_label] # Mimic constraints from PhysxMimicJointAPI (run after collapse so joint indices are final). # PhysxMimicJointAPI is an instance-applied schema (e.g. PhysxMimicJointAPI:rotZ) @@ -2760,7 +3188,7 @@ def _get_collision_mass_information(collider_prim: Usd.Prim): actuator_count = 0 if parse_actuator_prim is not None: path_to_dof = { - path: builder.joint_qd_start[idx] + path: builder.joint_qd_start[idx] + merged_dof_offset.get(path, 0) for path, idx in path_joint_map.items() if idx < len(builder.joint_qd_start) } diff --git a/newton/_src/viewer/gl/newton_envmap.jpg b/newton/_src/viewer/gl/newton_envmap.jpg index 26493412f25b3dee6b1c4a7d68f4588d1d615632..d9dccf61397f101de1dfd2c14c785c0b2e7ee59f 100644 GIT binary patch literal 105653 zcmb5UbzD<_^gli(F-ACWAnisdF}l-jgmlM9=~RhF!2Ek&;j( z6-52c_viEY{QmyEHtxo~clVyxc|FhboO{msyY%-H0HUd;p#~r!ApxipUx2^w0m^`D zK;XYOagY+;pxkmgADH$ah86}j4iU#`sd;IMI(1CyeQouD5IslN4(C zDDD3Z5+HymBRK_#c$AqqkALI;4gvrqK;qHAD*)12r;4Tc+-n8G43 z5edXS03;JP2+iOdXi>;k-(g8n3Lzy^>97Q$A@KmDaRx@2&JMwE&u#7)uO9{HG=`~b za)Z=5rl@~MBlODy?y#u4Vm_jTm}a}+;QQE=P1aV9?X6e5ZduzF|lO%p-|$e=}>dM zcN_#q3MjWXw`yM2NO8E$7mrZ`+nT7Tt46^e__i-%CxhdvRtRV?45pr5)&K_p$k3`` zoT~942h*7Gh*K$ZCxe*GBt{d$PX{cDGlj#+00S!ZB*47` z-o!rNLHV{UE03|0qKOX5Q2I%G?cET$HBZL2C{Q=?rEcmrc7t~;X=Id=2!b%EfvV&{ zfy86%xkp@@trqPs*2DHkFQq&n#*`oxDi9D71qUJN;2<=8@jqR{G_;+Tvs_GlTymPf zXx>!D%d|lf07zJKAB>a_Xj%g{#r~Si_w6^irgEyQC~erbu`p<~`sneU2p3FxTsTM_ zlAgp0ufv=3Gc3Q+i53Aua4;xJ1qw`Xn^4+GZvfGABu<8QNjFB?&jP|p{@ou2!i85u zG66^kDGzBFB@hXLVW;Ha2uv+q9LR(02~uWFPXXhLyi@urRTlA zC^D{}9uA;~L=jaGRYjr-%^)Lz=)-~Z^l@l31c%bcsROBfg9^j#3!U;Rvx@k`=*U#T z3;KaKZ354+BNaW0RIKl{ylwl`*dHq1s*qdye(R8UPmbGL&De^^8@3-B|Gmcq+guy1C3a*&i{2ElP@rUwF-l6#Kc zza@{|O@?rT=BCt2M0z1`N)Uu-vhFG{lmQf6?j&Yv*yTpRGKw~hpQl(qrbC2PlNX_p z%OJS5G1!oyB4frhQ&O$1oQIyC2Te)@1#0ZX{gKYdw^3EndRs`0#(}iLHU7pCP9%xekike(qPR!(iG62Y`=HibS>m<;hDKeFDWl+U!6Jr=^GUz-&EH5hOHNRpJqe>MUPk$FR zTGNPe<-w^+oR#S)=Dt{{pi%F9V`U50&xp4Ktq6Vkpfx3Q%oYYgf_TfIz|8FLEkjn{ zSw{;S1}h!%roVX-=I)7`Y-eXus`JF7C0lwbZ#j{0*ORJ)Ntn1Pf%FjWcufExVi^-g z<7;?6bLga>OgdcWzYroX_YRR#*r5f|QRot#WovJkczyMr`b8~_CmeQ<`UY)#uxz4i zAJ$uF!8-r-4LQpQ2u?pL;x>;h%c$gIH$q=+icPCck98O>S~E;l9}EH~a3&n<=KpFt zzuI>bmKREtGCxoh-;!Biqc^0qpTARR-d9o`?ii00AwjBWauF8|hz3OV8KR;X`ydvO zir=C19xf1^Zeb%~g_R4B&y9|@mMpwG3piW#e1vf}+pD=jD>Ky#*dQDiW`7txz`A&|Sm;(gUTI$7m(#v)J2lr!4T<84 z;?{64h69S?7*wOQ<+ctsTJq0M$M(xJHKT!m1-CC96EO1*!fwhXlEK3A903)+&za%H3@`{0vPk^buc}x&w%t>_RiTq)NVwr~% zk9HQYT`4BIy@8`LR$o94g_fOW!i~ot9^2>fA4)zK8+dWUD7*bc5G`u^88f24pz#s= zvEt}sh0ofd)Qfj>iwm!fXvb)@?GW~j8{D03>Q%Ky*IBz7A4jyb+i@skH;i~q$$-TO zLu4Ab4GkbhEXw|qPwGCOeU&}6T9K3yHp|O7{l33-P(GB!kYJG{`m%;5*9eMAYT~qv zrL;E8?pJ19Sd-T3OavGs`FlWdt`AOXcBW5i*F0RXGniAHn-0)t`$yq-h!gkGFCJhS!-ntvP|@kG{HJX-A6umY=B>XW3`X> zODna0n4L#-T>dMLj~rOy`jtW*#?1*PB&G=m_WiBI(8m;<0E7UfFdsd)PJKIrj@D8X zpW~%JYhqi{>PT+f((L6Tv+V|>Aw+j7aaPf2`bRDY z3yy+fRI5ci#$Tm;lsn`hMA8ak&%N=t?w#!72?_l*9Dd{5vo6V}JC*I%AbuX=*YB?{ zzQ6kIZy@n*b;?6l_I2CJw+AiaKVoKx=G&uIcE%C~2V=c1_RU89gGBYzO2)Yzo{NeO z^0;9bA$D0y&3;6zg8QK100198FR?l;?+b^Xp3%;M+31@tUFElIy_Ik!!+y7$j9MmC; z_2dZc1mIdUA7_7T{{FQyYux#A6}za49rK&?n`PA`k_;LWOUYt1@BWW)>=&wQcsls_ zlpah3=s1DX)Cn?9_A^@n!{fshqKIO9?v|0b+$1#Pg3^OVp$zM@36kttWra;MJ#X{8>#b!I5LylFY!j(qZ0&;u@)0q6S+3e<>L0~JkWu9x}gJp zwN0kB%LzzoO`P^KTX#amKy-ze!;;MTDXk?-tWnv(>wW3p?X8tJ^5&QE`v1xLnaeQf z;XiT&V9$3SHH#^P9Exstj6f5_8r*m&LMJO7ebc|4v5avU+TA22qu)RAa+=LQuc+Nw zsAwPd6`kCdIS-;pou9q<z9f5qU2@dx zXHq770uaj5+9x|Txr0sFO@-~3H{_2(ce2qUpDvV57_uyU?A9R0G_`Md3|=d+~KqiV|e(Rt^ujK}j0Y<4~Lq+tMX zpNI~7Hd)1l^&CN2%Y~V6yfVzxcKMcF+-U2e3osiFC+DP#pyKDRC$0ZdetCEDJ>-XO z&iI-gNI8Cd@4@(gLV>)!>lFVd=#>3!4gA7I(97NqDcNo*hwXcP-{UzS^IhFXVBoHi zQ3UUMuxK@stZIgAO7~9#h_=Ef%YPpIaXUOZ`OyBY^zB3w)hOeTJ!xk+CyQ7j34=a> zKp2#iEYTKMt*&e+9(YN$u{Y)kt(eR^%M#Zf_MwUplrVKzu4^)L;xwnCeJQ=iq3BoH za@I=>+Pp5_=;WM%YzIif9GLowT-QAwlD;<$bsj*a%g~V5DRf@>CtX$F$y|yCG0t)d znsa1M*11(bbBHoL21Kj&Bp3sP+QoUw`gQpyRy-I9(<9dQHHRT3bE@5&&AvVPf7g^%Vw)6r6D+xJVG{LW$prLgnO;+&tN9K=kr z5+yU&<#(c;9+RZJlHRAamNeP79M2>!GOf^~k_Egp(>u}qkOw8BQqFX}Ihp(0_^g-v zN!0GId1o~e8|S|6>%5$-yUV_RmtSKmiw{L1_GxtY;v?4C@Esuf9UlV1%_o3>eijNk z_*M@o>Wj0F?gVtK2s5coGTb z*NXD5sbBxrQyAaU(_8b$Eb!!<5frk-1(tLkOFrwY5Ynw6EPmge^6P(}KhRPn!5l<3 zIpP!O6sM0Knjn3Plzf#)&SwckfvL#g1{f7S8_L3OZki*S8{pbx9_Q_dl1RBh$<@na zEBWw++2Y;N+QXd$LsS(K0E{yw0VgDzm+8i1sS@31dfT7fZa3TzkY+Xf+-v#}yr`RJ zj_sFyaU^&$hslz7qYxT6S%EuMbV-)TUUX@H)yUzWS71}X^31<|E1-k_OiS83xx&0k zA=hf|oWF0UMyg^>Y+pC`uCz_*^rSpCW1(5JBvrX-i|@IBD!~gs(CwiVll!5+q=p0v z^Z-S(tZ2H==$v^UnNhK{5r+p?^>ApTda)X2_j^WB5<^mJtg=Cy@gKT zeU4rRxedG7yzG!mpQ}(RhnuW_@-P3aGK1e0gUFx;n*9(0O50~WQHx5g_E?)`y4Eft z-6~N$+R`qJZd9A>MA2p9n{V#K4(r~=u9fF=`J|m^;|;YP65!m%cNk`->|8U_i)bRMdrnSCOk0c4uEhNKSp8#}>`Jkt-`N1(ee z_T#G^EiK=i90YrLcfwrx~XgK5c6a=J|9AoRrY zxr}7cD7)iZ%*k$Pa_1o3#J2RCWKWG*??v{H(#}5$m6iy;7lC))X74^XoZFL>yuGx+ zHGw7coeRpQD2f{S5e|MxE-j{Br6|zsoGrdT+__v!6b#8tk^R2vkbdS~HoDzA{q;Sx zZYurEAfwjSc|p+GT%*r^rPaK>DJOGmWU;#hd(q08DB@HWNn_EaSl?NgpFQW+I!;bo z@%oiQd81(M>$lJSXA9!inYaL&7y^nEf@H{c^T`e1nk|fEnVYp3kh?Fm5LU|2qxGmr z1y4UIJ$IZaI@4Q|dwE#cOw~3J@W>zDIkp-)zTheSp4oiy{ua@;E4F4Qe*baVRlF1M zRUjW<@(f=mF!A--(tgs$q7goHFU{@S0KX`%=Od zD`nuvyCu(sOJQ@SA9<_hN4au za{fnEHF7Hsc(s{^^1c`|%|#07hn*j>(KZe)c=Hs@W4d!%=@PL984hdCCEIV0e0uir z<7-~KB~3-+@Akvn8+KE5)&dFpE~6EtbxL&ZsVZBulj6ROL4#Ia_l2`egI>L?Jsf{) z`0J0J)Ij@H!#KX+u3L^X;C~uhMB;YW62Ffj#eq0xkye z-~DY0^L{%-t zGtbK;oZHk1eGK_#2}xCfLC_^7=_QRtK#>Q2_A}Gz!o|Z09{f!f=0X$2k<9bGcl3P{ z7uEc-8MYY%qqD2s&(nz0Exqw<0$b_f#9-czw_KEVKK=6~zr4W4Z}?Kya#8VYvdG<4 zc3*t*WA3Te7$v|>yKhO>NuVR4+PST zyBPKCJ(M-75GUGD##HX=_E}*2<-|#?ba4Nj=L<>~-yBQ9t@#>GT_d0xvpB3^Fct~%>k+XO@VO%OVx+Z^DFVA~6bF0({!kI0GsWxGN zGF3|FpIXd|)-(xPHP`c1j-BlXLTB>?Ot21e8Jh%$I5{Ij|FrfR?`@5(j?Aqzy!%_L zmQu@$Nzs9Z+-1DlzT8gm$y@1?lhf^%!dHbC!e*>Nlg909YA^9xGN$8Jr3qIcce;K|4+@PNOzs4v8H79erIC4ZK)d>(C^HJV!Ex3J;pbC@Pn9be^4jUV zrSoaV8hv&%-#>TzINrHG@_D@~3RKCQGi`}EpL58~*bNQFtdYZHWI7d{ zyj_xcTW%w}ZGo-2I&tUJZ2PokoP0gUVtj{XHTQ|NSg_Am`HK$P&RRhxNl@5U;}}a_ zYbkW9l6_JsdN!zP#-U;{o%>kjHmKQdsi+Ov+lCe1) z55=1{x+=$|Ick1Ow&p*!51+phCwvpFeOWN?lKIHjw*|Y9w!MCFdB(K9uXK3tWl-SN%dQZzYYzvz zV&CS@k4X9aDtpb;**3jRd_3)NfzCLD=y4oQR;Zm+onA<1E;w(r;0ck}3tNLSGu32k zC7&7LRdy3Pe^274ldGd1PFd}D@Dhd;e&j8(r2C4$<;f;uiL6+R1XyqFbft-@#EE1D4X%~gFhnt{dJi%O*@O8DyU zU*GJH)?O;HE3{vo>{!W{x4j;Gsg;(uWqs5--oO5`iEw&fPsyV-IQ3S@!M+jUp!7O6 z{>-~pPy6`C#v{M#HSe`2E(~2t*!Os{FEJg@g)46iFU~8a3Y+XsZdz|dE%@l9$k`tj zR*T~w1y}g(x#jbr459)LK3-4W!tQl;BuXh>{g&1>V`^WJ@;$e7Zkk+E%W{9NS7`p& zf8yeoQiaXE$&ajTT;s{<=qfo`v)eLJB9|j_&T=eEMZ0xj=E`5Hx;!P}(E;==X)S&|&n12iSqNc}J1$ z*I&T(%A%dFJ9UbyZ9)0>nkLfL0)tO}4T=Yzh6G*S;^;hY^R_O$d3YjNxV~|E^5$6b zxpC8uRtlH-h#Z#{b~pR=vk$l5Xric07_wi!bFsln;wLM5<(tP3d%X$n+MNSi?>P%6 zB~F6s{qknTE2KLH?_rai&Bu>BpEJi}@o!D#;d_O$Yz(HHu1MDDL)QF51DEUX^A)cT?k;$+y|S^s?e}(|{lmt+ znEazC-06PgE&k?^qwW01Z<+0Vc|qqTI3u7ij(r6Vt@-wRv&8y)3@@3%D}HbQbW#u zUcF?OIQ}?Wz`SsX*L=})RxE^fC~)yQbvw(-xs`>|I%tE_ia`2WO?(L z+B0X3`prk7cKR2}Z0|>oXPjLEIy;s`3nX7OX}MSyIGFGJZkzoWtLaoxVSP)fV=YvC z`<1w*wM)x_RL6u4R(2tgJ(%WX7x6A@L#rV0qf!p@qQh)KV;Lbc_iSe)cA$Ntv(-!{ zXMv-sU^Z)~QgO$|@})phuuSerFha57zN$_}EsEM9D$9IDvk$fntwFO5HAc5#`YW}P zja#%vPIfECr#1regMN_*`rg+Y^?gmnQZ%6NP>AQSvdzpz9GWDrd(xb|`SD}J<<+ox zyb!Hq>qkZOdC;U{Z)=vEwF_?Neg4kOa_wl{ttV%J3W=*>d&;w)teoz2HGV>8W}5PQOYTTn1haMJF_(XW49ciy zuGC^SvU0_Rp!U7if-xGAraS|+7F(O*HENRMLjE+DNt39l_0)+9aq+Go3=gJ*mJ+af8clNWHV^<2g><$i2vQrk9JUjE99 zi@;=;@^SMTB2^&;ny`|wP7R|T^3jXS!}~1B8%>8h?{8vyx#+`GL}=XN^Hk>P=UT#e zwH|pA62%Udn1|d|N+Fz?ne%)J#2Gxc2s-V0b2ACu7#SH|yNrD?r22HgofL`{}Ierz3h z6w+a8X?^=*>Vb6rv&C`S?X|n&c%|@yY#)bZ}YJTXC3J<)RR=9e4neQ@csT;7|)5)Nxcrt_d7Vev=+BMn-Ggba#) z#@5^PtQI&@e#o^(n6NA!nPmU=}|U6lAl9V{nqh#43&-KpMse`Y+v~ zZ@<9Q%FD%lDlRf42rc`x!SecSg30G}b~Hm!0fQxxg3K(KnNWgXLK=JQ1^p#;oN}Zr z6keD{gxv!bv1CVq;td!03{WxlYJ3T=IC`-UJL`n<{{lEV_WG5pgxs6%rF0Mu&9N)k z{bzy|Y8UIiJ9}?reJ#f0>m&x1+^LPA%cdwh+itdaAS4V%tbIfD0mK40lu*=Lh2ib* zy<_Xb?6fYrF+u&}tC@^lqLH~^1^tF9Lu&+|fq}6J5<^VC@?b>xRRCddipofpD40P^ zF`(Lwm#>M@>Y6#YE7kek8_DIliC3(n<|qw=7dx}pp6jIA+>;+$6K_d;XIoL#YbEne zgxbp_<0v;vAexPfl$(-~nh#-)sBCfCVP z(@3|nk~y7faTFVh1YjcOGC;5hK(wEJv=awcIgc9e zlzY8qFOFL^li)?PaU4tt!7rlCMd=L(vXG0kaL#=G6bb9Ni0)hk{JMsM0b<{NFh;K008>)R9JX~ zg@x69vkH`-H8CORwLvQjH{~`WC4nOn>A=lV5hUQOW^_G3zs8XiY!`=2qKl!)Qs!fG z4Dw4CK>|m-V-ZX|MU)_9uQ3~($&r7kBva6}Tp+L33tgGI_+hztTwJs=ThZm2Zg%b#7?J++gzpOsUVX7y6owEIkQ;!v7(fZcVNm=HaK>UJih_wN z1sPUvmzEhP(hb^*WaKiU76Doii{#-<^<30)4Do<^dlKM6LQ6uN1Ji&kN^{DA*cg-u zFhHWz>Eh@HUs52nD44us*!=2!(?{9W$*BRTQWPD=9?VMt2!oLdBt%(^^g;C@+{Eie zMJ7SHF;U*Tqs8+Fb`c_Ik&P63BYMzA3N)dcCMqm~gaHD20XMKPH8nOhZO#P4aLoV` z4LeFsgqkT@q?fqvNn-7QqvERa2O>c;gpn7mnh;Y z6~N52NW^4w5pc#C+*KN?=_I^J00~+@Okay1jG%%VxFd-jIRG*Uy#* z44DMz2J{igOo%>MJ%bFQuOCgq8x2zfRu+y1z5|4*BY9Qy&Fs;*FfybHv4JEFSu)f*%(xT=t}4L+*=l8gxvQtG@VVNgy$7(l&&N!>#eLJ9~g3UZ9%>*iU5E|K6Uk%b9=`MltqXB(YDqMUpTXRNkG7Tppk(b~|qYd;i zS|AV-5(XgSd{;!K4yGqMt*Bx!7{?2QA<=>hD0LA|q8fPt^cMEq7)ZYzOOhrr2taf3 zg3v1Al%N-4VtoP-GFxTxp87abE+!R5>(?39nk8=Yd@qTBd3SlfI}G=VVokOTw>zf5=aUjNtBeb z{%tg|H4#KSm4pnqonn__m%PV1CtZcDVr#}7lE?YyU3-(we#FM{NaXNK>D$k#5LFI% zl7cc*K!V5-)b2A=Z=XSITH4e@M1yyK30`C#E!Dpt@KDv8P``CX${a20HkC^X(>EC|RFGfd$p}hLVHvM3zRC1~9RyOax zKEk+^eHy_&(~w_v~Q~x(tSLp0WUE*Y9)d>+S0S%;PCvvajDn zL}VMHGcr=#(Oy4yDg8D2%{8ZvlPcY)-vf;`k^~~r>MB4^VSjVtXuyQ=vvy8O0S&CpS%JFgJ5%pDsKRS=yV0j_dnLWd_$Svx`&aF{`*Vx}3PtFQ8-alL9== zw=JA)y%2DAQ$8GrVcMjkf--XQ0S5-iQd5v6V#v}~SzflX6brS!N)$sT^NrRUD+}4c_i1a{_$Wq1<;p)qE)h4bD-0Ufw>}RT`azWqT;RE{Ct&Vc!iCe#4_L{& zn+In9J2w)=drD* zb{0x5#a-i#5g*ALi`Rk%%*S7s+%y!NISk~>^qtSMvX`D*JBsRrK-;BJM55A0SYx4SSbrNwI_p^eD)TF1I_g?5jVTwG&v%ru*M|*{}{@}WeC7j2* z0nGPb*Ln?-R3hfM&6<>5m!uM)yeuk7#(_ZRLht%A7KY8)c4d8>O}hLalSD?ue^_S} zURh<%J;gd0X}jK=uc^8bkYANq7S-t(hrA4|OHL&30J~%xES)*tHzILXt3$3RXB2C~ zSs^D^T24xuf=_t&qO}A{TrrOHUMz-3*jy zuBqcbAO3NGX=r=I8hupXE-1y28HWq}qQX%18FHlH{W&H!L0`c*?Q>bgykNvUUAMby z43&P5NYWfnlwQ&&E}p;#kNyc^i&wstmqwz0Y#{!?xp{9rI?!_%_FHzCEe_5v!T->a z>)l}fBC`{MD;j)^X<*nAIo^k-22|U)LwO$(mD2pb8&xpFAyK^I?16KW?*n(2ciNsB zeQ2;-MMRC^nQ56Rl53iE6coHjWXrb z>{lf##6P*}NB7(U6wyX%C9_vy_E+Eh{0-i;uPcMJzN*rRPO0$Hll0G4$TL0{NwT5r zm#q{Xpev2ve5pDPdn25Vd`w!^tF@JlWq!8&J{rs}gK4nSEruP_;pEroXn#e>AA=C9 zkj^nV&pXf_$L4y?h7i|>tg68`H$_5jxe34Gmn-R_Dtfr)E6ka%WyjBRlWHS`x;ueZ z<~`-JYOZE(cV^w#TizQCR}ltf8{1ohbZ45{YR@_Bs92*D86n%Vv+Z5q)k=H)J+=|| zGdq2&!Ox1Y=9Gd@HIDhY{@_I!AkB~YS>)@0>AZ5j;VQFb@=E#Z_Wj8N%-N?{7kx)2 z=@xP{O3po0bqXU%cVjvG0Y!_kW2~P?1=}3flx<|xOK^t`XUFv<%9`(+rF34vqA*jGo7y0#=pgW?)%Cv8O zI+iVX`<^ay^`_ZV=X#U(NEAD7WB>>7te--hHkl%fB*kkf?pyAiyIvJgpd96B^IZ)t zQitxLZwG1H-H_(E&&nuG&drDC9C9(TcN(<1*TZU*m{=hu79o*n5c?M(Ps70<&tND? z*vc69&(3N$Z+~VI^U&}xme6@Npf%pOnykm1#$`C_tH`%ZJ}3Q=<`WM>x?+gy z8UvhZsEX1F^v|*W^RG0`Rs5uW(VspeWGhxgwhKbxs}Hi2J!N`I_sqvY9qpNM%jCBi zemPsQqXfb3`Ms{4g^mush4Ol8N8GN-!;{(>!3U6;ttM8%jlf^)Z5T(YsNEeIBC;NZzLAF(y$Vi1v(u5N2oNBwoBst%ZUxK zsVkM~M2EmN^(K$Kxc&iY;SC>cq?)q9U4+DF`b}2doVf4i33q>+75*3W5Zz0cCY09< z484`K8Z|syQ>7VpB_5vlES2ftD)5TBbGk%caKH;!U*mXY9M2^*{T4isb$@TNO0O7o zSJowv#dZv{Dh*^#I&=n`*VtIE@{ak!9jX(=St$_Wbc=HfIm2C4_qGtt#wVbuW951&olN}=Iwb2A-ZU10%v%nq@{>OsG3+m40*qvC$& zOvs9bwGL2N61S?X$Wt0SDq4==j!>_KvJ0@vKmz-k&2@A^i#$tmAyOk2I$pxBlfnPv zIwM_I{;k)W7v$+;d0}ox{H#;>q&ZI&y7Cs$1}kqS>BhuoS@BWM+ISwhqLRk+MV{Xh zFNVn~y?IROet3}iz%i>d$Rua1RoWBFbt~R6dLXmm1bNEHB;;**ZI#NOe0ztuOYBVu zUF-B+?ic7E%-v$4in`lgTV!#B&Aj4K(XlRy9D38v{R%Zdz2alaPSiXw0E z(N>#-Y^JmGlrK%fWUF|P3Wd75I+!u^F%ZFMf9Kz1IrpukBGl{PZ5d>aTrdtBX4H{YNFNYHJb#(O%wV9XUU*sV52^1TS^IH>Y2Z=+2lK-Q%$L z49AH+cfsEU2KyBC7LZD{AN#$m@Iieaa|&j8G#O5{ZbeDbYW%rjWk{0 zxa%WUuEZsZGXTSbFAKby(x@Ev#L`ht9&TgcYOJ)-PPbFO~%<{G!{s{S_?vT$_-m7{!G6Z^=}#Ktqq zF)N!zM14(UuaqN!^V*W6Wj3Ckfn(-palFR8#!^37)?_ll`WAyR&E_ZTRGHc#8TpOF9e+%x*U@$pNxsm z+0_{zVX}yC-fW~$GGo03Jh*4)!`Abq<}-D`cZ)mfZ0WSav?FI~DOXd;O3tj^B4J6v zG-=$=cINLsD!jXRp_9QY%rP2%z{v>jJFvHxiWzCs@aff!=o0=@np zh1Jq1wCxu4#oE{1s+#)ZWEsCOb1b$b9>;qx`@l)SP|Lejw6W1%iCi2-U0!mczd}?N zkrQmNd))T+T^#Q^rb~tIa(Ig$m8GWHXwuf}mhz<7D2|bPwlXky8>Xk>(pVeuqq1?% z!%oH7h$N?L87qTBV#U=yiXrie70&JoO1V!tMVG$(92mZ2C-gWm$1nvUJ!q9hL8a;g z(xZ`I-Jd7l4c$6GbhT=IySKD6%utGH8J(*QaF`sgS zCIusk)~K~+h!_=$U6Kc@eviy}42YMlt}-*g_dI}7759w1ru1q=Oz{5;{2xL=-CZjr znGTNadV&mx_stl!dlol((~rN>NZ zd~&XYvJMMmKKT?oy zN0h~`D$Iz z6d=13h}_A?2y;9Cpb{!i2G4gi?Xi5wg>_^%XR;zx=*6K6%YpKdFe6|DF;i)^yi~*x0Vo#U&)BU{6$j*R@oWlfJb)*u3{!>!RmX zm&+OCr717(En;poI>`G^)fdsJ$pACMdZ#lY9Gk;S_k23Oia3VQaC?3w$CX963DDP% zDRJ9=O!5*-d}y{P5GR2cVkXTjlxM5FhB>#Sd=w6&SDQx0{ckMtkd>qrwInFV{;s~^ z!z^dSh;9f^eQC8gR%a9i zBzxEPh!bRC{ABBzy5Y5-=QiN}TDjMkR;r_;>RC#vU?_+nm1+ZdYa}eTsiRZ%-E~sM zQiy(*@{H7;hj51k(c`;W%E6MZAjx?p$s6EoPUg1kMiH5fJC{?oqHe>@hGHF;audkr zI@>2#-~E2hFp(0r?JnT>MrHVBJjve8y0@FOe*rkL9BD^5{jbh|D#q$2PkkO#XAhJv z-3cYmtgkuKxSsy2@Jfq`o-_8hy8QeInBrYHGH!Uq*3RZRrJS49M{0>jO_e3BNrklhqQ~i)j&ET@FS9)D?K-q=VO4i@ zUyWtP__dseB8 z-7OJQ_0oLByreV#eGRvcM=%XLvPEU2r9UudvUFn+cC+Hy>YLvh zZ*8pzm(%<)bW-D%sklgPprLLVHK0AV&DESLMsdbW^VAHF^jK-!z8;~LOKjy(5rfzD z_t@BQLx<;Gxukv47p3IW?ho{Ron`LscU6gHky3G4RO{m{B-GcoEScyH|aC}~| zYmar_7oxKSO9C(Qoudb@6lvBK{xp|G2<@)bZgY;&HQlRX?2#SyM9TV01v33a@SAnfM0txX1VO2U1-Q!LD>*s{TRm z&bMJs0vmS37N|@paj0cq;hbNy% zWhaj~(Rr6A4gDw)=a+Q+&W@!isE}R5xUhZ5PAQHz9TN@VPHds>xCm&!>-Goz6aOl$ z0GqWc&eNJ+oMA$3@#8M58$tJXUlX~gd()rNzkpHv_o5JpDLoV(8ZVTGn$ieGmaZU& z;1bk)j_GSwppl=v>|LmP%7IjS4v5TZQG-@4oTa$emq%SRAwcF^D>9%v-~IwHp5xm@ z6Ywf>o?Tjkx3kFkplJB96oHddZc7{Q_-AJ ztHqP1G`m1HMSkb*iqHGa(l)M2)Dj}dzTk-2{>RevovUWMVN~B`9TCkrYo;+P+JvsXCL77*- z$Wb8r8XR?(4fM4BDbw9anZJPc;`@~!JLR6CR0ZxkztXsk{J@<qSMYl&i@4jW>#|v=-C#fYqBaMMs9h$>V8+N zWY?J#u<6*lvzH#K-P0oMmFytdnN^HkS8d}7M&wM}G>|S@5=imqb-~0TnqT_keN62U7Mjy3o7&xbnyTO7ytY@R;92 z#prOz|7wHyaSfJI27>$r*iKelKN%PPrjw~=_Tfn!-%9B%5*_#>X1e5J-5TLDc9nR3 zJAsaQG6VZ^f%GjNHx~b^57gm?HrXS-y*|`q87D85Ro?4Dbv+(^qra=5{O9{f^_6jn zC#NQNPx{j}uB+V_3QP}G*Gf&wW+RD8nEQWpeRWt{!4fZRad&ruySqEZwRmxN_u_8B z-QC?wp|}*6;9A@%4t=5b-uM1`-?uqAIoUHiyJvT1GV_~Ff_Y+6g0+<7oB==N6+bl1 zC~#7{T%K}yDoH7=m{Club2%fzhbd-HQVe*||E3M-F8i*dB*8q}w89$2F82|wIhJBp zvEmkZ-?*D4etu`}GpJZy(vHR}>nyP`Mc9a(el}JLNQzRQ-CRZG|7^}%6H-Ct#Lam0 zSv8lkI$Tf!{cXo1pEFZx4)!pv=&gbKuH-}v9X*;cmMmdYxlWM%jZK|WPAc5Kd)%$fI+G8O8^E=Pdy6vviV7wPBs6m(*ERjo5pw#V_{cDI9y<{N)&Mn zXuf3Wja3hj73qi0ILQ@`DfG`iVWh+}m-9LcUoFai)*(pE*t7cW0)2o0$VlQEb~c*Q zHigBA=9Ew=w%QwujXHlMDE#TT@5}@6Tjpt53B#1Yr!K39ZmoO#Wu`Pu}5Ep0a3+#i(NLX!PFCgNsqb z);c6<*A9Yc#LA7+hmjj16|QF=)+o8j8)}mM zQzFFtSM)LL$K}%GIdv0Tky?8vs^Gylifx7(;9&-@2AvqSe^Oh!bGluc zve8tm#=|@!z)H3I5wUJ3i?Ew6;&4rYBjtR}j^6dB?P%K_Mgw;8Z+BpkxQ1zQs~rs1 z>kwb((eI8-jgq8@u$lWLId+3;g`-iJqs#-^5*f9E;;g3Y-{yPmy(`*rxeLsGA>x~py6B}7h5hE&0eHXAA`&t6_?!Rkmz9(I5 zDU_fHTqj*fug|=F!*I>bPkK8df$4e|^Iro1joj3fNKH`wX_z-5p8Hv`^dXO9>ljo% z@Tv;PV|&|?^BZL6?gBr1@yjl&xj>!8t(N#IR5=pjv=3#>_DP?kIJ5T3(0eQ50Uc!e z=q<#*HC`7S+9R$Ow0W5?;&v`*iS%7fg91K<2jrjwQo0gj?gewK&0{b_y`9Y_BcnH# z)!jVasx2(VvrkRG@Gs|H(Biu5<)jXC$fVv$_Wa@_PM%ZrC{`&p!x#pG6Zei)62x=V zizq8Lvj3Fh40xz3b^Esp0oDgZZ;WXv;XlU7hhwK^iienxcG;=)@QbG=S6K5pwA(Q* z(6$zJwrO)#haEuQ!_YXxI)^h?v=S>&1s#%zw)a&XB|I_(Y0s-7fz#as?v0-Y$RWkL zD<2Y??Bs!wInQaLlKtA#p~qvmV+6sNFKIclmkmbNw-vuce)v67`*+Z!#5h0J-U=9Q zvD8I2s;ZKWG7jvJ7*M;eSsU|!wnqnc<@v8Fl@2rT2RN>?_p%zBLvu@&hSVFfHusuL?_ravZl~l2t798tVg=S9h*Ok7*s(O4%eS}hXx~7?FQ|i zMH*L=km)`q#>f0t^pYO1ocNIm6Sg}eEE>4eDrM9p_VK~gJBAKyG(@@r!@6W~*BA`p zY;*{J_<=mv^JPT`26~RU{hc=3*pH7RfHz$wM!0Gh9YJzbgK??&ibB6N&|~=gI7MH{ zy{urZMPXI;aOWILiZsz~$NdSzU-VK${YzZzJeQr(cteCvI5wa;4w;O}xao+g&>IGM-yOIBh~#HPZkvGl0GW@w|olR`Hl13q10 z%q6yCQm`n`vn?-~w!{z18e0SFOK3mQ(qu+AC_(0P6d4Vdj7zD}w9ttY*Kh8va6u>i zf&NiQ+S}ZTSe#@|@R^fsXH=^0`_H115+4LF^`<8pq}RU?w|RU0Zr?-#aWHl{AzR%q zY#*4zM4q-(o=z|nXZvQkk+!lS>#b4p+qQ%(>{-chLOm+iEi8iyxiF1>mCzHW=|=_G zRnjX#;cADc%&F3?utcE(QwHqdsM`>WQYS7R*4tDytN|pJ;hARa6iN>MlKsy1cpC-^ z^QU?zF6;>_p-wPiy_UFGE6>Pu*--|y`~kL*GAsL-6@1;9g} zz!)c6StE`7wdCL!?#V-#TI-(o2;5lUjOTW`_#UyN+M`@nKPNXPg;9plS3z&Z#vaGD zbHm)OV7h551-xG2tR8lt(ld}ONp(0%cB$Z<{F^tBN2f1JYV{#R-;Cx7(?msUi zdU=LV$R0<=;4!JY!3mNl))e=}l^C~3xWo+=N9*W4SYeOi`bL{ZD&$8rkIUK+RAG7j zfvqYjnvWcoPjEQ5JUT3e6L(xg9NOBx9rx|@(@tt{b7M|b+#E60ijP^emk5!Xz)NbJ zqqG&aau&<9ET)N`F9F;^lMC(a?q0*W+wc-Lb|uCc8*xleH1CqGZRl2WxtBD`LC$36 ze6|abB_}GVQaNW?D(6O43(Q6=gY@I-$MGR<387g;6#Q_|sQoAxjiEGlu$x9!2%p_A zM%7wESlYIS&3Zv#ZY^8Gs;#3RWEWa|R{B_K4&;X}B)xJ7P7r+yZXcOXZHr8!p&X}_G!`+y3sQUXO=X)gWm7rm?w=_qv0a`Yn4Qax@1^C%*lTVG zN}qtW02&Pp*tLToYXEOvaw##uPFna|*>Mw0i_D=mD&G+~r?q4)qv3f=b0HVD>gWvL z;6@fj-{rmmFP`of6Kc2>2GcP7K5K~zuUxT-89Xa4xPD|w?oTyb3MGOvM=J3pm*1Iu z&5=WbOMxXB^(L7m0ui&TYFA~#aOqQ`^6O*HtexZI>Gc)y@J0xJ4i$erS9YB)-%SgxzE+aC_{jiT9zuFy`0GV1F2n{=?q zL_E%@_}Yj?$JV@~ZqkfRz=#P zl{;gE=&xfrb30yY4($rNRC02uL1(i*Y=}_^61*~GpgH~IgzraI+n^aj;4G3r3Hp>< z)~Kxu-j{vS{=yQGt6S^eU?neJ+%2FLRDWHR<@FNAvwdQUCOLlz2;ou08Oa8sfymuh zGgX*zh^F6iB8=V95b?xZ{p%;R z_yVSvDm)+xnIdVz7357HMx}shiKMPqA=`!9Sz=5ElbGvm6YQLQ$Wd`vl36pKq0INK zQ9q@>5Z3r*FFtVfjab(GO;1uffbt9q*9@{TvU+qeSb>B`w};Om_Cn?>;*hJAV>!do zxO*|t(r5^W*0O)Y$1G)H(65r>kKL=$qs#v%opPv4Q7wSP-q0!k=X~km{}~E7~kD!HHN- z!+H6LvYA#vmTP|H9%sY@1#Rm*R|R=AA*9qzQHm_J&aaO^U6NCJ{>y>te3&5tO&L~@ zMXg|yEV{SK4PQ*)sv@A4*L%9CX4lK$(w-(bo=DcujoCOT%ZlzSR4&1!`9kf>V|YLk2LM;B0|)V#pBPGZXxhUCO@`N!s6%HDSK%w|aF@n)& z+RzO;fch^)3F<<4BeF1b#uYV7jLX>{57f+<_+)>%9nlXL8F3iayfiC{l&XYYO=$W| z;DoK+FCfB#6i%T{`t)S90x5HpavcV8RRkK6)vHQxav^39OYLI~5Aq z&&J(2e@t%Xvr!%&=4Jglrk-t_nh~RDM&;0Kg=*#|7wDvB<(S>q@5oy^ixZswt=xHq zXrG)FyCB&J?@@x{_>tk`Qgj^=T0G$}TVl0Id(u>MeyrGve2a~Q+#)23Ms?qD1r_1E z8Ya;sU%@J}XdAk20gv`CNUJ86#g7=~t1_1D=`0Q90T%tVPsApf#pKaZLpE1OiuDw4 zbeJ?WJ!pR+NFZOj9x-efL$D3yzhB&qdjEx339D4W)RU5BE!+o?OO!i}Bt_CifQM4V z>_^b2Olhs3< zyEVg016G^5AVh3h&h0NsP~`4DgqUm(+aw>$=C@88vs7(5X(2 zcpiLil~G*8HS2&{KW8!B$rc~m$JDP1MexTrnzz_fs6WbJ+`rbqIy;l|bwu7M~ZzGl_T7l-7 zn4wIHPB7Nt?i`249lL`=>P}OBevT5~EFYtpRoQc2u2V_sSJ82r@>b55{tNNVNYtGD z;EBZ^76XkmQ&`jsn>`>}`t29@4invrtzS0U^~IiKb!%waoYHt)L7}G1gu6#Eq?EX+ zDGmOI7Gr|2xyVO{Ygg#zU{8WnqSP?4>#%}91_a>1#5-*2hb6dQ&5VWGf>FqQPULc< zUwZOa>y`DsBn(@U7%_?xnSJ$N%znCnEISc=L_8Io$u%mN?`r0Fym`|}Xc5nBJd2fj zi7TJQZd@LvEi{`W2l}jM*|(u9(M&%P%e@^*wu^tx+O6%wrFip7R|!oYukVoO#ak4^ z6?_L;B@T)?+3#gA+dOc>^K1UF84T95AEhEV<$(+w%6lcp! z&P4A(FrYk0+D?;pR z1uTlBnxu;?CX`@Vq}+07o$b64Q$H*-E5O4s)%m?<9Eg7z(t(^+r4J0gsezXBXl{q6 z%rrrziU`E%6#-ADuN=Xo#i0P&4>Cs!ZjKz`oh`*I4?|drHFDLx*C1uH_ zdUQg(9EDsBdZ&1X=fr;4jHzWzJ4zOkHB9YGR~;o?Q|;rTQ3eEwa7}Rep&OC5GgyEVseqzn?Jc92G$hMo zh>=psp^9;d8&>csv@?3(b>%O2t=0R_TcBJ}kN+W`Kx75pmgn1!CHrGm^6^J!Iii*_ z$cTnwXeR~eo$H8YWpy>y^}VlGku2v~;(>h1izQaLUAlAdGK~CqWGvfk@ba2sjeQf* zC&)Y{!OA*86O8(Pa)cq}cB&tQB;dr};fsdA|9}|%b;0ol75O03U5B z>r;bNO|dH~oOodpFw$(L)8`W!@uU{WC8Pj-fRRjoiJ8evlRu@r=*j#&a&UtjqAaT- zRI^;D!i?}>09vmz*zZ9f>zHpvAliyKt>=R*$x=F5l8AcDFc?kxIbVq(P{z@{OxniN zy)E3@mEas#t&}^VVcu=a$ePr&2)ZwwXKO~R-8b%+1UKI|RaNw^chnsi$Oy(a|M!g` zCN9- z=3B8{XPY9cRS+&E@XLuA%7tye12SX5C{P0MDV>@X3{8v+iSj;AewcDREdX7V^j`s= zfQutD<6j7f5xfAz?w0<4;{p#B3}ER$0)rd)Q-;T+G5vImDCg@g!!X$_VYsxpqdVuv z5O{bo6Ex&syq|#LsUoXjCK6i3K=8J-`F2q^w8ho#u5q$)y2W%NPdgjfmrpynge~b@ zw(gn}l+9(aPWdvB2{Mr1WFZq|Aw>dFnax9eGzR(}!GY*)fA9NuBo}Nbcr=1k-?77J zaoWhr`^YkTao_?z`LZl-`5s^aeSL2>3&E5&p)@EHdW35tGyuhNKlWP!9K?I!3L+B= z{CK^Ik9BI;pocQ@^)>2xDfQ)+E9&~sw!h9b8vM=l3KDr>D1g9SYDA561>ThQn;jGf zQsO9K;uvfFKR7a2uCO)_y^qE?!3R?3J`Ucm30&YQ2p0b2q43*c?Mqimp`UJW@^+V* zaLy9pvG$qG+m{kX@ErM|6YTzQ1vVok*g>&?X+qC{nUDMOue|r-{RG@E@G%yQd*ebX z44VThignUyZ3d?0Ah*jw6JvXj!8t4C47~Vsu zLw)uCg5b&p;$T2c6gWKZRj!rXolGD8`5KqSmqxjc(V4I13PhW}gsL+HODb;$teb}e8})Ydx*O0eS4g1^=RhJrnZfldV?fsV|k@#_U( z@Dm%%`_uu;;%3`-Q7j36_b!*g!QlST0OUZg^7jv3@v%NB1MSMS!iQQ2J9>y(@L0de z{QUCb!D|vs7i*{+ycXW?2CF47z6IQj50?h@mY#Tp(>E(-G%^?hgO4e@BBZ`SHFg*0I2Fs*bE!3;(WM z3;xbh3)oK5;y?JW!{B>%!6CnQ-tI2q1~SqV0nC3P0I&VRdtiC+y7JD;Ke}3}-7Q04 zWb-&!Nc?AU{zp{Az9Y5~w*A*1r(&NEUf%nFu&YO-%sQ_f1Xk2oL+|q})FXa7Li{(qkT?14x3oqZ=T;^-gx{C{2E2Gghy^>KS401Ikx!|$(u zFmN!jFaH=E+6E)i+yC)Q1S9He`=xhl8cYedp!vUZ6ig4Ca>D}N8~npZD9Dc=KYjq` z-26+qLHme`PD;kY`UyisR9S_b&1n0pm{Z^kX5wZ2zibwh^lRq8JbZ2gnMWVwgG+D5TeIG5?dP}Lvym8B5-1y?2()C`p6S5??lI&|)6_T|vA z2jP8bta)MRmyWvbCC}8?!@OOfP%|&CD!Fx3yhR0Xx+My3c|-A1@=y1kZgv!qO`#xN z#?WF*0h&+V=I}h=lQT8qP>kiE>;tYE3$B63o|;-&pqu}|oSC3u1II&)dSz6_PpeVx zAOT$Rxz^kXw2YomX%J2pK!J)KV>8vn_}DLnckHEjH=1e*N>FxBTvbcLz>Zj6$6am1 zfv;4eaL!iPbT%@N@%$%QqGdC#Hj;Tn4`-*OYE`t>T&%{yM6}`nP;vf1eJ^5f_*VY0 zE~kc(*<3p^J$@j>h!WUSh=!;LZ!>6p7^^AUoYa8_$cf+q0Da9S!LC3zKi^L)z7I`z z(lZMFm2IjKOH)AKl*!E>J(V3-d!@Y%DRbcyK##9Mu+6AaZdVoC1bJv?1Ji#F80qwI z(Lzyc=C^&FFR6`a#|d6M)jDvF-j?3Z=C?g(w!5nYJn4S@g|Mjm7Wi?W?NrF7RNTm-&OFLM4!Dr18FOxM;0{u+l;59BNa|DC=~WrYaIu-3` z!>&Ey(9Ket%uJOkIxxd50%=j8&6j~bkIhF)ouchbm$7$~%;+u(;b^3sH|9DExvS1c z&Rg!4ORLC*xUZenr1`N8=7*aPWHs+ee`Xgh$elW@y9uQ^T(s;go`KK91NeWYzopff`fZ{*YTq7$z2 z5e#^zg~D&cDG;5sp2sClE&fWWw+eazMNW#9!dvx|8=1$PWHBi{@Z2)mX>nH?Le5jY zu9hs8s37I6_~@OO-qI3x+4#BssIX{2iK&h^Pc1CDqsp(DU1P(PjpQy+rA_%IbDt_NkzS)IW843W?a)$SY~o0J zuWIHMAw)Cci>;@!Bx+~AGA?&(zfW`0(8k>O|3l_DE$OP%%qXWeMm}|nqr9%-1=D&zg)i+>#WO4K zv|?opLsUo&By*#cc$G0CL;p}tB2%XFQwru1mjn3%zeJ+9ZXkNij}{VWY^E&qAm}6# zrNgk0-9R^d92GWMR&+UY%wOwNFo&)hx8j@<4XuwYoZHGC!hu?d=j4@hDjxb&d{Xm= zeDg#LP;NV0ZVIg4V1#qwSQ@%|W@lk3Q}msB`DcY@y6+P*4q}y^iey+ny>+34K2T*+o<$SZ207M@v^hd-0UHJX$U7;~^txhFhX{`mfD^ZM(X z;_5SwVo|euBB=OG)%}P?*{IkGiw3nyynh0cRp!anht>6H%g^G_jr-R=ydr273%omk zFD@b_Cm?QzKjPf>_K^s_)?snqL2cwXP;-^ER{58@MD#qU}whSt|d6MHqXmrX1Hx z?}g>4Hrd%*E3ac(QV?5Cb4)Wo5Q&4OyZpFP98*VuA2Zs_R3f8q?xEF$h4|u!YQ&N- zVqR!YFUvis1X?RTFZh%Gl)~EaV7fJ(9A!|ZwKz7(Ruh?&%7{Ke(;uNq$(vdTDjD3R z#-m#wm~ivU8H+oUb}s5rSt~zRH!-LB{0RB0?I~c@%zn=8*|fNd5y6gM-qg$b;Dxv? zT0de_L)*m*BWC`pO>zD63!8v8s4O;uw4VXU2P6uRV#nu?7*cxFU}BS{A``7iS+~L+ zRtxwo+ZU4!WGa$&!v(FI)bxVgMcR)jV8ev#KZeOC$PXW2!IsJY43ke_%Y+q!MU+hh zY?&BAQiy#8TPEA8n2CLt#`O*V%#)Ar=1JTD>IhkecFO<1Acl#PB{*EOh$4oGCI=yw zs=iwsq#Q;n6jvkN!6U6jf;1I+_WD!$7CevPu@mHo)PmgBk}HGO_Ji>OcXko&W}|&)5!DoyS+EntWt_M!Ed7AV=v;({$;_Q zF_VLrD0JpQK6j~Rd9E>(cA8^_f_co&?ssHvZh<9xsNYT+#NVhEeMeQfGx@@?!j#CT z{4m`?;>>g+;~8VuB?_%Zn;e7`Ti22w1WUf``@B-6?yM1Yj1f&WqsR>!B`POfem6Vc zi$V?2@9IcEl8Mbw_?jJ)bo4D>Rx_S_>5yx9lts;D=z_VtT8SZOrt0*tw=vT>MJ+>g zCcr|fuBj~Y&i@aQ+!D3!8Ig{xe365X27IktJ;`M(M;l$=Ux-K~XHf-vVCI5mEUIV& z;292(C2dzb0kpLZU#-G8^jU#Y$nvFNv^{#w;giunE%#J!*z&`5?X(KNSW(L2sNAcA ztA(Z}#56VsZ6L$lqbn5Er!N`9&bD-J*~_qHQ3%ffJ3Fv=-Ems3N}SdwzK=?**ilrF zspnQ?ErnImmCQ}nUr}3lQnW#$O1s+;MNqWiuWQPH@Nx_ijRHnwnFPnWw)EWFNXH^h z#facCgfg)FfD;4cBw-3N6JaTODMtIP#DLRVPD=`jJM&9vV?`O#c-x2Wwjbrs_ow=m zo_Fys430`5eYgvS`UYx?^IZwFb3>dGsj{=hP!KRr?(R(1fFzkQihlBfH171@X!C92 z=;S$_t?I8-OpYYe+{J$`U}fmW;G=Ua{xva?X3gvW+vh}WxAB6He5SH>p~A&?!)J}~ z;-d7=lfzq$H1m#TTCKuR4NMMwjvK9J*<|jBo~qaE>)QR5Ah+~0&B1QY9?(LGQUD>% z%zPUm*6mU-Nr>BSv!}Hj@J0I zTo+U`BlaSp@gr?dKrx4*WRkWAQ7g-t+4stdZ!^CE<2!Zf@w~4pg;$g6Ud7UT@7wvz_rT23)7U(O~pptkw27KU*r*wp}5w>m`=raP`Q8?!@| z_1gG2|1X5GaLCPH2SAeiE2_-fO{D0n97!0JSSZ&nDf( zo=V*mxK0Z@Rde^D#u@3P*XS2w;rml?qb?}3J>hwtYZ&}V{2Oh%;w|9EkQIPb|IlcL ztir@as;dEiDH4$h@8~>#QgLmn7%s>17XqIfBPx+@Hd0ehr&6*Lh*2Zzt3rX2 z&M&KxwcENF+^4?~F!8U?0_pxKrvmple(iK#kx^d_J^ULE1F36s7EG^_99xV~XV}YQzKQklb2aa?C76*w@tGb-orZ}oDYv7=?u<(k zvVsl8fZ*Y~zYwDb&)_yd-b-9&$eK?%d5B78n^s=LhES4>5(>wlk>zYq5|jXVdM0rV znHzOz4uJQsXFg4Xc7S5%)?m|Sm>6|tH3F2R^cILlDt)TxA2Twq@HbW|3}6~prNpWD zahl%N!?#|!b*xI22hEw1F!r8bNB-WsQ?Iw*BxQ|L_-S0mrvW2nvpvCh!6)BI=YSb{ zxkyF9SJzRVtb*h`V$1y?U7UH<<-H9#YR-Gi_{7e5+0V;A)kcA-ro}@A!UJVcQ{*9J zhD@srX;%cO|bIdK)={1gwbq!Q9umnTZBpS83;^!5Kf17#NFCWo* z>E)PIzlBCW;Z>OH7$%jPmWQeJMIH(u^|zv64>_qQNZO-iS+P`Q)@)^9^eB1KI2-kD z7?eFvA}k9xM2bRj>sGL0T&fMQ>1Za)6u(6H%a;eE!RcgL`R4GMTw#$|>?%PUE3X#= z3D}OV*>d5eOwGkAwDB}Fc==pYj0RJ~n>5p@{#Y4PA~*9DC#p|3_>aoloO)V%+P$mn zQOhaiV*~lyEOt77#N_1Jik*dR3ujlDaGE2Ypcv}Uz^|8d)@hT|1RYH@? zkm)A9bI_@|+-PY%+-AdLx-mOfH(MWwgrzhoJFt@FbYmtz4Lo63Wq=a#G&>)ffs7Ai z31(~=^2Ih)LE2PSl;{q(_G%;H$HsP!pM5uEu_XOVEPj%}Rt26)=7+kMNmyz$Xl8sW z5t0tSm6Xw_1B_x@s%OY>v$K~E>azD12_IU#BIjSBE$~$z&%0T(&zqNLMq(spe94k> zRwG0}uY=Z;>%fM;rc>SR(B%tPb{kc&bGBf|q5{oX$d7{R0;4t?I!fzKJWnSpx5hK# zkpOZuV|QIRT&^8_@<;3d6cnrJ$I=blb~?Y*GKr+Z%uEc$D~g{bIb7|+oMY_3*e(X+ z?xR$?jPyh`H9n=0`U(kOEMHXh;yP>XXOxmVgS0*+N$_p-2nYEBbKu(tMWmgp^OFy}{ zM*(@&J>3};x3y}N1=+4q@Uye&VewFZ2B9>mb{`%{3a*up%FY!Z&AQIaNh>Cmy&Hfe zWE!-24IRhAZ%U2NEe3UpQDd%)&vrW0V$-3+*Fwnn{VL13&-sD9LzhEk8oqZMC8cRE z33Y(yFQ*Gr)^2oP%GomT5=NX}7Btuk5ldCFwAWQZ3F^Z)A)w-k5K-(P7%>Zl476FX z66UvLL$JZChWftQ%_nGB1Slw&Pak2xd)h#J{DejZiOz~jE~;YWgh2}4`o=jhk%dD{ z)i?-P(9kynB~sY9jj62W(hm?faScwo{5pGuwIE6j>|EacO1T$rERo{vrDrj?7|Ns-Y0OxOA!y(JH3`enKXeC|pfqTzcf_*hEM zX2Y*_*wLpcGBB;t1usUfh7n9(iR<+q#G7k@C|*xYK%D;_QgOWW8JN9~jGmViP&PW< znQ+UtJqX*HC-N_BE4;pI;Fs1aI4!I&Ezi-O>eJuuuKyiFVKgv{pM913lar0F{9~dIGT- zm1WFZW@Nx|{}+Otf9G3^_R3lPL~_9}Vn7yl)Sjh6)TWFA&hmPn@Ps?;PhWJ{FCV%q z2P`#Wd_Eo#cQ>tcgglKGA{1CSACf)O7g{uS#GdO-cNBcB|H6R7=_2-voYJmB);ly=A61JiXXh!w2u2Uf}5H? z>7U4cYrysw;&Hjc>VniaEjIpMr^)VzgO6OlpT1fDbzm_^PA8VFvTEG!jE9qjTpyqP_$jvIu$Rwlg>55g(|cse0*>OoZ4|Y zBa08MyU$grv-f%8QYYz@JGf3}OYd=rI#@^3`}cD%H@&N}_wbiCLw^eum}ez&{G{7c zX+M^XBZ%uo3hKNkSox;fg^J{?`u*sST(x;yjU@;%`TA3VnI&0RuHI9x|I9t)VC%^a}x>wH^&uLs_ZNea#kSQ6FUUXF~Qt9R; zx;Zv}=+}6OJ0A$Dci&aj53e;9M4n(uPAkC*%ta-I#BDI2&Y-Ap?qcJ;UG44g=BNRv zwo$De^_t1ot1I)v1I$f&HTVS_G^rPy>!YE2h~BVUh;!5?cS%j>3E*yG9BpTMyup*% z>0I4M6JuQ?5Z-=owJmNr#%+mX0&`??E@EB_7TQ++d|kMs1g&MM#NeR+rajh2KAR51 zn7i4UcH#!H*BgS|z#{XhDlr^#SMElx*Mb}&R-&UsKWfyP4<&FRalnL*F<8!5zgcTp zxP?7;Q^01N3f{{3Ca3xV!@_AYI_yt?JiE};+BGNaP!Kyun-)6YQ*h{3$wAxpef43r z{XN|Z-m;dQQl(bvS)Z$l;CO-emCG434p=U`oG}HipA<%(YnZAm;(^OH66E868)({bYr4Huz+c1oHu%`_0b0V!u#LMEl8Zf{!mIu^ ze+Z7llS;7JMZTZgF&a5(1?_dFUz{+j2lTa9av$r9vyiw%QAA4Q;UmQyDBAcrN8n9@kvyXP^!1m7uH2jXSW8%_Y0`x)e@1uYRTj&@EDB5REVZ_rJ=LmCVFha&0oxC!SH58})B zO5l1-f~+q&eWb3NYEZ*#abkYnrNuOOj%&pjd&)1#9#THB9b&mPt&;Uj1^ z3&zl2a&pNg=&lH6ZR*>Ixa_MLl*5oWS;MwM4KFOc?>Lwh_D*Nx$D+WARjN$(R9zVy zm4rN=+Y+{jv%rMM*oX4R6>b{%{Y0(xtp|Pzo5GB?AtdCma18fn=>4}qzru;hBR<;L2$3>hYEB5LKGftK77x%>W_M` zm~lqBfgohb%1PupV`xbOEFB4qn&fFivRmOsjrcThOr>ayZ%)v4m zxWr9P^j&5>@{l@EiAQj8HwxV&35RjXhi=rHSh*gw{qseopr2Iqgz43qV6`&9ykNAo zr{CYCHjS~h`MWD-seawDoOaST_|ox4zeWgC)a{gw_Y>~y0U0yGc{-;ykg$r2RS~OSZZq9ajD%5Ubz^z5WLeFs|lLyfERs; z2WKAPw-_;7^Jy#mZo(Z2L;|^Fs!rB(1h!MM!%&_?!qS?rkWYM>EoQjXwL_#dM!Zs(;`#ud3D~u zVsr!+)#$UWxHHSTcXow%eYL{4tr?n-k-mEkqRUciU*bOK!T)5U2dBvse>{DV@wZ7e zN@{N29YkSwrI2o>VQ#vXh?HQptXr{DY?ipO?PRh0}2RzFFXW?w*%rrMpX8!&4lS zdPVO$&kx8s-FcQYQ*I>R2zct(t2nL@vc+{cl8r$8 z#w5Vmhqw#6KV{4CC;0eW{#%LVlG9$)$I~Tfjq|RgBXh9`S5W<;e!s7*G9XP*UlN;M zbEhAGzoO&c)Cwh?eAXj*jm2-|Q|}T}b)-H6pl_%zN$N0vd~EpkIqksPssEM zExcXiTs9%GPSfXTUZF&Xdr9?l98@>dURm8xOOw;cv7bv%J2h<#z|NtGAn1EK?54_v zx!%U8hC&j(%J!TCs+cBBdM*Lc6Q)d`6>JxyuC=BuA11|LjBGheq>i~5YE9Cv?7ur} zwCuQ?7ICrEMh{J}9@jz;OG}V(30$v~0;|4lXu1`m{^`F;_d6NF?+obIib3A#Hi{lH z^7+g~q2K;sywuEFCMtPn9nVrVJ!%q0TGd17z-@5a+q{ATV`2|9^SPCpG$F)FM(8Ni z>Q$t5505M->P2k(LnBYD`%Tl+8-INLFT}%+qwZQjtZDj$sjzPTVGTJw2ZU zuJpQQB5@Ap(?w6m)Oej9^D{j5NDk<## zqHu4!A?vtFUe=pIdx*OFj~0u2<&fnXmK{l;>#uWt`X#wPG6x{_W`C?Kv~ceUkNQUj z6Mr+BSewpC;6B5in?C2Pqs1J&t*7H6N>Cmbb$0Pl!%rAU(iOzQLyw%q`kg-PEEe`H z!%6TK2YamnX1#Z{TBoh`0bwwQ-HOwKF5u^w9&OoZoBdX)EVRJj@v!9|Svr0fo6Bm> zk=AdGu{`3mvh<0^frOWKC=eUN_ngrX^DNk(FSFl}6N{N{KvFw%=HiU}cSi^|eoZhk%^>bbW}L2#piPq0*@dIrz%OrL(x zk6-28>O1XV_vrqZWS%-x-2Ip85j*?s?Mmt%O#~mB4(^Vu<2o@<5A~5+Rnve7>I>C) z#GflGp*$-1uNxotq$U_0Z+Q^}^AEO`PIdx8% z+&njhP2j();MbzCiZu1=t1Bn^3!!1!(#gToYJ}EZWOc4m*za~|t}2*;kZn4ns^ax~ zYo;k$FEC-*;HIE}i?U})`Z6QlN{kTJE@V<+M+J|Y%Qq%308A7h-T0b0k4+v^FVN?`BHT{y=MJgbqy zbO4jcmmRF3RF0DrEd+Eb`!>Alqd_5H5?BcNZPcIV*cSGD1ne(sEN}IE&s&fk4)QN^ z8aJSt%deWOrU-6f`pCK;2J>rY;fDhqyFM|Ijx;|7${8Z&tX53_T?!*=d@UAv^Ajk* z%xDF?;}?!jCQ9VUkDEAZ=dKTFZe6nDbyQy3?P#2^wt2x#4#I#*Ev3M)fZtF^V`P$c zlsYh4TLMhB-29H}O;SPy2DAhq1A2mG`oY5I_ZNJt=l8KR$iEO~794G!J8_NWsV_C3 z`0xfp4Z_ZLWkyUuLk`K4+Lq>%lI9u0lb3ii`0M+g1Hx8v03)BT`pnz(#X_U{lzb(w z8#|rubkbpdW@0FTN#7_`)WSzeoF};pJX-XlM|$lEb;{TnG}{Sv=%Vv^zRhJS(tLsn zeOf@!Ua+nycny!J?3U$iTM(Ny6l!xR zzsxOnQr$6GI8VA{HX#_)cH-q6RUg{1FPDOvocGp!j70eG3Q@vNYT;u1ZLQ+g!UUlI zWU@_`O2Rr#E?K&_a0}KD$Q^7RhmL@uOzn_34%5 z77p^r+#e0byobu5G5M-};c}n6%xXJ*Q!qMTi$7Prf4?mGo8MesXxIECrX!YZu?*EQ z{+<@ziD2QeTwi7D^tBhTKHQh{i0`JL>!$=B0OW~pIfSC^S1jVrITlF}^#*llbG6RD zM^4~vxmPd5psMxV!&4}KirB7rP2#hSXb|H837pi!HajfDZQ4S!xa{el1&ha3^m_6_ z@cXOU*(=7rPM95Rx|f!*#-c7;wMAffR|Wgq8qEyMt8GcyEyr+Azr_(lS!=gc#s0=lRA&z$9xxE7XKciN9hZMd`vKAMwTAa0O`#FfQ3tv(%5Q-h_FjvIG zCThf~Hs`C%fBTDWebS-Y{iYWAr3}wfvGChn8v~7{*8c+_LEpaVSDl2UhC=WrsdQqxL*-$)3BAUw)3JK4QF^WT zeaX`qz)vmv#;YOMQ3-PBjOIPqtsF~t}$VLBUton=)1u~4la zw8MwO3EklDOWvD)*h?i_kib7Q;rnf)0h%sMeibJeu}_@%hvg+{dm9n2Y&SWlg?2LD zfI8Ki`S8Cu$p!M8TIrf52$pC!$r-{MYo$c~&vH+Yy5|KF?V`}e&VWRmyVM52ww(7# z+&e?G6G=%!e5~=B_uQk455W-V5sZO1nBee6?0w1;-7x1g6L?7XA-OkpPgHzdt-G1| z2OJG0aFGP!pLZ63lm*#HWpI`mDi#MODbhMJ*li)x5vQ9i6HQfG#>IFv4%*}!#zDCa z`6TwuR`Z1Q<#P6yweUlGJ_v4li`8et?oKW;3tE#JPUTrMde3okn1&~p)K2PrlwIF6 z);#9B4T}uj2)7B+iL3(+DvqC7J|m2n!*sc0#&zLBW)Bv{{K1kJSSD`D;}$zb+(4?7 z1`5<(tos6n$Hf+M@ivIB5btc3KIOo?hdHEkR|e>&8w4`!+;Ku}bYe8bcgqE6Fkv?V?3^2((m{oy@+ml ziPdMr?nRDMAisK(TP`u`D3O{&g~NDh8LBU5#X<*Cxcqb#ET##E$rCc!s)?-Gw{n39 zH->asro`ax-q1?sm4QW%6x@pqbsc<53I6~YzZInJ3KnVSgx(S>L6DGTG z8g$MB+<^Z8?ce#Bw^3U*G9S+)wnA^_ay@lrb{vq&5cyXd@pem5{{Rey+N{6kA%1a? z-oaS&uDAB6bKNxOw9Gl=`_bO4<3pa{f7^P3(s{R>J3_Qw{wK&}c34AH5UsnJ`3Ha- zxQ^^!qME?ucGHq(a@@4{WOZxA0j*;I9r-X{T(7#q?nsIap+Rf03Nnx{F~@gNMRQzQLudF??hBDmk)ZBS`oC2@A+u8);ABS{cR@PN zS6%1Ig+pvt---rvflW8AhG!Q^TVgh?Y-3jQaaw!Romn+m?It5Y;aK4edXB2Uz{kMn~l>z2+mErVYG9x z1)93b3|7H;G}dehwat%laV;V})`_Nz2TIj?AYjKP@b-l3d% z2ATE+6v!9fc0IK!3`Yq$%nmX|9FN%zfm^*#$TH6ss$~NvC2Qh4iv8SBu_}(26AXkN z{IxQ!La~wCmB@Pk00ckgh3qeH;G*>#@cYxciqq6Tl|(y2Zwb%4M}1KT5Yh2brT+ji zO?i8-HKc4^7}@b{3geE9rJS_`~gwqo;8`?uj+mXB1+0>sU z3-YJS8`=~g4KL%^Q`kg|jEbuGnR&D|yhT{q) zOK)jnYhqiYKJn%>G!KHe8}XfWu0 zoheCLtuUv-#JXEPsK{lC*r$e2hU}fEh%XslaA@96N-k+w6mxj2-}1|f=PD3Z99IT; zry&@rTi9rUXNW_o#^C_H1IIz-u#w}xEC^>xI=off0={-0PG4IhKG-R zK53w`Zn*Gn=*|`QD8$lc3{8%lhsg%%VIf8SVNh_m3%?_i-Z&|`2zMzwWI3|ZuD^!9 zWY!3N@gx98Eyy=>alBUp5<)8|K+9PvN>W#{O$o~dip1n}t4b+Le#Lh*yBv{XN_Sf{ zTr{jbdpRQ z7ykgTD8;8f?AyH%TPKS=TgO2ptB)r1K@LRvF+QIK4eg$DS$kFz`6%uLkYbW1p}riR z$6k|(HP76os}(bv z)ZGGE43M5WReYHfEl6sfpL(=E5M6d_YP3wqTtK#}Ton6I{?G4FGiOooT@hUi)$6xu zr9=U^IO4PB7daXP0XMYZr|77xo8}Lai4k2z1C_nP8CAGZL%im=7fOLNY))EH$lW;| zydk~c1l{fUFIVQfU+_@6zj}$eTY9P8aq~|8U&#+uMBYCr$(Y;Q$|mDG)^o!Lq7!L( z=gM_e=1vp!wQzBV2r<6YE<7EXVQ=DCKbqW(>o2o^mkaVJm`IetFadU*$b%jn^V1+1l^;9{{XQ?y=#jTIvpQ&yrXs|?@+*VnoMYQZX-M^ zzxs`{gV&qC%}#_Zww8;>&6xKnP5rVnfQcXoZ_!!eAGIR6t^tRVWPtWmXb{}q4!7bw zXLdi~zU{f95LJ z90zB(ND;A5LM06svy({kuAy1Uwkc*k@`oDJ%y z2!t2w){LF9YX1O|$Y6Hlw1J6+Q&iknJMfhS)0TMnAmG;)&lxF~0Euas*rH0c(5t-) zO+IkXJ4(CONDfbhkh$u8|1l)%@{II%`{BhojH}|BP@-i*EKqt zP~QIlf^S)$1bUy;k6Hf!1q-Y9sGF6laUR#2J2rt9!?eS8bn8U&1jWfwR7;wjzvMEw zO#~by0OqGfBCXJir=5lrOpe%KIM*yK{7Vn>21fOl*`?2jb0JVZUPi?0!jtmJDS$DJ zH?g`k6atH1A*14h%OuGFR-Jbtoz-$k(y2UIIl%>ifvN7H(pBpl@y@DzM0f4J1$>J!P3Y-mUEg~2vq zpq%;7O0_odzH{a_CK(p;;+m78wa&YAQYI;o;0$ z#MZc8oIuH_o4!feVa9XqjxZ6=;S_OT@1SZd}oKTRw{Kq@njGw+$%Fw>xQ4 zyw_?Y6xo`Sjyy$KuQiW0+x0DDtCW+M0>q3&4$oNh-L)u#~i!AJPNJGjbRbJpL zg1a6S!LCV=VmZtWb?nsUI?oU~cof#~F2_=K+T$lkL1GhYV_9-@fsYMG-u z$QC|kS%M)@JfPSh_t@z#rF zhY%@>i@nDtV4dG5T5*dG>oxI8fWRjARQ8|zsJoZjC(Qt3=_mw=-iUq$S~Xm6$$HKB zF5HDU6%(sPS%(iNT$6*FAorW9BOYfR(2EIFPG9#)Tv=wMzv|i7K zE9Gak4e5teSZDEs=z-v}Gj5vA7jTWZS$2M^u`s!=yBHbIaP_7GXh}oE2&OIZ&L}m z3c(eEo~({tulOeQq5K#6f7HL!KLrbS&%m|R2KQ=jl}_|0j}l5C9MdzBYP@SJVY2Ze zuhb@@?hEa3!zVlB;H<&Zn_`?d6=~|XwC{+{In*gG99^ zwXF>ezy-p-sAXpLCYd54w8*0F0wKR4MwJ3QODt$`%blF&5ILtKI?L>#{v1EZq6@xO zDTcDW@?m!9KW2tVZn?Q0vf*M`;YD$Y7G=ztqrX(a`yHG$?fw`~2FVD42b;mp zX7Nq_!vT_Xoc;_b_JL=G4efL}5Wz4@+o!b+=r<7PjA;jJf_QC`1?*_R6ez;Y3Ac=- z7&a&d92gf1+b1#@s*4e}TQ~w3o@hPPOlvIcaXOeas7;s+BK6kFv`)Wtsqj)W(2Pet z(>jz{W|wGFG?i7VG)_|NAqMHB+assB7um0uL}+X8ol4!-9|4lME4a%JBtEdq%`2Lk zAqkM>4k3jgCpv}ARS2Cr0>2QC&`jf$J;MwTXcFVIepqxI&#HkT{pbDJ z8`cZ#nc=~+@+XSkzL|BVW#1x-c#0>;LK8dQtn-FQ0p^O*;Xq@O5Uh)=(SZC3&Ba=r z$~3@Xmuu4+Jl6N87LY-+vkmS?tfED1rXLbu>CY-1su7t4IP6!jF0)KauH@lc*Sj%M zn^6!LXMT8Hsu9&17v~ADHJQ#5R_ilGz}JY-{$t*(a*%L{&}25JvBdC#8)4I7PL3Q{ z_XABBt0kq=>7Lnax%E)q(qXmEBAtt*Dvy$MU<629EbUO)6N4NrT3GwoDG<6H;1(Su}Nj?kIP&aJ4f3RCiB?^qsm(; z8=JbTrI%PqW<9Rlc(Oz$olOHQwB(kxXezD~RIW~O3!bzUgH{1p1caRpr`}Xu!F{%T z=#%_GLcT;62NFxwqkwFmNyI3UbpHTKljATMx|7}ib-q~&2<VOgd}TASTgxQeckz3ZRcq7vz6 zQfgPiX$m>kQ?I({B}<*PO^%+zw18@*Iw}#D?8E*OJ}NHYzS4R&4_xYjMuvTcX z9Xrk{+1R3W{{W?MjA@Z3dXTEkymu)UAA+9*?2?goyP|6BIg_eNqDj#rxzCxLg%CUv z=>6!r2{q7Ga8oV1?>Uqz^az*sb4rwUAN48kLj2*WvF(22lB+%wAK0eL@K2!SGVu`T zF=2-w01vyVO|ahAb!MjKx7LF%k|nUL;GAVYst^5`-o}wB@J);wSZ>{sGfv*PD3O^n z5zq3poyd>dVfQ=eqD5t{71zVNj@0O!JQ7Hh_*VT?Xl;BqILbgpX0f$TYKCwEBOFek z92MhkfjyCe1Y03EU6(ly20L8C5E(YIP*~m-?`N9<=j5To7HeCJNAMlx zEF`9?!zDKm)`UwNd(r}#0o&jlr>1KKToYk5O81sirOlU|j6MP+T=|I!qF({_i6CD)$8t z+;p!KhK1UxL$PPL-Z&H_>&-foj*SX(3k8DvFn@&4ii_C3-`gKwroPP{bKUY^YBU@{sD1l>xhOkv~RcI=( z+NlM*!pw9*xy2i?T&5!)SS5!=R{e$&hi8I+I%tjcAZpMWxMdsRF!Up2aQ@_pWrpo36KNm7WXY z?PF=)xks`9)H9r>_L%P16wlnG1cl+0F4=L!wX7T5v2St{l{ExQ;KYkPIzs4e1N}9d zXN>)Z5ee}{lY$QNXcb!4?{dzK2yUv*j!#vYS-m?TPRVEMeNmo_fp(yu)+-J(axiEm zRgUjeX&cIR^xz2+)TerT&^T>RY*=#A*GmwzEJAse2~0)0O%@tcUwM)uc&fyP70bf2CW+TG)|s8x)(D2_}irPD*Ymu;o=; z_$!B8Jk`lZp2&mfrq(;H0q8W^UDb}?s^ws@{aP+jkB8YcOG_KpqU7SW{Z~y)nXEgO z3!9S#f-?w|GV9`Ev!tdJfF)`Q>s(?xQ!2A;#iLwPb#nHbzKjv`QxHSl=S0rpdc!DO z85o(*j8t07Kjfz~+_62&7k4i!+`OQs0rrvFPH2@U3T;%&RM(12MojPy^$J*B2%5NTT?>dp z^GimhIZ2T!HY{>|mHfDWnMUkiZ-1Howf18hTa$Z^s;X}&I2nafu7g!t9V;|;pxNey z5rv`Qy4C0cKr}t0;)Fmkqnov9+@{Am_A+u~fT|*3gQa8Gp7CA{HZ(KKLZgPX*sN1B z2PMaGWaftrMRYe0_-5+ltq*TpURkCTUeeW{Wr^y^%chS5edezmy}W|4W4DD^P@Uct zY+(NYsH=AJ!RLxi!N_7^wY!l5XxJP~sI+ zk%`;#oR(|N4{Y%7To_}njcWbZPFN|GO8h0?29&^y#_#rCzCxWu$~XC|?^ z(xP*WClz+A7}o@Dyg6frrF!J&r3UFK&+^U*tvF6<_^E3yxO~;mA~R>&n(MqIw2dnK zC+}%fWYcd9{VQrLCa%||Ik6l4nk_GCT$8RHAQ}}XLYuXz%2UvT#;DaBlS|3@-GI0_9&% zHM9zYidy^~hDUE$@iX2A#mTVmat?`K3nC^KVeBiKRhks@+lb4W(iA(?x-e1{87%&) zjo7VU&UeKVvxyE#g-&vsu9QM!yq8d>{{Rt&@KM}+vZPUC**Jd$Zt{#c5Q)1Yfx$@C zVG`)pWGp)UUgobSCcOJz6@+ySRgja%a2_)C4$gi7vpg z5Qn0s?B{DLgTP#OJbTm5(yDHatDk$TRmsEca;wN1n@_paO>;+bpyE_08^Vp)qd2t5 z(FsKyqluhkgA2v=4q%rATOtO9M-X*MVo`NnqD@jG8sdp#3->mPrtem(H{P>Y+*9s$(VAeujM>KSKty3kZIS{?3O!nF4;a9D)ut4~-a_!7BD&fF-84XIdoFy_(0 z3BFxZB{Ng6@37~sK5*vOtQ`!Z=x*UzqzqLQc6`ls_6jS)muZm01G-aM|#Tzg2VT4J5=Reiyrl%U~*B? z?OgYFu6bPb&-X5WxpUV@?)6um)0YgI@?xkv)p*&2vvR;ZY@*K0>wVg$OEskXm0cmJ zs)NE{uw2l&t2Ll*{qdaDLaANn63 zyJ7zTRbV*(0HXar>OcR)04NXu0s#UA0|fyA0RR91000000TCfF5J6F4aeWb^pWJRgTZ>Wp+~0n;H(#yI*XwigUnb@vY_t=~E z{{Te)0Il|W8czb>!DOEw!T29W&!OFTe`Eddin{y#jdZ;IBz{2$xq0i4MBxN731FTc zXFo@VqzFVJ5eS4rArK%(7Ed8NF!DG=CQUVdG82NeK5O1>{{TCiKi=iro%a)Gv42;g zgM%N0_&?VAAMO1Go%nDp-oqAmaxBlsk!gQ9C!ije^O5BDUt`Pfhmdc{^grABAL@NQ zA`~zo=b!mQPG{>=XZzgRe)lhnn)Zz!WLnw@X8wc8!aS=n<-SFe`!j{%leKKqLg**k z0Q;#YVly-D@HJvXDAAmpvB+VejFNp|NR~?_lF1~JNhFd%M(6F z!TFoe^HHLWz`_}U(m!!72BxLqp2!9Gen;BiKJT%rI^8gI!UQr1!5{aMNhF*S7nv?f zy=77Tms$c<-i2Hl%0uvOgdBNfC+BoA5`PbQf&y=2?mbpy!8Ud_%OI)`I0=Y$Y`eCE zj1^{=+&xI-JP?wQvw(R;bpD~HgtcdwbMQd2x4&LX)k-cLXlFR4m*L%c9xt=A;f$9T8%o`m!yPYg96M2Qjus$XH&Kn&$%)9x=Uf`!9R#m%Thgb19D zM76@$C#DFH8VO;;(NICj9Ct#zn&&8E-rQt( zbo9wSnIw{ZR3L%~Ac6?>%Op&err@(ea=ECFl7Uj9T8G{V=yZ7P0`xZL*kstWJ2(?m z6|C>6YD;8<-$}9Ku9Le@;7FQHlu_VMxm8Uw*^QP&dS)=mERh^3c1YiDt?V6=*%Ez~ zHLA`B+5MAV%aH16yTFKB=N2Yhvz}kr#Fq?Dp{`H9d=Mc~2v`O$8Dbh_&`L{-CXbXu zEcbmnlH?jA3H8n~CPC|2mU4ujak5;z)HF7ea@%!c#XguCjYb>eFqTcVx$g&IG*7YF z)!igU6O07*l~359QlCzKBvK}vr=R>M(*zJf4+$iaNhF{8kHnMel0?X0ZQbRN^%sTUjg`i4z!}bwN8RDQIr`tB%SdQd#-|RIg}>bt6ssnlX2NJMpyH{u?=oc!eqcgz{Nre9>yo;M3g1| z9(tEyB$7!uK?Hgu(F71d7)d^eAYq2Xz+$<%7S5yQmnfNY=#&wW5v5ff;T)w-F1#{H z!6cGTqCepzM~#N0bs%s!;FiRWXEIun)e_j2#{+=&{{YG%NZiEeD{1`bEUb*L`a1U@ z(6c=(x^^bIa~*i!<|GY|(k7RaxAG#iv@f}lFIZh$%O;~!(OC$KLqXR{wbXueB(zTD zkc^Xg-yVXFY*Ha2?u5$ExR{8UXp5nK*RmA#N<6nw{0kT(1?rquGlcpk3H3n)V9?Sb z5M#D1^NP5s3$f0__@dia4s5ErK1tr4TGi2rNSMx_FR5 zatI?C#f_2)0}@kLMWQ;XXU1xxB78bOat+zIZSw@-K8PSlf-zx~qO!6_WL29&D6c^J z$@%?ReTg{zr2Le0{{R^tQua&GsSi?Gk%SzMWNt>~bt+VrZpNAmIN7>+JZB#eT3r7C z1^tmJn=hRZrtGnyvS>y)l#E;wnGG?cB}+?ZBz+1WqfEH9F9T&@u_9w)#r#x!ksYS; z{{X@;RMM=C{&Y1}1)ubxC1W!z+&{5)oMs85Z(2LD-i!L-q95NMR-A0&_*s*PSKz3q zu77zDH?)R{QPF-{=us*p@~WgV1W`y(g2Bk}h@zg?Mh^3)gdb`9Sl`@2P2ohTTa`n` zNW>)(;F5$G&|#SLNhIKJ2ZoWk7F-x*@t%)WlMvEO=C$2V$pmBV-4La$(}H*;k(SL8 ztBz+I6cQSW66;T;d$V~Y##aMa$s%~aOnTl7N?{gkLw*IlNXFY<~3OlDOLFKw*?p+$q@rldJ#KdnmI^`qNZ&Ml~XIRFc$L5*g5F%p-sa`rqeRs zY!*K{-WbuSG3`S2WAEb+X~dblJ~I?H=`MolU8SYeuM_z`u2~YP%Dy*qv_0G?WQ#*ls%#Nj`%f z4P?`XvqTgto4Gd6>hQ+N77`3X%0lUiJ*67D3-8?&{{VsWz=}v288}4YaGB50CS6X< z_;`ktJikFbbkrp?s`(3|opa)*h?dnL5!)hy{RR}Ys~uS0zG0jWP8lhex;S2J`esQu zMlm8W7&&Vk0?375nlM7aFVz>jEzU->S+}_@;N?ylLGJ`I zok_(*E~rZhRh9Jl3csMCv@_I7x zK+5z*me07*Zn|#aYvroZe9DZyMsmk-FVU-9dZU6`p-otqy2cL;%EGAHm6Z|O;8d@X z;9jaP+%#EFBYdgG1vV!5Cw9_A=Wc`4cPgUWa91Kus!fop4)Z=#^`60Ou_1aI_cOENRB!_2v$KSD-R zIDEYp>|m)kPS)Qn-AC_asnn@_mdY=fq*Yg7W33*^_9Pl=Q^>w0UEZ1!H3R@xwgp@) zIZ$a44zZX04$SnnOMZliO8t=F4Ui@&s~%*yHl1ob_Su|m@*^XBXj{O~woi6#P~raoga?3>4hpQqGFa=YzF(JjhAEJ$e~aqR$v73pNwx`gdfyQeK(m9dfrK<)h#+uuI!1tI@9`b~je@Vq#@QHttRl zPDmsupahw0o#USn^6vv|-v0o<84_FweHZjNf!MfJwnR)hUInCqP->+gfZFgA>}#PE ztuE-ap-Q&__$j7(QbjzpjG>`bGtM0p4ji}1K%AycYKDZ+Q+P-BVq}VNAk?wqnzx(R zfybSeXNuf&;Fk?XjoOk5?yW>}@-@jXKEF=ok$7mQnX1O4I1r_Fhp9n48#kcJvUd9@ zpu3laa2yv;Hfdx$y%q2#o{G#CNq7{Xb?i=4J6R9(i=e{3Z9%;hF_uB zq?Sihbzsz&M$W%w{lx|?&$-97SE~9F)Nd%~LWWI_o&qZs@OVmc<* zM5@LVec>W?n^bo(-ce=wdkxAfu18|^`y%qlCs$T6TyT045WP{15GREui6pdr*WgUH z`cNk5R)3qgq@(hU`N>)r=*;6JYOaGcOAKRT4|*?E!7QttKb_6eYsKzdXiOqlT1^xQ z(bvGaNokkqFjMH&nqI-v1B6#)nhpd(SJg3hYj|yD>Qh{dpw_i8t3EI%;<7SC(?^CR zkvJJudj};gkz#gCY?d%V zZQ%(p*mFA86371k&u4=#zXXMN;dMh_zo;wtKj*$ zz~Uci5if0XgTz{BcrlsRbV?@J_UqU)P0Rd7L~l}8*X&9rnrY^W>?1N3NK{Kg+)kB` zp%*gNn_#YiXK?xoqmMphupipTnbD6~*q>g+XlGG7h(r#pp4~v5`DeKFPfMuTSs|%l ztTQ4+vt&oPU#y7}LFp+8W=L3W)X+?iutO5)mJ_pYxczNE=hh_)KT-bx7N`=gRQVJY z`$6j&zYU4O3L$Wigi{3r5g6L4G@y@eefD15q$o#3mjks$kSyv-bu9CHwqkCA+Zwt& z?jdOxvI)9VdC)wcd?gxPEJK}HmeFy36$Ej9jY3_RXF%b!qt1H zWx{{Ygb0ypSaUQcew&`sj%V&R*!;Zwd;fyJ|Wg~+% zN%yU>2O$lek{Gk$rg3V|R;7u^AV`80KjH?^Xf=^??NcPwANska4EC35qMrk{{7`{T zeoT3=l9RJeM2!?kkxmx>0GkMJGR>DFXJl?-O*@mLN{Cm~D%fkK!_a8Bg!x+=RGY$k zcQ}aXA^r$|fv5Nq=s7H7LqrP%a2C=&Xd#h)+Mk zOMRrY!py}GMuIJ>M3Dg^LS+&+$uNe@!ra$E)N4_zj3oSIC(E*=C-8=^AU13q;!3T_7Fn`e^=1Z_8;g?X(E+T zg#s8z+i>36AUv&Cs-7>rX~ee*U4-+;O5bEp6B?QFaL+|O*z|t74K|EUTPFJc!~CbX zr#b|UU#`PwDNNL=&{S7|Pm(68((D?!NGzxP5_9F0QMW mWq?GUHQ)n8aM(@x1IDGlf% zioY?JAkW;7u^y7)BFY;IQQ^`glU;q+{%Vr89NG+5?#qJ|<>w$oN7&z**)j}H85VYZr)*r5+ZwJBXvp$aI5skNI~ z>^&h$7mCqJHWI-t;_juxRxT1<@V?^TpNUb(q#(!=`UoI` zJptkvVdFJ6jwO*h^b!DQvPQK=`D8m|qM{NNrJNQ7As4xOiPQN`)AkkYynY-LsJ3$@ zW=n0Vxm;L*h*9`7b3u_Fw-Yh$Sr>;#hJi?BuTUrIWbFMh(&31Zv=@Q)#+<%#2#b<7qGCIZLhCRG-OGh*~MMi#btU3AS+uJfwIIG~=Nv?2a&7VO;r& z)9|SrdUFwSN))2Rs&wG~p0bp;&LhKIjH_Z2TaKlK$+Sahr^BgQ<`Cd{<@gqNLp4_Y zhg3FoP9k6HpwkPK@-Ma%Z6o(t7YPYH!Tp96x?K6eG)2TnaKs}`GG@}?C>QA9S#LOh zNv=B-iuU8+G)56oraZm~QdLO>WdpKN5m8Cj=3bT(a7fZt5U*% zk>;6kt?+P{kw~JH4&nk#sFJt{FOS^!y{NOO{$7G#qaw4AK^S8Z;5-I~hK8^vC1Ni} znIEJIvJ0X@m!S(8A3NO(qELsLi5Ie-0vQQa`DgW{g)Fa#WoDf1T+PO!NKMg2E?>ap zG(~2T{h+7PYgd74M(&>Cr0gm78!vNZ4^+x?a%_V%9pf}7N+mB~>Zed+Nu_bZC?-{M zv_p|dYE5CLzB44rEZ`+HdDhMuMj*3qLTQJiVt8P!C3;6*qrRinDtsq3noYt{y}S_6X|9igM)`Oeuui}!J_fHMrt-1w$6$#n94za3lQQ>@W7uB9pMmY+ z7U6T}1UhVnvS?Z|gpUb`A~>4pL%zO4gzWo-wUdRgtCUc&EupI368IJ}Z-J=_m31*_ zcS%jsdZHZ~s=6ZhSjrAQjvv{K)jAuI!UnFFG{C5vPO44zD46Ml3r^~VN2qe)I7)nY zBTGeyH5`nTr%;9~=U(Dl@j#L*_%b8#AeC?$tnLqV zT39x5C}YFvsZC4$2xv78Js5{fmN^kf>ahVL2q0A`_=01BP@p*#Qe~v_AtW+QHcj*Q zMwPwV9-=i}Dciu+ETSfHWz%vG6V9a=b*uLq5hXB`s)wVgGJ#_2wZYWVt_JIh{ zLn>yW$BDGDN|Q?yX*O}%9l&9FuM}|jVAu5^C3}kKp>#Ot(26Qyi&ZJO@E#X?sFV+9Roe6y9ov?qgVD75NvFX2vsXBOUcGVjlIF85s1*kDQMoKTeMRo zwMf*gxkA+^psLi6za`0JQlLi;s3tW}XYMC+*caGULC#@B3JjD95rKL@!w(Q>co#^t zi3wCuDg=wX3oiVsD>?#}y%G;Kdsj10u(F{OLoFQNsI$OS=8198tt5LiIio_icHM@0 zt>}9I^FR#07jYW0yAt$W$TI9gEc*zGCOt&*xTJ{*nR=G(^mYkhtR%P~FwXJCcNnFO zq)7tIsm~_AR1}Qe=m$8Oo?Ca0#<(UGD0BT$99mNLeHDozA$Fw-NNC~Jm5Zq4XxmD> zaSoH$GEBsjOHJyBl^@91xKR~KwS2@w?Fh^~r@1D1Zz_9WxbPV!{=q3lUQ#WMH2mKn ze%w$O>#FD?lA!XIp+Jtw1WwgwSCLH$E{{C?mvej;1)5D;w^7cf4cknuCB&7U>jUh$ zbbzg5(AgR-Ih&PE{ea4_3spqDhKAFmhhyD54N#d6eZqqFS?;tMd!i=WA&koMhv~_8kQaOziGXTq|ScbtK z$|P=SZ=wqj+-Qu!*MpVVe_5EC=k7Tz6u%@bOut~X#UrU2go31H@dyxJkXdDh7fKg)}V3G!3N{L~ln00&2HbA*}n6 z2)73JbAQw>N)<}YrzAzD395-HOB5AgV@py`H)e(S+(u60N$M@0@*}k*zBcML$&TMd z7&;+fNKAq2p&Ga`O%$`gC3OaKMcKD17NOuu({YYX+Rn^q-qK8vkTmEdAg~rah8bbt7-(pL zp&&>?WyD@TCgauJ>>KuE9yokr|#A*97yJU&q?rb8j77C4rSbLCHVis_bblp5Zkhw=oD>(u5j{GPlc#8rEf$vbny=?oTJDGNV;7pOk1dEr`{* zBVa(?-V@wwg)mDSj$%#JjhF8wRb)Rz`_rhY6n;oCTWKF6b3s&=_(GF98<3T~i79qO zRozW8u^iBoF-BrTFC|%LFLDc&2^fE@DM~D;hKhz>f{GFfQ#vh`F*W@|)mfrK$f`cJtFySg5yDGTEo_S2*stAcNn3HX+Kve*YM`uch4Oc* zy|8;_Bl3l#UjkSst;m96rc3RFr% zQUjJ}LKI~e%tDrPsalF%Y~ZH_t$K-HXgf?cxrTZ+d08L6)&*O5R19rqgNO^63A z6>jXe5tElC4iZ{3n~cod-<`Wp)bHl_EtZg+oG)Cr7i~aYC(8M2bpf6Gd9pclaj~k%ysQvJ-l) z#Y2&zjP9t*IhB%a}L8QAB4pN!|Ydqt2m4G9rSGU7yjeNpHcR zR84~pm2IQiVs!!i?nw#WH)(qZ`~GXl2(7ACR;K4 ze2Tv&AnH!~)J;`^%`*(1OO_6+l=4XVqYu3O%4s@KrW_)}`kO|Ma10`OU57?#54)H9 zp;4CPa{M!~M79{MIBE`gO*)Lzg1*BNrKPmmOrpBQR&3E7ii(u9Eu6*Vp&@SwO&!`1 zz#7MtFYQZU0ldF2a?G|`rlm%7CwfRuZDg;2uCT$Vr&5`^uW_c<$8>P2le|-~*4|d6 zr@MZjVN{Cc3 zZL-#4sg+PcR>LF;kXFTsE;Sa1k?z8j*pc{Kgh^daD&h-2mBoTsYaHlgT<);lk|85& zMj+L25~A)Q@$(?;GDIRpHEbp)frw6nqV=zja;^utL4g9wEgs`Gg*5u7sLhn>3NoOg z1{iK`szGj|No2IZ+(_i0N!;mQ1C@G5g>8F@QAcKJtq_`Wa;2QX25fSwjt<-nY+Q?E z+C^yg1gV$RjY1-|CFw0Mk_p&R)MHdSj4eDNLZs*hK|L0&VS45kK0>6Tk<3_~wW4bO z00i&VAy&G1CpS6xL#d?Pwd64E$9K&Ny^%+%t~57UER42Fc|J%ve&SBeJIBP(_ZR4j z-WpvC1+*(VZ>4Ft=1Hy5SxS3^wRWv6JOlp7qb<`&mq8(j$|6?OSrpWjye7z(yfxTU zd>Z-EN`_piN)7NNUWTkzr>qSgiPb1oOT>K+iscw@MN(dxlD4JhxeH1JtI#&T3sI9| z#UrY5sU=f3sE|={H8gNHnMTGL!7&p`)e*zo$t}xofYS%inHj9kND&NfjYdrXOHP$! zm9bIMzL@Nq42fZ+it4yxqm^=j(w;;nCcKs{O-b4=lhN{PR_kh?!24#=a2{rp8Rmx> z=dVNk82#-cZo4RlsyqlTaEg5071 z08GD{N?vKI>Khbk<)OTbibJ`?NYFVo+l@!| zSVERPNeZM{P>Sh*n4yO8Xvk)QK6DpK1nj-Z6ji8f_7b6^S2gqxRHBLWE%|eod3z!1 zQc-^sHG674w3Me@&1DC!?4{E-D>vRpaEDzMMeK&Vgtky?m+A}tWt`>PNPMy)% zc??x8Gcq18NKNKXp^L`|geSLByaYvfC&@Cr^Hze0RO$5^dMPP-G@%5{H?KsV+Yix| zB_pCsR6wiA(te2`)h(NdRbO(AtdgeXP@FV|knse=Zy{fw+*AQUFl{xGkWpK{irtS1FEi6DMV0> zW)*x8f~ig{mb)R!DV-7izUa6G;&7hhXs+$@W~#%Evd)Z7AuckbN@e*M1>8FtN1bJM zDaUk}V{}B425)xZ6;{t2j<{sNxWl%)mSy4f5 zB8f>TNjL>ckd*{^Q9NMACTIG@V87fES{lU#hTVwNRcfA7=vOYrER|LhiPe@!x;v90 z6GxIz@r$b{srwtWV?e3opty*XWTs+ET%kiV=w1|3-BBA*DjxSMkh^Kd#=+5LQriAh zep#2fg^N6|b|95;4G=XXK#^LiHdNjP)TWG1Zl#dMsX9&xLEMrpR3)yiZoko~MMOzv zP5a@Xu;yA+>L%S;)L8rt$y5%TYKm9gMaqaAy9F(}C2ot?`KYI@@F`t}QbZu>Xt4cLKH;&NTw;SLxNT!Or7{7<$DQLd&tHGMW@(bP1f3^%-dzy zX+~iQMaWC`CY@Ww&ryAQ66FKrLc1PCMlnnaMcFr75Yi<*d?7AUry?dGhWs$tna7r@ zv^#6yOu}ZH{?|eD%OoV2pc0mm(ITfexd$X8jTp8eUfx6V9R$tckB_G~g1|+~rEPOM+u5 zZcbo>i#f?!tNJ}j7}Z3J{YeKvm8@91L~6fc03h0wsb8^>Dht%)ZGDiY(Qu7TMpNwQ zqTo*2-0a00MrqJ27VI%_{!}Q-QisTpsIwIeM559fIKA~^`6gV5n2id0;F+YUYjT2h z4Jaz0+^S|YFq4wq5%eaDYlxiVur#7>TvSVX(>_L(`m{ny=eWHD-4D21ffRuHyz}gLONQ`AVax{{WaI*6AGhIUd;#QnyukDZO zc^pxvWupt#uynuJIVul(2gRI$rnEahvUijuq&hq_B@m-FDE1aX2S|&N?kHh1g(*?w zlI)8JD)2~(d(A;t$hCiylJx0eh8*YNTaR+)wg=7!l zyfrO`O{qxPcgsQ-4q%kKx+aUsxVn~dCWp|F?W6)>wuo<`TB5T!LZP7t+5445coKSfi zLS&$=PDy(Onw5`Ms;t`{v;t6uI8d2&3D%QqYmnxiRnSN9ZT|qBhjoc(psi7kuQ00- zstQCb)VVm_6te#SL2H2HIwcF_RFY}QP95a|q{~}ZLryH%8)(F79SFqtAZyeFr1rX$ z$h%=wiPLPq4j%}jM#Uw1N@)K8z|b;xSJ0^oDxy@TkSM1ul1-k$>bW30k=PK81U!z= zY~wtXkpf&9hFCViN_>(VJk^1X5uyoGJMu}vbO>sco!O8EnVQN-My|tUc^;4=wm2y% z8;OYMKCMwdC9zlg9p%wq;avJ7C8-Hj-lPanxG09ST7{Z#3%M%GDHjIX3NP$*fGXwZ@!(wrnss@0=| ze5G;16QfQOrGejs0uVEWJz{Brjp!+N|$IpO(+Su)Bp^B^h}gT9w@jNt(!DSG#dg#Y z5{)ZEqcQ?|hqYxNa1||34Z&1eI@pCdDRjazB#I8gOvH}@I%>F-M0&uDm*UFR|_fXIjY(maC0erpa)I zWm8<*!mte(LC6r`WHS^jX=Q4B~8N}hQp!cOS=wOQd280Yx$?hS9 zsc4Zv2ePgH3lO)Ph+-XAMogrudi8qQi-iMp?3A{kD!psy>)(wQ?SDPXu5h1cZhl;vTPHni`o5v6D*_ zO5Mgl21_W(x{{mZ$yAoS5-2JBpRnhCFjWp@)Tu$_tMGTg%kC!L$B)o?ktuCU)sRF# zh0wk4fvVtbcRn!D7$QWnem+Iglt^rX)JIgulvYR7U)&Q384(hMl{y}H&n2~k7uLNJ z{SfW;q0>)uI2BN^jMH0*ID4US%`R0*0gxcc3Z_#N)ao`<$+Xxtvkk(r3Q27G3+D&) zEIwvJY~7m3Pj}o|OiGz!^1pmt!{&8ELM>9JqADP$t9lIQ;6q$1$H_?NlV;5Hy@Tvg zlHC)qYp$Xu7N;GC*<4Ymgmy(TlVS%zweO&xQ#iYa+oXwGP&-3QmP{(p&uQP5Q6(No zfq6juw;RMZ0Gs$L?qB9yM=DI<`F#zN4>DdzBqa%CussI?V`Wzp84X)Ydf5~x%P?i4 zS0vh~JjVhl9+{Bk{{SfuoAe4hvTh*z;)7r2w)6IGlAbMrSK z#Gr_wMWF>E=y0L~rjbT7n2iLl6~KxavaF z&muKLb$#LBe8;fnEDIJ6$0RKn6eqZ?ld zF#gNfhihqW-w|yr)pjO(#89rYe*>7wRSv|`7eQAut&z~yrJcvQRCbF#-op~BRn`<61C2q5hC#0ZkZFX{xI(rJw4mAs?_uDDP^u8` zOiswq(3A;Bc^yXHloGNd=6?bL2Y~&AyW&8(XoF`R3~ZGgNjUZ&8qFq>D;a8Qkb7&@n40FArVRxEaGRNysJG$$FO)B@=ksp;u%%*k|{RHEQU3!9--YEZis48y<+=_ zR(#^4rb?J#M{6F^Eqi(dLBioQ5*kfGYq=O_voIfd!am_lt#(6FADtnJsS@`xPIO`p zf|L$whM`JK3YjN3M6$_~N1DRDRM9chh|%O@!Xo6V4bhPur(9dtdW6jU-G?d@qmN%(tnG%qR zEr`NB3^prJU?w+2Mugk~VjdT;)tTb3Aq(GP6c8mM_ehCdMrn*ngmf1PbC=eA7R7hxR12Y*={5FIu5QT$5rh|v0N#9Z5tp zY7^T6qhTm7&WSiL(3m^j3Q3i+kH^Vy%_=J0!^20N4U_>kDB@C$#WGcr$c_r6*KH7* zB(^evMJnCwPNjkF?m}v;vMMuF=A?>r$Ay6fGt-jz`Z|pT!;gBt2F<*dy~_5^e6r3Vj9g@>UhzFQ;c7X4 z6qQwKJR@6lU+_|TufqE&uU~{0fi;T{(zx{vhY^?vsB%Z~<48pqN}79@!4Teu$wPPc zF&fBxNzh97LEN?^aFG$}J&UT4=y){}q>zv{xB4^AGRwIuttz5Z({f`-nUxUv1`(|} zI*sULSV<`m>~rA--C?0s$1spadjXH%3qW zGRN zt%KAcD?K9=m0c@C z_ozi;M2gsfZA42`q8ch9^g6NiPRQjZlIe&by#SgClk1Xw4U>sDNZ9ZyB?)d)B1KYK zTC$7~4rLdT%NSn+EfRvx5yoTDjMWu{geE~PYa>2keoE?{S_|LiWhmp@;cK-ka ziI9>eBSa4b7ZM%>A>kt)C_*FE<%ww)#@O(qx*-@T;F&t=74nEJCg5a~!!<_b6M8Bj zN9tZpZ%PEUXJ6p+AMOP(+P8vvqn1$(b=1>73L+ZL=%uci8S=&)9U&}O-c0psKV()k zHkE*-WQOM98L`!x?udB^>Nt>^s&64>kLIJ;R^7eH(6G>0i6o!+fJr2hJQs$=qFZLi z_@l6@m#Ki!FQfEmC-ETTmyCPK`jXk9N^`2$hBrq$j5m>x#3$WD6_v@nl~C;fK9;TO%R;V#RzagI3}YIR;IhLb6=4emlZ@hoAt43m1SNqX z;W(0HY#b3p=_rWv5`nh}=5z_C)NHqbe#qoqAozGHp%VnW-I4kro&1S&^hmk%;eqU~ z^TUy*N%k9U9I?Gg6T1%?K$p2gEsGsKU$_KwkHJpp*rV7Br=wlVFpAXqXf!fBSZ~A z#)h%n$c8jKjR_HiV#S1viTPkbAt4tQ5J1A8Ng)9OLQI5lA@;$l^5EHe3|Wc2Qxj<> zqIM(sqw`Uso<=8HU0Hm(qNO1#uI7hAh1FZ zmI(9+XMv$9#Zx1p0izju>iI)jIB+3ZJxxBK@`G;8N!(V_>i&fLzc8Qp`-#55kuSMN zu$|MmB!r2g66hs127ydLv}|CU`9F;H-cD8l^CQzl>{RMgs>zm6$Fe(SSk`giWG@rmhdGlL?Ez% z2{5pf;4slJI}W%&@Yu4FA|V|FKwqqpI}_O0GzXg}0QM3dkrqSJCW#Ux@+G0LEh1uZ z6sSv}-35kG!B~M~iee~0g24j8BoTtejCeKZXk$aGbnAhv2r;}Qmx(bGiiSw2Az-Ho zIl(v(gdrgd2B;-$LWibFh)77R)F*^uN;--TSTU$1DGDS|w#Q18)K&z--bBijX2|fV zA?zN};Z}x{7y1*>lO`+#P+J622q20p1z=H#6=V#8F_K9bXe>vJF{v6OLK+zH8ygsG z*hs}(Btl|h!YetGg!%$v6-2NS5?+Lr)Q#AZ-?*V#f?~ojfhVYh{R;`g34%s7BSpr; zSPu{~;!128!$&09vOS~Ofu0x{;Bh#d4kFqpiEtvY5k+7iqAx&!q69$jS{Ts@dR5?T za@~U@ZxIHD8IaJ?1&fFwAuJLgg2dq%6GKeMz(HXm35kkC`Urg)6i$*m&t^Hk%Z1GU>3xPe9^QT2h9iT`<2$5kVLc1Ynqo5HbZt=!qae@F)KO z1Hp(8j0~{Q(ATGsO9Dhe0uVt03jmV}AuKMyf(S_KN;sa6}DYW#c0f1~Al(4G#rJ3&401n84$OVQh)Ov0Kq3h$yn!5~C5a zaEuTkdIIR~#o)`03}ZtHhJsj}2ofMdQb7bIaw7`~fQ5t*CJ{(M1dAdet6_(jkpu}& z1cZoTO9}|W8-+LER8N3PMSzEYa?7aM4!M##kVm0H2ZF`O#CX?+#eS6FH7Zn9Qw?lD z)Aa-qfv9nr1@L%IDZwO?CyE408}t{2BV%~6+Auf}n8OWW7)PLZZ_v;|1Q0bi zK+yw44G=*LV!;wf-sF>p35*g{t~MlO5&r-HkVX(jC`#v{2%#9Hgd`y{Sc)A*Q9wja z2o?koBt{V4a4KgcJx4({$@E4M7}%0Wiz$Q*)g-3EQaBL= z5HvCfBN3tou_TF-CP_Y|lhBe$B!XCFr>pc}f&?lMhZMd#D>#HCEMQ1TM3aFw%Q4F( zy~rdalGu?qtPL5?1jOeXV6j-DaFTGGAZybkzg%H3H-lpmJIzTO86=g$3k_$nO>lwZ zVKOmrJXqN4=$}qQA^ISUAc6?>hVXb}(m<3DK^Y)L#IZ&MBMOo)LU9%v{{WDOFH6fJ zSSJ*co_IkXm<^8yib&~-b}NHU2rYz04em}dFzR0m`WVORf#6Y$#|x%}(<208qsX^6 zQ~hK~=Un5%3`e9!1st$J1Q0@5iwV$?Hb}iGB#~gt(K(3ATniH%c=|M)h!P|sM^aX} z5!8tRt5zjNI|U5Pfbo6(pCaPYEQxGENf7+?~!?>L2y_ z*yGO`onh5xE&2wD(A(UZ?+Pd&u*+)q7;!Xm;qAgKjNBh@6oNzTaNy#h%c2T%NP zU`H3E>GVE~9LVA3LsA1zl!`V<5Y&`PAV7wNFpMCKJC)q75J3!rJpy{0#QiVG<>^oV z+5ij#0RRF30{{R35Eu9U5n>`u%>>JL;Zr&gO?h3GPy4EtwF#ohw)=4O*_u4F9DpQL zYgMlRKC3o@HWtzU0H%`P=GNbIyZddnYnBg`(D%fGr*ZstZLZRHUP0Ae9#Yow$+Uu5 z$dgQ>;p@Hn)&&k?`Yo>6EOkqIK50eb!c1pK_v}k4 z79(tyN^4Mo^IJWCo=X{WK-i5tEd`QEzxVp$>mf}&zgl86`+^~!us z_i#q|sX1n(pkW}8@+8Qb#>?O72k8R2KCRdYHV}XIAOIH0aO6znr(Lj zj$Ibp+GsYbTvke7a*}O~0}QGX4j$?$B$8wk6x#t4GKj(fUD?jGK=qiJCB7oKT@(es zE>Zsg6T(y^!Q%i31Y(wiK_9db2@nY+w4{?suq>S{L(N@xm5K@FHiY$Q?z1Xs{ADT* zy;E2fw!4NCOY|{&1TH`e4-;$>_g~(-WZafx$n9GyEy=A~SPLFAB&sZ`O1$^8W+fYN zIv^HEARGGl!`5_&_Abqopa$$5+|m;7{SRIS)j|7~Njs8Bd%64<=~@{82>_5u zCYGR)qPN~Odf#uhl9NCw{RTrT7A_S2+hL>#6j>yaNhy*^BT#9=lQ#mA(NgI+$ByUsy0Q{1>J6m>b^`|o{8@Ty- zCybJhRb+><#Zl1V?3NhD*SU;hBpg{1VboBsgK8h@7KO2G!( zZ8X!`_^BYI8Y%z@1uY$JM&TrrX(W9ebx2Vx+ zugri*Op$ivl-QHK4e2D3DFT1tj9f(|=gX3M{oy;dw$Hz1+421W8d6Oiw%e{*rde_Y zT<9XU*(l8Kw8bQm5vl;anwzFA_gb>v{{Y;C*Q)Jb>q!IctG8F`#1^!ZO{SWUI)IM{ z_dN$))i0GNO{*l(IXZ%43JULyJ@;E-2Gea1X4oDm+Y@K|V=E+@P3_Zu%0SPn{{ZMX z*?ry)+gXfaGs!0b9DVim8Kl8qLP-H5nrp;fsYa=M%OeRi)9I$uPTL{tWmf0JqRWZ%yHzm@a@owBOm}`a;QR=#EknU7U%JVYbVZ z!tzK>?R*_+U5`Y9%hP2|6n~O^xt{M)f*wgJwtfEq{c~hVL&aJY7V-$v1}fhBMH^~J ze=5dV@3@R$YfcOVcBzV5O2~n2;|OzL1RCp_-MuuC2u8A;?YY_) zKLvYtep{2D05TQkK*$Ng4+231fIzH}SoybX=X<+hg%rE{3$Sqmf-_qCWHXFcCHZ3X&#r=EkjBD=1xPii0GS76LOn%c*+F zL_QM#0FscM+(7-p!VCKay~tE@iC{^4@|69LrekCMrAHz5lvIDNlb<|b$pJ3}Oe5r; zbW$?9L=v4qEy}Tt)Q!tRtp@AA)WZD9c9pv;Ge_WzK$DEUF>FkmDUTXHz7&ep;Wk5n ztK$5{q07xpWSt1_jle59BFwwd8W78;oh~4ZGMfvg$bWZTAp?r+wxJPMhE~{jHzr`@ zA`I}{yE!Q|Kqn@&h}B+BIZ|E1pj8kFi(^+V-wD;pA9$0h>L$#i>NW$9%tfv{LIJ`_ z+7dYEXOK{;3+Sk~TzUl=%>HS>yh41YyfbH-9;;!k;J3l@R43{q53M&905`~Lt+PB>irThuiP&lD@B_Hsn;hYoS(q9#%m<(-&D z4KRVtWSLj?u%<{>%MRS=P)dU;e3)^UGLdcT`OP5d0E~d>A2`6blXgax4UL5rwVQmj zzGLsTmP8p+%Vt{mv$O4l(u&fDeb-XJn?#=+asmoMXo?0Rz==fwBYh1ukK0M$+k|gC z7EA@mNXAmwy59XdYUUsUb1Bjk!g~uPTqw$Zt{JP6vu^Xp5C8`|CYo6$C)aQP0G0@! zl0pW0ShiZXuLF-3y+(n}t-cn??0`Ip<{^s2VnVFH8hDTlFa7uXZ@&Kkf90G@L3WTX zQrf>TKm+9czUk82`tbl3{PqSYG!uPFpX|$#qY}`@CwuR`+kgJwf4^;y8;}cP+iqX{6=pKqyf*(qH{9*Y5lh%XuVSpPFp<=z?u#041gF`t+93A5sjG z@nDuqb=uO}dLTt%Ewi2f0IZ~+`7Z(bwh{%hHv4Hc_tfsTm?ZdS*&>^#{{X>1_N4P9 zlG_)y^gjOpA@sDCX@FC2J0Y|HAE0f!LSGprmq6DS@3Ros+SYQyTV9q!_1k{S?L)nA2(-&|fZJi2 zrQFG@L=0a)wq13f{{a1{mACzGx6l!{-{dQ-5=+E#Y`3QS`|3!t*#QE}f17r+S+#hJ zQf#vOYD;f&uuY%V2=Wco)|!9+0N-Q*K!{)@86}ofzS%$kvesNQY?|NXpYQ#owgfe> z?=GI{HlTtA!lF&KQb*tIn*kKaliC3yPXU&{`)zOoB4oQC{Ig9gBO<_Lfx#`7wwh|< zw%YOm27z%e&!p`X1Jfde6KX7`*kpshzu)k+r*F9*Z}eQ7WP-#DE!k}nG@EVz0J7YS z{5mRY5xu6N(3tgqTNSkCp=`AO0FpM{+5KDmT>k+4 z)W~o2n*|5uoj-wTf=!ZtsVCq1SG=L1x&C8jMkZS#&lzxOLv&Dd80zM#`Dy!^Iv}s} zE>r$4B=nMR=dV8>pfBp0$T@`c2ll5@1fu@{C9fKqU)`t#-6C{IlHDk@Aza*Sk&emI z?vbQGpPl$otq?M^WfnD;Lsi#11Q7#4q9cbmPEv5e{9E3p+XDwA82+>pkrp39s4qF;RV+7I#T@)U`G76Nm45%()y7t$hRra$jJ0o)j-9Lx#muLPa z!1H;U;vz-FQ81Mo0pWgZsD5pz)O7j*S@f$Q$$kszFd%+LR>l)jwgnnV z34eoJ-Rgk7%&mf?b0<=?x8nu2*$vj;k4AtN4x-PXANkl*cO{uKP4>V4!~iQ100RI5 z0RsaB0|5X70RR91009vpF%TdyK|oPqP;s&FfsvuXU~tjl|Jncu0RsU6KM?06d{Uor z9^?_g(2sHnB%Z_o6Tu{qN4ZzI9^`wKdzEvZGG~fWbixy&5S(L~=qR5>GFh=B%3}~g z13`QU;T;3)E7-4N;yxqdJ}=+s_=_u~AdXldf;3b?N{Uy8dmI#H=je2=a=57b2q;9z z#wMRt?qvJ-CFr7<{3($~f-(GrzDRyZkr2O1L_{`i5j=59ii%*UzTGpGk`d(z8bm}x zRzT2&wl;bwkICfraiX%Jq{z`Oisym|Ac%;aG`&#~5fKnU9F#^*#)Rlf#*-}H3q9%4 zI}VvLI`Twt$X-h-j((1wE2pVjz%LZD}qPei;WhI!6=9g^up+9b%s1)pCaaQ zJ31($-$v47_H}rN>94DVaLOwaz3h!Tlk<8Ss9z&^`ZgHjp)oqIt-hh8G**ROx5IVx zB}9_!q;y;QLU~;eY@)wacNYu{np;dKl4kDmB__s3+&?Da%GaZ=$6s zU!$cjZb3P|kB+D1E7P78qO!O_9^=@x+NDKBMMWu(Q1QYxuV$C7jhEI^iS`;B$1|pn zESzO%tj}PCLf>ZE1>l?9%n#iP3_i z1x5^U3ENChstrLpsJ+TTTQd4Yz2-4RY>cijMcjyj3M1h+3ZH%Oo6-}#kGQcQG!0ga8C5KNYRtzMbPlMN-kKt4Wu?UCKtGi(?Ouv(3nj=<8z?#+f#ju z#>wtrsM$)(*I8Lgj1WxmF9y2TySb+cp4-6L8yCEZddM)-LTw4B*s!hP3*0?%xcU;$ zQ+;=cV7|p~p(f9Zf{NkyaH5MSkE4EsFItY2^j<92 z2|W*VNVUZ*;aHd_^2zKro=JEirN)6>kjozteWLqDM~utx#<8ZhJn)CsP7U8ig}f<1 znc*mF6)q92kvJ}cLb5l)3EzlC25H#vJ~}jx!a+7W;Jda(7Z7+5Rr||Yl{jJZz4iY)h}`% z0=2Ot>w{3IQ)`NfxLo+UQ-jV}?SyDiir$LbLFy_!gWqirv*216JNF=+q-KL;LZu-> zW{~$02u@pI`NVh>QHO?nLzMz|vr$Tlii(PicHJ35N7UN#Y2%Fzi`bq%rCf z3Gb%~!B+T=6`3IjN<=~t5paZP$?_nn^|~?=G6v;rgHzG!5m^#dj{t7(p%2q7b78+_ z3mJM3Jqfj=Jt+<3IetTUG+O9O-_k@zipshi52)1|>_QWWG!GrP^;jA>y(Xp2v1^`#?P?5hPaH6q#;9MhMM8@ZNq(QT~LJRL+3qfT(R~N zZI@tUSLqS1l(bA|xM{769SlnU00lceza+ePW}ozaN9WNs)f*D%orTLEPTiHFaT)xN zh43qstgLif9|}iCmw}|D8qr}@t~?7|vGt_ei1sfX7?o)c50Pt@G4&?XtJI$tGotgL{{Zk> z{=Xyt0O{xYHGSXb(MnHD)f$}}a?=vdNRZn^;b?eh*lz{HNk8L+t`B`4N63}Iv>$^( zxTv^XvHGlaB@r{%tY7>;f75U5^2V>b{QCFXXlsekLTxP1^hwcWiJ`ED=!rIwu|yI% z!`&_yHSnb2@c3vj41@4sgCtoYWmnMjJ@bBmvL|f8Wu7|oq+jt5_xl-N?712~@ALG! zblhr2%!lp65?CBzVia^vGBQ2007B7>7u0;A|};LT^-fof1;4 zm(bf_h004TrqUqlLjM4Z@-@Hb@_+hy8b0soS_+VxoThm2W@uR0vj)p-TQrP5E{jFBO%H@a zL?wUE$kso<$+!3T68(M0Hti=}tN|ku=>z!Ky=a zLx&q8l`=1JWs~Ilhk-j(^AU_r3N7Jyjjv*hd^Thni$q$cSS;;_>>}^#1^#$v@xx z7N2j({{UyBUG=e*t}BqKFE62Qgj%E$bFZ2HZhlktp?JL%vdpl1? zS!2T%I6`?7dKLzqHW>Kibh?eWhrAQY5(zlWD@%QwcZH%Ec1iCSaN3xz30$|uGQ6s0M6X^iveJPG2Nv@aj6jfeW# z{{Ug>_FtbvmiuhCv1qfx@=#hR#d`iHcaSRD6q{t{s}VChR}<`!39C{hrn*{m9qSzycguJ z0(my*S{w~F&oqfF@S_cM>xqJ}XdOilcv?^$IrH&FG5BJ=Va9oVK9t1x$O6WB4j0r3IAs0f<3lwU4 z65SO~12St3Z9XGZ(MNp81Ip6rTa&QWVP-80MjRev3Ec33X(BXq$#|S zE6A$2YbZ!6$`er$G3>&&g>W$)$ zBw?3}6BSE|w)QU|n5m7lsAa5TB<&|8#avGU#-0mQ-nc?VjIz*_S|2s=U}&sw!v6pX zCX?|00MXL?ufWp}h-8N2WIoiRQ-o;|y7+F|8@vsN%zVVt+3>iHmQF9EAYubxG2mXw z77=5>qi8VaKreJD|zt0>6cHHs-k8E zP0xX&VJVs+D?^?og$INrs9H~ul(Bgj&4fGdSMF@vk3HtV&~&&xd|-)4<0Ui+Kv3V@ zY}64HqsJ_cgtR?|Hb?9!wf-2uEWl->DjNgXXUs8dgK`@WQBt@`E}TL92{N9MPXs(3 z$U+UtDlqLdniC;`JaF1Vw*FrUnJ47D&m5_d4O%}V9C{n7JP(vINHe?-RIdzULRLfF z8?qbhn9Kc(9E~1^%L4e1V15w%0!9YY4PF`((ApB6qg%r;M7@MkF;d6<4``T`ENPzL z$S>>-qFWMC2vm{aZV32gW`?w5Lr_CZq7c-gYVdYhKGG??2;nu-J)3^#++&pYF~l=* z0#IJS-Z$-yp8340XE0T?qYnZVJ%Fq#8_XMw2JV z+=l6BwOkt0!G0VmGAPePc^&Nw!YU!;M1cLFI5gf%Yb;*)fqUP9FN4`cO(Zqr61YQw zTVT=XO2T3~$i`L=6-V%p+`DwlXWTECr^`14hW_jOG211Z8pq;8e+#gUqh!!&B@yJq z>=dOa-$Lebpkm;VWhYy~q<9-|jPN!Hc@-Mmhrq_ofeofyQjh)5gcx8uVpAO~SS=jU z7~*(FnHnQcgcF~Uu1k1Zh;1?>OT_;Gf0N+G4L@TXH?W(7dzldgcLgDwA`{V#6hcB(lk;+%8#rVo8643T z(-q`m8zuaZH}^gkf>4yf3Bw?_k(v=T!a+to@U;omQM5EA!ynYrIC(?LLVkztLifMZ zEitq5SGd)|5O1*AjkZ!LiLv~#tAFTg@-^um0z9zIpJDVarY}ckRUPLdO9R^7Bk=zK z-r4a)$BOv*2VDs^C0rzGd|v^p48f@Q&lWVwVJ9nOE(M|QiU*?)MI*rQETLr?rZzDu zoe!>w!a8h9A35@$Hy6x&qi>VvV|Sh}b@rZx+okKUsI+3DNceRw!t`E@l;R7K3Qs4W zN*GOHa*=!sVj2;qSq&jjv}|~MQ>bGYi8T5v?L7;!`sY#}_12So5{CPUwUItV)6)^B zY{v}|kqdg~(Mot84T%uSBqltMDhZa1VwOkrMz~#vp?6_|_FA0Ae29u)LYphxt@a;- z5Yu3aN04ggp0tuT{p8jGtr+%dlHkI{{V^KrQiJake~a8^jq4- z=kL)t-wOrd@XOIrzAtBF9~YvRrW2o@+vuGOqWuRvefZxOrikA&wM%*#S1+bcH2B#j zI{w8V+~?q<>7(O*gIrHRj+@cGXB+BV-ftf~XnhzoUNOeFy^2ZL*}f#=r`Xw&jdWbj znd~f-d^b9wJQjd5%@XYec zQm-O~g&#(GzTDE6oO1|HCqy9#P9X@%(O*@4Fle77Aq2RH{&~q+eGKZQ=LR^uQkRTz zg3c8ei^L~t5pfY0IqYMjBq0byLJ*9MhyTO?D-i$#009F70|NyC0RaF2000015g`yD zF)%?VJ)_z^quM>K zpdQAd>>k1F9?>qxuzLk~AdJaMQk2P(l%?5Bmr8T!Aqcm^XrViVH8{lMbg%Y`(+{}O zaPIC&K1JVuPxSX6@&2CU{y)>*`hTap^#1@wmJUSFm)%etU@j0I%?%+j0^XM6>>hmj)V*4c_0MozE6d0f}FS z=jZ$$BP4nity3%VSGsMQV9_xh8|LOU|gnR;k$Qz17Zm6WWdBGM7=OS>CyfscU;ktDd*jTa+c+8;D{)s>(^ z%HVxl1cgOhiKoGO)U65K(C{1&Ini}KJzacKv9mamK~y4mBe6qe)vrj21gPCFmL)c~ zWzv*uU}~rvvmQFlC&>f~1gE0P7nbhezeR-GH&>z#ee^b4rn6-jiRqG*qfXo4#7X0V z8c+0Y1ok|M93P{a%^?Uv5SmS42tp8qCeLlOQKZJpJx)Z560KYfx6y1K4$Oa}r?GpT zy&NGoMnVvTAvBsoZkj@EqJ!XRJg$-!yuq_tqo~3tHFXMPQ*`gJ2TqPXlPW7o#{d{G7y?iPeksmM+LGId?7T1C#{6vz?$W9 zCw(B@*$RdTQ!gmP5CWtVMG${%CFv}PLBUcQ zp3=(dR#9Y;q*^AIt8t=LV^xGVdZURAUD0bgbjcY6gx4FeW3dQCLpmm&>!cdmoFSgU zhQ+$BR;|~nA3-W4I2s}Nji08lp(czqvh)=Qg77TtTx5F|iEsELBGZmb;EYL<5Qv+h z5gH>ivO5{2^S!R8EgKs+9`wA8!T62eSw-X~nAI9w&GQQMrNVRiuTY9Zoe`CAtv!Cy^zkoSn!=WH<0WQ!>Pax@jCSE4aMTi9%XLA;&?g zG|JH$AvLAe5QJz*+)Qf0QCLYL18w!;85tQF86N4;uwFz=ajgeiTN+DMsF>;{qR}n0 z$q$3wql+x#vNgsIQIUy+QwSj_f+2i`9|jW1L_{)m+z?E*A@wHNwrHx1TEZCBXx5=m z1w^P~bR*P=R3oAONHQYPA5AzWnGQ5&xYdG)5*n%$wOo^`Rg+}WUUW-X?J3AJkvOPG zj5!#*3qU7k7UhZDghWW?qZ*oMa3#QuDTp8@dkc)oM*2-$2{ni4k;D+oQVAwb`whsD zVg3a;8lw_xM0YA_qTae;7$RfnlY(@HR`tl%Feg3e$V(+6;94aX-gpv&X)4aaX4R32 z$YqIm7I32E;7i;jb`rQ-*ta(Fj>Idxqbu5-^+{q~7DO_cqX;qRUy-9k4WQh&qXs&YBlnP zD@3fMSW*s2!+>QebxD%fBf}cOTFO1stD(n6GB!~~6h=p~6KWF}V{MRvOyy@x5fg4S zghXrJYTO?1wHr-iY9U8jiDFG3BIBm|UA8&86egLhxL0;II?$1DMW!{zjohP>MjVUx z{{W1 zOpFG|Oi2?<=(&c3NZ#&3!z$D-`b}{|I*PlOQ-0p{3{!g^&-RaHMY;aml?_q7`(F=DWJtN6)2u_`b z-bt825Rw{A3r4DNCi}6Ke2Lc6KXPL7!Ci-8a6KPkZ*3)F?scxojgOv%@vkxG_Z}Pl z{=yxA zP6^$d9;iGi;$lmYzQS~Tk{V+sqGtTG||He;PTy7u(ie+BHV$Q9KQ$>@iV*%-fI0kIy_7 z!??Ky=1?|JJwX;<%ow32NtZ41>DYWE@1uE|Be1kv$jO6}3CWWVb9;Y68cT-%0QLSM z+~K98(W^%d8I~UK0lM2;d-^PbGsVNPT10=(}s(aoowIe&C4P)z(aUYNHs(63axvQhZ(;? zZTR*+{)r`*xgNui{K(%!>|##i13n`bW^%l~amTy&9;W7`YnA%@ou%GqzFkiC!kMQ^rN0RmHYiV*W z2CXhyEu1v&N^k1@g&r84!yZQj#+u~CG~S`9FF(RLAPEoB_T8H~2?ZC?Xxk{FDL+>;YtL@27e4K1i4B00n?B37~NLSw^2w@&&k zGH>Jl55MDslKsBIe@FIQzJ9~#JzAR1gG55ujuJ5qjrhPF42*0K+Sj-~OXE_76jep%V7^{{W)oN_p@i_&%Q= z-o{xuhLZ3aSOlgPQ3{exVO8WnkSOj0ZYLZJmXOV-8iWUPD=RB29!gve0&TpVhD2se znHqk<_xx~jUq4}fkiPG;q??=5cywFL(JpBc)ohv~>{?Grgy2bu>qq>_Fv$hOL*Vdm zXmX(NpTG5@7$V2d{%9Ak+$O0N%`H0&JR%Y{{g~q&9y)($Sc3zr!x^*t(2q;TMyw8^aTBk+d$(*&w{7 zaSBP}xAufQ47c(sVTkHqjIqsEDE|N;Xp-=Ut~l-{H9=CCTFebQ5!{}{K2B{ZYT8_q zCb%7hK`e_>UDMVOSrZgaPe(0+_S5K2@1L;dzZ_{7OR&1GLm0m+{1rq7hDj>Ml+zmmf^JbG;pA-*_kYm4 z3}ah;^kq!M^~i4Lk-Ci8gP{d$AT5_3JyF7 zObbV51lHcxh(ZiVKU5KNJ4j89PXr|r9u6PAj9k5HFjQGoilgFed6CTw;iXt3TnqeS zbMy8MmH6QP@3_A&gO8)YSw*#rkj@arCM~Z{6Mk?d)>_i+iZ zkM92fL#m+5$V1x4E;seiNx*%S zhP4DY10<3{W0Zolj9>Gt@S|r_k`Dy zV7XdZ-3}hQWDX)%tWE{{OJ}(F`8T%tJp#(p8`w3lJV0exr-o5P*ZeFT^fpyFCn&= zM%XfKRyLawI|(Sv>=L4xVw{N=2xC-o$6?g{hXN3gN7dA8mxrZ0%)2aSY%0@!x5^d_p%m4 z0`3S<#-!B{=4o(G#8V9pkH{s79f>$01hsfuVx%Zztg+ zJuLV{egsZNX>wsjq05HOLhv?`N6dkf{yzFr1Z{&f%xt~L@F zISd}dfgRU_?dX>biF>p{r5T4hRCgM9WJWs-78j6cxkRd=CuBbW`~&a}+CFwC<*`dp z(NXiUToa+@G%~t`ahSO{DVL`b7Ob1(l0E~D!`UE~MuoBI zH*Fj$T7EEuiJcHgn!O&2bQ0t&5k(Tn{0xyJ0<`jRkAll+O;(;pPa)}%=@Ak3+A#76 zN)6p^h z#A$EO^q!r?xuHs3GlBk*8)#OZ3T^SL$dOVhfU=4!$x=pS_(K&Y2EM~#K7h3YcO@>g zctTyyN=&E7)JJU^I6OlZ91|I*P@kUWoRH69r)D+sA^!lQYsxKhg&m3TCTUd0kpiO( z!XLn!d?U8{1>qBUV(&As2{?2XuX-NWs@IYabeM3CFw6KvQOU*pv^E#oKZLqiA`pac zww}P0*xF2u-i%vX9{J6qSqU1bx*}SJRvPN?Q6c4sMG(0wT#)ox9vJbcN}(YQA4+Kk z&ckP8*gc{rvU>zO34M=bh1*HhT_wo*+V(z$(hyi6-p-$pJ8ph}nYy+GAzuezoa%(< z22_r9Y)iPu>?a0ti7_^Z3P>a_G|0uN+e`W)7O#5bdtR?ctJ3RBr5hYo+S_m4?7Fs) z{08q%5SI*RVY1~4XqKs*B9%m@HeE%w9mSMzJz~*~3kD2mnjw!LqOBi6ay_hDuDI4| zbwg1tBSUPRNx7u?MED};ceGm(M$uZz8nNZoqQM&)7~u(Ajo)#Ce&R*RA|ZZ;w7nI` z#j%TZE|;M+ZNd{r>1OyzQ9O`EcoQ>-jdD)nDT0%aSDF#PgdsL1`U+azTi&@I*RDFV zpvmg1D560pb|vAWYH*kp`N2g6+&E-l_}hO&hXpS9LTZMLnKDK~5pBC>vuyRSYiE1qU*_h1?gvW+h;~=JryqKO*q{MP4BCBUH0_vRqVSt+k$C#O(yPn z=uHtO_p)gT)A;ll{RVm&uR25HYv**{#n7II8>ai{F4#?Ty6HUYcJM{5@vPX^+viwK zyz4baHZt@tgF9iJkoonOtKXw^?WYCO?4sRz9Bt0IMbhrDt6QQw>u#Ls5aG#m7u7@TCwiz;KSS>JeO>bX~nbPzq%3ZvW;8dj^v}7Y>(rHRp(dSBCeZ_(3-pQs| zlp+?qZpOEvHo_2u((T5Sw^(pe-8tEkX+<{krP2~^n!*!Y4sL9^Qt82TyIV#y<65@h zx_oSxL@{rgGHtq2muzHO!m_hI3+!a9$&)7}dSuB6LTmdUw(r|+bjcZ?MV;8vmux2M zvg1dH(?5 zP_ZJJ0Kb#wAJl!pIUmnhH%Ir@S;hTzgYbEY#Jtake3Z}!kp0acsvmKo^{E=R@=(XI zKo4SJe0-#fr10bow}JZzkMdqb&67O8QBM7B`z1c&L*5<1>3`;+)>mWcE49R~A()K6 zGknW+h@8u1_ha0_UbO|^-eCU#uuSej{{R!vgX=H&73(~uI?AKD^B%N0ncnECCY z@C?s12T7L?v^kGyq)$iz6QS6RfnrpVr!OV?pUL^wLzV<>oUR9S{Rkkxt|zlU36IO? zT+VUvImt7^ei$Xe@V}_7KM5D7;W5ZB3V-)8!G9`6v*e)LeohZ>$UjlwUo2j)=2!Fo z0Ffd4?P{RKJya^-)1fXn3Bx2k5n4V*ky#-7oPGd-^<#C($ zmhUYdgu98@{2i%jX=!O`X=!PBck*Mz@P#!qYWI(+S?CA%KfF(Mlr()l(g6%kX?{ea zz2*B+m5ZIVA0zQ8i=Bt&E9L}r*VWXxpy}={L6See=)IIkd%fi>#D$)acerziyO&`? z0qp?j%Dy2%sh-m}8#f#3%+}eTGcoUTjZaB_pM&`Tf;_=_iWlZ85@V$Z>qYz{Cc@vV z$@)hTAfc0-7CqsER;h38%G=1X_Z$ydzqXa2=}gp zp6T&4J_M6+S?+$NLYJX?0w=JK6Ev#yKXG44&GQ#my1VRz-MwGbccGV&^;rpSvnN?P zApzfr{{T{kl<8005vqLu0JQlXU$~;_c89F@mVc!G0Njrk2epaHXx*?nKdM}d@#63|=tOHKN{3-@a$;2+g64rP%AfFJKF9$n z?L#Y4N=Dbx$Fyb3YopX=TaXt8cBMTkRhNnV#X)-!Z7V?!;Z@&3J)??v8GxlpYq?BK zSp&OowDl1taL^96Qg<4NXTyJ2J+A)dpnafEwJ@&rq`@B5A3-<2!0D7#{kt)xZwvPl z$Eg1Rs2{XH)Y5q0;RDflBoF)&v-G7f93Igv{{SgwRq`XazL@McpYoq3P5PfFNA*8d zpXzLb(E6LQ{;Ws!5bnX>NuRYAKAZhWw&6N{(lgz={OlcTxc>k$45U|{ftJpvL)`*_u5y@E$np<{DKgQviLO~80n&A7x2M(&@cHKpp142^88-7yA${^q||>0JRf%C#}f5 zE}qY$Er=aP$ygCH6M14U64FU~gP!h$wN_qJeFle!K!Lls#C3gL}WA`GFMmuj4;62_eT>*?DgxI~hu;*j4Jkn90al0x2ycJC*HbnwMtP zI}!c30>p4mf}i`K{1D~DHMS5PWri)oyhFS1E8xeH{H!Mr2y<^=TiHK+;C0l;cJdsWaw*=^z@Ilxv<(qg1+$ooj z^<@X{W@_Pdc`W*u2;coEM5&lRg~Xy3bc`wbsB@!DdWqsbs7Tlj#;Lh&Wq&Ag``GkO zjIT-Y63!ws32#Ykwq{!zOxfi-u`lw6F$qhFPLszH{{V-3Jc;B?Ie{vrXLDVMx6HKb zIIedYM=a?4rA8U+9><`~Xw>BWn8p*x`(b?&ht$f?s|pFaZ+KoEG@K0ImKfC+nx5i1 z<~&>wPYT!FCZ?ca-!&e@sif3)pC5>=n)`pLiPz76HlGt?oOn2#VG9z^+y$r8nEV%6K z?eWrD$2!03*%Y=~t!JFSTthr&4d$f?2mVbDX)hwT+&(mX;`s^C5j zAM`NMN~yTxj%@L#ns}MS2#KhJiDU#40ScawCD-6*nO);mCME}E8AR!OsF>I^h@TKD z5i}J(Bh-Icue2MEwISXCqEp1Qf*32rq~K*eC3c8-#9s%rcUjS2SS=S6Y^mV|;scOl zD$Ktk?dx)gfwG}?b?}XQX+*kH5jFD~XH$r7P(Wy5cI>p@I<6XNcI!c9~k!&&UwYfMMCq*l>BMh z2?=uQT=Ih=IA90rRSu0M$|1NW`?e2tg$lC>^a?l1P$;A<3v^j|1^I zWu9T*3PA4)iGAS}0f5U({srM#n6F9Y?alBhi2LF3N8q66LsKZOWh$VTG$ssq4T;^NOJZ=(V91JY@!P5ujG+DrC@u=~e- z<&$n8rB~s(MCYWe?kGf&fDWS%d`pkKdx-aCtic^-SoH5*L?srPPzXoY7qaP6uXuTR78KAt3@;H=2L%*RHgKh-@n0sAD{Id;Q zQ;25L<=1CKchAxZY8=XZWOg_6In28&hqvn1m<$*vqD_6+_?If>jx(+ zKv37jp|-kZ5!q2zGjf6=nQ*QJXEacqRAZ4?D`o)luhJ?XaT)5BnQoBr2sr#)Ac1oa z!l7`1`~-C=W@lKq6y%6HVkh8x&rfNjtVBWuM{aEsfrYApwNN$=i3v5)=lDH5Yf#Fi z#dn;X7`?(m<}haf2i%du5W|#NWtUK&aKkLf^@4>WB4G82#8)ijE?J?Skrr~Nx?7pW4^TID-%GVp#feeG}p#Psu^UZ21W3HmN~1# zgC#iWF*$@NGj1@e5|F%MhJ+P8)3V4Pr*vZY0SZL1AscB0j*o|rZjosq%N1n* z0D}r3oHhJ-Mv!A^b8v)VDf|k=iUh7z%uhLw1|n8f{B|_r2df@>J-;DeFyW*FeB#j% z&sHC*uZTK1>OQhP{qxHo{Sa3|S<&E>a)LQ!cb4ld)h*R78%tGMSN;-*KZZyUOPIaL zz?^@KScCv4N%J94YQMnl!6VhiZ(Vq$;Vl7mFzP`A--( zh`>G5R9_Ycxbp*mb}FwU_P%q{8b*@gcC#>%iSZqOWd150+(_$1AIO8s#r-lP@ATs0 z-B2azPWF!n%Pp?eW9Bhn%A|S-UeeXSkWcjHU+niru~lv=Vqp&U*e=Sf+#AGC5Nj+3 z9I!@$a3xrZwuF09WP#P)ZN08;UzPO5dGwq5f&Tz6si7Yz{Yyq`IbO`OhziVJb#URl z*XWsS1E|~wQGw_|TPk)@8kEX-i#Uyui%~|S7{n)k!+D96Op?!7{7Yq-e$M9RXEYic zA>^Ax6Jv2n-;BSk#nsFh?SS=&k>e+-E$+ha`XGHsslZIxh#f#x%5{}sm+c^}Wdpm= zgeW~@q5c7UUgH5xS3i`$i0TVNYu?X_oac+F;@OuW1oHdJo;Ad}mcp=r>o@pNgsA2i zN`Z+|swKw|M1S&F=iW7JwFG-HFjumBUJpc?5kpbuaC)#d(oNOkh4t|UP z%K2q(SfiLO@D5;FM~Qb=TiHsCVD^k5HURnr9!TkC>HdM}aWoEd2N(doZ)Lq$N_Z4R z#YP)S4_QQRrIvJ}#6X%!`l|dy0^C1I7;?IO@TMJR=#OeZnpN(;tkDxLx3stfTn_r< z5|*+TkbdTnyr1vzQAT|if>p=RAKXtLy{FVEXg2-fJAijz5Ct<{<`jjIJmKyK<^%v7 zy!*dNdpiiHt*?n*bjwev511i$MQ>79nA6O=Mk1P)Hbtm1mvZ;G*KDUzQrIk}7O2Q) zKT2g^)9|p$BLdgTAoxfmrtwV!D)b=3LZw)oHAV5Scq+eY9IE^PqOY_ba22Vb0J7XU zs>P5-q>W^^N{q5>iifjU3%4!ad6;}cjc!!V=BF`n)aRs5PaPnxluPS{`z}7(C9hmy zPY3#WjgoCh?VTN^Ew$nS{{Ue0DLs?1m-uGd3wjU@gQ`&n*W3R9W(H5+{Ga)U{D=4d z0C4{Rlm7r`{15$~`9JnQ?4R}>KDhq?kQSNglkAwc{X5KfugWGNh>zp4T3OzF%#P!9 zb%{vCb#luGZO>afM^whJ1=CCL_LOGqnQ6>J4q;i`h}PktHX|-OF|ig~8oVzJB7VEBG2cQ91wLLIo)@zwDa(53fx3-*N5jsT~S72*q|6dNxrLS3Pj zgJ@T#{l`@%z&_z};4R4O(Nc6m)t?b?HNr=tC(OTVck?Soq*zKjSd2&sMK$cNa?5xP zC7FKTWlBzkw!2yEnzFC?@WvDqRaboiHE9DGg zbSO~2a8s3G8jH$O($83{)th@8?dTg`#$!3=fJd`O-SH8M+Y!}W!LG3$Q-6fH+EJ&i zQRKI&_fgcl{A!|&6T$nMC~;ACofmV;Xba$(KdM;W9#EanWBs4_7{A;8(%ZHDb(L?} zg4i8YKy`+DoG)m$OthYls+{I^z2GIp3o zH;>(}PUKmMez5MuqF+czbYO92OlvM& zX@}(eD1zT;Hyzmm5#m?Zlsz6jNiyIiKpoLXp?&4C03DHMGdixb=riz_B#r_*t9w8d z5B&h1kTpOhkT4x3J3)C^19s^=37tjn{^ zu@JkN{{Wf23rAa4j1X|Ki8yffijV<72D>D|Z{{O0eitp& zQVDAV*(Lt~8WCP64|5(MfNpDCP>>G%_8AD7QMhqk9O!b7;$=|2wov{|juT=M= z);$=Ax|a<`8EtP`Zl%ou-VL9Au~E8CDyTc|0BeYWWVIi_+edh&MTG$D>%~1~=(f<^ zcU>M>$n07rotKYe)@YQB*L>hrHGBpES zd%$)wh@^U1)gY%yd#qweqL;X~J;)5Pe`Mdw#6nqX*rD{(HO300dauyeW;%hYwLfpe z4{2wF8eO4AnEOPO+(u`w1!rH3^t-P%J3UT53XxV_j@- zHoTU4$5v48htNSA8kAU(tcq=}`kl|JoAsCZB^(SAv^4I&CL*&eb33z0`Ia%L9!U!+ z(Bb%=Vh6&+J5}2aVhzJPh_nmhJ1c*T#J~fozjy~Qpi`)$-G_Gi8a?0gb}r)IIQW{C znilF+pf2*f#Odt>bpcnOs)fa)Z$AK`^B7clIphuagk^d@y_`8?(EX5kg!V|cQNKzL z?E*co{O%I?p?!(#e){Nw&u0?$YZD<|UU$$$IEqWbY^yNMt4H=rF9O3I<2nJT$}_gi zL;3)*Efa1s^wdl!4l;<-evZB3?a#EqA6#v=T;}4r%{lLNf8pF>QQHTRhAr1FU?)Ryc(@hk?^ z-TiF#hUuQ^K#2p2qJh;|nrtO~!}gvIV&G)4W4pM8pEy&+^ggo&C<;C%T*~-~*s5gQ z3MO8V3?qn;TBa{VJQBw+Z!t{|OO2f&-x_mqSg3}G^qQ6EG{M#j{BKSn zB?=vh+=2l!MW^wvXd=M>00Ma2RmX*a?rGWgBly^|m((vXi+E#fOpjOy&9tXp#p~68 zZ7e|)`T(w|b1EsYD&pB>EWLw37y|$Si1%;@po!FAAmi_7C_bdi{{Zoz>SZfkUsLLuyFDM+J^J&1IPaiyCQgR&iI%M)CYE=bNu5rSU;M`JS`AxDKS8pqa82}iUMU7Ec5 zwD&=p)i-E>7`E!YP&S!c)t87DgY^l45g27utju6}f-JWoNm1I@msBd@=3e!#P8jQF z(}>loe+DsO1!l+Ol=UIo*0h3(qmQ&N;wqhZJ|O#-VR;oj@TfuMeF7@0J#-yk(V1oW zeVD)aLV6x0ul<_XW6|nCG!9Vy~ zlKY0!)gNLq7M_pog^C(}v49+~yk_NJNEN0#G$tGtJ4E3ThBG5kbrw37Y=)r{O0pq} z25b+TejN8@uZ3es$=(fL~aNZXQ4EcAC3q>QXc6DMS6s4Wpi4crM?@n(eJY)&Bqq zc}D(J3TqI)nf*iqt|h6w(pfkvcEdJrmTA4Sl7YK4YdmQTQ134-&qKWhVG9DP8-sXLH_ey1eob^X|<+uR55c-Zia6p8Eo*qq* z3^{-<5Nf3hV7}vH}qTeyI+KnOT z-{K%Qd${~4I@71vq%P#?SIZ@<4#gI8{{TEi^gO@n4eh_sPm(PC;FsCIO+gGpHonXV z$94y+2N3A%?)pqUJw@z3(V$CuzD4|?Byz!f!zs|g=$>Nug69lY)V~>m_XC9CYowzi zb5CQ#`<;_;k9fV5IW6fk>|4n(sm!Cc%P{3w*f{HgtOEe~RU zv|TBHd1LOfx-nTUD0BL-wz$b<6Y&k#grPuz!Q-$R(|R?Vs3;FSTu;N_G9LqRwc4XqH}1?un9q*s#V z4&y*N=pEE0UgAu6T%(Z#+6XfHBo9%7@Ijj=tVbYv4_J#u_#1ttw{Y3^+zN1or`Yp%@0d{{U2>Yf()C?^J68sLWi7>zfKS}31*Vx+99Om_P$H%2EPE!AnHfi86LqE4 z$KK2&TN4X3j%0mh*LOYy2S{I!$P%3*2oPdF3c%?HqMjq5cqVG7^tUE*#}?pNX0p1E z5lv*bDKQgcmkfJH7)QRB%{)hRbh)wNwb>$X6T?Hy!ka*ct;yM%!Qj3(=zT6Tu)Kt* zE;v8M`0m6)OGWMx3`O;q_C#X!WhD(1k9xiaQ%__)#7HtmBB1bYyio;Rg(>cRM^T^r zP1nQ#B>n)DcZ0MLAWAP#A-F|!f%veczkohqA=fRh(p>`32kD3AF3QBdS_m1=0>kLb z6nZAlSui~=YY4aA%O|M-nz@qIc8cJ}J>sJGE|;)cHddFa;g-kvEOdRihk*2th~I8} z?Q7mFMk-vu&W;?ukOd6_iAU^?vg)u!sL)6<-ZU_!xd4< zRj|4S&k}TF@go(1hXq_ z044aovqqz*NR+;u^u&Km0i&Q`?pf@d3*On)ZFg;eln{i?+EUs;|Wnt=noZ`Qh?aCXJ$M>{{Y@Y)&!(0{{W=2vr4ePctBlSU7l{^2Vka( z@_&-8Y-5su`k&DN)fVr&D(ml*hc>O1zoI-sotsknV2^oS`Ta(+@^{3u0Wi#Im4gls zQVYv1;eg}al=1Tm!S6aF-YbW^PfwXnkG!MSJ>KzMn7tWK5TZJgt3%Z6;y=a>HQNq} zr0mNUcx`(*_t%JY*R2&oo|S~l2|xs-wlKfc?&F@Yo7vQl7;L0U{W5ubisk6_fUe9K zwa}I&DX1vEZiVgp777K?N5m@!;eM46Igb&chRS8FL}kv9eWj{)r(#-ZsC}m~aW=$2 zV&O%M6&ZOieQ3k#FgVd~=!O@*AsJW~W3#_3S<_5xelq^%^WT+GuAs~!MZ186U-gPZjZA7yaihf2G=}HFmT68aHy<^ zfg3VqFh=}Z<7(Ln81YCqn7m(sghfdx1AiT+ zNvp5?VKxVU^Mz8n1^S$!if^$s_JVRsq+93S3ttrC1)sSK<{FGa?;A4mF|<|79y>tw zk*2)|?^5It;acpM+69xIq4^wfjTVb_A`cY8SQk-|;!(|Zy!v&Gu=~ydItX@K3s{^W zLKjq~s$C=>(6QY0j#JTs2g(9$*+Yg|-SG|EM8v}&H1&$5-|o171V75)WDXbmT(=3- z$HbxJVZ0Fw(pSt=cN|>qJB2A|Bs+|GYnnIuoO&mSm1gL+JMHFImN;8+cPDN>&nya! zVpx$`DiQ$p8k)=26eS3LE=CN*+l4rPaQyGN_eEPX(%9uZW|SX2HTt#KwrNta?^% z=I^FcG!R1-Gb`htcOAKg0)S}ZBad{h9R^E@@;OF4ogNQ(xJQ%R98!S$c;Te^#r_-tH z96eALGPfKtAMJ}s!*J&X+UR@fl-D<0_gQoa=X}~eW>owP;qV{1+Mc20yXs;3ao4SW z(w>FLS?=JeQ=n08oHrj%l9x`b0q7ymNE7V0?pRF7V?x;ZpVpPqHb&`>-IlBU1U_Ks zBS^1tC4o_*AGS$sqvQNI5}7&q>Iqd*WFzXY;&DLA-?02lfQtCbMp3wdW12>$#p%c4JAHnPr{P|!}>}d3hI1rHP1_LV{ zkawe5#X16pv5V#dze^Ca2h_2R92zk2M1Soq%6(xLW)OW@lTbQJ9zO}r@66cX;51Gk z96yS)&JTE&kw}1}SAq+H0;Cr?(dXh0ftM>foUe9c!az`ZfAFaIZLfaA!7S@A@WjJ`&bl3m>>fN068sF1GJcTB(LAk-V1P@Tx)uVP>wzJr{q{{XI0#3yVa zci}LDdXL3IdxS^De&KOmFY4g87u;5lSZknO>k%_a@VR8XWpbhvt)KmarZ5Mor+D=`P83t}CR6)7ojFfkVp@epb=h)aYudVoFEa@e;viS220 zSEzvZ9>g>TIyQAy-vV>HRDwiKrt}r?*tO+%YA4igePf@y49an!X;)mPekPz9!4tico1F>B}1J)Py0KE z-~6BO$NZo8;B$ZHnZx%&zi|HmkS8~b{{SHSdy;|td8QEC3_vLi zK#ISQ=!@BdLrCT2@!iyga>Z4clZBNS;ac`~IK+!_UDj#LfPh;H59>tJy(- zOYMxfdJX-d$6)qk@@4*(WyD2lx8x&*uDcKQD8juaZ)u*xNSc|kj?s*7#H(19376<$ zHHZdLMaOtzWC#BMr(>9wUeCAk41fz)h_3;Uwuj;jx2pj7A21GoqNiIvh(nP&q?YFn zj60%Vv^a#K*RLxlP*}88RltA`u_!8?-9-yox9?0s3ONjguKiVKo*0G#$Zh8EhT#=O zo{YX=5LG!|g)U`AVa4>b@U#xHk{8uhfw#0*Ad(u*{gx|>q0Kl{gL zSM{I$R++at%^Mialoge$y+G|RBCF`bj5MX6;J&atg2-KB;=9~so*UqTxya3GWCp8x zm(y@O6{CHiz73hHfNT}$P)Pxo2y3jGhI@JIN;t3sAJ3?!=~ z=`d{1fhXboHwo&53a+ITaguTujRBz3A#1?2zZw$6fJdEo-r#ecsTx#fnKy1XxY-df zFjyAImg4xq%g#9!ShZ=awYW~V#1WF3kXM5Z4v^>tKn>1NBZ?<5(eW8eRd02Faaw{6 z0=;kiCy}hxOEu;6LzLulT+rTNTN;lH!g9C?vY?!a!@pKsVxaVn@Mj44m@1{EC$SDi zQo%#=lEIh*M^R$g!`3!H_m)bp61M;bK-3870BhBNK|lftP&zsKrFAo5?G^!x z`Go9Y{GbQvdNYjLPSK@D9+xmWv*S02y+)T)$MCmYO-xMj<8+zW&Ei~SQuQjJkf+lV z-gn<^9$qE8ef%Ck5=%q;P{OXRMr|`D0qUK!~s&m=!V;4 zH6L#DpYQN)09&)Wl=`GKu6p5?D*{Xy0A4GY8di4UHjM#8a!s`a(m1Pj^-d>c~RD5nEBDZ!e z_lhqP>{OO&k+iyqCw2?9{2>yr9(lrX>+q-($|1_N1WPe?6?hTHZt0=&dA zwO*ka!!U$FI!xJ7+m=yZgWP_pk*;TSHvExc8dvPhKX2s)E}vKNJ7%(%t-^M=#@-^o z12pk6OOj)84Ojt%m}pv%YFJrz9hKmr^@hUeK^V~niXjeqOpx|c-MLxXNoPUP#XaUy zKx`sI{P7yj=&0IXv*h)RxB|>th0W2;7Xp}263`nno^yR*a2f%q2L{ne?z7@!+l367 zP^Q;`rXt%5LX|lkI!Y|@VE05ws_XugHU*J~5)3iT4Zl`9JxHp_^o$n6Q2^S!NoBDr&v4Fro=jjAg|@hb&N6fnK0KvX5hY@&4fYG$%$8fEQir zyWgkp@j$-{tO1{FL=4Pl4M)(a`B&YATP|G-m*!k|p)iZpeV>Dt$JV*|636ZR!RlF~ zTSDPJ9FoCpyltSh=rY9HHUOE}CC?%e4Mvi|_7GlIN#K57MYs~wE z31ow?CAPrEluGV5* zg9))ICCUz_nSf=3FEIeZgDl4I!;RlrQMK~Ia)H9|GNWtW>KlRdE49sMt~YZYwA_fm zD`3hQmJoJP0xGa@9v;!9QCxq-bbxQMkQVX3h|1l<5qK$08Kqtr-7wa!fk-9jhG3!3 z;1C@wj*)b*VGyedXu?+Itrsv6)gcC`R&?gsxQuZHa2?(;Rq2TQhQI-Nt-be~j_a#{ zb2M01b4VhhYfghOG*xP?!+MC3(@o$7cA%qz67E>vANPQbCuWA6D$F=-6Q&S$Ut@UR zy7!8-Hl#Re{{V9DI5-RmG}%`~d6eC#>(Tz_K~0HjO{o|XAV{TwMx9zUdTPp7_;!rM zgKm}z##)3MKupuDShq$R-g>L@il$1ysdm!0Ebjj3aBk#^ZWfs-Y7HVc;U-}WpQA1^ z*KgE%0z{(S7Ew-0G$;(d3qa|iqc;Yok)UlQa}grMhUPlZAz99Oo>lvR zfUu`@7+3%VTQUa#t_68uB-UR`he+V0-7f^99j?DOH+{XS^dbYgBX4w0O_x+S; z2Unt(?^ynWcTk+c7{qPHbUDk8Vu>1)(Q`Vz11~*$LhqPM)JHNHcawfA*OSC~Z`12dce9W`B zfEkC!sK2->FtQO=&YB0010GArlmnN~qL0`b*loFNIEYit+D7mrw)F#9_d#YVThd-Ix)hN3n2}@(FxA zRmzxdP&fM|-)Xjnt!XQ!HN+(wqg-1KcC~q`f?HXs&`_E(zDmu6&;aEsC98(Lvt|{l zHWx(L1TCPov*kzvsurkwcJ*NKNy-*{ta5lgcakNy?peOSg-fhAW`=tF5d$e`ipoELm*H+qe-9S=*(p;{bLqISRl^}hnd@`C%sky)C`4*uMz z{n<^)LL*e|^fM@gDCsEN55ZVyPlS7t?qRFu905f0pVe{1IJ7n%7>0c;{Y_!=Dh8uL zEm>4Yrla6wNG)ridX6^$8ci-wd2^wji`oEie>jJ-fMipiW<>Nu`+`dvylLJBR9Osx zKsf8Hi)z0`lYoJjyZwun3RHL0;Hi>rQ5b$KOrwdGXZ*4bCI&UdloKQ?I+VGFVzyNYFS#@`X04 z96~@vs8uu12S$1aHaM}KIhFbcMxW@aC*jQtbKgP@?wuL0I78xME;6{T$KS!&me z{*ZG49Pn24TWfuwj;^P`tzLO0U<%N!MkP$_q!RVoP`9$0?YM(s+CkLim#WJ3_<@(E z*2reMK#!RHj8qSkIlM6jx@A!7^(z1ZGgfi>!(9Fju-_Y@f3Y90T%U1I#-7`@C00Qkw@r=T1XaH{~GRzL&1nSXzkrXI; zHov$y46(y5($4#f{{WC`D!LPROWR};7|nc45d$jX4Tq4Z7Fx%nHsWRNePqbpSlo(^ zR{h`X#PIy40xE`!b$A}C`oO552W;GKkd0G({+Oq&hF^}b=6u0<i<+^>aLhMBw>J#NBuKi4*ePiQpk3J)u-eU`ll#PxJAhb307)_%k!)5aN%!R9p zY(*8r2PY;g(fdlHwV_vq*9)qlD`_oTcX@Mi%Z9>A$_=wb+9>-OH*{AGDlJ~BRAcmM9U9Rb3w65jzSC(F=*(jG$K6%-+d2YO%A^i;PSV zHRD1FJxm@LDz8KRz2XM9gNi?E_>E#l!^Cnw9l}%tQE*&JNM469)E6>KraLO3IA#9; zJDv#HTKtwe;;{H15f;2aV1SQ9E9-rzFD9g=Q;qFi>C~h_3x!)yygnA`WwA(%mhMx# zwNv#k%oU5#dxiw~SH;`rVg2vwS&pr?ObJ%jwbo$)Sfa`R$EQm_((QhlIddB)&1J*Q| zZ`vJ&y97sVjEZ)H&Q55oy{rbyR!{>2Im_sr3obJGb$aZk2)1MHS0 z(}_eGvo5CknT%%!4E{PG?h*o4stB}d<8<5_MbWvGvRE6@1gIX925!h}uVL^aaYg}e z2l(}Y(G&78vb3mIL<||)EAZS$SQT&z-lgSx${6l_MwO&<6Sb^p_KtL}_3|5qXHK5l zA47=Hs8A>Dj0@r#4Zt*eB*YQJbjeDgfkkI8S$3do1pl*)9m- z-vn&{je3;ID(d?C@odpTog5$qVBD`A6te=7oaU}Bt7*o1bq-QX6mh1 zd&Id>WmTI&lEtM{yTxHMR3PppH`}DiwadH7S8a3t#v@qlohVwVeN5ngvg)3} zAe8~d-(aY-F=ODZD%UsD_Z^80J#dH>QWk5aW0YQG)v#xZWrJ~XQZ~m*S5|7;WUNH~ zEijh@WF#seHYnzz^WkV^-Nyz`l_74QH!vzdCe_PEB2~XDaSShf<1sEi3!o`in=+to z#XdfxR9o03G}*?Ul#?8Yh5}PgY7O>k=Gaz^UURVKC>Kzn&uA#CRgM^gDU4ldltHKV zBddJMpjKN?Xh`RRAq%jatj%|nx;EVBN--;RO{s4zBfkh5 ztH}nSxfD%~XAg=?3Za8aBxscf1_-9d2brdn!ZPS9pO^~01hci`C&@4nqafm;>mov` zbs_s}K_P4l!+vHf4$}~UeNhNPoQB5O!r>quDE5F3nWxs!nz|ohJ%8y;=WpEmWwPcH*DHQuV2*YbvlJk__L&(}!HaWw z9JMevDD|h5;VMA7=A!BtQq|&JPS{$FcFxe#T=N1XcYqi-oc+NAT51vi-wZn}&W!Ey zL>jWcjyzbt(ZK;`M4@iFO58wNyP%3X6e|j8nuIKjMot)zipuA(0NhFO1HHdmymr7j4GOH{EH(jZXx=;p01LDxAVY)G1x&X%R zrIB|nL2?D#MfHN*#9UR3U29^Fdl?Z(#;ld&kUnnVs=Np&!d1xinJrOkYWB??U@M$5 zjqJegHO=|L#|KnUxd95aj$snX&>*WiDrna{ zg{eVP5E-lJuQWx3lAut!yXD5cVX-hp1RFHMK1+6FEEH>vYE&=FAPwfV941atEJ`ad zpu=jXoldg=ONmO%nRfW7o{#$L0w$9!&J5KY(Czu3M9N!f2ka2fsY4j{a@S(U4rh;JAE>7FRR zsw%48?;>8jep3vzaVlHic8i%2~idyTV*q25hy6=S;Vfuhqzo!uTQxabP$zm?gpG~+ZB_j3+c|a zIHAV7KrAYnS6kLo$1=rVgJx=6U1e?UfR@ce3F1BKZpzpyPzZ6D3WH?;0#dH%h;vZ3 zsZy%96x%{!)af)y;GF~5g=kk=l&-67>n0^K1^l+dWQfinWB5v>Nh=3K`@T_C!{w%ikMgwGQM+Xx*2 zzK|I$2%yl2wP~v3iyK3beKSh(-IwlYAq9Ferpl)I9O3~B=%6m1^jVhd!w$HipsLQ4 z)-Z}ppwNf`mCf<5Xa`nv{NQql+ihLoZfaX-urAsRS4C!_eP{LTp^MtZ*>_5~>68u? zoCTI%p`K+%hzGroh9veNtJrQW+Ts8b4+TK@nbCMpX@`vZkxW%YVT zxbo{Ph1=E0K?@gExk%W7g+u*OYQqBG>N85xxK0(Wkt>EGF)K2BqSSRosOYQS4eG4^ z^3XRvX_8kRZWTPrWzEYr0i&w}@QDDDmwF3K-m>IX0iwuhLl;%7bgf4rsb;uJc~LNH zH#c757QaYaS#U2}$gdGGx<4YKaJgn7Mjk%i5{wPLPn0E+R%=2(-%&>D_&YQR z?mx->Kxv0Dh*GLrAUuO0(6q(z!6<$?w|YYIwio6Ey?}uZDDiGz6$v;P=LiSGjD4S7PaoVuX$c zO}=Ko<1A%3tPOy}B-@&+EQBb;yGsCCEhjvgg?PBr!YW$m>3tx^+LDwJ-C@EaRx)+0 zM5zpzYe{`9mR?-}Ii~pO8bDA{D)lf%&eTT`N;!t;3p7qIAp!Cm*k2<_DsMZ)mQUgj1RXz9iz=(vPmQdU-q zr3SEt!@~3|4%vx^282rZm$(I1C|rC)yy$+1^$c*%avE+6`%D;PY%SmQ@h>jUZ>Ovh z#$Bt7AYzP$1TH*#2KxzOplotBKT#a|gMb?8Gi@40*TnrqG0ipb?vi#OK_v!Yt>Ayu zBrE^|)L7xy>}Jt&CdAxibh$i2nc1h@A%HZaILx=qitEEfY5=Mg-wXvvu-e)mOm?BG zaklIC81_&rMhrqzV=>woPXpb`-nx=iwZrch2P}$aa$}LJ-eHwQN*$xq6L1G32JCm| zh%I7UFym`g>fC*H2JmHd&3}YSS(5aQlmS``Z!*f4BP&9_(+!P4GceuOsF|ADEp=n` zl9zKKE$2|ZkwhZ-R1i%-K$*IAK`)D&zs1G71?G!H=$Q^On8*|a3(Ypkn%n?0WYLD zK($P=02Kqwq!(-z{{WkrUl(w^gZ*VkrvoO1QD18=dSZBQ58t#!3xNj0v zu`+KE^0tE+Ewat<^@&4{N}&sOIHwNugxPE@;Nl}4Sodz}Is)qf ze#&0C=N+F&q|D7in;!M6YIDL&{UX~UB@ z=26M$4@gsBwWAlgbyzMs1waOAUa^=K0Z~&?P-h$iafKD47c>YLRjhA#jE`uz<8-a? z;b%@@4Pz051p&cbH2`hI@CvC;)I9N8g<4ith?JYR(in1?%9&|W35xxDOZ5{gjUTLQdeA$#!!I`P^-mEk~`iXXXOvs z+=>_49_S{#GUUTvF*Tuot;~=oH*vF_N1FlS(&8+&d=Ej>=MugGYljp!?FdsTmxf(& zTz8HRTXrj$<8WOH$46qiFIbaRN*zZCs;VH@h;+D&x?uKKx*zP+{lx6(! zyXh{KoC2s8`KX1O3yI9G24h;;1u>)2j~CV+wF9HU(g7rzz9qL#VAE2veNPd;)WLRT z72_I%ag~F`KXG<|i$e!UxR@-s`gN4#2Ri)`xzOoj8sm!MQr3oDPyG=TG;LdhKJ!9| z1>(2g5|+V;iGkOaW5H2C;br}?*D9j&;Ad>ttbH}!$eBY$8G(Guq+mXYFPlR`+7D|W zewd};q!9MFmgr$!6=^Y+Iz!ZP-~^WSFvjw*&~)uy^Pi9{Myf3#bTp$`M)*>X0ZNEV zBD8Gb)Xjbr87+;4uk6i$JrskIu!lD>GfuMFz^vaMvk&piK~yPMXuqfpfz)_C6gFgf zMKu@EWC=J70nHsDfgqq$tIk!M@8A-;k_%$#oqVuv;-Zt_YtEF+Y3frWP`bjyyI3ZF z5xbd9Qqje_;t46u1;Aj|xPwZ9idDx*o0U+~APlO58U0qa?x(LnscPA1+*NFy7ZO(3 zf&khm+EA(FDJe59KpC!wXqbFx;eSj5+dTv>&<}M=)|A47_bjSt=_%}`-BcelvG{~vh(i^~ z27JA^hzO)~ZC_f%XQjHirL-lYqEaj7Sc0xNDn83bi|;DTNre_)5~%+GSgyz+R>+B+ z@Ib`xAKW^sr39YTT*8diVk38cl``VsF4Z>qgkP{CW2?KKPcCQ^6_he(JBCUzRO+A* z&v<-NtG^-2<_fk<5Ed4$D<)#YaJsy1;m8XHz)|Elz9B-Z)m^Ii#Y8n~C8Fx-zCW6z zHF!Cvu)qXPQ+LQgwB^HS0=e$xxBysC3baiyZ#yw6g13U&gW4n+4xxAxdzd(7pl?#U z%4=g}{K3Z~QvFiCU}QAk)Ua$;z!y*IK!s!5{XoR8QFZqaws)H>E7}j~<`bYQ^#1^gQ0~Cl3PZ`dmf@BPkjY?GF;qL1 zZIdL%TIX21(TQmgyT#W$)M)0GTCub0BhbweJeMiJK^*xg!T~g*ik~&{GuFzrJK{F+ zm8+Ik8N571fXEeg-Ua^v*xHRbzDX)bShe0Dz#$79{{X3$VRLy@(cuetN~)E#EIZTM zRAxj$(`Q+Ds+*G6bGd4vA@|J7XGc*pS&9T_Mb%>&iUFZIc!y{Hz3U$A&RHHx{ zb`75i@i;%ZV5G_|#~@;XQsp!J%)9Yk0Iqer;yfhHiqZNb`t(d-F3!6I?F`Knkyf3V zM@;vaLjvSipnzcAUwLSuJEbM{DMqF)!EqQbcV*u@t96KilnYwu;%8$kMm>p7!b>es z;ncxBv7cv&4Th~g^38co_nmP95IApBB0C9GcaFkd-ADuMmdYa>`pOJtXEiQuYUFxHcYQfWtws596s)@&9x;9k>P{>>cf@XI>5o)&_IgEJl|YJ? z0n+s|k;n#8xj;2`{s0=+wJ05iF6$oVwfi^~kOKf%K%jLCmg4t;8DpQyyag2-JAS;=ZE}qfKfB+`y z#dV9aBEzr&W8ut7g5vspSVdp}0{Cn0IF#cIGTS`Xx$4$E20b3hg!p8P*U$yKgW*dl z*+VPSvGqyKwVu9dv(__|I^_B?(|OwYxH^-+eOyR{R*~;t66|i?zXdLzUba# zQA*cHCos-c0cb?4Ml!&j9wsLoRw`x`%_vaaoP*gj3dL&;TT6&^VC3T1L#{iR_XsC| zSg0v#6`fPW}=5x#(M&y7Q%!M+u$RWftLZ*bPw9Edkg%}d9Vs2Yk) z+chrT$vuQApJjYOSBrmNmxpo+Qj! zlw?J@nwmtaypF#8pcYVqu-dR2eC4Ofb3RyR)ov+axQGK_H+bKTMDbWQqh-*Db%9g{ ztQ;uwk67n^0t2K&6tImT4ZzMZt-_04#lu&A(-m43fr`_he8!-?KR}6h57Pr2@^!tH zAe1N%IA0y*vA0U~q0#0aBJ|I@gf&sUp3omKd_NetH1TUU{$V;U!q$62j1my4zvnO} zDWpEoTIr_h>0|~uzybW!Zte$SakQgtx<1gB*N8v5z(=9~0HnGoX$E@Q2^Q!GZ36?S z2-aXy=uvPjeLr!IR=AH6y5*Tc@3kpRT)m)r!A-p!v%ayfMPHf@d`$!sXX?1XG~o}_ ztk%5H`seFZCY++4V%Y-#|;r zvQwtQ&GqdbnW#frjmz%ODo$68{w;b5u;plE&U=3A8?nnYyck1S6!tg^8>KaxUnHOOvYPe3>U&= z^OzmvMYz&ll?1596)WU)WAm%leZq<{x*X!Vz=Nt*7kMM+(`7;BYtk{G@opPtqmk^4 zPWj3Ek@kb$5WCbN(yde86ngQU{kN2G0#}4!!hyB9#>P|Z z)X+#-G;xetigf<~$$ASkpG?kx2tny_ku_mg)M6k#7y2f3o=>4ERrq8#;4xzE!TXm; z!)DOgp0HH0flE8y82pl7`78yV#_$2kEB@veqCey&eCO(5An6i9` z5pcbZ;MhAFM?QlvY!%D^0Q4re9Z=|8hhdi~F_W($iC6i{Y)~gKZXoxNL-iONU0`~u z`9_C*kI9COz$PSnU}Cw09R~Cfti@9(o|#5u4mW8_6HHykW7a=vWqc4%f=wxnU%W-6 z-L$`Kr?EJU(cH4`^M1HEgF~Tak472tLx)&Dbs3Pv&b>hQXRYF{6u`aF^SOe5_S#~b z)7lh{aeYt7p#K2qmcu{~5KwZUUXSTL9nK>+Ebu;%gt$Vf!TsqMq{gzdboqf8t`xn< z4XuELVr=&Wq?{jdv~5qiQc!|v3yLF}myAn}I6?!z=@$cWuBZ*uOIY{6NX_A>HPyns zqRF9o#m4GZ+-sv|C8`!^b&PUfsP>iEzJz*ZIydzg z_BvP>3BT1r#E=EK-^4#+w54@`Yn;siFV`^;j%E;W3Ggd|_r%zL-;O}uQ#^4LS~JR_ zM@NeoVQa;Il8m=w-Y3l?vIVaj{t}pC-;&o@sf=X(sq_y;{{WDx?F?F~qpG=zpp=`3 znPk*x2Nx&{f?$-^^8gS=9y&n?S+pq{6zM3~ z2pc6LAehtX4wUKTk-P0tmaL<_N_;WjKr;RwC9|r-{qLs? z9H;yL0Ang8(3UYyv|^<+s<8R^`<7yv>L4PY>Y|M9}4F=&=C8CGc8>h=G<7>6Rf00u*0NU;@RazVs z3e`)cS@SFslL*A4NurySldI_iV#UyzInld?TL)@HwvNP^iw8ngGS3uaye&o9^d*L9 zWRl3?R_p5Fz!ue$-ZzSAW6-fM-E~Lb;{+j?PqO?aO#!ue$(VWs2R0xS5zNV*{cbv$ ziCElYw1v1DmbL)m9t!Ktz>Z0iSmW{8;!)T#!7Pv)4xt$Cglm)9S^AIpE!U&|5&D>= z
*+FxWWu=-9NZI#dU=JOvXi4?Uvz&g+9?qtNhLoc=)%TQzY=l=-GKahlmFQKDcoa1b)_ zxmp2Q7g3~*k{B!d)*%XRQmYXQRAF#XHv+~iHY>2%$4OCB=1>CbNu(VmlmPmLyWDKi z(kNreOt7x?F111JJvxeZx$F~Gfkf=r5r%sVBY_jvV{Qinulyjm3du3!7S@|K8|vU3 z`bvX0FgsV>hDfa}i zInV&-LT9*?f%ajd!s^x9;$G1UiM?~d&1bZfh#agBB@BssbafPaG!`Cn*!Anu_Qe-$k3Mh!tc!+g=6DE<}uj*7f0Z?r<_y?KJr-`yJj0Ob=9 z)WrTWm;V4hAm!2=;UGs?Y5xFq6`3%Fl}p=qqA-!ho?k26#;QH++BB=9rafX?yAFHG zvxVXJFaG?p^_CNl;ny-T!Sxb{Fl1vArfb2gG1qqU1_~*|P1K~ht+!W*bOBY%HdGe| zj>Lc%E`l(mim*avTylpeRtsu;=_jimOL=*N5O{|pUW6i#=(h?_<9$)vqgISDfQf4h zp7{*v6!Ol~oE=I)0F8ZC62|O4AQD>MT2Xk`)?(#U1Lr-t@d6Q~sB^r1#`<3w?F8l; z9uKCXu}tPlcZ%OAE5+jwtAqoQ(q8y%;{3hhJSiqyZV0>}&K8Gk)6*W6g-r#~D4p#2 znfJDpuR%2b0E{XGL9Y+K*+p;+hlGtZxE;DUmxV9n3;yXIYqYFY<33pB5g}J(od+Hm zm=9Y^8LlsyeHcS_SPyvTGioBFJJ(r-M<9DZ7(gQ`6C4~)5ZB;{Ffava=5DK~{nF*( zzQ8@H^R%UDZO8f8hsS@mLzGW#^)(*ikZK3626NvRlTReEeS7^D2;AYwe4u$Qxt|H% z1biwI@Ee2oRl(s}1rsS%GJ*Kf1eTFwaZt>x%>MxEe~#9a6QPNFc|TL71{s*jp8{gN zn5cLCCTaXsSt8BWAeJ}rM5DBR*rn8Mb9L5db(iX1SZ4yA^o_CKMX6H@UXgNM{U%Sl z=#`hl25yh?hVtoK(pMhEbY8*leW2&Oyo_7~hg&&xJSC5c3CaCe*X_A@UR3arK+=#b_!2Bl&JxRyB@jp*jO#T1db zfZ#^Xyv1+?RqE#usd)KjE>{I1m+@O7r#Mp6la@!|(Y&!%7MI796`NeuegtJQt^%1Q=p|;=DLRb}0I?UE# zlWFL2X%+w|OL$!!Oh%#g@s;+Jc%#!*A8Lk1md=lO;AZ+&KS>-k`SZL^g4x-wBRrZ+ zQ$&4gqbpKvuU6Rhsm02~01CQX(ql(yYLrlLRsyxs9>bxs@rw_W)))*0Ff;Beh^t(X zA>Pjf2f3JC0-w|-!jM9h+A`fLIhQ1HZBzjTRhQF$xqg;Zu$TpC&q-RABvTT zpPGVHNRv{rIFv*}(OA337C#juF*Ck@+EhS8Yph4uF+mb5{n&*vCJD+_RCGMqsHkrV z%XWQ3gYg4c%(Kh-CO)yBwm0(|Dbic!m-mSw^Q!j?>^y-a5rX z28&aNWxP@5F_iDvQ+}m{iB5zPfryu?Bd4@wFdz^pB@6)dSHGD@PM>nEs2{xnVf4&5 z0=u;-z$w}~%BgI365mC?5r;^a z?x(2|aShn%g7`bYp0ErnoF3#(02AE<`y<#_+G0e#D>FKW7~e5-v{Ne_^u#_9pwSpS zrLXXqvaz3}0ZbF_n6xbCiirjIaYS26Yz|?f3R)f0{3E9rU!VM!yt1b~B3Ft$&>ViF zr)+Rw9T?X|@che+w=fuJ(jMO%P)I zX7vckT`70O#1c}J!_UWX1jV{@ala1bsUu#ZVu&HDtMD-U!~{nz z4dAWC05BKgb4x6{f1)cEW^Q2gg05u%CB}iUUr zyfs4+p+PKn8@OK*oZAAN#~n|c_)9v9b~8Sa%U2hqxvPoNrfaPAg1s1JWj#Oeh_Tp0 zphifvmlPzSt3jVwr6JWf5_GYZ#uLNfUQmB(!LIRYqA4C2^_B^^3YfSyg1gJ`0IWeJ zQ_+gUWmPaKX8dT(YH3+Vcb+EB7Su=_>ocA$Aek571`LDbpozo~yf;9>5M#I8tE zGrd~~gd;71+Sr2R<8toxfWrWX8vg*0oid_eGcK7C!JfejKY+{%l@HBIxc(ZBn6)q? z-S|Dw{{Z4ilhT4M2i(6_>brlEg#raYkS+^K-sp_G1M?R^vqS7|y((d*S ze6D3~-KGFNptb~BDy}me!Y%O#Xr7Q%#vS>VykRfW7KP%!HpY;6S}UB#K3lKaKkTxJ6Cd2 z&?LD06KcCp)~v7r-B!J7T2`52rJ+H zb+9nr{4Xb@K=JWncIWD%kt*B^u3kMQ;O*-j8?PwG(`9l3jMbRw3=N>oJXCvahkyf+ZT?K;6qw2D!x!+K(Yk?pfc$6j zwJ-3>EV#a(ffXrH=!=UQ&g`#KW@C~)s)((=i$|fi;t6@n`Z{_L;&-8K%=?t{HFE*i@gVPttS~{p&ds8t zn75esMk@s7Cy0@uxmPd})z;ns%P@Bye?j|C5Wufbb>PwIE93B^C79+3#jw=H&Xs;4 z%pues;xihATKz#*CKWmUBi3b(ZTZ0bOsUGAbpTo7{{RA4z$)|s=;@eQG*Dox8G#bC z%>&vRp&jHl-{9@SE#2q#t^vk6eE|zX9iJU_I*z=nI4urh+`2T&Y``w!4-vai26r1b4AAGDMPm)KoP;7I^h)@a@ezp2IEXlk zGg8-DmYIZ7R{OzwPKj`7nCl+VslP)r@WpZ71ST+6V@$JVC<;#L$C%&=Is$xC3r|)r z!#{BoAadpVn8(yt=`m?noFBPtspOFn8_r@a7xmJ1kN46IR6BppCe2-!>V4oolB;XW z`(}dw03r5@t82y2x|+&7A6F`4z%C`t&ZGWKiU*abrfl#C&R;?Q0ATAo3=m?1=_uGw zV=?BXF&C*iqn7>ld`wE`E9GJLA)8!`PqWd3hMGpk1I#gV#O}ks5>9i;f=p0NZ+ zSeuXFcO?_O1m+eL>Z1Pu*@W$T?xp(-Z*jwF?z8Ptr3>{-%D^2!s3#D%%j$_$VrR63 zRwZysF;J5>C0&nbE{BPdS=A6qNzqh-@+Aod>o@@bv@i?Qq|{Ja)OXP7Fw|wtF_kkn z)Vg+}oTYvPwjQxgvDRklXMyOdmugd)gQ(g<&LgUcpYjnYEOtaDMit%}KrF2ZqRMIq z(qP0mSk!%>6vjxKMuW6l;$_AlPB8`40jim96)u*#L#kB8L#;-uXB`7Dh1ib>UQ9ml zO}LyL`jDIz>c61li1^`njGggMjz0qn1s-7(OY z;&&i=z`%8$e}y7rp5xsq<_%@U0n!sK?CDr2SEl8l$;15W`HoZ5aJ-Zm<{g95a|i$%c>s53M$`a-j;?L#vVdvQ7H003$PSch0EoE>MZ8tV~x%mqqk ziAvnNI!YU>m2^bl`paBZMJ85i zgElfiY6084tJk{{3YX#;;u_SVEOka zmIs)HD!f8^rc}aLXj2~9E3~spdP=amia9INGrX$A<{+6RP`-x4;N$s`1kHH;Y^j*y z{{YZLYu1|^4+vttC#U+Bg;U7CbN!Y5V{(Je`EeJtFSRN9xc>lL<&nyL%o))mB?gl- zr-*`7m3kuZh~IX#1Ci}F_&Iis233}POsC==B107y8H|7Ica29Ifi@GyVwS*fdxdov{h$MwLlLyUNS9m^ z^EHR!49gYxYFI9?ux2C{@RID1bv+5t8GDRHK79D3O35s zhper@d$SOYPTpg!N*aiPUNb6W&owI*!?q&l?JZq9_52;Oq}ywjSex|*7CD-A2hwB2 z#OAbhjoc?lFx5nBq*jJFa>TN2G1BLRtWA(kg`7-BaH%>FuHj=6{SXFn#tNu>EAYME z<$J;S1rcqcTyYY4ifiyNf7po{3&nJma@-K^N;u4+GDe!$iDyd?<~>rV)PGQJ$m7yx zCL>;-Fgq6sG3^(g9@3Vhb|HT9j%o|eFR2hZ*GOBPc8y>W!rn=&KTM>)u%AU$QYZ5b*(aVo|Ha+=5+I%y0-016U=6!NXaGilQ{J^DsQz3n;Hh z+mD&Qf+PO`VI>T+Ziz*;;EJ`cZAwK_j5}p|C~2lSmu|^f#t) zcr*7ZTRak`JbM_SWu20sI-?L9ghn4&xsmjTMU{-T(kSf~I_4Q zMs`5GPLg2MuCEZv#Cpu5hz$fzlN!&)B~FO@sKTtPI&_ClB_mcH@I+x!u|M21Lr zlvkOyC74r)+ukPP2bkST{{YEt(Qs!}%=Y3~O8^rZU^HZ#@c4;)F$i9mlp2C_XNc`t znX=qkgUJT;#c-ki!5L#PkxT}H4RbUxm|(h=a1b#HOA>(jh%kT2gM7l?V|r#`#C>A2 zP+x0^PcRvk=@e93#8+=Jnum%?n79>&VgtAo?>*w6WSQzB?;Riw&43i-OS7kLB2Yf? zrx$a=QsQQ}f(i@19pJTJp)fXl#H>_3ec&#>AaqwrZIeAYit8!G)IzlHk|KWf5ERE2 z+-DI{()NOi<2dGL8Z}buz)5;gI-JKGL0~3Tm+2Ri0zupd{{RxDBEc2C*gSoZ4kx7P zsx|W++$+R0h+QEXjK(KTHBkqo9tb42H4I88YFWgj)@6F3Ww)yW5k}AiV&eY*3u5yt zP&$xXZI%}dH6O**OQ%;7;s8pC=@nZ}Mjp^Ud&2$zGL;XkGcm4Q=#5P-D0;>;mM0MG z#R{HLuOy)B5rX#smDC`i<_gY`PQQlJ7_3EOZYZnYM4;e??YY2!b*NFyRam$#6WRlE zJqRvp^#1@R72DMq>EK6qG?(uM(g%n}b?wQChPMedP^JKQfVdz}Gu9bmRmvt|XKALU zQ50*48xihH9c89w-f9)4Vp*zy?1buCP_^6ETFC|gKx2{^@i&H5_ydGqpmc`t_CQ@q z5t{}u)u4Bb6|N9CPK)9lB(r4bkbNZ#SBfAUW(hS9q_J9s8XBu!gfqTaG8BIS)YJ;f zcw$QuoLzQ+u33SN#m&kUv$Xq*9Kx)&N}V8bN&<{*vL|SdqL9TEN+tN z+^*5)i_$kqn>5GZgSHUjV8Qqgz)}JQf7m9VUiATRt^VZ%G*#_i-KD~^O6YGrWgX?H zDrnp)VTl$c^^I{T+3tnYQqf2OhI5j>U^_DqMMD8`_X6<Jjk`JIYgZA{C!|83q@ZyCXfITh)L)On*2*B_pqy8D4wnmYP#o@C zq()T)AWjGd9;l0o8q_6~Wg`rGrcON|O}>y8R#};uc5bD1h-SzX>jL1Zi^Q{xz#d>Y zm0e~f`HyLJyv(9*CL@M%+wiv zBv;G>f>7dFD#S&2jiMM|WzFh{5&{;6U1AGmTT?5W^2|7iQm_6*Bo{Fy_n6G4C7mJ# zeN6X75)4*}gBU3U=>~uR>_knW)MiVVKdIRp!xgNsO|e&r*_LY_CHHscB<&krXT+(~ za2>*XLtWo#Y_C>5Vhvhhj(CEZDioGdc4F3`;?}AZ=7M(J_Lp=eP%msAkfEpm0ll}M zNEn96g9Sp)VAgdh{eB#p8pX;}mg+S-d`v^Mk&bfiRl~~oE>?@^fE>GzqjP{+)(IEB z&;wJb{0^61kjFO)X;=eLyDh|4-FcOyZU>p&hF#_W#Az}0DNR7lpHatoc)%L8a|j z$Q5#?;vHwqEo)32Vl8zpX9UBAh!hf)A#(sw9^9}>j=q^z_<(5#yeJsMGHU%J+f}T` z8qoyQy6(Lt-}X`tnqh7rj;(-a1KKxdUL}|sXr;dJZi5*%j0TWPw;u31Z<%497~WPP zk)dY)0Av)UcBZ0(0C+b%mn_GAJW5XRA|F_Qd7EZhxQKeeHS-e5(giguP9JH0mFp~x zjY{fLIDj)#rhH2du~(Txi9~Tx0Z}Vn>CXd&r`{S;URxtaQO`-?a5tzL+^tHkBZaJP zYFTOqMwciwrSyryH*jKIahZfrBTWaq46W3qZe`4=zrX{;AToyGyHI)(tZ3sgQEszw z%e+pdkxQm7)x>*#2p0!7TE^ZzS#>GX=00BX^{A`FulcAI$U*XE3F|51A`L>@#d(Jz za^brnlJY>J-9d_t841^3&{=5#zR)ROWWC*Eq&l@rx2!jHtAOAjGiR&^$8?>nz3QOT8p!lwTHGFU0{X_A_?dZ?ufo_dEm)Z)fS+Em3*5=9d%=)@ z`4#G$D=u>gO53=v2--I)mI9^KwaRjw*V#! z>pAK;fWrzySIlpu)YQXNvZ-2UW)N`PDH!kAA=?6-W2q`(uB0fZ$vLgqfy}k+%0q~x zq6&ZHylz#uc$VWVN43WUGGh}??k_?`z#KEyppd|TH8tL17b`P~*Wh6S&HBQcB9N;ovM}o~xsC&j zCkn@wP)|}-Z7#3;hbn_ct^&wZD)mq=D=xr}dE5vuiI3)Aw0N18^nD`1%P@n@!gJ-9 z-cVTQnMsoFxfMoZ?8(XDt=68Ie25?Fyj^`2UC{>W&qSogi zK4Q2Y)4LCdTi$YvA4okP6Ccc?YW!TVH*B%SM9-Up{c(CnIpCQt%to-kSP6WQ(}?%u ztW@UZ-)IwM|G<{Ah<`?cY)$D zpHFYV1B)0lo812Zvc|{QkmnPq{{Xl)`giG$GNx}c1=X^h2o49PU=B+?8E@h-Pch#g z5Vjkx`hlQ4Kwa}O^_a%YrDgYLD0{$g+^X3NH^aOatV5l4l^sCg^o=dI?*jOg4j8KM z9wAef3hz?&)^=f*DD{tNm~4T*VSORySn7)F4~PSp$)N|lRmxvd71MsOrdT#EdCfQT zDCu&&A9+rhmvt)ch5&)K%HG%ws!U(xu*i>I`op#6Q699r{D_1nMgv+O0$INsALMB1 zEO5~h@qOx2vSYkYQ`!hid5=p`FPNp&b;qre&hQ5y_kwd*)+n2{1!btwtVh11+)i-B zQ*j2v-lgy*)4G)9sIMZ|No&J>q8#VU9i_TV+ROEiv`++R(lPgsK_2lVFI;QUnLz#{ zOp>;(u2aSig9_{^_9uJsNpNWSI5t;{iTocePV?Bhk#H7LxiOyfdwNnK5sZP*Vy^tqQNDlBJ zy7Lus=e8v)5Jv~qO+2O72{F6H9828?M&kc?WfBC><yi7N10Qsr&d?2dW1>Hdd$pI z>k7B+FV%dpX~F9(=^l@??LrA{m+9{=oA!$JVxw}GwTShLjKrqyBTD*2gmshNZT|pa z3ziWr(p~Ds7PEb&9;4n{=hkKw>Os#iJI4937*nhzyuKkrm(o*^xSfd8RU7W2JA1%9 z5j+o~&o{di=jAdv_n7s9I@f|%e~-cD&m{7cIay!gcD^MJB_U7zmi{HW{7X;mPZ-08 z;&?^+Gu1s%Iv*n74T0W4r?7xFEO;sD0nzr4C$Rqjkp_V-`76O7dM_>(;XNi2oAtTM z0pNfPtjAVcs#^JFe;IC)xf09~%%`g})>O3STP%Jn{{Ry5-3YFPWV9{N{`8lYd7e+a z?m?WXXuoNGr@Xc7^<}$z%Xasc>Opmt?E22Z?>rvyJ*7KJ_4Z2ek4fZA`aqnMK4P6o zSbCD3Wgo#RZS-c#)XaYf1XqW&SCV(hY%J3h;Vp6V8twR1aW>Sac}GS!$I@T$N?X5T zQ~XE6+CSQz&xvlo68(N9y8KU1w6|EMobP?V4fEIl literal 187281 zcmbSybx>Pf^lfk`uEm2E*S1)J0L7&gD^Ms7A8rLovEUBDrC6bOf#Oymc+gVZid(S) z!9x;WelzdAnfLEI$=sW{=ghq)C;RNZ_S!3tOOKlX3QbiFRR9(i0Dy&g0UlQYkpLWQ z>?i*pjg<7s6U_SwAr=lUETE#e;I4OL?GeB%n5q8===Ava2uS9O zi5i>I7CK-@uY#Ea_#pX38y-8!S&f#r9;l5ASnd0r8t+HIC#2VzIYfKw&~1JfxB}iu z#$H907A58&T<7jei^OB@cG3&OHU|!vz$Af-a#8VI6{uZk!j^kbA=Nl)e*kANZd+}h z{JcN);)P{1G;HwWsh}9^!{9om_Y%_m@2gKHy41P?`8Dy%8UoFrK%Mn&ca3h#qs^;< zr+MeV0oFDeBXBqHE%e@V+1YsULh3k2R!n~>8(aF#iy9Ud@*4uQxzHm(>Sd1?@B~b3 z9SYjNGy8dfu!-8;ma_QmjC{v=W&H?9V6AYxyc=S;r^74)m+`?pn1tg9^dEfCPJI<9 z;z)32fOBArG`QVqg83Zmd;^yZ4_wYhQ&z%($*gJsIIx^kv^u?X3chexb%opl-qCOQ zSHZI{rr}OIsG9+`GD}j>!C|Dsh{x@_4Q*rbpeCL}f3mPgKwhOsnFc7G3M?q=KCDug zDGn)h2Z<6PJ@NGVj1SwAhnJi?3@?yWBUu}rgCUVNA;ZS*GO;d_c9~k|lf)37*kYt% z{ou<_Pu>l6gqi#2e0c<AR}MkP4A6}-M+nlsS6%c(+?y0FFQHB1oO7)?PKJmsP^33KWLcDM zBgl)V1@_frY86p8*M0A{{l$~sNK-U5g>YNg1(eRV!&&9qm-AocM$pS70NR%OQGP7) z?Z}IhhZlVO-}6Y7ZlAV30t|X2nLqbNhieEf@&aTCTZ^r27FW-Qi=w=$8N%oD4;c-E zE4^wmpI<+`Sblelvp9A~O9&faIqv9KM@u{cNTgp3)P^Cz(a*0tD?0bR0|yRyHLHyV z-Nr8o&UsjCoCBiKTLY5-cO^(c%rPX%@Kb9UGMVO*80ER!9|U@3TY2q@pCTIw9iZ+}r^GFmf7c(L z@)^>buL+<0u?7-#yJr>^T(<%nl3z&O+~WqRPHKWi&^*k6o%e~-F8*yhkAOPLBJre< zN5DPuf_?J_sf$Pd2w>Z39)AQ(HsIy@L3DvblG|$My@f8TLsH8oZ6m-xGJox_1SGeO? zRWu<}x6zc2)Hk8`qP>|w8`IrxyEwHg91V{?R}iyw`tq+D551h&n~iQ}aJm#Iiw7wF zV1|CCGZyy%F1oY+=I})R4v`uwwuAymWXsI0^S4koppRTYS#&W?<~in!U#irX3e9go z7W#Y$X8)8|W7geJf8>Rs)`AKez5}_3RRB*3wngs)<;V22YUQ*yi3`~2@2;6oEm%zs zgw1Os=-~(1x_USEF_VfP!No&bL-0LAn(HeI*5byA*b4f;F3ErR@_ zKcE5pw>Od9@8T2AGadmu^jBWULYj=%=gr++<9+}83Pe|c7Yvejc19loe`bRDsBhEbFF1^=R&A0~Fqa&b-V3jdNK%ZW zU~Pv9#AtKfZOmhq%VO@Bx%GzAA%ro>bH4#W(BG4EpH17}x>)u-ZAxQVuARssav!xhB9ADBAsJx<{xynEh zjIqz53)@dFuGI`^MK?UI9XlZk`0F9<`15jQt%U540ML2zci#KKN5B9vPqU8HIk?6H zDXPW8I<=Usbr@g--KMt&-3LkARI zaD}epFgpYVYZ9!y)mt6R7P!wbW450+Oo!Ea`>#AlPn*(`U$dHU8pE+n@=o0@c1&1G zKikN%e4lQ6FhZZBrSzoMGdtDglR?QG+gr@t@p0mp*!3NPwt^9XY1LTgf9P;6E6juo zQg`9zKc1@}9mQ9ITI~TviXRWd5NaRg_JTD0n{vq2JkChe4d#?XE_mh}-WhqitCFP} z%l_B9Virs`1lYw`RR{~ftF%3_kq8? z+tuYK4#m*ix=;7A-XV%{plIrvlb;e0R7vV1peru@vK7~O|4rYCeVzE;xyQ`X>0wL` z@D-TZKmgwj_`q9=uKA+7?^&Shm>UWHrQaQsS@Z}XKO1xn8B|~49$Nvqfhm(!q~sVM z0UTmF27Y&6S5#&%6VcYbX1LOyTvOyieF#Qac+Mq;2!N$rtCEC;Syxzk_1J1j+pLifU$Onf8ZJ)EuS(~ujcJ6jm>Zb56l_OZNnhku-sfnukhVcN6`X<^!Yj~F{pufcf66N$ zjP6(9)Mp#r8fUMGQt}l9F*=6gVw@LM)QbuH!rULXv95S-BN7rZW7IPeujk~Gke&$! z!}6DC9;D}}zTzhN#5GE^Bl6k~cyIu*dl-QaT1Zp){0B0BbI#+auRrO(9Nzk?G%Zn9 zn6$4g?7X*&AKD0Ff2gm=xiLnfM2G0UwJsE{Sah1W-;E4)c_p5Kik$hNj0KP%WY9@s>sG&etzTr&8|JH7h~$5?n!(-J*_j^#($5@w7PhDu7g! z(Noa#yG@7b+cY{O!wg^jAex$Qzy2e71Q7lVF-b`X6=3>43xks#T-FaRIIYY*aie+> zGjRgKdRVf-uV`i*l_wP=|62*&RsAsZs zUW-?YY_}psg|Duuz|wkrR|^YB5eRiuc9o!R?%?jjC|jVCw3IEsMboQCz~aQlEfe7* z;I2$Y_3SDade+0Jn2xmx!a|B3dSC2g0Knh8O~nG|E zdO-u!oq={CsA8j{Th6~5_w{i*ngh2b2zJ!&Rs+~_5lD{$n+N)|jx>3x=pA!F(nQY8 zy`{n{P=^S92vW)&@Ce{x!MCImv$hLwDxW-(bpYRi;ai}fJk&|iIu7AzE^H_IEMH|G z8asFcAU#L(BgP=NLx3;^#5U${p)jONj6=TQb$kXi^%m}eZz)4X+?<5?j$rM~(A-H9E|TH(QjuEFewvlub`bo7GmgBn`ODqZVA2sMrL z+~gnKaL5$4M!}m9ln}I5~NewZ^MtT%?d9=`YVZ9j)r+OP}>AUhjG^NMC)o!%qB zZ)vL?#4kCUQ*Czh2a^c|x-zH@HPrKDs`0fB_Ti1fxsCjg7h^f}Yk&FjdjIaTA&Wc; zdU9^RaNUC(S-W$T`_C7LcMwMd%v#GTmWGbIKr!g1TR7q$O-Xhcr-H}AbLP;X$kd2O z04qDp;Yj`oB33ulE(Pm4E+0G)yH4H=;Y}VUor~|73YUnSKd0 zvmGLLlK-!(0Id%P7GM@q-g!GnbmmJvWea3v3#lJ*3nsxg|G3V6;Z{L%*0|q9Hgt>3TF8`st+PYLZgY>%~}~sntcT)3UJ&igK}eb5zv};?`FwE zk6KI|6;$5O7c{Fb%3-qcCdW77W8sF9@)o?T>6_i^4sAeXTU5JsL-g9YJmL=^uQ=-u z4AQII)s;Lvr~v1edRy(+Oj|W@X9k?Q!*+X4{gja7s=I77_p2%bM&0PUVWMJc)#|TN zWHn0*^{5D$cNMXTSeQofG>r>PecsQ;WE_stJq>=;b7+!Pa#D zpzYV4lU)7~aTH=^YwPvQns;oNHkJ@>H)Ss_*cQoLtt)v1Zlb3|;Y{{6lA+76=Ef8y+fkhs)4NzMu(5ugB@9MZKA!#c z6We{e#66ZPh!R3$77*s@nF?8=yJ+PU2Z#&H*7zH$%L&(jUPw9Rd<<*WccyzPOv6<8 z6$==X%ZdMD*_-UVEwk%l_XKY;T9&EMme_z2&!(gxYNEO)S`;igjv(>m$aMD|+<0M+ zyly*;kzS-LAw3Z@y!g+>EECeTUO-SKM{pcYZmi)aV6x9@d@&cd#n6^ci72aQ&%N2P zQTU*P!luXB)rqQ&?h;tqbMq~9*zI4vt$RtX%(8#ql6{bnoY0`%8O|=GD<~3~`2jed zi5)(}gk+~&Dw3t(NN%vX0nPT_XSnfDI?y`&R$c)43-z9_{mP)bI0I&pN`aSu)qT51 zBv}4at5$sk#Arh9>b<`BjZ!7O$S7BIE33BFA!Nm~vTXH8&*@RamX2YZpK5NYscP8O zOV^>edSFt=0OvTam^q&ToJ|FmZ&eeydCRN(rJNi597)Mr{QS7yl4FE%xzL}s*MluQ zRQ5CrG*`28{?75aeBTHb-nW`E?Wamk0Ze@bT|$fm{<)hd8#c(9G`Z_eY)~aloL5|* zb&8Bv@lYv>7g_-|W9=o~J{F$PWc-HUf6=HmJBoF}cmvUaCw0>T8(#VblUC7%+}Dy~ zKheTwi#YlWNX|HL>-&v0`u&pRlAA?B*3^-;U{8*;?FG5*PopWpx8W7y(-7ogLKRj(%g+5ym6ha0L03>tKyBZpl+?&inMuWW_Q^Uj zJ;Ju#v90MGv(L)p`4zjPAFTaO)LvwttPsQ6@wU@c_2!7{6&C*1S}nBvQyG2tU1N9# z%%|E|#_$K1GUA1$*d1o|m=l*}O+j5k9am>_?#zU2V{alMztr418`7-C}b8~7Jg3Ph_y?jZ|$ zmhf_Hygi+yPE=4gSlj21mTudsNcMiPY_iDT?#RXA4fL$YKW)Lne!d;sN5C;Ahu`Z{ zi`;kw;K)4!(!Zf?uXEu);x^^DEu&P>5$+K%qBhEY^JH(V;3Sx0J^Y+0U`JK5J~8A8 z6g>|@n{!Im`>%`@p%+1DZT~x?N5Hu_2>u0pA6Jx~!2WDs8D~1`W(fMc@|o*3o)Nj5xe zXb@o9_zhnI7V_N@gSWxzdbOoj)`;Fe1F=d8?izoqg>_Tf^mRl3+>?OD?)XbwUX;$N zwGI)_Q3Sjf>ImrM%T1rsXeDenUOtm9{#hm^E{0?La|B*;myxdJ$mEXQ@XEJUZt|7P zFO?;guT4*_xr`*d*R;}sLHEb)=WL;ZO$Lrq#EfPx)&>1uPjP0IUJpEJ{GX=zu?ujwRK)g|1?c9EA3U0=93dkvR( zflW+W`=b9vF}!f`eXrJAs~4+V&f6jp@S0mibkyI-lPPbmx1V%)=X-<<{%Tq zA^yR-FLck_L2to=fi8k|ipO}DB-QGVfPAA=avjYY@@q3+o)KpPgjD8elM8^;iKA^T z+0>@(#wZ-kv6K~`r`x|kP+bTIez_V5_{F5g6r4wvg?2?k4Da20a?)FRitoos$FG26 zT0iLK$)n4aWDc{W?1B2D-_ZhFj(7VWP*T~Rs>uqE+Aqq`QH9=u-PpqvmM+BVEkv*N znUl%O+QYB{DT{zOj+1k{j6aHM&t_*QSr85CN1VvFHAUylYNN{zrus@lLh`Ll9OGjt z$l`285L@X^le*`66X!cz83Ak=3MP!FEHWn_XDRj16*s7TSW0Cc0W<7$ zf9=cv1g#TDwpG`ot9o;ppwE|JGxnd-Zq`HYr%_fySMFIz(ZI}$v38~iu;M+%8@js9 z_fM{c$fDgwMU%~Y@4EzPAyXQ-KDLXr@7$J7b)afUPDQ$}TWJKUFuaG`7Hz%|m-H`6O4$)nNXN-zs_Vf|@V z<|_MLZCS>golo1`PU$$LVlVcI`F>48yk5n`D0qYq`g_Z+s>-c@@aNSmH>_wKSdN!% z(KuWmz#wzwhE@R8$t7oO1aA6$DJj|g$iZ~?t!P0p`8(f{U$Evc2}TOyjlKwtvJBr# zf^tEoKVx6ec0=zhKn{<9ECyY}@2!h%ryhu%SuH*Ht7^6695C8?(Eg1cPnf}xtr@zV z*Gd1|x*00N!FAcqL?6o(g8>J4Upd3&O-7iF_yW2~+etK_I(1$ZulO>*efwcbZ@xSi zspnRE>`^GbBj#MSzCGiXTd%>(!MUSvE=# zIKjjniHvrS4PFk`Q4!j6fFwPJweBm7eV$bAi+;Rns~pv$+bA6uONOM9V!x$c5@m}Q zizm6mjIn5;OAX+b+SBB7M4J!#_gWVrQ(hy#NmYuucu4|zB-Y<*A#h3u%8T?Y8H@Ln zO0~^O!U)F-J4LOe@;Kfs$^Yhk?h}C~thM=B51|_2kPDn3qQ(Q9(n^J%ZwvHZKis+F zlJiY`<`jfO{tE_iZ!7{R?SAmhv)g_IGkF{wTz3piWJmWWhZf1cQA(CzA}7TVkGKF4 zY(-qS&F4?V{8#4M5*7qnA^y(k8kfLASrS+k=Uyz=6ba#u7P$z9(0@L+^C$%4=e#43sXREb5Mya}lM#F_i-olzt!Tf5%zUgX{coEMyzR881(6qW69m_mIi zRnK|GV~xXuZEOioWJ$%)mep-2Q3T{!ZT5Yq>8A@e$XbMUMf2$Xs_@vgh>o>(QCyrR z?k7$>yc>v~Ab+sO0{fQ&kVM%+EwwrZZaXQiC&CW$imVPMq-oOjAmnq*7MhnC2Ir0Qn~lJGSqllS2Curm z^FIPk)eB?C!Z&zNV-v?)b5w`RmhPQX&_8Wn$DKks6mH~}DM%afWAx@r9(Q10T%zgz zwM8$o%743PQG5h=Xk5->Xqv+>kQ6G-W8I#0V5xb8QF3? zno5O^Q_98BcW4(8pzjMP5k7Md^b+Ow`jaubv1aE(; z7q@<1Oxrl-H(0Zdqt&{%woeMUy5HtHja6BZbG*yVL;U+CA2yK4Ey5JN{@$ci-i?GD zQC;-wE+aWpPBg#yHRWKv0mmCB<>50`iq#q&SK5=P z*5>&mojJ{d^g2Xm1A6(KWh6Y*QM<(I`m02a@oLlTMNwYkYV-0pw=D~ zd#2mcd8;O^R$HpK(@NjQVxaCbuRM1e$nZAKN@&NAPORvqXQ_W!_(@*uW`=WI)al34 z46C3qOuEzX%QqGF_QfQB)<}=QJ5b9Bv}}G?|y*4^nt> zGcW!n;<`S`m4DtUajIYLFq(OkM`#RUn zO`sh(ALGBOZ^AczEH5RwH-1d5e*Qsj_(tfkhS#yTp_7ubKw>s%biXu>7 z*N8R)`Y3^>)_7T!Su%TPYx1# z?eqfU@D)4`4fRQH@}K|qnqg05ZWH2hd1dc}BWzJ-$nvbw*TRK*cCBjnpQ`NVrXx?R zX2&4w>)(CN`?fO?sK?xb#C&(S?Uzv*n9G zLEn_#KK;cHF{+$bQXI)r;kM~ViPre9z?JZSGSxM;*IW(l7aOkH_DKDbl@_(XW1|mI z4X+d$^GuhJBi4@q+H>9PSHizIy|$l(f&{FNh;}Hom__{MbY!HKGms-FF#+8yz6)S1 z@?0Z(mtw-NT=7AhEN^3%;H)oMXX)I9#=!RA9Q}$qW>!2Lm6mI;NgmHam( z8magn!%FR`x9ntUu%t_f!j2C4f3;xWsS=@{z<+9UNex1o57NESr_7passfYXp-v!- zbp9({KHD?imCLu2r9{b9Rn`AV#52%;E_EMA-A)4!Vp9A#O{E*GfjNRRQs_aB4IQw# zdv(av;cTUo(8GT}QS&n(&NxkH6`fRCf-6H3*V#?skP_U9pLgM92t|(-o38Aoy~1JD zf~llbYs=Kp&)mfX&lagmY5<~K`2SxBl*RS0~EJdtukG#7R@#% z`TJ`KylAxh3vY>yai_3r!*DDB&O|*+U~2rI&vXKw1GpI&JXOn zhIx&6oyU-+<))Bg6EQC~Q8;0UrAOw=|`rc0XfpnNtQr1B3cDziGg3eoG4fKfe=C#?{~zurBv zNUD4?h*%#$BkKmZg0DyZ`u)9nWtcj$@ucw16oHi|>Qg56B% zz~wNocPzsodgcQ>xJUH zHJf|`dzZ&Vr=%d5eR&3}cR86T9t(=wH}54QIt8S>V2WrfnzH@9Jy7z)+r!)AZ?~Ar zMH^u^Zr4biwe1~P83E~ZgKE>C$I!YM$*g+HiFVKbW6Ca#a);Hll%*GQUcpkHeP4wS z%1Vc|=?CLMLuke?6JEx){aQrUC(klyj)$u`o=>-T=Og1VB~;3kDJcnityhxW?{N4Ck>?i}7)nbBnC^L+#ih%7Rxb7_tO3h`Q_Stv)#% zdZhhpyPR)(9aab2N{J^rUR)$?w@DcrHfAb-ePzOew~{dCgxLcEQrzw-6SAI2^pWdL zC?yj!Id2T#4A#7;_}Xwi=<1s&e3HV`&crAq-sWGWX;AU~&0%S~ z?qM`CbUN}{2M<=!UkLgceOQL1&vyJLf_DhFV@y)oC~o}0Jj{^zwnpgKEhE_Dvj6_Tso6)hsNn<$aKRM%_;J!B|&syd3vA**C+oPY<;T2P{%l>NvZjUwY8*g-Rbj^dmFyO4Q<|z?M3kPX~2WWzF*0b45cih)BPo_-Y?o+h8@h5%=NyZItPvlXyLL!0@a`SUx|B z(@bQuoi@GM|My>oS+PHav*0!GSE;02_)-Y{%4dT0FRCd;h{{N>P;eE|8Gd{C2){8W-R%af}Z3{H94TyGV<#PT^M)Zm^&RdJ9qz z4d1POa6?@py`%*fK`_FOhQn}O8&wHaHGOcG*Wn1PXy1#C;x5hOphvFYrlrAk$}Q1m zgyuBnMc0c`lq&NuZ2Y2s89WqN2-Q~APSj~LZi9% zl~ePcTNaI2W91|)v9q@Sr;|zcb8BVD)t|@}=2ddH%93r#7GmP~?6_4nzM_94i(l>e zY`o*lZW1JE^5P_xTw8!!#&`V@Ao%==$oFw7taPBT-tHTj7!hmm;uNzQMl38H-L-v} zMnt7Abrlvo6%}>Sua0-^Dmwfl7S~ye(#0}38kc8+yXsC$?dhq{C*U-+zo)h1s#i&= zC4xT9^br7D%GuJ<-T8fZZ9Ag=x;P+`KS?iM;v*N(4Zl?KoTkPSRb^FiR zG3-*5x?1d*SO{u&C0+ziE6K4a{#@_>CbAjK$&2&aqfxtB=jNl^_saqCXAj6l8~LJv z^TA=2;aQ~+A$8UCdMmZ`;(sHueNXSVYoPi39YCtZQK?irwn5n2HAM+uRx97O>NGh| zjSp!9?_0mCCc8MjZ=ZW={qT~qpj@}eA3PKv9m5^|4XWM$MGq<{cI)TjRvZ(OIi>Xo zcpaN+B94Zzt8@(qjYh_Ffx2WEC%GxDw(mYBhA`>3ujgR934*Ysj#+r_rb zDREUBpE+$L;XWOWodxr~bAHu5dc*%Kxbog+=p(YYF3Gu73S z9DM)h0D|hZe5>~lm zdDuh&c1e9J$Ymo)*20fPod6fX~6X|pjaGGg2D zitLYpSccgIq{d?Z5WOwpW`}IH^);JwX4P#MGTp-?fP+<%h;4nyi*krH1z&g)7ZGuQHjr1w8$$Wo{yb&fz>+WPeGe z!Hl4Y>VyyPB97(}Hczq>N|VY;0N&R}4xC*JugE%8YP+NF+U@(O$_Uxx(%$Y#VxN5J zDYbbA;aIt4A}2;8`E;@q%uPPqsD@Kvbs)o-Z25-$sonD^y!#b@CDW5aCeYs~KJS^2 zkcOL0$D)>mvzmz;+907Dw35!umSagZSUmQuc2@)Zx%A;KN@;6lABIhv=RcNlY56%| zHRoMFl!n!}o&-I8`cEfwc6ZK3L$#cXSEW9!#Knz~dYa}_Zl@akv%wS+wWbX$n2zo< z>vu}&Oxkc!t|9E(+!|pGPhlETwf3*(t5{tsgGMhiRa=T508ggBQI|`-3^EIk)*vJm zz!qL$supUVsmFiDoyGi5PWOa!K=-9#d39A-Zg^;?Yih~A)Zx+svD#m$-tMM3P0y)R zw6drdF-+BNdeG~=j)%gAHeKwBg$LFg;jtz*Kl@a0z1uYh+CoaSv>}1XNLAY<-QLpe z_i}0%@`;TZ@0JT&`)Ux~dAF<^$D!nM7|$HJ*kOcVOc>*vza*+RMn`H@e+hDXUSw-y zUy8ZTUmj-ag_35NC-=PG*G0GIZ=vziw8WS~X2UB%)iP~UVb?eSUx9=((G%~d zHb!e$lJ&FJeyZ8)DTjG1mvzN@Z)!tJu zlni*$akDbN^uL%Uel9)xj`Jg(l!@qOD^2Wn)JU4ZXl$80O>z+#jkQlj|K5bXQ&N^J zuTy z3a%*|tS0A>jMk)HZ~(x=E4HMVoI}Dk2_gG04%=^TfGFqUUssTrS1PXh^OT&wBm%B} z-(x3;7~)F(G4ixOzG3N{uIDq>{x+@h^N=55RJx{YHm^)kVq1Bnef^bPTA2&!)Gw^HclD1l8!B8qaFNGP(i(-wz}etzbRN_k;P zCHxRUITzv@5dsZZ=y^G0uuUyKKBM*2$VP@r@+n*n>?icWVrI&dXO3rogVNK$7vujm z0wG_nK!rF(BKGU!ZYM@Mur27DuS@~9SO3YLkYxqdi>vTS?(^ZJlOvtH?m+2@Z{@z; z(CICO*V-aalxb{K`;~DsJ&LCD$~guiB1lbe?VmY@Q?2t1Y_-!}y&`96Wh81~)TvK$ zcUU2RGfkh40P&Cw7%FoE))Zv6DmV! z2AUMrhoz1o?|;}M0av|DaYwNw2eIt(oFB^TX1j({C&OIs{hK4fi;FtS#VAP31S zhF7V^lVq0f$C=cdhA%1;ow+kuYDoJo@Rz2{MQ4@T0yMK+vO3F$_aE-I|BVMKrx7MT zd*L~uxxQIxZ98j2^e0?QUwJsqzQc5DN?cp!(ibK&38E^LHtd z=GjTv)UNlo>fbbIsv5ZS6T$-XeC}-|TWgNsukrFSs%zPwX#UAt+4MIdp_<(%lix0? z0@h-j1;g%k_T zVN-{e6^_L?ku6S~o3a2JRZ710XG$XRZbIW)yCTGN72mV0(Ld?H{6gsIc%8)9^E;V=rU zw*ZO8u)|n{Y)uokhQp<82=wc{TLdm_kagP*?Y0tBC+#I7EFX$TIV>xojL~p?xWE!5 z=NaBjpA#N{A7As}&N1`LG!V=@n33<5=+)yK#*MIWw?5>Org|<6e7z^p9Z$!TCq3{& zP$u*JhXV!{E~N$iacet6ib_0F$5w{vx3v!ZhMW($9*56-7)nLbyN2}m7k$aVs8%N^ zTbXJU$%`_P4Vz1c{KleW{JBnf+7T{D+bz)ZTireQaRl>EX;Zb-i%V1hkQ`?#rne^a zkGVVPFwS$=$U)y;Es+y5Usf5Sb9CJC{q{2HZQ-8uDd`p<*mJ%8j#=USCg{i98Dh2a z68AF;#i#IL@&cJjR&{+ymeF}i}$DTXA z$>>Ft*E3^mZ51KJY7i$2+kD{aZ|i~=3rCUzNAFowZ#UrdHK}ogxjLT#Im|dM6Z%-K zYi@3xKu#|RXL%)%suF#UTAB-bdFmG*Nta`xk&n06c)R}zM=QeG0i*iT)~;w#d0r)% z6vreu_q!EsJiRk>C-bL(5L9YDhf)OAz%0jw>5DDSk8Kb30&NdJW?#I%YCw^_Xw`)= z*kLQ#R%90Ft$vVs;~Q#}>dVK5U0l;6=r=ed@0&4cV>M0+OME851Xiv?hj79NTjs0! z(6i%asj%Bz>E{pck2b>4^eK?IMVO1Np@CM3h8W@BAuMu9OYK@ z{Q9p9kr0zAUF9qW1^8VGaBy2E^MENbRFI|IMpmifEX4oHFyi<2QO%8GsZFmgKP^+7 zQ}nvASi>eG}>&B+<`M=iQJrIi-NV zTg1(xac`9;d14?INoAE9`Y;_Pet#X?(9)$&U+XYhW=cG|Ze4Hjh2YvO@ID-VzpsGd*ohzY%RH56ef7oa zn>PS^_X_ZNgOuMTRDxyy-00XtJb?Eaq_y?kApNIFVX<0&PsL3v>f4o3|AVf-Ny$R? zGCqd8@*nt7&3BA)sE3n?%?mMB3H=mX>R5w}+>xu)Uk$|b_8qAmc+_!|5YjDxezH!q zaypiuKjqnbIKO9zs*|yit2PQ?@+UoSX22Ai7b)x`Y}DtptVCK6MS{u>L9%ti72W#; zN3x!nP20;ExV2ME*Q?PNy{cr<}I2C)Pf{)vrf2P2K`umf-Ou?VqOQX+U*z+HyEAp?HtPF7{-kJLx`+9Y@Zf@so zy?Lh3_~olhw2L{lOA$d5bop0yr_|DwBmtG7_d`ZF5inQ#*3s_Jeq}FajbELbZJC&W zWnoDDZ2h@GsAz!38{RSQF@D>+GKVZ80ExL}(bEU@a!z+wD;B%3N~hG2JMst3(QW^o zA0=msqI1;W2lt0HKY^xS4ZqnR44U$m2%D~|P}v>x3pDTJu4!Ux?=V|}bVWsPrnrPq zrRdE~Wov`yo#{&oVv~JkQmQsO-Roj(rp51>S(rFMHFycln?9#c$DXrzMZY@-%4*I| z2m)jv2JTSyozP|Pg|dPYPk@czIf=YL0MoIhQc%5GX30Or)hR%Or=3u4!rlyRr6*ow zEHL=zp}j|yQY87`^qsiNY*CpQ9VloGVf9*~W=3xmD%AH1HLw&P`0c;Qn+W>m~$Kd)bF!}@-?g^#gMqRk>pvaN9G$#xC|UZ7t8m+0xCHy9*K zck|hBxDi0Mazch8lp;HIiC(xNDp~pR*LuZq5(%C6L>HBFEFi z3L6xhLLeYQcgz$i*>)Rle?$CnOGA|Z04Qc@Phw(Av+3z!@m%<9Lj2p)68vMAMHFl` z&Rf8lq_zH9t@&Wv+4hzyN=d7v_)4?f?o4TWZ@DH$-`4AmT{`EOt=4DKXT7xMh2)Da zi{VWZR9kRA+{Q-#00=zIHu%~TzMYw6xof7%+85ygNl~|k))v?S^28=jU10S!By;Lm z$lzR?w(5!o_EBJ?r~z;A;%b>Ckc<6_lhdq(e6MBt-1>RAa>oOpnZ^6}lhJ0xTU+Wj zwTKK)rHCi@oDfh^vyIVG_8^g^y$DsY+xk|*84gU54OZ`d(YrZ5T8~Tl3k+C17sJL^ z3Zs6m-E@y3`VYq%+GSq2n3}tv>4ba@!sc5GT!Jp<-aUG5Pp5`7&u3kpB8AilLu;KZ z#hay=fn^_EzdSeW%d->+q_9<9fLWNIHom|c9=nn0i>>nlKpOxDMc95GA1@3Z)-G^5 zM5?cEE!H}wsS%(>00rq_03JOD`8Z4YRCwY#Suor!{BcDQ)yYv^>EB@;*4yOHiPFF<LiJgtkBfU=>Qo(NftU)!ABl&@FHAu8b!b z!m4mHJvvCRszZ+vvD%yjnNlZ;xb0IOjCxKgO!QGB$6^d5hY}RS0Aq+$0LJ1RI)GtA z9u$Qz27JaWpjmLhY{tdljgHd+H2u3 zx5KDt?}yRSf#Hgq0`!&$S~I4mIFek691zH@a7N%>#2v3|+kNor0z5G*L0U9J~V*1K<{oyhVxzt0&vjWTlyBS0(Q_UL>ATHnCq^wTlRV~}Z) z6~~h(Z`Y^O6hCVI&#e01o-p9`jIbn&4}=gbM*9*$7U_V~ZqtU0-A?XDS^3vr#4@R| zNWs5dCB8=F+wt6V^2Ba=#8n{)LYl3&a9H|p=lbHz?IVH=O=1p`!~y@aWo zsMu@*r9d6hdVe~jmveiO5c{|ws-yu30@|D{zCgQl^(%&X&kTtnWkw=SsKD5yighEY z>Ih&6BcaAMz%OaLQ7_(AoucrIQC0789KG#{0>tmQx5C~Y0E`;&o?lKuy0ysbu20ZD z2>A7eXO}Hatvo@Ds0QgGU1ve#q}!ODV@|`S1A8j0VlC8;=|3+Y-}S{eZbCbVGBDYa z71=~c+r~VBCGLL{j_D~NJCW0<-}Tje7jY*K>s4kq^&k4+TmDU3rr`A#{us**nA>!b z(`8CzkC(C5w!5+FMTLtIw~j8Z-1F1OqKiwNF_PWiyr2)me_T}=HcuK&0*jUsFH%YC zeaY+iV%P28GZ&{-Alfo5w%tCsXdgh8QNfh{Up4KiN}Ks&H#Ceqfh+(f=KVQoWU`Wt^K}{u#t8n8efROZFjM_pR2=guB&xUh-yXQwn+^V$X%$tk zf1$!Ou}M6O0J+v|boJAFSRVq%x;(B=h9d--1maKjUBJewLoBQoo)BecHvwZ?g5;kT zu~_^qss8|H5gb*TzGqcvKuTJ5VNR!HR9^2sOL)23CB5H&0OT9?tD4v@Q%T;ogI3A6 zG1yrkxahVQbI~F~NdPg#T{c(9hm?df6M0+<27aB-DAadjUj-N3l1Vd;e^2|8J-=W2 zjcTfuVMvh_6gO+gY{cJF>b3PTJqYM52mlNN*5Ja1&89ezb!U>rRYBWT ziDs}>W40XTRL?Yq2#Fd&GRb=cQDXN#3W`B<)LbaLFa&Qu;;5<9-RZaAQF1KOH-pLK z7kvqHpm^%k#({Ek-VnA1B;IMBQ)S7bnDZuZRq7aNk-;71L?oDDB=2%%ac*OGLWTUBEY%~`f_luLC zw0)J)s_wv#EA;$&f1a2nr^>;%hs(aRh!0r!Q z{eOlBlPe-BGIP1{`Qc2y4JW;Ge<6MF{K?dj^0)89cJtIg{y4Vm$dXW1fz*%l=Zxx@Uwv1#iVNgPtK`^^kZr2ha}k9Ti9w!uKi!Gg{XRy11m^TKfFN-w_tzF4v{ zPi2~eWo-xz@6DY>zLAzcmL{Y2RE1^HH0Jt4UMN~c+>k=Fg>FTWmBjjB4CZSHyr zO-;p-j-+9uaY7O-82MD~-~)k%0Y6C=R(gMF<5Lc^Im1O% zP4rvKul`@(hf&j2gR&37zP=c-Kj;1<(jq)ILH--#x?gCXUCIYvKI#$W(XY1nubO}3 zAl5(SGg{^n0v6+c=#9R(awT#sTW_z2*9lfYHK@OV{K)?R96c1DJT`F@8JtC1AhzT2 zBljFH7Hua|e?RcUbxd^{_qzQt7|f9!wr3&S-)@}<{c!s);)!FwdB=};Q2cCg&N#94 zR9$Rv7E$dA2_4~HSK8#Mvdqds@ne6Lk6*40cw^cQqCJ_CMDlb~`HLT|&M1twiu<1) zpD!P&BHtnFhcy)T>G^H?W6e^LBw9q&^d8W$76eAoAH2~u$s_tE-&-6P9@;6Y58BBK zg|GsmB_*%a63Tn4w~t?zF=af=IurHZ4yp5b2a)`+KPZo-jJKK()S_$}t`W*AcW4YG z?XH$i;qv=3SqIQA0<({12;^dDs-kA_j$mMr4x-LAME?Nr;)l!l{o^+bRF4~xivxx` za+DtUNmp-+X88tP{{UPQ&ap?R1O4QMt-5g_xP!2~#)z?!Ig;k(nRQ0r^@CJx>0^j$ zD%n$KLDzjFN%@h`-{vuM9zARc$8`J=M^&y#(W7Y% z_0p6)kOs)n*sIvwyKSk7Ac0^l=G5JI`^$L`)p?o93WR=}A5D+cVesi~$n(XE#y-sQ zs4~*J)W$cwUDr|9y$L#p_6?3ITE1)~tAg51oA!b7AlQTGY<*53(t3z7W)2!iENV}N z7bf0U^~6;sXpiun{{R9#2y86*u-x2E<#KZJf* zZ5~itc^>2TM#J#&`k$sH=%rN_QDKU0#5U}~%)>5Ydy5XX>Ou3rr;x<&4(8%S_gVK% ztiyH|_*r^xw>B5E0@1e3k18YD_!`V&BJ2&AZV&nM#E(=NJ9(B*2IlVx_eqV}KbmoU zEQAIC6Vz!sko76C-A*UFMao{X81w}*KrO3fZdzT?llQr1;YWhV{cJ5-Nt^rJ0i(Lq zQ*YC}R9(t#b|p>Zh*;k8ARlNfU&4H8trkmw-5f698w=a|ET-eHb%s1WCor404Zo!B zs$*S2%;{50VBqXPTYyOZiSDumrJwJFhgeG9VI0#Ig`YtVy?@{& z~G|4-WTh921NC8d=S`MsRrMR5HTAU3rr-{B(cPL?$1?ly zawY4-yj-!*4yid{I`_Kx`26~PaRJ)T8mGU?OKJ>@q}ZG8dRqH_xUXlTzRgs`gViH* z`ISM_*Ka&^OP8XObkux#`ibaTW?$v&~|@OHT2L>$8mA2vyt-qL;8I& z9$iDIkRH?0QoL8hk5JLZ0Z{IMw@U)R6ZjljJ+kJl6cn^Ds3~QVYy2v)+mf1g)pi=~ zaqunnI5*)A%3!?0tWgP5NsS{wENo8tg~`|vZin)cs-=ucprXojjZ9HZk3cWKhs$g< ztg13PNflW61oJ5TmpamQa@piPWOfD5^?VS2ML_i@2H8ItTH2%eZa*AZaO4p``xFDw z68`}AaLQ={mn%;TA{`*G7iRIW3*dJAe6Z~$9OG<8`r5zhk+~*n(#Qg@c>F#{JXqsw zdpGc0e5IAsQUV2-l`=QpZHDT;M1W4-2NWk~92+FAg=u08#W{+$La>($yZABh9f7b` zHacu}PF@x?SkXc%fE83(R1X2u@$ts6Kt=~ihTfBsa$#LXOn2@opy({2cJ;OsHGa5* zTC8?zu{$v{ zrSSTdu$_EoYaA)RClQ^ZSG-BZtsbkTjke#z#}z$(c*U+eqW1tEpIlo!c}Eh4XL1dX zaPM+<*mcDs7?Za6>-;$org1rc5O-GFn59hRjmf?eiYz~&%k{8dhUcm9`gO&zkZ?^r zWlpAIM)o!zkhsIQYSMu->C(N&GND+#Fs~;U_FKYK+|eSb)GyTCN%aTE32{dNYkp*U zZ{vNo^6B_vGyec8g|J2@hyE?V&Sf)_aO29>17T~Eu(9>Utw-4`20hS*^Aa2VFSp__ z`h$kqMT+S@mi+MMlscOnC8^dmhtSxM(V|MnsAd4?J(9|;_FeS0#Mm48e+&oJQ8F=B z7Gbd-SkZK{n;rgGsk=y}V`26tBi(2m69xJTSqAv7-Hpi+l=*OjT&}MVQ zPc4N85xzSZCs-)T6Dc}ecDV3k z+v0{+ET;<$HbaGw;3h_5qa6mqXC8x!$%?7NxLXXy7LNj9E`~^>X!xXG+-WJLAPTaT5#(n97XD5fVIb`UmsF1(0E7n+iD0c?c3nRN?#* zfxaPQlMAEaS4iqSn@RAYmuq?b58^QtD(!?GzYF<9n8%s~qx)&>ILH~}*D+;wkz~6u z0^bV-_`vC`>TRvK#vbFGkCw%HTX^2v{H}VD_lMUXs!&2?x{+{2h&>295OIfnrMNIf zTP$l#V~s+{nwecB1hR<`f!qX*EUa}ab+}+lRW=UOD9RjenO8il8X~sry4k*LYys={ zRCT@rt9Z54{{T1R`(NRUii))_{Lo(mvYQZXxC8MxlB!i({gM&C-532ZzO6@fjp-Qn zGM((>i&bi5R$U2DmvM2UnuFsT4~;Gx&qW!+ZI3IBmpTo53(%RCMB4kb)XEvjM%%mQo1uJN4;|&o2XaX``I+ z-c}3Rbc{5*kf+If{QBPwMso-^FK_JWAE3bm**u8AwH-UE^$8@2t8SaO*XA&slyJ9P zzMv2N)Y`4`xi`Wlwe1hM^f9jpaa>;cPv2AD2Ec+bV0Pu2B$JB~V1m}`e!Co0Rs26r zz2{ok2Cm~WDft3)AhFL zd_H;SLA*tWn7`A&kIxWB2NJ7{^E;Zp-EHzXGT=&urKG6LB{pIVbmH5WVWl+s*}C`^ zZ!A^S8Htpt2-p`kB->$q`d@z!OWy~)e1V#tkz4HP;}0#i9N9d5bSb#MiwsyVZ}$>F z87KYBZQ1xRz**QdvaY$Q{#v zL$UgJb+?!4q>`R+eLj}QttZIf3uL*fS5;JOq=r&G2)F*fPw+m&T2|zAKO?pJA3w+O z*s=3ii!iu84R7Cw9Lt7~?zdBZhjsq|56=b+3>MNPbq^I0weCE;Kf~$$(}`*v(NDs3 zlfAYepG$0iCLWj?tjh}gLvJzD{Q2MW@NWx|(|_~w{4O^0#jp&oB3SgffIByL>#_MC z53lEsYb73c`ru10o=4e1W98Pv!sma^{{TE#yeI7c08=pLNO@76?(L;O>#!Gg{4pz5 zOt$zPm}g!H0XMMupASQcERTX~>PT2(cE5yZ&VLXzkEzAJy`9iPmNGQN?XJQ&;x_KO zrHN+`V!Hdc8-flcbN>Ko(i4&xAWIHZ3(7_VZC&2+4cBw9Ham<|zbpg!t>T7a6)+Szs z6v+O!+4t}Sw%(W?&%LGLa8T~(u{ER^-5Xwn6ZN6PTr|aX0%5?t#K3I88 zA47}nQP4^kW8OQLH=K}eeSgRpN^H_gX>G>$9){QJ@(1aK)>~n`&3ssV2|`c2m#5F+ z+w7#cApZb3qW=Jqx8sg8JmNM5V}+HP)@GXece(C`vGE;kh;CjT($igrEr~giPQ0-ymkWLr6eQnu5pv!iY3#gK(c-0IVC4=-0#C ztF$>3ja}6i04~d6zV`2LsK+|I2UhHkB zZ!j)c`4B!u76$r;Alkfgrd1S>hTV<#>Gwy|$LoR!p4RZgPA=f5r#!_Pqv_q;eLRnv z{vKF|kBHO(z5M{W{4qvfX;pl6h1}t93?U9;x3%tV;ko>?aU(jUD<-EBGg+Wk&F#EhKDxZpy5(pQk%#^3n05r)+nlxoLBNPLTyZkud11^lth z95_msEEEB`Cf|qo-w}CsLS&I+iKHs5{4P$>x0i!Ws`&>}WzJ?1(J z<&>pfaHp?6PPfEk3}r$| z&G5xL9Q;9E9<|SZX;syBA6pn#uB!J^!)RocNT+WV$7R_7cN?T4J*kY zyv*)R_7H)@7eGHN31u`rE6&^3j*65^iQ zLdg=nGdnpEAPk!mw!rjI1<#H%?mLdrG&D+A*5*9PxQR!?B|75;Z`yR<=J_5C79WJ?E3&b zt#U>8-+jvK2srCGYi=&bCQERK2&FVih9nacs#ybTEO*iaSOp5CfUB_Ia!J8eK3S^_ zq!@QiF&J;4;wzopnIZg)pl{a^RS;O=`&Mm;>0f+#bKXhBLb<9g}-oa1H){EPG#=MnC~~8w+?0L%Amja!wHo?s`XZI|(sOCLL2| z8}-B#wfkD%Tp=BHJX11vVje9;`r91VQ3f4;xDSIeH|v5LJmqi$SzeHWz+$q*>0lR7 z^B4`|9G+QrHx}FrY<&xO92vH8axI5dR6HLzkJtgKk1Oz$lz1cTHa z@xvw#;^0fqrHLtj1G)MB`(dXWaBn4nTWD{D3+?l{{PERStVUp+%;jv+x~Xh*fo!<( zMjS~N5-E*EGcATEtA#^hC0r>Q;_{QV7*u1Ge0ByaCMdY>F^&Mji;75!E;=I|t`#E` zGt2MuiCj*B$7(Uk|+Wi zYPkCxlaG{OSclKF=r%pqkFnT~6*A*9sNW8wd^QP%;9Lp7j3JMq7;>Wx;5g{E5+gH3 zPZQZ+2_$zo@s1tC6}P|B9zKyh)XD6k5C{3+1KfMSRP~75=(&ukA|ojKMGtG}+;4SK z0XEbD!@6p|@Erj-B7t`B`eQc0ROV__cMJ*nr`k7V4->O!WpGN!j;w@^iy&6%ar8cW zUjrs4u)Ie0-prf$c#)0q?E}Hc@fm{1WCF)d=oABT!|rTu2-u#zZ;V^S96ZXzYHhdc z;CdWrqj|}L6>;S@M6WYASZ=U6D%yYsGq|xA?~S&@OyZ^8ODt@T$zrD3hfCi{AnrUb ziHz4MklcrLxAfb8p7<4BBxq$$W!-g!le{($-3Io*b%-Z>TKLX%#{y{6X6~`S0&w5F z$|01n5(WT|iAWdUr?2oh9L{?faUn`tvmw^Vk<2+x?ygX*PS%c7a7BR(ZSd|dE5#kA zG|eQ4U3e;b3+{e5sdRm3xB*DOlus@k44U{70LO~Lt{ z@%ks*JTQn-q`;o<96(7TveX7(gfgp(KH5}G6o+e^sL8-nC&Wje;*T?igK;tWJV0C-{CRip#{df;Vo(pWK)S*1ct%e0B1 zTsy{gXA9A7(2MmK-w_-`lg%^hPqd9U20J@koy*6&F6P#?hn^otQiN$Begg@|l-TM= zF`qHv^6?)-isus9&sh;h?1trTKcm;`59kR#n3Ot842FD7?RUjW}qG4{f zv;7+3zY^apLsuA$z_?+)k}uP9W&m622hR{j?y~CTdO{}6lpQ62HtBus=kobsMyUjM zPtV5#Ty0D)cIb+4<+17I^u#t_UdT2&hp%7p#2S5}Mx)*ztfcj}8&u|cNAc^3CE{?v zebeKIS$7Y~G5f$CgYOW3KzuxKF;UF3TnOTPE7^^dU(@`5b_w`fg5FJ9(SijpwSu1| z9&CI%?{7R1Q1JXT>Wy)5JIQX1bFuN)jn1oZTMoPuj0lm zSQb0qZGb&)2ZsCYp^~btPaU3i_WCz|6O4+>4K)Kb}2QKE7WpbqzI-TVmkiRPzyM++ou#@SnK#+ZAP3?aTj{Y7;&&IU>0F{yfw5|UDYTuzaR+~F%bq8YWZjB%t`P_ryd|!9W zk59BIUdyPiRy@L;?947h$8mB2-sZ;F7w|tkEd7iz{%)q7zw3bd_pmKXmCR#K^e(m< zRiuEG9s>jMOsV0K0ce6t(9-e6BWKsuFp!#1BJ|#*Y zX;cPf@+ZpLPw@RPqF39k$D<9u9+;ZVpqeHz&k!sL2K$gfv9 zkI#S1;G-j~79(RKdatVV`j3b5$3%Ra)pkFDHa|o3!*i68e=jsYsQ&;Dt`dP;pcnrD zhw%pE^v8}2_c8KBJP*utHu)XT;Bb`m*EijI-@^X@PY=WCh0t5Z=kgyccO&AMmj*D@ zM$5O<{{Ww^3OIj_nJhJ0!oXkj@HiK&sRL{xxoNhx1TTOdKVQ`13W@BV(*5CnHI0;{ zmLZ1fZEn6d{{TDSUyZm@5REi!0VG*Y=XL_u@fPWQ{Z1=9wyDj^n^^uw!v$3FGXM!K zZT|qH_+p?CVK_2Ao)9cIKE7BX;MhLWFglh$zYKFdF#*1&{gv2#P9}RSrvgYAed1ZJ zZ@CTU`>lejWrVKG2&_e9lBaI+E9o}e5bxLLY$uQsY`~9SOe?|lAkCNqw{lVspW4iR zo|sc4q_iw+yIkM>623u`*oI z<64>wl~pB%Zbe0M{iM|@1>}@f5+Z>CxG=|Zpn$BGzC6yBe8-bjn7N{%jDM+8CWAbH z4LX2TQjE%U^A%BJO{3+D$s|u2@hB9=2qP5K%ArJ2ZK~(uk%z=d+>eIj>`lp|fA;+& zNP$Nmte)XM&1jXhO2(>Z{&P#PgHdapM`oxeqXTH#=TLp`HJ?@#k>g+H#(=B$P#`-h zjg)WD05BWC)qz|wy_0>1mL5%*yRnpCOpHqT*julU<&SPENz7wvlpIIZ*{J}Yrrt;R zV!q(0{o^wZ(kiCk469ZKGx-g@N(gr^^DJnB_dmN|$D3_sMx$m*Wu+ zhzo=9DwVyq*XMyL>e3$r0787V#EkN_gG%OOe!GApQasWnMLxQ`@nB_;qbNGX#gz29 z9v1n0KZn+;Or8~$B2!T8MxvqDP*6a*B|@VA08O^?40a{FH3GFtQziAeEay`di3aU! z*tLN8n#GSrTYxsS!B~lhs4b2rrR+C^R!3KrS(S~nfw+u(z7XeP*R{NEMl_ryP-%@q zD7BP&3tae+mFEI52m>>frowVi98KlASY1u=GX_=&z!|pnhgIA- zfw0n?O3`Jfz}N14s18y zd_-lONXT{<#MMtOR|d+r{Qh{8JR=$JBLG*R@IO3sA*)3S!eErK*s_@4FXG7>+XKC= zZ~KjttS!*iJ(k=3ut@;w(vt z2Yp*%33B2F5MDaRU!IeQ8u*r^rM?c2V??IM zLL5B{kGUA1GE-z|k>Ny-4mmhcW5>78Y={W4=}bIWvDYIN-#xN4QH3psT!1m;i;C~e zp^x1X_43Nk$e{!{d?3w{g4OHva%N`s2B{c2ydR z5IT4h_zRpWZ%=U=8hbzDV?~z=ESPso!&0(qRlfGq_qOynl#hWVusW0<6+Rx97z64m zAJrL6HOHcv1|-6Wamj|ngVY-zo)uKZ_XE-lD-N@I$O^a{{RcZf+;y-xDtU!5;RB^}9o)alD$AFvKIc)I9Y9r*4O1Z#!S*fPT{W9-mdO$t~VjAI<8$?#eeqf4rR!fa{MT zuOXGXX=Q8NbO#Ccm74PaKU?8fJA`Lw5qztSStzf=%NffpWj@-+h^Wpx~!1%NZ_GhDi6${d~^DgGy;o)a`Lbe_T^%(|5T>SgiLSaiQtAcJBK z3LkeJ;F`U>_V+NjKj+WO3Rh)oqA3o=%dO7B+FSwkAYn=pfo0SQBp@1vw1Xn*Bf#8k zx9`Utp;Qldj4iCUum^3G_a0a%m17+Cl|mGdf85{x@cq~krOU;Iw%B_A0FUR31Gdbq zQO)dIkSu(9wXi9cAkn`6051XM{y2s_$n7NfPlr*+FKw6$lig8k>ObSK!F6X7M-B8_ zRfs34Bg}seqih6J!s@qDKtFhHza!=KvA`~SQ6>BBa8HKck;G#&#Nrb14;r&x&1;Jr zc;91x^K1&eOE%{J04#G24y%+T+j|jXZ$BgSI93+$J0HvFe|KDX!D2h1roU5;swgeE z>-l|ujyjG&Jn*oZ_6GyWg$f9bYl*!1+klzOr&2`M2QFkp|~W;_$B=@E}SWn(~CWHwUYt5Qq!>-hfpMz z!oc|0pF`6XCosuN9UF5-yl!V`2PUwg^p}??i-$f?0$o<&um`J+GPYPzVDL< zVPmekruRNNqfm=)=-Sr8QTs>MFY_XTiAKR`>6NSpnN?6vuCs~!p$%YlX;tOiF_=s~ z&X#K*9!$3Ubb`X%_Q8!$U5D$p#K1j;$J@P^15H=a|)*O5v*{p($_zh1mw>Q zy-iHl>#AuOAMUFCaqm}bNd8dklM0~rYMT09qL~j z6omD%!%+VKgIIWacw?$w%yNK#{U;k6>;)vd{I0_L`e0>vl2NxXk02$Df9_lS{!8VV zAox5Lp1^~c5o<&7PJXXZ3Y9k8~hA9=c4 zuZPz7a3MJGz)mMs7u@W*ocX|#uT_X9woC1hG6aR zR3m~n3`ieEaL7J~9P=GnSfO349x!@Xnks>ma<`3oR`CyT%!*0m0f4-Za?~`=3 z?0+mrO-w@*jC;myx80C`^Jg1=7~_X$Q3N*KgUfO0Xs!9* z6L|yyj%?d(B>w>S^kWR_)EF6 zTDanhNU0J1!)X}4x|?YztWD#kTLT*JZfWo704cByh>p*yKG59%06e;z#Fta0$v$T4 zPl+e434x8ntgiev*<-$F^FK0n*Ef1MI}PJ~OGdUToqL!XSU>;hBjz(1i z@vD#k9TeKa<9}W8Vbw&Mt~S4sALjV0vaM25(U`^8-d)>!T0U*>X0`9Jw_F>=m+L0! zvGLpS>59KdRc>(uds)wPM#!WR{nZz_yKD!p=MveTXYP>GKng~Q2nJVSVI+VS3m7`x z!YUhgRBGM4Fgu=PD=mE_Hn0+NUfv5C7AMnD7&VJ0NnPr6A(5GbF;yf)4WnSz_(B9$ z9s~o>n_OThf^tbQeiF>7V@A;`vzxOsFfvHpZpX*TKpIq7C;$PATiI8Fxs%INDDOGf zZzz=7HU9vte)01}^~EEb*0j?>Ngb3sYLKYhMw_|4yZ}Ewo;cmTn{b-bQy|l&hdAhTd3Hk4QB>Pi?mqDX z!@IXzpHG;^EuyNFu$xu2wy;wOa<^qSUA-|rGub@t^2C;1k|MY4!ik_?}@y( ziZ5V6w@di_a5Yv%?luP;$9yc*D~?2DYFQ5kShUG1RpL zjqrluMO<~r^u;(3ht)YuEV$-4x3Sw64nx9l*cJ@LfNpjlfc^Md{X*0-V>*31T5upT z#g4S%!OXZSCv8Er4ZErZzt77Lvi=pPL1Mbkn{I!A!Y9O28NtkV{{S51<0BHX7RRdC zvFo^6p2o{#Zvt*UL#6=pyriMJh6s9U^BsT5!xU=P(~M#%ev#@KJj6BQ=5dBgj>aF` zGRsE~COlcNq07y#2s>}S5iuN46*3Bu9Kx3%4awMGqK|}-MkJMpy@(5Mz}y?04P{WV zbtSYdp(IV9bU zh7|}9?zmy{y1wUMIwupHu+rs0{AJTt+vc|!v6ruYks?6!%=ACtX%0TJctky-F7~> z@s120Sc$m+o|hu{<+ye;xZBFzKMWXZfck_1(VyusQ4xRrr}#=0L+K(+*Za ziC74YUG~F4QDcXbE*ZT!!>No#Sf0~3`%`d<0czDvn`hha0lohKtfJ%9Po6SnYnZ6< z1bJih>xp9Y+#s!#k>Mj93n95;-X0kU!CQ_*1{Qm%*u*Rj? z-gRSf8Y{1zm=ZxgKU_I{*#_j>=yv?E5gux$dX9iJ0E7Ki9X}t}2&w7}WsY$X$g5G} z4{#Z`)B88*JwOr)WYm8yG@+u;sL8mXUs3n?uV5;d)ZV!h*7M6;#(0@7Ic2-f|4 zuEX%hd^=O`fF)?=j*(8r(#Dq>5#Owl06y{7y+a)k3e zNPw8++U28T*QnH{%sfXz(Go*pz3h5IQOI^rvjDSy>bya|*3?4CH4dI4z|Tz#3_!{Sm8t+2lwQvU#`C!jtGG++Z3_(5*Vm^$!Z|X4@ z6)`5jUlL7_g=FR%DFB^66}*RC?dCC4gDIKlQof_l_k-j5;a_+iZ;37}$wVz0pdno~ zSdw?R-+qLHzwX1Vm8p?|ksd}PWK&>I^p9V|17V3HtcIkPM_`DAl5Kk&6o1W-QVm^1 zFavJseR6#wjFJ!am~YnDQ!(NOU`KM9FYrPEf9*cterFI#ZlHBH4#a+~{{V$?QSl3q zI`a-Ps_e22T)J6mWhtZ567zQlTl5)?}fDB06t-8C$*A z#1r#4tmn>S9ayt@3y-D9y}t~7N5!rU(IW@Iu-3qlU~bpx>1Q0edA;o^FNLp$t;>x9#uq9@anJw`mu`>^E>(AR=Pmirx?1fWed)S z6iwi5tDADJ!_dSx<{MxG94)sfwS?l$h!^*>W=5bhnPu(Ck*F;n2t zk^N>L_;8(HW7UCn2yfya_<@F|9L_skr$P5dw13rw@Un3RU}tJ`+!diwma!$b+W>*3}90I#ke)lkT!>x_$ejjj4(CbnbK{ESAfY{8sh1@5gjGUx~OrekbMS`r<+uMUA}e^ZDRRGGP`aPOrHw@oa1d zPb>8wOcC&T(=fMP4{z@Ne=J1>wT377A~Vkh-4*`;?wm@f63|WztjMBE_xCNPz>6J? ztzs~glH6KVE<7E6AU?O>>ff75IGz}*AZXTCCK2(Dtwi_-#cUkl@jhZ{{Y%5 zz!v%&VlRNWR-$@%Xwh{@&hFdTC}Vp&TFMk#Svw1O^u>Xb@chP?F<5~z)l902I<~yV zwMB;3*xP-EEgl%)>UwH+%hiOHa;O!OgS1{GE8JKmjfp$8*o!V1*5a@}&^ka}kKS1w zh4v*+mQxJEI;c`cM~|BF^oP7nt#KF5 zM}aNq1^)m(pPo6w8JhszKq9|$ber4N7i!2X);VNCEQ_|?Sf8K(erE#QIZ$C>81EdS z`vKjPxPF0(lk&mLvp)Jj0Qv5J0kFT%0U6d`_Le94)o97-V!-MD0E*acI$|K_oXa0J zWYZvP5hN|K7rR8@sQQT;Z%jo)TB?UcXQtLme&Kw1m1ZVLVUSzmLT}d6BPadxqZ0J! zNVT`O>4{;55rpN;iQ#YrLpPyo zvAZvbHW(z~x@nO~c7ZG`JI?kNu>@&R({GjqDCB4$X#z8rs%=WPxBxf@du%K`dfO6N zvpkV^7fzwOI}NTcdoH7Y3mb2SKbGE}e{7fPO`bRz=8d)t`d5DV_2 zUo39CzG(Ds@e}xBhV~W7QS#@diP0-jPHDCm;@z zSz=Ofb;A5R0b93uy4w9bw!l0yM#oA^8y!V7>d^Xuu~QtPIROW2Xu%B{JbT%f)Pe!} z^gm2=S6H_%^4@dQ*3~!j5?HN8X!NF)7U_WuzL!-&9ds&!tJdsq*YMbHj^BtF_~Xoi zZ7yBIHQx6O096(M_;vB}wlFmnSd||6o3z-EV8;^BRJF$IU>D49xfjBZ5I!A97hfUQ zY%SQD z4X?ei)@eO8f@e3X^|=B;RIVcGF=oq>!LiUf`kVS3FH6HTC4z(40$B=3Uzm z2t8EvwjsPlh6=9|$>D>L$C*cn2{r(e3C(Z6sf75a| zx&ndLzz_X!q&blr3){@#ZQ_rgO2V&&E@FU`mNOeF zl6^7FMqbKn%2fK|JjKp4E#pqP)#N{P=Ms7RIMY?Q0LlA&rMHm%`8>}UEZ0R0V&K<97ZTR4;AmSY= z12<1R2QC&9rd;Kr%cGM&O4u5_*AZ>Ym;(xKE{B)_KDA6yA7@!62!QKbO!8f{@9 zj`93i`(EdBg?NXEIiL$zc>M7XryZ<#WKw{J$4HUA%9YG+wAkoV;o8TJ^x)>h6Y}C{ z_~ucCQY>;;rOk(l@)#avww{JcaQ#U`-4r2CR07N!8gPvZJ7gLp9mWP zh;=V}*x>_6v((&8dhRuitIR!0@X@vYYv^z*TT{PWKBulBH2LA9(_G&IsX`N&)r7bb zITV~s&{GrB9K!(dI9X-W(Bk%4o&*|Ix2%+;$O-Cgg))@1c9?R@`Oa%At@+rKVR7N-z8XDa9rv&*ci33% z)2SY~?zw*Q_pI7CN%tXrzw>^#@<^un*4#*+kQ3UOXq7;emLN|6{FhTK_? zQd+{q;ngZ$G`;Q=2EScP-D~>XVdiz-Mg)^|y^ww7>8s`E{up79z14vPSb_r^oh~&4 ze;xHjiqspW+Nfb5$zszq<3yluZ}U7w|@bacQe}*fniiIL{LJG8Hhn>{ieMRt#EYuC!62&Pu>9`i$b@3R7&Z2Q8t9=KCF0eOBM@o&KXc*`Jf#B-cToVtz%UC34!wfl$n zV2>t%j!0(=HO)6$+#(3qe?rT)8s#b72EgjM{PD<}yvJav8X)vC7IyrCU|#T@#2n)q zz2~v}iwge$T2Av@`z3$7iB1$-B7z3MUf2(>snyFJb-PS$S&RqkSPtkbKnL ze>)NRVz0{LQ~IUv*xwhd60b9KH&zXOB^zc_ZNNSZ2q@MgrY%n1a!PsWmZa*Eok}5@ z2zrGlLdP9KjUq*lycVTSyAUNL8=R{{o?6!oKQZ{N{{TD?@Yia_7Ajjf zyM`mg5oQ}>6?CLonXbBk6KoyrJ0fam-BQw|u@;VGI-_{OvCwUOL9QKG22-&eFe{u= z$a0wEWo-qgK;&#&mnkX_ONBQ$y0W_ZSsUEs2(icmK_U$>v)aX?LVn6lqF71N;^ln@ zyIJ8Er^%8QwUVl^iyMLkJwaAqLZ{H}W78cbm9Pq)xS2YITz!}0Y2?^_F!G@Wl2^m21Ta5=+v|_JWPkM> zt;jpUe=d_rVe_%Yh6v(Rf+bfB#O%Gn^4$GDjvvEMU`g`aozMCCVLY;RJFnLLNBR6P zK}@ItE^G)VrP+nP>iK$`DD%SXane~6ba%y!9MhB4slm5~`fw>V2nP2(ErM<;2mMsr zZ+8Rm3AdIa4UdQ8g0P+#kP=NI-=XqrUw^K^{KgqiP|dsQH}O6{FAu{6p+^3m7)p9U zrrX%>r^5bY_D|$+JmPqX0+0+lNNzUjI(qtHIjG8;4)ylf8{fcNuhSBA+&xfjXqaEl z!}TKsCnJeWMhbkt3`jvr#BQeEXSzQ-eJzQa4h^Xn-DAIB6ZsF&;z}M0TZ1gkw^Oo< ze9oi#U?hoPrUsb`>_|SKgZTR6-{l}W;=zOYHb0D``P@9G<^Tj=9gaJoPv)uJ&raeb zWAwk}f`-7J+3x`(61Tw=jq*l6ovr!d{9Geg_5vGU_L&#*)ql$bQue4<;G{q;)=7uv zEI(Xw-KN#Gv_(!lMU|u@%i+E~xXIchIzGti$gvTNb-bUr1N?C(N7!9c{3UJXHIP3Q z1Ah(h&G@4;JtWb8*^O5If6f4L%vr8rclXJZ-(V(Gzn}Vct^3tqg0Js<3_eLxPk2afPR%QS_RbWd;K@q^pkCweljHvY!XK_61~S`3 zvnJvyeOimM?Q0vVZMQ;$5bwp&20A8;3-q}Bb|d&>iua|lD(?2@8%reCJ4VqBh3#W1 z1|$|>3s`TDX=(D?2j5WA93F0)=>)JA?|y66afghw_T0o zGmb8nGDMU`kP-tj>I?z3_g4J;@Se7$(<*>+Od_|`uzU26iD}1mNou<;B>83s}Ih>~=ow_C4p{wrgFdAI^Q>D0pa>OS|68nDA5Po5pf5I@vY__T`)#M<0tfOz4SGUL$gQm+I1`P|az3<$U$F0zo zHvXu>S$Ts&4B81ldg^cGXB~Fva3G<&OJt6)0zT3uQ)fWl8(m5M%M5v$$IZN&RcsWI z)Tk!H{sf<{9cP(aYXZTR_YS05+w~nmx0S)eZWjlWSP8w1V0?s|+s^^VGQ{y3tAW=I zUycw@I){D$m) zo?fSKTorb4P_Hj4z&)jFToM{hg#5 zYl-+p6;<@9YYj2(0J|Q(0Gv0=^Xqg;8^dJL`M#gXVqe*K5guk%#EibL=h7Qn*9|FY zwHuwc`g!1(!scHwj}Ye56}rZYYn!nw-4B4$KQoIX*;9v$*3dX$JC4k!?*SVVW9Q^O zF4Vv+jjg2 zogu2+eavxDl15c(BLJ)H!rR9ENIO^qxnHh4j;q4h6yY8sZ9KLli-O-zy}w^0_~4ql z9Rvks(8B6SCdb8Zw&TOhe2y}$ue^O5aFR6hZMeYi7Er4ThSI>?T<>wXx7QM>)4d~n zg_rc-^TT&V9RT0Q$MM{p01k5uXFM@A;*nz)VA|D5>v!g=+o=0MV;)2dN#(hc2O7a5 zKprx0(2dZ8@UpNVi(DIyqXRL&EyRdGKhoJxqyGRz`0d>`Zwwj9M->u0fDN$2`rW!ri;& zwMirCH0E-7hDgIBI_MhMrT0*QNzkN&i%+wR+J@6CQ&WVI)S5J*!7dVXvEI2W(smrb;=zd{I*bpFeK!f}YWN3}|r(l&}| z(C%G>NEDK8blYO9&|lX0xHvP~2C7C;DOs(sG7bKWnphvl52gBq9Z3^8^wg7_49n{* zLP@(T5nwIdU`E6MLXZLIEO1|x(8*v!+Q*{{lW)Tnrbow+Sn5ZNwaF^tR0Q=pBm>0W z*Ecvf$g`SvRns*#yFBJfwU~cl|z?XxVpokXPzI zh7whfPLZ^MkjC$DEW`@|dmC62u^v7ck$kj|g|Fy${QCa5x8iVdE93(pGdc+ue(7IB z)8~98MV(s?GfH_!P;J-G^uO-FWoBbyaPk$fVl4Tr=1td6sGA<9`{Bg{lVN-ajOgL* zHha?eVAgR2EmCtVYFUDf_dPu@zLRT?m=&ka*4=)XbarSA2_5Lcm|3>tS&!|;Q18k_w802>o*M`xTYfrBS^SKtq)mL*L^#@LOh zW;5~m>czQVkkU;*Z0{)nW zs^C-L<8!seg}r@#Lk#ll;ElTCW^N*~fI-!7rUVVOoGFDh(_qU8&Q1kovnvL+_UKK# z2VTCoX)MkyWVP?%iEM*2EWi?dKZYLW8IV)qe_MZ@@ozfK*luUP4_@4-5+!nJwj~FK zz>EDxJDoxv@)7H?2jp?l%rASn2h+#&!}?6kSZQELJ8!-Io*1Ea>O{8194Y2ROHmo{ zI9iH|Ci52aIQpk5DoFf3UKmVK;NFrrFH(!*+`V6@$St zrt%L0NY7lXZ){5CnW7E4U~wVa9mNhI>QXT(x`qca)ohnyM~TOgNO8!*v8DQB+yRM9 zl5-xU*TbmJ8ATEDKZZUziVwU#oBo(tu^UXs^R>a=-nPEpHpF_?>gXBGf%Mc3h&I~R z^WO?jnxgDje1`u3rWjQ5ErHO#2qfQY0o2>muUsVPq~R+>`iV7dqm$eOB=xk_EQ{!*D#kdSEp1Nr~CZ zuB{{}Hf_ls2IHm0{e5mFM&6QGZtE^7^R)Y#r1V5B`RoVdfo>q;xzI6=6|!GjNL#tE zAdsWR{Q*4=0kdCd4FgO{1<5ydF5CGFDuLuIZGgP%wOOSai;cVmhTk9s`ugCa$Imhi zHRF!3n}~C&=QcBP)qxjS%uBlwyPo}k8i@k-wYuVs?L$4Kr7mN0Q9G`kEc%-MEY{fr z9nJ36upT&9i@1tfg)6C#hyworpQb5pCE?~K+R`uDF2HT*qU?VR99Te}T2!3k094cq zmzB=9B(khPpO9l97PiA~m=esgL{QQq6bz*lABl-OwT8mN$8X1c8RlzG0oj_R{0Rm) zhtT)h-%I(72WNS+NJ(w{08wD0$y9V7e;10Ok>Kw{|r@eEInz^>gH*ma9Yb9>^=Z5b|Y?K z{)+E!+Hy}pzqVpXJtJt@8OAB3gA3%`5(g(l+UF_$NBo<^*;ST zKQWIo%7Z4?IUP5{%(o{KHluARV#JI80B6*n5z^m04kae02!ZvUfE$gvk`BNR96sVq z=tUaDo&xN5yD=V?7bJZ?gA-L_>OCYg_Jo{2UGEEBXu# zfZlT_aoQxEWms*VGC!mSrTkZM^#EaB)-zpnR3k|SD9E`RFf*GFd{^i`xNRdf&g6dl zNp{N__Z+;R8ewaCPDPKX7`R*xBomoW(UKVHxF@KwHu-sdZP%_RDWnG4-%;zN0V|R= z_yN(Y)<n-&RCw?E&Ie?qE3h{n z0Pa7C{P8cI(ndSPrRR8lsv43cPQ zza)B(Qgu69=3PMk?h11G)bl}8VNWr+CHGw?U`g)*($+iM97n`*+VRspt?@pHg}lzD z)&Bqv3KRj%w_fmkc54#+PUq2A_%H9n)7i{LNDAAHi!&P^k!xXjrl^03;f(oeG9Sx8 z!-15&yVYzh;Ti?o(6C~09%6~@khX`jqa%XJ(0fI%bch-}9w3nc9Aaa5xO|UDo+<}ezDJ+Lh?>NAwa%weYwu&fhvA9(t|+H5uplgerI0B%)Im}R766YD zaRh3@*rWghxGE3<_$J?$9^|sLgs@28oHQO}p=|1QWF)P$gMO>fTH|b6PQuGJxx}r2 zs^m#*(~W8MX|fBGZNb0yZ{hRDlsr)er8)_}?4;K6-$H@)I2hs%5vfz}QADuC29$S( zq9-Z7hHWb&u(%|ACc@Y0v_(029fQ_R00^91dU3C9ZNnrUeobw;es zK@_yH%>;^-8W)`*2bCCAVx>j2l6(dk<-8X~J3}i+6l7D=X0t>T2;`iyNIPcEy3(7GFvHoRu`4$f|QS)dOzSvPVf$CV)2OpktzVN&f(6Dk%V^ zg>A*T3{=j#rYkj7+0j7>7k|23?pPJJk_fQ}s2E3Gb$SI;r(6@9{e&fGZ6rDA470A# zs$PlUQj@^yi>pcJ#IYWXqq=nMX+naafKEK@l9A_%SCXhf6jD<}rf9^mGt|k;Rc-YE zm)Edv>XB=e1ssQhq>hzpjDu1uO34uoB1ImMv&dAC7D*iy5ZT?0!kaaryFTHmYbKs( z+A<@&^2R~ZP(L>4mrnBX$!*9U3dMjqm-wAm>4?S}7*fdm^o9Ao5~i-=4Gzj=gIqzG zPL?4}mdB{pg5Zx!fJvDSW4RiYuW;76U!P0;E$M@v(0Hk*NP$p|JDG`P9Kh2tEKGnY zc%A#}bl44v0AO!D;Fpb^kxbO+;dO!oFx8|2qr3|@bQJ_{r^H`N!8FQhFK6{}kBGLV z&g?H}FPu>zbZFz!7#p^oEnsc;c4a$nVlU!0yk`c{mWr?`vusq6evHj~c=X%pi|>l~ zw=bJ7b&Z5ms0xr6u1j14b!8$qQF3Y`WIF)C`eLETuF12ePv$$)4u?u_c-~n$dcwzSxBP)0jf04JZf&2y(;kO2O{0+hN z#d^r;3OfVJeca};gROnSqQ|DklsnxBD{k<&(-Ba$g@z?^o-Jxhn)X1h)1t<8ZWSFq z({7Af%clD&7vH7^V6Acq(totdqw*|&EP2luk^wR^k0LrecNaLleTd+_eGsZQ0#@6#<2mCnFUc+3rub@O_Vz5+}TY|vyEx7A@dRSmcc@Two zkR6jybE)&o9XhFLKqJgGQ*Y>QLBNM;nO2;uA_sr}08D;$G@d_Ay*^m7yE3L&=<{K^ zo=q=?_6<|yI&Ln1$O-MDhV&UAR|9O=jaTnprkn7$*RBYy!ID>rOVee<5J4M%pRNdU z{M{UKq_O^m_tWR+Ww znTzX+p{s)JAZYiuc}kDQ*2J9@@g2ca<+#83`C{NQ^q$-gSz*#}6KcFtuxnUY^8f_i z#4e`mVosI%VrD$9tp|8RI0t(W8~dld`C`0_h#7ZNznLfZZ-P9hj;62|TMmGe`|pU{ zd#tt>vBaE%G=l#CZ%Zoql+*{{2p^Z@g)?3*qbsEh;P@k6=gDqCBg?KJ>iF#d?+yO| zqp`oxjqx6!8CF?#Kx|H%wyyx%M)va{pPnnU9@E9h?vFrFsIz`}sUr+`SqbzyU-%!(68Ua#r>|c<*Y&u=Dl#}GD&I3)c3)beCYDIG zM$(AeV&Ong!MniOcd_qvBhv;ikWt9`EMj{X4H+n`JER5GbZZ6#?TSa)`?SzmXqgM7 z?ISDdu~H%|!G}ju6VQX_;d;Y)Nf)tD6lxpk7Z%hy0s!#xz}ygUWoyHIq#brcQ3Gm< zb!|Tmtx>hSKy=iHe*zR^@A>bjr@5LJU_3$x2m5i7KfP=t#4jv%x-uJBy6&xe*n+kI zjlLm%xR0RB*}N64-MPA(fvWn3+wX0O*x=ztIp$WxBk3^ThJB`JXRt5JKDI0PjmOjs z8yKnTS5g#^AH5qX{B3{0jAvT@1*VfxXu)glbb!ijb7^C-u<*D8ae>6(mqsl|S0WHE zW+k@pvng2s`G(&WYLs%P5pe7{VJ=+jCA{2%kESIkC<#4AJfbSy;KD>cRwRE_hmWDe-bpn+qPOn?MwZy@ zZE<@8)58tdtXl_67^~>n54ej^Wv7^`N$#$z0=6WzfwAjreJ|^R*x|SM?0S0Kd35n7 z(*smh>L-0d%XC$`>bOz8x)3jZmjwKVdkD>DPZ$ z-3MNn6oJ%>5rhm2>w&rlJi@JvgNREH6klZne!o0R=5YoAiLnD~boIbRJ%%M|>-XF- z7+vZB|ol~?jz~4q*1ePgeoK0ZZYLF1nqlz;m7hW{{R-=g90EgQw$lHdPHkN zaFpX5?oAo%Giy}k!$oYYVW6RY>w}@q-{EV}eYkg!Q)L3qurr zK*QR6%G&{ey@ZYgC3OWnnbl=T2E-C=;5T%on-``B!4L3b&tgTN$4?I=e@E4 zaS~eB?>_DHQDq-e-z))V9BU+(F6>A2k9X+1DEbT(yr82UW`L*TDpbAYLPvl)zJkDl zen)IVW?is=Z4`eZ-9NfNdBqbS5l3t4y|?loiN|fm1pEtqudu&QUZ18GVUw8Jj0_2A z*YTv%{BCS~2X%h|*Xw*mzI?0W_#9U?IgE#Qkw>PjM12QzemH-Y!mYU_`tEvq`2*B# zz6ZdC8HTmJp{|<%Z~bo{puYHmtm0{3r*wI-w_T3Lupr9dQY)F}K0{{WD~ zXUtHj1z0t%TKf&okQ2lmu1P25j|@u?W32gPRMccr2>@91xHi4Ow%~)}Fcn#Dtswa* zEPoTEezYh^gzA0@wwjLGm6JE;%j~F{$3wn;fwvCvnMkdQ&)|=Hy8TY zVh*b|1EBF`>(bx);u-Uc`ICtLA9+p>*$rj;nRIp8o*n@x$DwC6)JEupUEisV2km#BP*h%wsiE4xljkTMn}7pyx_mPhIVA znYr5%vrq`XoRAObMgt#_ZiDC!8Ri+%l_-&f2dN(ue_6VpmM4SORFfuOF^(0}6P9+` zSr};^ilX-bd39s?R{5(tIW2H6V0lKhDG9;qxN~+;&!88-;VURZ{&Be z9)4KPnG`^2(IP$6Y(0k$qu^Ck}jhSzM5X!)QB~Rst`KEcOP(`N88eNZZCV0*9H6? z*mY$@CF4b1VOlqN(G(%Q`-1Gnwzc%>>w!F*gx+pff8&y+Btg4J?)pO&1d#i>>bJrT z_ZK2HdIYkmVosI@z!UKgLFv1CwS zRU?{al2IZfNfLyCL{hscamcAzY*eTq5^r;HSK-uSoS)h;=GZ< zTG6QR)I#4#H+BF82JK~6vtxgKDTGNl(%p`vXg37E}&R=VR{VGqIYOvR(7h67@iIT%M9mQ5_HtCrgl z9U31RBUY+;^n{aEreZaddv`{lNV<@5&k7K0G1!>P z*zH%^I?uaPsjbx{ktD`CIbf(}vX+JIb|h(HRfe<|VjA`xG}B`$Yl0Yc9Zip4mNeG} z(`Bxahl&>u5^V9Sg(KrE+D)x}*@!B9v03ol1rtM1lITMwValheBJBe5o=8a`5@3~esqDNa?5n-9BG1*UXbo@l>xdfK$ zYn2@cw}r5sT8($G{O6fzlTlMM1EdxgTLE^|TcK4^-snZZ{rGCxlHa`{1uPc&iBvY- zLHI{YD%kpMhdDx5c)F3oVIi7jPOdz*1sdnlgO`40sMbRg_8p0KZoC?gIY+y8-_I!BbsLY0m;% z@r=YQla?^@%+(BZsd&_}D5@h2stU2!p;c^IZY?Fo7Nv#I-ktQY)D1Mo;1PT2Vc;D1 z4aLb)7?2JveAb$tsp<7oQ_BTKLO~p|86$Rw-KCi(MvlaL#HeG9P0XKUMU}Bmc2!9v z(=pN-o|)?ey4(j1CZvc(s{QDZM{wx?Z`FXuBd66}N!*9>nx0ZO1Vu%3GX^zDqGt@; ziv`mIN_qHQ?uQR$?MZ=@7F@18Hlz#-VMicPvWZxsEz^FX5O0cI)amWgXc=?u+O9nd3T8-2;;M`ZerPWJIuAY*mWQ9V_RM4;^T9!l( z8{$=CsQ}b|&}snOW2kQ(SD>PdIpg9YbY)*Bq^y=wvgu>gfC;lIkZvw7xZ1>d91&(Q zs44+&V;1H{@s#D8jUYAb+JQR-T{iIqT1$v{ey(D*GSfv9La8jMp;6^o2RKOTY-DnR z;1Q@sKpKc3IINMKd9014g6J{>bvvCZ#^JVMsDrh~bYq>Q7qL`#F_yqmXU2)8BFfCo zvguMu(gwf)by#(+V)+TTwOmc^&pR}@nFtPsl*X-@ck)#H(` zu4IvH@wwF3WgvmKO|TD3z@kWND{KIE9xH+(Wpl2#Dkum^%DbdIfw@R z2AlZruVmEm*QOyEUnNtF56fV62$fJ=y2mF&6+NxvYP^L z(%voB_8)tw9d0)mmn)&c1b$KK_Lw!q+$A(ImT9fwr9zL4Np;f z*pp~U8=c3~uZ{6Zc8?CI3kzxd{=b#H4}rEVKVYK&0LqzufDW2!mLQV1UPx18VlUqW z17K~`Vw944%h&)sLe9@Pp-gq^QHvT%YbKGUzRFTUz1O~V{2fT#UdI)mZ4^Y(T4Lu_pZ<>91^8Hap8B8Jz7y>#rkLef zR1!n3cY2B8sJD3{il9YN7Ng(MFE$p^4^&cbq*~PiOG??mnZ7KUfwD0cxdDJ-ZAEq< z1J}$PdZ_KQByt7V*}K5sq1+MpV@G5#{HyNl=CWkFl9gnYT@=-RjPmxiIsy@XejJi)u+|`~~ zv=G8TW7(7{?sOG8j{g8YgxyLsysgGhHG?!x7xsddAC}*aKBLVfjQ3cN9f?!;cpNL6 z<>E5H3F+JRZo}5Z8!!XZ^xq5RIed<)dChVGvjFSU*85_{wUeJ?AJX=zI_yrh@^Bvi z0FBNa!N!qDcci6qMVL55CjKf(LKt-gTWj>hbX+|n2h+-OmedR){qC02Vnz1brW;9+ ze$-2QbXApqU9n|R?>t=hk5U>!NFk&0(jxZ zC9Fb%d`jRZlV4M==XNAodUvs+Hv?XlnS z>C+b*Vy5LcH7Zl9( z@-#s}lAb`tmhH1E0H*7v^63Yy)9H=b*~61b6B}w^Ndu=+HvBP(;!ewk5ZZigl5ooE z&ETM4?JO=lMa9Ly-*I9vjC?&Ca|O8$_B}4G;;pA;Bonbh4*s}HiYu8THn_NJwvzfl zU0(<-8M+HxdYngRbx}rzTmpHP2SS2ZYal*@U5MC^9)}a$Sutqc)!k#d zumtKx8h-03E!6G<5EyPj77IQ_OFS`0HPO)kS%CnXf<7x1+>_mX$A&dk!$|=`jf&lSx8B73L|)`t+P3I7zT1vwyeN_p&V&}*?IU0$0>Z@Hqwl|qUwyX0u`uAzT0$K`_F7VQ>Tg_Yk=?CQAw>joc&AcA^8WEpi$oh9_@3V&sellV2ShqP74 z!+(**Q<-+0&O7NFSlnuigSV=;)8WA0VcHV8xrtPPZsd%gk&NH*!PU6I5JtXo4AD~5 z>K#D(j6~G&EJ?AJA#VdB_+EsTZ`k4I>bEX?p_Ncq5L?HT+^!PAfxRfU| zNLKOW0D-JAZGb>r{{X@cA~WtQDITadVny|<02hCj_qHf_xY9*q%2ZH&S@fOy6QtVb zrsMF%x52fD&=#m`xd5(_U`_Y9`EDpjQd;HBpw%b&V$A zt19?d-$3c)I^x1ww*8U#pW%pH!#IUyvZ)%FY2V>r5O&`CSl?_(!P;FgmDiQAP`Yn> z5I14BkK>A+LmrdfQul)S*Jy7G6)2>Q{B831y5X#Sw7r1}hTt8Gc=#UoUr#(#9j51h zXj|SVKuOsO+taI$(-qL-A`f=1ukm00<_;~$=18Sxr>E_HQ*W|O#qZwpw*BkkRvy<} z3y~QD*S5Rg%dd_yY+PF8f6}Uahk1YdxRuH?*F9<~4gA=CKh9!z&l=QCi=o#gPEbq=tQnI&7eMZaVn=Jg}`V8dzB-mOaTD7=ix) z3xRR&BraIsLEPHDVs5FU!@aTm4cq<^hP3$@8=yv~tq6=(}8-X_s-2`X-OzTk~J^d1-M>CJr`2+gCAAUe#Y7-_f*q_|sX z8yz~d>gm@Jzc8Lrkd&0%vKUwp4S^cZOYBLvpO6G~7=G13fgqEyB|?Azw^loa7xX8~ zuFgjWRZONR66M)JW-5h6uA=P0g7>@1H`~- z+*lLf4*0s^hgmOP!_$b*E`lc1blCTFjY@38;to2V=p+OH-q>@PS4g94={7eP(`y53 z8`$nH0k=;>gGhTnshT*JK@=?l=}SfwwU2bkq>~|K7q!K%NwFkh%?DvY*aoQ6wU`9h zo$h`i=kWB{VMnn+Qr(W&6iLF+<<@( zJh2Al1PCRlvau67cBh*Zk-b(E^xPlJV!Ex**8c$GiN4f$l_ZrB2zD`|upKpOVg>%b z9Wh(+B@-i%Ptn&DQ#;$M zMIOq1Utm71^u>mKhGu|Xx_U}o?`oQ)FK<3v9LMnJZN3vWE@k)rNX!|UsZnV`N$4$h z!Njn^SXu4UUL<-Z7aDSyE#OpG?YHBM*OqXMi~&hJFWw5?9d{SS^X;D@2AnpLY_1Tc zSdd1NM^#b|{uds&sCXf-8j^nM^*arRUm=R$%N$DAoBp8I1V;9W$`$bzf1oBe-5Jm+?Q5ClkG(QQoD%zlUEB^L#PNX|(Ou$MN3= z!N%-y20+dscWS)1k|K@>jTujmQY~w2dSZLB9?sHKdWl>|2Yw)QhndZQeE|0&UiOY- z+~46}6A6~(OYbqqDu!7jatBd&fyy76xEAtdz|RTiZn3SItiTeX*;JcvvfHnT$6Kb* z)q%6FGnt=d>>Dl8cbM??=9wwg<&Gv`7z>>WPV7e4JJ=1|0J=a$zrY*{=kS%Y4u}5$ zU(feo{!HbTFp>S3xhL;#KpKG{6+2${Ha#tfYRsA`5Gm#>3)qGQN$|Rr*bhQat{vBD zn%ati$mtiZz#B2A3g_^p-bChiO_jC*{217afxmah1bkD&b4CGjgf%kGIc;$oIT}># z2Cc`zseMTX@VQ1wPaMe1y5m#cR|T~L;>rqwRBo%VECu~$^IGVp)v1wmun{UoVqbSh zU@6$BZ}wKuKmjBtayA&tW~B;(hmNtWm9Rdk-a*>T&_oeK5~9oA0c<*7$8SswBk`XrS?$l9z&c~k-p)*U+G@XFz^?+`;H3zA#nH&)w8(k*fY&9A=rmEp?b zvbZw zrQUh`lVo~a0uBc>I(kdiZ zncgxAJcW6#rGVNnfUUvZoC|_RGOjn4!xCZYYRc{d5brzfdRnKQXrZ6&REkw(GfgWX z9M1VIt*sk5Qtry4+J*FrpEGonmR+19#UhcV%S1H^O89Eip@A0;rx%YIWlIyoLrFYr zlyMxwnn`6TDm^JIv_;fM36gNyW18yRv!%f)sp!5Bt!J$@6$+@5Nj%bXE^cNIbpraC zuO+}@I&N_k*Jyp<9wqLuFvesh4t5HWasX0I_7?H^{Jd~=Q`u?dEkLNJDRk3f#I~*M zpaRwwu{P2=k_PyWZWNE)<7&{KBrv#BA?O$YovWg_mu@D0-l5$b>9SB zKf^N2+9|2!o%}>`m(%0lAZbD5T&VTMi^Q4e&vPnh;EAc!$D&4U1;l90B$Ay3uXRqC z!7blmeU2>t(K}&-CRpfbsgSThpP_i3~_&mPQJZi(Q!CVR8pRP00WOaz-}a5b&H;l#59z3eO5WO|fX?L_j4$ z2gHs+>x{$MPDL#?c}WbbqDZP)SarRjl!jB{t}M!YRE~z=TT7`0TmC~bZqt=v>|oCk zaGcb$G!v&TRMV+-D{Sf+NGM8>RDvvgd=17s;Y4qGhd>2_&Q|8a{FhO4;km)zw3S}0 z+N;x$KMH8Sjs^Qa7N~a?ymZpA)q4V3G#9r20DHrHXzHykqb_}*Yp4xCPT7N%FIZjH zp~P}5)ZC!~Z79^~%2$U&T}eY=R2F8pkQglBN||WnnW^ID#>M27rqmGwGa|_I1$9Ov zQ3gkxR11p- zj_U47X&C7XYh%vCcQ7=mVF~y%hH9&;CRc_?DkG7(+?8c0nnK45 z1Y>?u>CzJSO-9E1*dwzVdW42Ff?)}eg3+@|(MUq~*oAosVy=z$X$k}k*RjM8W;K;= zwH0t0nInNMJm}>)K_k*hI|(kIbSWq-dTvnSJ`1f$a&bq^mZO(YNv4p7P-I8h&6$uW zms3e~16d?4$1c0y&D^IL={7YwWUUoAB#y94i#Q{ZQ&mocm4Uwb0J1PvTYT3SWAhbr=EkS;5}Eu?yB<%&q`sO*U< z-$cFc<0D$lscd>JzL=8X%&vBRWD3GaWDFa+3c7dEfnrpVqfoW}8}!EA8tpp}Rq^+V zIxrlFcg5YDQ7qH4Rf=j@CHG?_=`}%mv;@qN2oSSGmN#}C#nMYLa0Cw#_GM8{vO6xQ zI#0QTLNjDy)7L4DV$ZDi$>a05rVhy7UY`C?(+gO2;!o z@w9Aos3l1NTwCHB_yghRjS1`(lPYGkwz&e1r9&OBWl__^r}*POa)7e_&-p(;ELxt= zeXB>8=2WsxXrQ!^Jwx9_B4j8eaGUrCVc6$xTMQgOj*3i;<~z|7jLot(>OvYe?# zQJE6f)lCo0Mx`qw zCZMEW)EdnV^w;JU;PWMIOIu(($~aQ2bu7fkC}mYB?y<0S2nn+jq*<2C+a1Nm*Ez|c zrgaXhA`5}Bz4czi1tp4$8?ap<_~1W3;iU=;ZZt~ECn=7Sr9pirZ8}@;#LYV!m0#JC1sC8IrN%2te1XNDSWy zC4$@2aeoX~Ik#xF5XADN?9xjk#|)%*j3E82yWjckmiIRs-w!Km8clTaCAq4QtZokD zTTAa7ixLs8x~veD(O?b$IL|a$C1p*ch;pMJ(M_-Yrn&qvrQy17I?R#4fYjZE#JKw^ z?Se{{WnoIw5WUKXQNYsr^;29~Z}-zlYi+o-uO{tsakRO1RX88DMGeiiw{%8#`Q!87 zFRv)z+=8ayjff!ZLGU9N&k6RS%nGwe>epK^3Q>ncs2gcxa!VG{Y&Hk0TAdE;*g5z2 ziq~)+lP)eA?FyA^W|Ca0m_+e&UIpey3FWSZ3IvWc2c7D zOMQRz$GoA~%XE?%wo3`HM`nb{BC9wE=01S3sbH;cx>$gE9B7^z;U|fWDadCQ$8d^r<8b?T1-5MNtzKnx3L1Q!ryJ62t_l32s>~iUf)* z#xrLMK`UYo1v05!2rD23cMLVF1Lg?11b7jGstzuwZDFO6!4Bj!uECtBR&uO&a~L48 z?-drkh9y|^F*1_p_HyBY_LC4n38Zd!yn(+yQO3&Q`a>KLs_6k^L8SP1LAU3Oo$ULV zk9Ct!vYBIyb==xgZ`Ri4FXfG#XjfnyZMNXAPoWsX@iWK~wHs7OeA6v5tAng+jK&J- zaDv3fpd85R6(NY5_X!dt69;nWfx)6J+!rIiE3)p;#{{WGs0^ncONN>}B z%K={v2i2STM-oLWa!eg!5#XSSU!=`Xz}^ z*@L;)5FO1jjo8_4+K%LIOHq~&0kPWaxITq<2joT><@^mCTKQ-!pM^#DL4R?irTey8t~6#wN{C-<3F$aAO6bkSJ6n06_yy(0KeOb=$@#Uy;JoWpPY& zPaUi_btc2)!p@&28huV1@XIqXKWecu84#AK4lb*0B2KEA`hpw{ z{{Usbb~Ha0cn!?5F|Qy2o@Gnfa(l3lH%oTegkXRSc~F-?URYfL_u&&(lY{g z`!!TMlh;!l{{Tw;dYj*c_{W(gk;0B+0s-BX2^y?Mh7Gv5?=8CcVQ{pFYQ9gV9R=0314`a&2utir@bLTtPB7 z=2^TgCZ_Ke7hSgUJ{Ta)v(T%e=HlC5!x33Edve#IR95oaTd&mIj6rAFuiBe>4gNsl zrDgYILb?p`M~7cix95q<9wkuM{pS_ME`HrLkHh>iH%**hs|)>qh6m-y4TwXV@rrA{ zn~}ed@x(nQdKt^<-p9`ad96!$NCo{E;wB8$hTPlz8*E=>g5xqXi#Vi~H-%gK1mIiw zYUlZc`Dn4h26T0A&mj5+z|6Cd-_N(tOYiyPz)NoVlGHWd`-SuxPw9!=yD{JSl^@wZ z#{x0tEKl?2`>lz}T*q0)-ftKr^)?&fgVlGsb^U&ra$3uC;-ufNi5MW_N{Bg_Rw}3h;{Jmj zWwI&pKE2=Z$J|F#szz-KYxn>F`2lNTr8L&?`eOMe3Alx^SKh!KzF3+{@T0HgfjqWx z)UWG>>hpCT1Mxq{6$_XlVT6Z23JERwe~tlokBXK<@tb)Ie;h|=oJJbp1+~A=Q-L|> z>ixwZPx0xCg~u?t%u_Yu%~EJV)Y|@b#rN1|dUQykP?H=Eb(;?Ewemak#!#)yn^nOd zLH+|5-?Kh?edGq%G!m&N%^6&NSKk2Cw%W-Zqg3!^{{Wchb8{jeXQ7D<6tQdRxNn3K zssYvXz9ka58@SBP-%vn}m97LU0}Z&cw3vx>2&;B3w=yYF+~qHH7iJ&=#>>}9>4leC!LT@ke^*mGqRq9aV<;f* zKGIeLYg=bk7V#DY9kAL!y+n?Gs`4$qUuba)z;s_^TR~YJ*v+rKc~`jQZ_#cn6aj9V z+T@79_SvoSAK{Nase=*LR51e?kbGs@62TjHq$LxWe%eE|^s1iy$1vOtj={XJ<0z6U z>Ny=_1hjIcwHLF6BI-#ybSrQTh`s{5O5hqQi6C0+z|xIZSkx*s_UU;FuvJ1@+kNBH zt}YG@;fi`V#B|dlKn|wr<%`%BXJa3cPYqQcTSp zU_8*7WQx%RCN|Upu|48!NMJYH8zk`%#H}kTpTPcLVX@(gsXhoKlKnYx$sxC(MQw+k zEeylj2B`vwBBz8Zg$61*WhYOIGe*R*w&b17@HL$KN@ngud*xtY2nIO>HU!*(%G0qR z8+r@_arTx~9`K2(6be|Dke4yRF?Eaugpl#e%(7}-VQ*%&ok{q%#ZlTi0W_;%Kbt>{ zc)IuxFlO(uV$VYfVok|zWY;%7Hzbp}-xN1&^4e*Sjo=sm0ICNbj@oxD<1FBrrV3-w zR`xoijS1f5S(rDEfcaqihP|Ka9TmxMOI(=7qg;RbL(hg8}8F1F5X1Uh6_*_0UXS$ zsg_-KP_`O?>Pfl+5w^LwCjtX_Bn}5z85zW|^Zwa$N#xNjY>F6MA&?|{SXd-lV+4XW z3N9{i5yaV>nAn<~X2(dsb+q-i`|b$ovA`b?W*{&@dn@i;tj6p{;B2f=>_IoSJ+98< zO(eQqfnur{7?kN^Orqg+0_w^G6>)M$fVP3mxEbPE{gI%T-rrFqDOuxu6#*!-(lA<@g)FZSq{h1^Yt8hWS;EM|ph@QOB1EO4S{d2JJ1owrr+jkhPZy+>p z35uN}(&KgjcU)|}(hb+Zi(m^N$>fsh3~wn>zLnT{7CjdI2BI(Ff?1%voa2d6a*mO` zE=sC47G3x1N%1GtpA)(9$9a1Mk~t4VVtsxR1-_@{f*h-YY9x|0F}f@6Ucs~=c_U_F zs0C$sq+Kjj>i`>SQf2a^8jVzu$L_#APN|6N^bJ#C7Qf7>|ig zmo`!~qks*^-tfhTobgeB)2yRhi5j%A5{E>D$fbjgT4jur@ZpWeF$>fP1XV{njJ*V!+A8Fr%h2Ynn%^GaV&|EXFiPDN)skPqZJh zd^(Vecjg{b&-im+3iutqX5|N@zPShrO!X#WKo&P34ei%$$=H2xLBRYh)iolWo0Jrj zGm(B;sj;_#c0JSt+WYPlgJJd=?B3auG|cR=jX_mN1+*O`l0n;0ASfH!_qDNL()&6r z49aUKiCit-G>Ft414@o_21QUjc}36d4!G36R%>hnGsO<$(<;8+_**WbYItbnnn~G9 z)U1yiEJ#4*gQZlgu5S7dNbE=&mi2m0zBa|1+lRB;P$JYu^34OV4)bX;scwwSfkUev z={iFOBKNr<3$pGVj-s}n32)1h%CH22K#kZ7jm6nT{V-J4?M=s-0)nI|>l&_{a?$~U z{@eR4G!lo8dU;Kd+@4&Pxrp48xCM}tb^(Xn-`>plRtkzrqaxl^W(eT0Dhwf#z#S&e z814=HcEJaUR#SK!LVg{$ZGr7jxaXcQW!M)BQq)ILHBy)5l>idq6*+p@tb`KB*7ggq zxi_CYL&M{6y0++Hsv~}%5W?-^st(YE{h^mgO5~6wU#w%kNI0>3HOcboy2`{@%R|eB z-~`BpdaUI}px+ZA0k2`xY*o3;W*KFO-toxsl6svCR2{tR4&Hcny=`uASF{7r$}^b! z#4XndG7KS{(#rz{nm3HF)B{^}y|1w&uTj)^fqYwii*T(g($7;@3QD2eAbnO5#TYI| zmK(E{Tli?(5pKB^cL6Arvo_gNnHSR>ir_3RKP*{2pK-ExtPAT70o0lih`-ep-kkg$O!JT>K)|9vk1o3qOdmoCJ)flo68B zwf0A=Uw@PvYHB%jdF>=cfck!z8SU#YbA`+qpJbURXO2NVNm2k;6Vx#4r&56w2-e)5TD67s zTG-3|sBz5Mgws??2DucfBA)DVfJAXAHY6xJv9_ix)?HdwQ#aZl7y=gpn)Z{)nortW zh$W*rOz|5$Z0&38>LZ9eZRW1GQ+wNDH&KGva;R(O%QILkraeXPZALbVRph;{Ij~ID z>tG9w?lDYzNA|NzUMUup-T6G-WulfaH3-7nnyIS#PeHfWc&@@bVOkfGIm>&jgI{%7 z%ySC>%8PTRMee=26+>>P3!O6x_o%~j`a_G?e%AVU{bN4gvkT_6zLG{i2q732%QJ%= zJ$#{6w9~|vZ-j|zqEZcrxUe@D-wJk(pQTN0O+;k!=9f}x8d};BMc1f3-kotDSx;=c zGjAb4KN^yMb{p0^4Ib0%B4|OoBi>ll{f)^DH4MTz8{ZLxgmX+n+shQKtCt$`Zz0r< zN=D#ZoE&h^Vzm(gO$|jX(bU4qQfVZJ?Ao-($QUsf46MqIw!WV*p2jjf-mZE$s%JG3 zLL`t<^P&cva>}Dg7#c~CxC3b!L9=MPX|{Maimxt~zNWHCGb!oSVW)-&CXtd!Q=G1` zs>o9JRB^vAOWlR+IE@7qyX~~iU47Q<41#-RZNezLuUzGdb8r6jBJel+au( zh38|TBo{gvSTu}Ot-ve~c$17^pDRi#x@n`TSs_Y}Wh9U8lEw)#$s)44!!@)=q4Y_p zUs7tord!8y#hZKeH5BsG&jmDfS`}VXGA*Q;VnSRC?gIOtLbx!Hx0-avUE1#%yWR{{V-(ICH^Y`j`lI z*B)J!*JU*N1eFy?1aZh^`w2O1P_8y0?9i%Mk_fkm#~qdShZJ>EiRuj?qnZh0l?sO} zl+vryfaD8I&d5~k8pMm+4QAo|vXZ_!j&v|E5tVm_S?ShrWsjKJEgCGk5@i>>K2W6;EYyNnVKEa{ zjXJ{f9$bFxY2$T0R5XO7fU(sfZh)xpT=JaY-^OA9>Kw)WQpe5?nJ0kr-(z zLa^0+L=1QA@7c{{l~GESijdQyPpX}{k_0DOtHmaT3;-<3;eZ|l*oJAeIvjHlvZA&E zWXB2QH8llJWCyv3)0oJP8Wf0yPET>$SXL{fF(FF;y#^#ZM5>yS1>{3KO!Tz%1Wjj) zlB}^LsKAnfHHZck0_)vt1}v&Y+qZ9(bXn1+s1VAqtXzXl07q>?@wBlPeRCt~8bfcf zQf{GZPT4zBtP{0E8DNgM$xQUq293~CtY$=(5^k$1)QJ?e)x?d|D8j0i`I}Ej?fz4s zW&2_raXk5A#Y~)+iljo0@}ugBi>Mok8p|U#sR*)>V!j}Oo)5|5YFgPPE6jnFqXmYf zT{`r)nQoWyxV9#xIZbTTe3h#AhbWR#zcWQd1TfVcuArpI?Q{#N9dB(LFp%xU!wH#AbDV~vECJ}HGk^t;h|tevB;|_7CJx-Rb(Z1)vXv0ymlB<{z1ny zXhf$_3?(aP8uV*b1G}e9oqDlh86aJianB9s6%;IWD+WbSU2aB|EU5P#0{};Q#AzUb zV~?!f>TBA)xSXXxi#Hi+afwD^xs4;M80^)s$Dzq4=+%^srCnA|@=Qcph_^MixOWlu zPaGgtQ-M$;2;r%TXx#1`Jv&}lu5`>uIspYkH*^@j(|doKwm6|Dc;)7E6p&O{fQr|? zlYLA9)7=|&!0uDV@~wiB7@q4XD8Y}7*Jk>y&z?D({2IHfHiNXymDUj3ahR7EXKInO zx+6&zHKs<67^Uf|yZ-<@7IvSXYnPS{#8(9Pw2i!se92>P zq4U5dyAg!+H2xg{_b_)p_MB%i*{|n`eh|((+FPO99A>cUTi|^p(s7{q)7&4iff!}P zxPmNy8tRFNI+awlfHnZ0gMRko@dE`}Wl1U-SRUwLb$}F-S4jW>ueJ08waxAg@EO3I zMzXIePanwn;pS&UQ9}I4Sb%=0TC1#{bW(8HJz=}5>^nq z1a9eI3w%vt0q%9~6W4KLeYO~ls)3F5b@B4s_jq8Vh4|K*qBIH$)dd1*r5)KxVp-#K z0QdDaQGA+1E+Ci?IU3 zxJt2)Pz+MU^~U4&c%qHouH{JnP-#(hsC#mPlVX19Hz0Sdz5$%Lkw75K+1gUF(Pfw1 zH2JmFueIwEI)}`zOG{LbvL%hd@D9;$_<5xBY!J&{{TKXK`X9DkRO&EysFn5dH!BFkr(1^ z-)9~U28xZOS0<(6sTv3hoW_U+Z@g42L4X7Orkm}2YI*2xZ>V+gI#1_pQk|aGnrdn^ zjY~W=j#MODAUxMnu%x6cXYn##0tt<}`4br%c>BT(}Ps5t6_ zi|HJZ6-r!n1Q18{fdlgxe-3F2beb=kN`vuI-@^(rH?**35+y2}u(%7|(m-RdUx1Cb z>Thre+jDLB&oj4*GQoL{N~$Qixg>Sc3u#eyasjX%Fijp*8rCtt$c1mqV~WeP?AcxoKyp%s-@Xj@|1h3p8wbe$mTHrm45^}tjanb=$R z-~9OD^%Yk3wT}DwV%U}yiEP1^fB;7l_cd!kKvEe?1ABZovD(;+%-k6*>-lM1JK!wb ztV9jUF9Mcx``{1fiDJ2k`RoAIBY4RjKLt`S^dI^Jp2)B$OD; zkeU@?)2~Z`x8`vvPr-ELT-3%d{{Xs{{{Z(60p6>Aw*&OYFPMS2{{Rn`Dsw5YNj&=@ zRb!;AgTaE4d-^a0ThwAVE8$q3h>}?01EUl#e@iLb=5W?*%xM<$vHimcnqhm|-d~RQ z>xjvg*gHaMp3do&3oUdG!=!wdQg{8M-3He?+YylD$!@4k`dj#I`Qw^cW7D?neZ6gd zfL!`wRtbf#qyReX0l4$|?{Aj)_UuR%g9-AE4S=XV^9XBhr6#!BrNR(!{qnR%vbs1Q zcxnLs7z2SEx?6Si`u^-mK~=f*{{S|{PGz=%(ogb^!EJl>y@%)gFy?%rhUQ4DIsoSX z0QW{Asp>~xJO2Rb`|;G7j@$ZJeEjheWR)x(4eXcVT}IAD$!=0@a?fLaH)~bq&;&ZO+HbV{eh^h#L6|5C)!yt0*3QO8`E&jLmqM z5Z)VLMz1#p=EBze{{YX14V(!c$TsHUkK-XE)a;?s)cqW zo_Y~}ol#qV5HVfT)w4RSuc?&=-8B$DE8(tnn}Z|iQKwN+u;{y9-WRp;?!D!<;ulrq z2pLssp>o$3jhjf@?-Ggy`VH-W93OTP;ws1#uy3_0Y;G+iWq0%MThDw`RN1E82l?xQ z?#{D`bEwQN-M`^2gj@o~Q)};Q6ET8jChUXMTMUc!01@2u~1sT zo~MqfKrPG}w3zmmxD86A7E5YSZdT&!a5`LWJjNn(?AAvpnl%mFvs@@>*%=o5ShI9H z?5Au>cQPfWco)>%l_i)a6z%UnV&tNI08CksC`cD4Q;?;3hLC$9-sg^3P`N|39#RM zXQ}I+_at20p1YE7e!h6vJ-z`qzPg2UsZ?cUHv&bC6|61$O09F^2*xp*pbKBe3`R53YqPZ)6Q%viEA9r|$t`}L zkMYKE?dZ2YVSm33{*Vl4uE|5Pg^d}=p@@*GO@Mh#&5podt~0l9m7q;HJ04_1{{WCY zF%iaGBnG0UF8zE#{Wrl8tqI<^J@UE$7a>#<-8z0ah~XM*vu}2=AObo8-s|Jw1_-0b zLd$0wmf(w)1ao#Mzn2IKs7CMHox6(i;cIE!c?7)sEtaH%EwdIV6Rz_x5k&-aK?H<8w zYk106`U$mU@|6?BGy0@3N9da5GsN z(4>YGnHCr#tgHbvyixxEsnOUGc*#+!JwUTnP8DycsxGBCjo|8OD^XSIUMh9e^F*fQ zrUg}*6X4e3&CHVe18l9hC%i*Y)U=4vKw_jb7)FrVXOt*m?=$Sqt|nm2F{csn^9c9#!poIgQMXk~@kRuZbrC37e+s03YHv9b%O00prdZGj`1M3EYH zdUI}UA8G`#u!3PNJdPs;h-8vPNmk@I7X%B6+N@N#chMvA(7O}4R9>ui?x?uAI}f3< z)wG`!vM3GARtkMuQTF9V~w{2I$J|f_-Z%sTi($q;`M;t8S zkSucouKbp~Y_eQ3GCkGUC9E%tNxh)fyD_OSuPPKVJvS|RC}D~~3FY`|EP#dT63uu@`C6k`(C2WRx=Z>9RnWT;x<&}9_ivSd=-Y|!_31Xm}Vm_|xkMnv7q2yMI3Ux8J z2}~%eXQ!s3YPy)IrIO&@Rge9)qzpqHBwLoH>`j5bE9%N3lTNlfO2mWxARG7M!;3JH zt12t$nNq%feJG$a1osb6%y;dv&t=V_qj3Z{{V{qINb0( zo^ut6YeNJZrjG1Wj9Lmf`DWeL1P?IHs{a66;GsCrntR60^ZfCj`!nLOs?i??);zSe zgMJOa_Pq`ctD;64k*t1r-@i<(*$@?3>6SNYJV0m5=YiX}AeT=~h*H4c(SScpWX{Z` zBDR*^GsZu>bpHGtakm*1r+A6)OWYg%&aQt8FU`FU0y{Qu_3Ary_o{n;+O8!u;8wuF zJLSaD6H_y>Q{&whf9(3pkVryt!6zg$OqJ@G~7mY!3nRHw@cH} z0si@q)0K@o2=h||-Xw$hZ8PNc*kdCDkCvaz;oK093u9NzYfMB8L|}st5i!^U9GOR+ z992XdkvtWfpr2#Fm~hZrs3QF?2*2a=!sd{Hs>CTJZgyQl#I5>V0tpwm1bK`Ey=3yk z^^#GP;DZv199tcb=JhaBRy`$5bhAko$zBQvAU7Bzw@tg)o1FeZp2%tWRsRZ&Amfz=kH zk{jaY5C9mS?Ee7ULav)Ifod8V0E%Il7<+sNPyw)JrPIQlM(l6BT4bHnwD9H0rVIjAx$aDGSw04zTmf%7E0MNutzw z)3k+KLcYJS0f=z7Hn}+9=wrN-Hf>R`ZI;ggcHs2>?G1b>I>@@#WVbRYE_r~mFl2Qn zRpW3b<3zz^4^b`>RMJ5zP97YKh&09gDIsT{qQm2y5QwJdCEoysE_D7iV>8a?dR6H*-x=SHeb0TR( zSJ9-g7YnQ_Slr3tMtz?6pk?`VmDN!!+FVn|7-SPYLpLl$%*U3NkT$kwVF<`ofE ztsQGeBSlSFq3LD<@+!W|Bd`IZ43a5LN;ERz_i8z!)5xhU3>=PRhP1&ENJNtAm_#Id zJy3;Rt{kDAn&2T&t0lvoop8kPB}4{6Q12WlkvpIjG9z;D9Zlhi?`91ntZQq7dlRpv z6{}^39p)Xy`es%P_3 z2;-{*sCv5*ZEq)`=?`9PQNOT(Sw2rgnM9RT6y|E|zwGl2v?+$AVu&3T5kSB6oQJq>MCzs2bwuX>6yCmP!grYU(+;4J1-dX9W^si@5GE za9EQl45H*)$6%ulNBfyubI1F{?}NKn&SIx%V}spfq0%Q=qYWiIY>a`%qBZQ{!6lGH zL*2F^C!v}uVwL);5;~}(c;a18B-L(V42@=YB4xNm2ULwK|eRW4%%R%DSQ)?0& ziBe@ilOb5xz5Bh^8HbE0CXQ*0$;&+H7DXX+MJln^9;NPmnFV{j)286>d}(NWe*9w5 zmG|!htMJrD!ti~kS&s=rGcbwi(5Pkx09hGz5Cnud?}A3Rux*Jk_mMz_NosCvj62ZX z5Ow=fN{^Ub&&vcnL&FaXlpqELNziVgm@9?VVZP(1i1EM|X|=>ShUD`1kon5?Epy|f zZS%f5#qlN7)+?;_>+mK&;mvK9fTTb#n-^Ss7A}lsR5AfzlYbr;;G?$kDDk5;9m3m zuhZt;FZ0I3?9vK8P>InL1+Y3nw@r%J+#eHSN3Ipo_><{)>OG?;Pv#8D!-~5V0R=@f zhlrhsJ@q~VZyWUS#K&h{z0X3?rA$U>;$T&PyMO>ttc8L|paMISOUb*qCag8N1; zdxxOXNmH;6D*|$|$cq%w#_T3jBuy$QT`~i(2fQ`f>TTXz+zocM*+nW;^KxnCk_{z; z9ca+K$8tGaM3SK!>Seg-UGK0iN5^y1N(}LH2q#gnSKQp4fL7o7y-qnjSAbbq-%d*W z^_tcAf|3hx!}OaEwT=a+iWsFR%N*0g6GRxx7P)~5Ej0b@H`8LS%q?I^QMEh89i5~z zO$~u)Ws)Y?ZewDk?eg#^=5e6uyGx+WvI=TSN|;)%lA@NPT3J|A&WQ~A?|w=#rlsNN9No=%8}!1Hij#z!+RdTUo2P|UTqyamv9B_ z16Y&4QE(6DEw&QkeiV{s1`>}XrbZ~vk!VEkGZ&GR8v}E1rTPyG6MhMqtc+J6ME?N% zDDx;IiWsI%F(6P{7~RMn12Y4v!oX}c0{6rEFKg`G-8Ib#Qb1$wv6j>0U@dY5?SLL2 z?0&8=U5qUntc1x7=`44P;)_~b34B5uYVao$otgGyJ4mminG*svuIMa#;IjY&3uz;* znE4$yb5=9NqKk8mWu*sfS^oh0{HU(Qbw&XmR|_K8+otW?d6VtV6hF5%38rS^cX5_3&88IY!e$vlcmgL@yeH?iDa=cf2~RonE^ zpS8=?uho*N+sE$>4Pkzl7@6&3vD#SH8DbKmGO=ZYmo37u?~PI+YXf7TABN-(xUV>N ziira{)zpnzLDdTAHagXHBQQIQk*F~j79iUd%_p=r%Ve}Yzao+vfe8({S&_E~!1Dh9 zLu@;!?fRMiDh9aNH!&EG4Zah&^~X6^2hmLgV6QGsV^oMAaK!0dwGH(k9p335Om|Dz znI(n7Sx%PLt~r9>qbP)ep@1jeGC*x2?u*x%mu}^K6opp?7ncWM$H|&hQP2l+#Z6& zSb|0*>#}K`qK-{glqu&mHj&Lo80wl57g@;0D<48>too#CiA(L(fb#J1NpZ)oa`h z`Tz#o?{C8mZpg@rg(HI#l8mV!^#;eUcH3VbBx=Kdi*13p@FS)7wf_JC>xaBcn_gRu zgJ^TL{wrVpF9U1hHhN*I;>7jwxB~m^O5WBWbv|3-L6S2$GJvARj-Yn(BggB1-G`|m zEoDAdzTYr>x4pdo090ynwEz?Mh;Jjf1Y1$rMeWx3_b03u>t(g}8#J9{{XJn>GJ8e9ne;(DhMQa*nQK}%H3~!{taHw1a!;Mi?$oj3Ul@9zdgUaFou0)fL^5v!)%d`|vYMXK-6 z64$>=_44_2!sre3uqn7+mj?G17V1w?wih`uCM_E)B9=GPxVte`B%6)5@wUUu&1QPY zMcW=nmW|9zOKG-}HyuGYumo6bZN>dC^DdEe>1AR`1Xz<{;m~e+gMTsQhVtd^oeq~# ze(4Mi&F&uOpt}vou>#=jhXhC&4wgl^yKU29s>IlLdUt>)r-lMdlDOnYOCVJ}2-I`~ z*330;`QzHku9{b7mmsHF`h}yslFejyrulrkf zMS$M;D08=%AiTwB=I-3;2L2mOM`wgvQ=PXP(wN$s&+c>bVVZDJ#oMOEh{bZy6X!`A-*=HEMET-!Ag zNH^5XT}2l)H+`gIwKNk?W4C-MNbkQ>BdPjec9j7Pda+{L9j)tcJMKTn z1eCdJ#Ys{a1!-EI00SvHL6T`r$5VLY2j}&`mQZv9-bFXCEWwKD+TdSuf6tx(0nZTZ zKmt4!C3=Cj_O-50hxqljCb(;h5*8vsr5qcv4XVU#qzm^?LAD`h%$ctymSLzUzd}!# z{{X@|4YtI871PY_2^Q|C9p&&A@jv=ufHTAf?()~nJ*X>-pY_BE;ids`Zl4rH-rl`$ zf!hB7Y0ShOtE6GqWeNwSgku%HL&H)@AXi};?n|>NQDL^hu1V>RYx2bkKq^pCfnpSgS7|49B-VV%9OcQPPWu+yuaHPAd#^Ef=1)e;CZ;dm8Nj0;WZGUSacTsqxIjWAfO$k$E&<8OwLGC zQKYx@`H>Aof^?0yBn^jC6P8vB zBJPB!e}?-Vz7laj@h(Rpkg_9LjmQJxd)d&B3pM=>_S+XuMkk$i^DO@W`TqL{iYk2t zg9T=jUo5}Gbd}!MC05`A=YWitgn81(8ZM@g0D!)bTgv3v3_@l34F3S`-^*nnAI(_&Vp zj#bsV>PncIE)K+8Sc9B`HE(DfekG_;GN(QH%v}IQ7m5{IL|0O% zWpX>)-r~UHG(|)9?#`ORsc6HJs?rt#H?bBb`c~cM09wJU&aS1U_U0$2&TGfTX4kFeCekUDd5Fy-t>n=lH@H>V ziz2f3MX{Qd8=GoFWsqkui#3%4MA{~VR1}U?Rc1v~qnT7}(icb9t&;0tuA;zL24~qs zD=Tu?v`M5RG9qfzxndL!?xJ*DD;3jlwzeZGIH}ISAF29(3`W!!ao#^c)BJJJQJ_>F zv$*?qfM+MC5c9H{V>M0EoYX8z%&I%E^M$#5*0qFS_m~T_TVQT+E84GS(uI;~suk)O zmuU2mr^Kpna1?BSi&z1+EZ)wz`Uo=kBd3fj^2as5_njX53$bgG$F1>N@#hm>O>%VJ zz@5*aALrKyk+pIMY$mnw^LPQ+HGg zl6*EK9%UVyswx=^7iVgDBW)T|Qo58!AU0Pirbr!$j!%G<)}$TmTJZu9w2SQ9KIF@5 z{A62wxr^{yz-qZqnOpSQ=+66eccW@KDGagB@y2I57rLyj6Ie}3>nD4d3bDH>Ciu@) z8F@(=E(=EGbuU6yt*L%wTzKHiHmRAS3J1k!Wjk6xR22ip?`8tqY91J?S5KHMun*1; za}_Ef4{AN1!wC;fASjU;B-F;`k-q3=W*yrer_*y`3zbrmC9^J~jU;zFGekpa>(Hrn zK0k&B>M5$FJicQ$HN;^78?xPqH?@^)N!7Q{Y!NqPHFWU4X*9!?PDFgTmzqkI8xS9t z9pi0hTWcX$6hZ;UKZ#vimBS7_qjV+-;wznJRTNUjoXDu2qLpMOq!xx+dV#JmN^H9H z0=kGR(SqM{4kF^DugRc}p~Fu{QzUHE;4q3dUUkr3%&!&hP3*$gB}NImB+8?ys%hQU zMWv=hiQNE58bywp4KgyA~wjkmMf~oTHQJJLa_7tK;D@Lyr)pn7U9!iM* z(N!Z&eZr_&$Rq%DW`Mhbk7&_S6M5;GSN3UDPQrNOl2vI0H0>iW9JnfFoUx&Whoa-W*3@OI?XOU6>l1gE+>R z!pR!9y;aw&6F!BJ#SDN(iXsTy_fYL6z~&hv8}t~pdr07vbIWkx~^f3 zTb9a$ob{3x4$*4_o3@tOTWnUx0Qq?9{ypVTAFtX%=UtFxu;!3aML87nbE0Q?KGp#6 z$nY`|V|ivOfe7zDog=0O`y-`=YlRX#t6U9QG~nJfRYy`Hh}zE4hBqwM)WZF4>$FY* zrd+|f3L8X`PaJDi6+I)<#ONFeB-GsHkd-X1!IevB8n&o2jxJg(%*{-V&r>jew@IQB z&aR}>G%B}^1f9)Ai8~uu+yHOS5z1}yok`~gUi>}7xny!pTRvkYDWnC0z*C!2;1pz1 z$iSbtS4p|t=>t%zxT2?AsVKdsrl*u@wxStI-H6*)cfD<|dtv57n^THPV>DpZ!J0-T ziLP2$!PH}Pv0h%A>$oAENNtUa{O=>0p&+Y{5+U~p9#%jEQ8UXh2nENE%AjlqfEe8H zg0)%dIDzpt^GPT_C@zXYxHcoiAM^FXwHfTd3o#b*zW)F*(EeCB;=aQ33PWm$40~$1 zWo5VZkg|j5NH`j);JTGpW`a<${{T4JNmc9Bg~hfz-rHlgEk%PNhwC}vy?DeBs*#x8 ziDTw}PnHvkLZlE#BE%3#AdSHUZU{Sq4Z*~;)Lw`1IAtt0{{S}paXwJ&Wlnm=I#I+bFE+LZVoI~~W0oxvD_k}-tDSOYTw zw2X;R=Q+%q;r#k~Vof}TEkFj-ZNlG8!31q{Z!4TnKWsUV{{WP?_hbJ6$$+)KJ6HPR zzDRyb%lXVY7_N1k%QKlJV(!+v8((2zumD&AZLqXlS3fI}%zjBX<=?w~TE2f5de_|H zB5~@l!M_WUh(9prF*+L8M_D5!T}WkR*oGYl$92-lE0>X(-K};>^1B|*b)cPvIcEZ=tTGQVy%<2_vEu~8}lwR8d z@@g!)y44tx*!i7H(_0e2jAmB-opA}MtE8r23dtmK$a)q8?rtnW>%ZlVf56;9lU7hk zOu-Veo_QgX5&(H(5*6m70d^iGt{HkC3+DWnBZ0HZSu*e>ryQvpmNt&c;kAnm2Fe+M z9}zw~U~98MS0!yiQq##(B$7#Wj={g2W7ODnK4SO}h*sL#x{%#RIKlav{tIU)Y z&pc-$YrZhdsp5i;DV1uXnYj|i#?2%rnI4Tmh7tf#gDFx9uK3Ozb4!)2Bv7}!qQNBY zh#gF_Nhv`ga#X3eEkc|3MaA%A$9x5x(>`BQn9xZ}MIBTz>v>^&G?FV`K^%_A4w5xE z3-@nw0joWxcyv?dQ$(WiYcs?L`>FfkO}7L#rTGASaIc5ytf572$2^nF(ed3yT9R$7 z3=9FrIFlaFow&ANQAaFtM-xEKSjtX=9;I@mg*RtVRc&th>N;cee}g#DWq75qy-Ud68y_rwW)EiU>SYZcUP>?_3~f!K-x1QnUF;6#guBGSg8dOnO9SIVxeg zPVy$LXP6o|mB)V3>MMOJ+53g_d8T!pLrGZ&Ai~E^k;#!+41lt!P!uJa<&Ca-k+Cx# zD$X;wC5XQ0Cuu2VS%16Vm23sC>SnXMjl@N_9rh45Cdjje2{g%vp5{f#Zt*0NK)+A3La} zfJ;s8 zl#?WHRt;SBUtN-YlO1d(>Jbcxg?4isva3tl{M1MtaB8Q z5(u z#e*C@_MGAmbS;q%=1TCM>Le?kpxQ|a~9-I#Rz4T#;m7u=HkIsjxGK>$#S}yaZyc6 zDyC(YG?db$EYwj>(X+f#SQVz%p;@DlEO$0ggq$eo7S1!t{o|=&di_I@{iQ!AY*h3) zhF3f-V^W4mY)B6x6^c0)ytSu2(26MT^{px`Smmh-RwhWzkjh!Y%Y7uBo^e04r9w?5 zB~2udQhVY~l2fQ;<)G85H;qyj6%!6-rH~!TWdyR|l-Ax*IKjtBm34uxIp-z}cB#cK zvOCnZBgq;^H~Of33Zfw$ECxwHcP_tb!2As5ZrX2*wVPI#W@g=)i#Mqz=kqu}?N^EU zu2cY}+|42>Bu1oK2zMm?lvdcE5PWf6%DC-(E}gY*Jxs#YHd`Hpk8_1{Ou6H2G9x1Z z4wf2Ch`O5}0y-bzf^N;Yab=%en?p_v@}CVc?x6nwS-%jhFk!}dXYz#f5+Et>Fdcn6 ziwj-J@VcwmdfN;&;5Nh31W~zn4zjGurLn~2Y&RI0$@?yntDh|zg9=Di5bguYHy|T5 zm77QhyjJ>vy}`s~bsNUb9E!;6vm=76J#2grffonBoNegtS529T-AgYfN$?(AG)mq& z)lbMR$L3BaX|oqc_>I3z4)Bg{v6&UN4h4^e)SkXwaXJ8fhUe+NGBpEbn3{Ta1pt=M z25|sl1dJGZo%ixMxHHbrX{xCnCB2<{(XqOcHw>q$x{;|H;tVz;7};ZzCcW7W`W?UZ z#g9$f>(kSvlYB1!Qla!-jT#FNzc;b)2?xFa29I+j)17$3an-7<5CMVnAj z$}bz*+l6p8J_LCmQHkCX?bk4&LlR7tROLb%da%<*5E4L*wIq>{Se4TDTl^#oVz!ng z9yszSFVpeDnwCq(*HB^V44i{6z5?xAFQ@`4=;x=A^#M9Yl@#Ex(!A7GNs(5-myRh2 zZR`c@v3ooANu#NXDPgUOqM5Z?qMW3R!9s;qV{s9;xJA3w_Iu7 z!FzVD%ILk?o+nWxjXZ=?p)WLnMawRYC?&sP>xLds)sKq}TaB zvZxjl%L6HH`o$En>azo`;!p&vE*XljI=0(vKa1IV6^YYW=4!kX0Q#d+K`7{4$0Cq4 zI3Nd7ZZF=(YRvt%a~Sj)1j-sjQ*?<%uimwi_tSDW8{2$6lefI+$nhktDwYi#rbS(7 z>K-RvT6{7gRsilUK_G$$FXb^aUvL96LC5T?Owmq~wzrk_B+1N4A_n(Sc^op_n=5y8 zn-FZeX`J7&3Vgdc%affiDpwDxK%{F0kS)cAokaoh->w9+nRuq6#x|4y8sR0Md-Wd@ z4ZJ#Hx5@a5ywwV9##uEGEHF{DH@x7&zQxHN!X=H15DX^_3ter$VL3xLd4wlzg#My z`@`@=kIHzXA&=~$g@_I|B|_cJwcV#Afu!oNI&}2uf;`i*{HkBKn&~6lxM|9^wIy2p zE<*#j*oz!douqbgm{GmjXhJs8N{bXINhRl>1IK;W?@;rzVUEn3U-lKEtVIcf%guj<^IG0NM zsRHNkIlaODm+OEY8SG9ZThvrW(H8p_Bq&!P7EM=SW7Mg&h$MA5d&OOw(#IX+U>Bx1P>!|(|78)r=;>GZTf8bhgjz-$#QmxYNdCSN8Mp77}y_K6|Kf4f_ zrcFd*B04g&5Omzi%8h#ya@tzpY%Oj5FM-U9F`Alz8p>THF|c5EQdqBuBG&`!h`h>uQAvv zo2hQ?$UBfXD{X>{ZhCFDI5oDpzjWVM#qk5y))&%F>-#tG0}*k=3dr~BRGWvg*b)uY zY4}4aTilR+F(XFdG`KRnS~R}2=_4x#Lf|k|{g-POU9Hx@ZX+so^o;4N$i0Za$Q|$N zeKsIin_Kku859;F5Vwx4ti%8fiPNa~_-;pBB|Op;NY({SL`ohavOIyo5r!&B7t~Wo z3PzAhj<}Vk;rTnlL1D_d3^rFU%R;VN*Ra)l+q!leHUe7_?@faw;xTmA#DaB_08yw7 zIzpRX_fiPBzjP_NH@Kar%Sy)AzWRw4Cvt7w^Yq{Ah`hTg(!tKKhj86*YpWFgJLz4)a=q;q@VL0^ zbG|*J;`RqhhB^m#N&?n51x1F#eZdwd%cd91XdOv?Pa7UuvTg`c+inVKJ>Z%xeI(xY z-<-ESXq%M!zRYR`Nz_1+$pJ2lxUe?_ zIj}8#$;8%U!}2msqf=@s?XXvk?PiTmqpMPtC04`7sJ0{E%N%tPdU{eur0*rPh62h6 zCgaTh9$W8*Q&9na=+sTGaz%jEsEb)b*xc&hZLAIv;rfyGOm+3Oh~0>|GCl8oNOrZr zuo#o#D&>jPx`IDs=_uVrn*9d-Ml89+r$7hS;vacgKbj zsmK@|WzfYVU7Rp*qWVa-)^HA@ro`zxTdO9fX-&ZbGu}&V%^2C2rndo(k!B>6IC&02 zu#gOgxCbyY_Yq2v0bNAuz4u^1({McMT!9J~lQ{SHLRE!|F;)OBJAi# zFpb#XnQ(iR%7pV1JaA=;!m#DDYc(lR8j;*EjbirSS6c=E5pBHsVa`v( znNzE@($*_ntZ5Jr-TkB7vYYe(^zp!_{Hrvya5@G1Lf5^>w&udt`Fy`7nICDh$s|#z zjd_d)%61pusqh!JG*yC(MYe++XL8c4+7+h}t^WX?wxUQIvWMPb{%OKm=SH1t46D zp0@+>z*~boBn>2MVwJ5ahJtw|{*^hBJtbJoVifK?)nI!n&pdRo?9i@+*aJFAkRLdg))AyZ}%g<@Mxw>AnoT$_O>K2=n& zrP?4aL4ULab-A#U%%7?HK4CWhx66W;+y&yAnt&8bjVT zRkjeyID)pnJgogoLC#`*K^Xxq3MV4b~i8@ zSkk#SEWp02SXd73)+5h*_+lY@M9dU!tZ%XYZ1lbV0L`)3?XsdYc_zBr%8Q{1k=tOa zZvZaLPemR##1>O0YY3$`W0QjAj16}@v8jMmDsQ?=HZSuoPZrbN-9gX(>X}s^y97)036OiPfI#9XpNWTEsT#IhjP&{ri8<6*& z+R!Y=tQLV?iwyOXsR0a7+ig9qjXb$#wM#~?PffmYb< z@b8YYh+bBW%!IN4npJ}8Ym()b;`*4IUi}6o^D5}$V1)#e5p{$F*SAvVbwu$ld@o>e z<)_RzQ73U;OsjLQAD5Z$l1L*#WdW{P_9IGxZQADGbnCDi&SaT%kFF|rJ=9Yu2Fl>y zNmgrsMZhCg;8+f%R{Vd*4^cA>L8Ff0bZr?vXgpT^8}EExBO5dQ9ktn8`{a3w$IY}R z7kz)t*~6!FSa*mwVlR6PJ*d(uRk{BFI1uc|3D#z6ZUM|s*{pRYCPfZHNu`xWk~IKE zt9N!gFH^PfJDu=Uk;Waq=_*G0)pZc1!M=^ffW3vqvHGvt7il~%MX4i2sHi|xMFUEz zHoljZ`WMsUJYzb8W@!JTqyvDsah|b*{t1 z;$#UH-#l;_;pTNh(a7;X#D>?lokG`EvD|7>8r~PghYN7PoJe`A8z!3vQc&tP1=t&+ zU%FTV6p?!Z4m%TKh27dL6z38zENRI+o@Z4J%M3s)Y`W|UtJ1=3kWU6NQlrDYtcXw=6Iup}4nO8#T(%Leckq*f@CYIE*4n)|6{PM6*)NwpMW3 zqh%oY;4d-aMLdX8vwd=l{(mtVx4N>f(qh8DvqkKG!R8A!or<&Y34Pl)JGFD*j_>f zn2(5?0CvL++kxHy0ZweXinK_65um=J+v-&oC54j5;yZyo*$sQu)Vz9@7}6aF-Vn%; zbyX=E6=`IU-AH7^68n%n4;%uV4)01-Sjjg-F zBV-x_kU%64zA=|;wTCQW6#^Uq3VTJNtFLN$z*d#&s%E5>P^zqPA~QV2k&-aHnB=l3 zR%KQ1l5n>I=Pa2N^i=Uw%QaPdq;qnal4q7QjslWcr^2Chmll^-fx*uo$td=17N?3tO)3h?QM=;v zwuqdmA)CA~n(ZEu7;*hZ4e+lBr9|=ywVNxTr-~>h_iEHyS!$qCp&qJR{j|-@f3pr$ z*jY>6i+efYytbWYXjWN-k{Dded7c_(QE<)^k>6tWd1P4?5HLY)>8d%Fttvtyv{bdL z$~Ul)Wg28(HaA^Cn{`%Dwi{yp;vUUoT)I5!YLyX7uihyNp7>pK+JvF>iPSN*ypCW2b2AqBR)(~WH8a7>lnCT^j#UgJXy=TOvn+zcRDiXOg9`!y^E~>3TFSbLbgP1$Dxu6!(#OqM zS|Rq2Bo5KEP&Cb|GF$BR>G)Ro(W^dd79VJp^%X_hcrb&ve`VTAJjRZW86BZ`ADgM} z>B~`ijqPArh16Lt000Z%SF>+pn%erK9SpF%a1kWcQx=AvomH-)NdmYsJ+7%3W*`$~ zUGVBDtFs!q+|VS=9LiFi=K?ZNkXAH6S#&DybTL2;%af?!>)EQFx=1P}S@RhwOp-N5 zU6)bIIF?A)K=+ByE}AFPVj(iSn8G_MtBqDAi{Kt3sG4-rhGG1|cs{^EJ~H8G>7|;g zUU7YLnEn=t*lI*$sH}yGkjeIHtOl$3TOEUTgHK132dhyfGs3V)w$z%Eu6U5Tjr3kc z7as{KaGh^pxxQ%^yhW8g4qS{TX3T0psjEacXyb!OF=_ySrZr8)r8q!U(Zx)$)j-s= zbDGL;b%`C!lFTV)f;g5WX$LZB<}nbU0y>SZ!vF^ne?QD@@x-j(HU%Tm0eoXL463!O>KI&}9)7VCj(-V`yk zaR%qJ7dnzOjM+v0^O0fX$8pl<5PhG@B!*bk6i)L*X-&a(kXcnjHJZe+UCy5SU(XUf ztZ7SJgeG(Tf$zjN_lmNp`c9#|>PR^tWP> zMA}4cCZ;N^_RsObzt5XogDb{-bn z1I4^cQ%a~;BP0y_P0tCUtBEc;57u?r=K|$3=}C+UCo5FEs;Oj1&b=zZ+{bW1P*ese z%x*{n4ZWs&CZWqIp_VOZ@;a$jkiEeKk~I_14O?c;MYxN`yXQ z=+_q0jk~-@QA&mkPd|PpJz84qBu4aopJnsSG&zok%#vAs?nRa3X(nkI+CUeUj2loP zgg_hg8{u9$_Fu~&iVCEXVHm8Wj-oQ*!KapGNm)o$btOdCLYg)s{2KlFD+3r{)i!zExl4Ov?`ow_p((W}O(jLTENLKf_ z)D^9sX}B;be1hax^ygu@}JvLm#bc0f;jY1B8`;|(|? zwThgVG?~z^=Sl-_JZ3Tt~`h{KFD)No}Qs;oy<}r26m1h$c(Z^ zNoNFYzQW;7!xukg^f^^%KK}p>0$0slSg#zVOp-a7rLb~AU=l?{V{KpyUln^*54rD- zqwC@hk)FiS1bjcx5cN#^7$hg1f&u1023h`5fvQIQINKWL(B&Zo} zeuN#(x?<4n#*$(Dsb1h1X3VF_+El09H5HlceK58A)lXD5GDBxA{J%=d5LFOGe9Y z4GXI0!HLJ}rycf*n@OKjttMt^^5|&k4AiR>PtK~9UF23QnuX(Nn4NoESwSR`*QvqENn%BgQsn> z_i9{26)jyiyQqaisEtqni)Qk-ndo*mI8NJmJ4Sep>C`hSla65CUta59Qu0O?USx%p zBXX|SzNJNAe$;)Uuq8=-Lg4RiaF-Xvv{J68Zq=coCXMoYt@q28x8r>mN- zc_fChDJq(hq37l+Eo2H_IHrix28u8}&Pz zYqZ`vss8|z#iJsj8m1ug#?KVFbHOq+Z>LSqIG$2Ui~=(-JC(m_Zr4ny!Jjs$+g-a@ zWEoF!S8A1#P>H3O$yZ-e(@!Z0%nKB28d*XGh!qQ@rk?27Z;LD0(~RSbE@3Ft#z{fd zxh0z9@4d)4=e7<5hQ5*<=PzAyN)dA?kRl>Zz>a)z+%gw+wCDj+>?ImQNN_pBJRsDN zf2>$DJ2E1$ZT3J7iCwHqZbkg@leAle?o8Kv4N6?}0vC39*%DOLRZ~kF$3>WFmKwBM z#S_B9>e6XsjrDX5;B0nl3n#HoF=_;_$|$NHz6l_lMSCP`Qp)JjtNb!XZX3D>dr<>& za0}Q!XbDd95?W4k1T^~DVnC%yk(3ZzleMp=%g~%$y{C2%kWnsqkVK4V&oa7zHR33M zmYOANwa_25gdHsyETdBCbu}7G7Tkv55y#uS-SC}On#%tG`2c`H=jXJ|nO1iokV8B# z9QF!hmNOKgf258Bcf1H4>ur2m91q%64qYaQo=9t*+A7wO4EcL=H3g@AE=+9@(#82L z-eMg{0Er&eDy6Q;psk&0=Bi#y)cly*IpBe&T6&5=@<{yk9Mq8>JwatlX*xqaC!N(A zK?K!#brVy&Bh0}{)i#+}a^-QPi6rj{2n>&=#Hc%yS#^5LH(Av2`bjt4rKoA@K7}NM zj>q0>KFK>=rg}WZ<%*UXdZ(Y>sn<%!Bp&QxnZ};uE1(*Juf*2^`(R_T?k~%#awxL8 zBP4Q7t!mNx^1)7^%~2DNVPwcIY)(p{zTPGQcdl8I+mOLwBCbmhmc z)i8!)OpdD>{{S*Snqj9&8%lP8#d20r)4y>hz($%^wtNKEBi6m-{tXP|}gIxB-?A2G6op)M_a!E>vK^6d;7l@N2X27-VRcvm`MX{=ynzaf8 z`dj;%4NKBVUPMohDJkMeGV>&mH9D-RFdt-RaN5gS&vAW0*4lLua7D2ib4Qwjd8(Ms z$nn!syL?Hd!!s*bF$@c8)pEf=JKqq4v}M_-8?6(i880FS5`zc}KZDQA~3mCv40A_M9JLQnOD#t-M(#$g4%&^?Kp|CCMw7NQ ze;4N_=1xD)#7yb-HUo12YCB1nPL)s(n{EflSblg6t(}~fb8>&rL9qD@A7&gRv&*9` zT8gj`JE@4P!bu<_xd|Iy$4d)pv9_xdfxP1&k_Y9_6T>C1rbQ}9^IrxR+UiKY*TIss zJSqIUz_D@Hq=AZ;(-Jg!dHG>gTrU_W3@ssfGK$%bBBW8*d_0ap;f5lH-A+FDu)dga zPCH^=T%OB4he@1f@KXzNA+=po8|e_jz^rE9{!uQ7h`1&`X;XBzKSgsc3(H^%W@>mz z8^BW-{UByl0qEWOe$!0x?3vELjIiRw-F5Dx>1(CMo3(|ud;ehBt-wu7ByGx;iFNPPFmpoj>c$Hd4h%2>_ zNa(E5sQ4W9QZQ9Z7D)jic~V^bAu1{?-F6`I)EoF)!yeMt<%-3k%aNFymReYWZLM-- zVo%|Wg1>m^B=(N8PTZ-}a3^zX+q$O5q1c|j7z^V(wu>;ThE<}Lp>C@rrDPGXBFNUV zD=PQ35=F&@?lvOhj?|^5r;=2mNRd~U3o(s!$tlqisw`($+At@)29S3c&OM2HV@m7p za~R_geUi!|)W#J$Vs~5Ehd>E%HeznO-v*;gZMpJ>aTU7dOb0S=i}+tLpn={hX&#(Z zO+3%`V5DjGakCQO*oJ04Bjsa@f3jbBjKcG}EEAwA@ysM0^$ex7jexz$>0o!;40~D5 z%(-<)Y{cBgJBlI^mDIP?v8Ja5dX0PFGlV-%<)VPNMcFT2?}6m=wwDFEoAqVM*ZvHQ?T}q zs5z)e*`jrg7IoCIy4i`d3kD>r`HOYM1&14RHGIEFv!plS%GyMm+?=zCK-iQE-wNo! zFL)bT%r{&0w%9V^oUTQPa;PHKSb`nhtiRGCJ6sXdS5Bt)$C%wus4TIcvw=$} zBr6S8*+T9&xYR5<;vY9m$(_C>UaDl7R4;dM6dgnZf4hpV1Ot+JGGjZgo-3&|@Dc+u zq+`U88tl$DHd0FU*!g0dukA8XQ!G+W@QJ{Q9Dy^&Bx8J?F}1lZI#dx72!p_qI| zu_sZ>i~>gD%mSvLJtUG3QG7)w3C;=AB&&X-N|Cqql-uct2DLMT#8I^B6FED*r4^Lq z6(>r`PbgFuv5f9~0Ncm(zCFw`^QpN5&F^D;UXXCqfweTGn|lEfQDDBXx3D9mdhY68MPpDr~{yqz*@&ji;eN3=;Wz|wW~l)`birVH|u`! z-^h-bYsEFyRSl_yARt+EDHb19YoDLf6gtZG&v`?BGsnEm6x=x+Q!o15CKhjjBYVkh zMOr}0P_QgQjqRv)I8Q!}noSElO9sKar4PbvSye!1jGL)rxw$=YrsJV36g?#)5n>wR z;DR?Aq1ccJ^ujr|TM8tPJq!&JsVpN@l2R^pFjb3Ol347ZUgK<4HAu&#D^j3v(tv}9 z;5@bF!)Wbr6~n#EjV9y;yqcEx9vgJ;O4qamuA`|zBmix=2En{^@3xP zmC{{oqJ2xLz}n<8D_w_OTi^0yMZ+khlb6G|0E@&ywf^f11HR-~k!$oAt(wJN6iKdt z+?K@8)mhb?vN&_$c9b6SvbLQf%V5_6$Kmh>*ySP;%PW}>BQ3dlWwN(1BnIf9kXSHl zzM@Z{({pi$0|!+RW#Sgp326B%WwE%}j=OL7dhdWbZVW0VRS$U>Dq6sX7P$-yE0RMX zAg#1X>2g(ixXwR$OA}$*4rFF$0%@|c71JH=)2nk97Ko7gbpT6iu(s=NhiEA2mLUA1 zk%qevuQOeZt~D~>P3}PJ>(>+YeVWz+F9lKPcHCHtgK(sH`QH*5PiNDQj*_VQ^!c6B zt-2o!c+LvS2*8}N`=7%Y!(t&t%H!OEcN;MmhNn#_r6Jc_C;s-OORNj1+0jb!dyXevw z-B-B1@&|WOv0>C=;`;N!gD-*1qN*vvsu3+JqOPPw5<0Nj`hx;>Y8wl!m|TN=Gt4R} ztF;#WZWoE0<6MDgmUjuuB2~Rpr=T_cpc2A3QOIUa$>lBLZiZmYz=X)y5sp zw|J;n7qMTnW+wUuowwC%-Hpx}({Su+q(?N`TTodHZVE1)8>W&1w^MCff#z{_X5FAD zBbN;fYBcN>j==YabvD#CxFq4}?TN_yIO&C~TF|tgLK{xrqpyw%JiKHWquA(u9L(Q6 zBu?wfGfAg#%Dv*s%Vh&i*=(bz2EdE?z0dez*$7&BNhDYZT-*lR?%!?vKYlKp$F_;C ztd1iqd-7ma)DMFWVc7ZrN1pf=&wEp=pW`x+E(Vn<06rEv?ehlsJ$9#a1ol~u2Qrf5 zJ`l`ZQ5J@*#-m~>+bEgz=pN)=6sy2GC!bh>oeYC z$HGARSc{_pW8!*Se!nah@FyG3P!b^{yI$&q#5!&T+%4_BuGcuVD5)~3LYlm`FvKZo zAQ7>#d$Ic+G83l2DNEbN_+AfZ+@7Se($zc;NW5%8E9uLU&H(W5bnAjGgtsC?kQc96 z16`ce!?e`W3vKq4?x;ugfn_!xBI6MmUlP-@%97K=H!!)nFh-8{2mrD$So_CgbGKfY ziQ~Q#tEZ?{hOyt36fp%^B#DTH2-T#xOF6l<&(vEDtLt+M4t*=inpeFfD>du}{J^Zj z{eB_W4hpl*B1ZglXxcog2`8A$DpC~+u_P*i>;v~dyM*ulmwPu?vi)eiTPrNmMWPB zrMVYi#IR6VZZC31^5Qmy@5RkTv@z9#LBsUJ)(i?ncq~+8atK}Mi%VA zmeZ!nZ~0=2sH$e>6S;O~W76dJzC(Y*3$yO$7>BJkah%N?AG0QG(3utmVIf(Fj%c;_ z;*9`0*+#88wkE)yy=~g?tyL-kB^F^C0i-g=9IJh;{MnG(%f#XG$P+?2|gDff8xa5E>8rM?#&_v=Ax2~a!RX61+Gr)6Q<;h8Ri|KWfeuEgCV8X ziFT1>XyJ$-_L2arVX@K;orpSBh_*9NX`FPBmWGrff^NkWss`zGQdsoabrQjRajQ;< zpH-s+_mwvBh3gAAx3mOKb%2-0(ClrYXF$h zuquTJF$B5iJkC!KM)F9ocVaHu42@v1f^=(RbJDx4Lef?h<{!J((y;ZRGKw{a|WNvVf%Y{Z_I8{%_==~k8JW~X(X4dISb z2iZDZ8sh!=2xMYFDPjQL?2f-%Swml5A*iVC-5=-rrk-geWsF>wDngTOI-2ZQ>NMb_$tL~^8^s=jh?XT7vh#WeEIOQ6FOEk31k&mw_!noF~S%*2A~Knl?7P-;`8+0tzHrNs@oa2Bcl7tE^ zE+VZIv&yA3M>!!2N=~Op)HrsK6;h!_k_GT5z&u4xWQn1s3TX;O0g!Yv!PV6Y{^0XWwXA3+Nc)kBgA-0A)Y=AsZoJ6~lBDXeBOK1Q`wzb4-;GM}E*tBjYGix}c72SG#KWM19_+!BmgC8PY+P^JzsOu9ebp6Tp0I%~;xF zYcL$`0D~NA$C&JFN#$y5G158$2H2mMgi?lz0w9a|Rpl`%gYQ*3nrR{=A~8r=6e>g! zSiYrgL9TGGvt*I0&Sa*I{@LT5pP1Dx6GqA@V1)s(5`!epMXUg81q1_z=^-y3gxp5mS5!>nCX^Ew+P83LTa$E zM-87_D)Qg~gnX6O_aN!-Ggf)teho@#2SosQTL*om_H`{@ zQf3kBGy-W>PHSR|6V^Dc}F zN|Hr&(`5&7jDb|NzWq&2K@u{;(HE>N?@jkP*h0d4a<#oAPxK0#pjb}buUjL zoWaahsOC(a)d*i(Ng?~BvDC|Rb7DH1R?k7qPOxkl_K;a87VCsO2!sh*G^U0yixaB= z4wN1ClVUG&Z-Xqqvf-G~R#Mj0OG#4%vDDK-&-N~|#@fMwfG$LcrI|=&znQtN`zGOq zrJ?u9CU*Ci<|HT;1Za%PBrd^@xfMew00bIub9@um_SGb_R5dkVF+5ISrISTGG^$kt zncmTfrUe||n$eMVVY;EpO*?)h*ht6k_L|n#S4^aizwhq?GTso5f|g@6b0RXw?^?(b zJEf$KnMT1`+sNt&bzi0n>avkbkxLpCj!NvlDwxzY$cD1LS)c{(@)V{>ke%(ZHpOS! zR&Q5R3{gnMU<5xpQOidr_h_Th8_F27H!w$L78>jY?W#`5GhEt>FKB6^NNA~&7^-R| z5c|wZilE0BStQcIREBV>NCio`IMaKo(+$?J8TT|PE2&C^ZDqb4BIig1jb-ht!|6d!k!3Ju zPe)9Ll`IDCivp1&*37Yj^0Z91?=F(Wk)q5)!qjXL)2zuMx=U|6_MTe!D(PaJcMO#B zJT4e3g|RV7VWrmvHGRSY>^utkdVS^qQ`pFUr~$d7(8D z$#BL*peqrpmO%D-46mX#)!&d>;42ZG^KQ(kq|By=G|nN07~P_j*EEi0mOqY438|tn z2;y_gxsU+sA~LY*Tftd({{ZCEvP$q#W%Mx9#ZHdVwOuO4kqT>}Qeb+8cc~!Rw6YQ3 zC2p?JGs-E9Gv*?hRwgS4KSIS3ai>gb)$`r z_ukmq+*jE>B;_TdN+{{-XGEG&PXwLb_1+dL+I3jQ$eK}{qxDiAC%62cEJGY|<@9TQ ztqfuZw@cm~0{%OLz89_4ZSwL-KK-L7NbjdQfCkl+)=ZGWM?qG|1do_21_ORv6Y3xX zuu>Co;%sqe_WuB$<;#@3QB;b|%Bra+mDsCEOBm9^5LEXfPyj$~#^<2;YaSrtm`w1~ zwJOY%vARV}uckJdz{c|dW|2S)T>}Fp>{w!Eo3LYB1Li`q2;w2-o&^lDKvbXgbY1=h z7EO9UT{bP(8d{qb8)@wY;reT@Le-wVN5qTmkBKCd!81ptCrITW3!@)}hwQ1-u^mCZ z>_Hf1*&tb}YNe^Ck-h1!9O34Pqc0;fa@sdQOYAPe&;_-u#`5%>I@!X>DhgUfrBscC zF)U_fRAPnD6c-8)c-@(kS&!!-*eyw_*(0juF|>5%tNiyrF$S~f#w3dCH2)Ei>B;yx^*sETOoX`^bF zsBpCo6msB>QSR}=%eo^+w2BxPXKh|X8%e8AF|%37BRvVv!2a>;>20G8!T$hxl>Yz$ zaG})!R|E+}u1G3EMvWsM9jv8yw|I;k_EE)D8e#XIS1oD_ib9MTs$EhzXI4@!$OYur zaLjsXUF)aKUY=^Op|r^ywCQ`Txw=Ku)dr=t{$~fBo93;QORtnF9%*8Qm7_XhW?`x~ zatem;YD-&Hf$+y)W?HXE&-a+M;5gkj=lVMPYj`qXfF+@-(;#Es5y>IcM&jpj^8H9X zv%7M7?58-SWK|TknKDH%*@Mqi8N-Y0L}*2YuB>miFh^khs@2ibm}wDIbq;jz zV7j(myY=~WI4R@K+XuM7D=O)$8lt;hUR@PBtel8qk`$<@l~F;E77qkW#Gd0{X47`5 zw|Sws_JTscPCq!0V7<7@3(b{P%4Ah}MLW4H%IHXF^)b0e15|!nj)g$0ds)k4mZ9Al zPPQSmk==CIgXOiqJXaOjfcKK|JGc{Sjz`(p2D&rbVAi&)ZF}O}pMW(a)p5*>+Jn75 zh7PJl-NTcmhN4cxet_P}a%|GAcAM1Tk^0SwwGCnlh{y-_h52T9wG^g2#&fEoB&QRT z-n}|$gtImEvV}lP5wB~oCisP>>^3K-nMF&@SY(bE*)MAgG?5640>m%GT17=GxdP`4 z_HCWgPaMf0SLFp@9x%XaxYW9oi{H!UcEHC5@q5#|t1mEKS7k=FxMq(`g&YC{paH&M zubv5~4!g2B>o2dhA7Dek7?!_baKkK;P>7^SsgN;g863#B16X9b-sMQO#fY)k;^yLB z0TnQEN)2zo03nCDxS!=eW0b5wwcnG-aX!eifY>(5XN2R zsFP(EcDlq0h3+QBO|d1~CuCwMR(!{ZXOv5*LmfC}6R-oiqA*iV_qkBId`DbT-Aaes zyZgjahGopIIR5~KWXyA_s$8#^s+r+}o;#`qf{G~M0Uv*cP;LjE?~AiJ?O^1zEYim# zRWX*HFiCIqzzR%clKXPlJ6^=Ln-5I+?9bX*%kvehtLDn_z|cn=XdUdjZVB7@v_os$ zo$f`ijRD)IX*qU#M;g&lNYW)yo$}Bu6qL>Sked2f+B+@0uFIqZ~vHfphOO z&j|6Mr^=^}Foju^$ZU0%O*(Exw_5-S@V&fn0mN19T4M@Ep>jz-3hi=w>1RX)PI7@+2gi18YDO!qoQb@FS>7TmkqDC5J z8qipP2wUFwz8gwFumkS|Y&!{AY*F@qm{(G~QPsyJkIG`N5l3c*+`SSj5pV$blY4wi zxy3icw6!3vSyRc4(yB=sdC`(s+0-dXX55%a3nGg)b9lAyC{As0=xs7++8%DO<2`7#rBy#~kOJ8e@{0u8OJZDuXPND<#ZMsu@UNEZ~sH(P;!* zWza#!5~(ATI#PXD#Fwn>;u=4HNb@60Jum`VX@rO?#kHrpNS9L1x=$u(!A5Hd3LRK? z*#<_HW#Tm{2B!=az-42w)!ubG-rduFr^gaJcg7U?g)|P-B0R~Zb6q?@q%9I5jueVL zWdebqfEMeZ_nTh89iMQ0H0El0wWvo|Qyj4obXyQXjlo9MU_m?i5scG%iw-y9EX|^( zjLZJ2(b%g9QR)XMJkpDVLBBxoY5HKhE{L2)LC9KNCQ(w zGyrUTe9k{lj}*}5t(Oe8nwC0@?s;IEHZ2rSQ5`GG&oQXdOp_`>DFH#}D>mTjBNk-O zc!3Bk#@+`L9&tyqU3~^!JHgQ&3aV)@8BJK}@KV%N(M3YNMw^6)=!QEl#C~ zW(>&eMv|j(j(g3wAInh3cPF?X6LVccp&2*?a63l+&KX4yxlw;6wPZQHYpoSQj;hhT zX6;cV(Gc1d673U5XI3Da4M!V$h`U#$$}&optBFcdGE>JKO?9jiXi8>{CFPL%Sz1EC zA_TssUCtKGYDP~(N|1zFiic=c=Es%_&0hS=mMY9)phKuKr!j*Kh6v>1$}G(%TE~(Y zm0oxfDuBTr7#iS4{N89bHdpvpWwtsUIy<+TJ9NzB^==S(L~we?w0_!@%TQi8S~Q!v zH6=hn6hg#vp_N(LByprVX$kk1#|1V0s=@CNf2$<1W=zsMSxHD-AbBU0X+;1YX5h0X zz4a}HAfC;&dBo3AMAXNch{+vQK}pC9%iIW90d%k}q#mNe))j6N%u%PwrlzS}$Oudn zfT53)o5*>KAc>-Q^)9|-h;)G1%WtfxH^?(`>s-qkZlT76OpVG@gK@&7otg0Sq zk)skZF@zF0nnWlkF3lQ(%#3>2X~vS{9uA|9o;c|vi7KIsnN6zdBy~ann49w&KwWhn z_1@s)^T#yf$nxr{Y9*ja#bJm0ZXaAG4+kP6ez(R{pR+Pk}Y;Eka`bknQ|`8 zV9Zu@N?ECD;!t*uMT$Kj4ovary3SQyi z0XC6%+hQ(zw;MJr$h&7+fixnns)6KrIg&-npPE=%5?)x1iWM)dp(^K5yAg{^**~-g zsI5%8as$(((7vOoB&1gV09JIp)G}+5I|9VS>!{sqbo4$UWmyh#J-xp;9ZrXF2OWF= z0QoWR7I9?NGIJ(vO{6FQSyfb61yQgbC(Q4BP39a&5@qpILUlaSbLz6e! z2-~@St#fyFf$Yg~1gac0RPsbt71q@9ps|W{0C(C@Y;79pBfZmAOU2!R*HbeqL|mY| zDp<&%jX}A0F6vis@pBTu-G(>xy8S+<0ZuX7=4Icewt{od%$4Gd`f5zNf*MzNmZm12 zX_D&lNWmDWlj2Y{?WBeZiU9x+P?Iv2rzV-I3rh6WP)AJdc9qP914J9*k%F^tyB_Ey zmA)akTeT*N0ZlbLHMGF$jU-~GJKWwm0>0awJ6v3V);0wkG1?+jR71^3X=vz`>Jpg< z($XNZZbF$P)YleKYZGEk@X4*zeLUwm_k#?i_2U@Cj_rrCSn~Mk3b}TX8EOe2sHjk` zLI69frHHX4_iy5G9hzj12#c7yd9f_WFTRH8S$e5HL|^m8r`h&i*|bu{P{Q%oMOx(U z7AFiQL3?eWIu9XYM%b_T*ElsbGS7bNF%b_1g?q69<=p{~^qAr88`@6B>N@`bh&z!0 z+&lDxQpj;D*{=c|#<~hWg(Pv#ZTpZXdS^BSfup(@1EraEIAK)VV@&%P@W(CYsxm_q z#vO5_(S|ZpscY!JgpRgtA&!+xs|N1JiCg4USeY7HjkX07S9?Tf1}NxOofalC!wixo z*#$H*BZvd+2Brv5HJGZslL&B)62|lU(`%@ns-i`jOE74pnVOmvdk$YJB9SadNCi%v zSGk4a>S^YyN&W7R1QLgmOX6*jubH~ zv62$KN}XW{z1~h%>yUkr}FLvB0t?sCxmWI>T_7W9(4E|CV z+c&j^6!FCq8>&e=0tg~TQ%_D99=+)vKssJ9d@+OSrErl|LUhRw*}c41?%a5(_((lR z%NGZcjf2=x;JrL zDi*mKpMInRJ(6YFVs}L%yQ)}|5prZvX1OK0bW`cE#RI`!($zCZB<)PKQ7zJEj-r`r z(PFtWH5qlCm&(y}gS zAdp>UfxQDLKV2+8Oi9vAqoud~k#G37YkzAQY#lzOBkm!=4c;?$nB22+!8_XEp8;}7 zbGMc86~y^dH9X4$pLlrLVmlACBFZl)+ROXoj~*; zj}UFQQ|o|vhdDCX<UaDHLHVDS6_Tt2s3!eEW-V)UJMFiqIBdC#o`C7MQU~NZpP8`oz6Xf`bJi#P zg>I+uz|KXQnP!j+^3<4?+FH{_(g_2U3}b5mLdeQ=+qwxO1*W>)RnFZ)mi<3)z~=zu z{G(GNA&shL=Q?+YG6WHq7XXHp5;DtcDPE_1HBu;2Tk?=okR;1xr^J!l07#_V`-&2m?+a4UD%R*0kFj4RxO2r+yl5E z?k~7IgXTJnQ*Pd5>=Gyx39OI1sNUBm*RUQZ)2TS-1Xl!w+fe}7NMJtjwe~(9J7O=5 z)!kJRJE>(dNL^K97qA*wF>=7L(iX%6xZ3kvH&6CgV&}g5HM@gXbprusKt2by<8Gr8 z$^vfh2ai@GYRsYj;-~hB2kB)a_uyb~*p1d^3mH}eQkfmQ<%PS}07&m*En#v+x5U?I zdDN*+c@3gc@TwJwr*8DAsB*>0x@rWEgk0@wiCmUdC>vilQ#-3$Pj%R`t*%HBsR#k@ zcYE946+%>IP@pFf_Gg=E&;qeMxcVbo;T|3yx5Z`0lhq@0oVLXMKprT}Eh=d@nPCW(2GyGs}y<+~D|B!Ee}_4OXO zs|W*f`wq7|Tk*!ug}e=|{(g9^dqnJxHVrj8D3I<_)>iSj2VmcTC(9e!ZGL?(GpwY6 zku$zYMJqcQm19yDmZxSU?n_?!Pk~Z)KP|{kN=DWr#CTuS5wZD$hO*K!vueJ+hgVf2 z^xu8FcgKC4B&0|s<_O|icw<=*$99e@$smn@U>LfnasiMaYmh<4&frEwL@7OEnu=)% zDsIEjkbk@^-i& zTkRxAZ@i;H{47xY0-szns>pV-NC^FjKo`3R_>J&IwB|_=3T(b;+gVpq-+5iM9}D-nu@P;CfCsJ!a{kdOQr3{|;OW-h zI*`BR65Ad_m^%I4B>vBJkIW9~`iwf3CL;W})b-TSA|I{Fq50{<>8Y_g7zU+ZsD=ZM zqN$EFo}5Sm5bm+8q%qjo54ExDeLH$#u5sBP4^IjrIEqIsWQk=lzP1y+IJkSZ7oGSu%RxWWh88}Xqj&4;YFJI&X(?rqY;ctJyG9o zhQxS-<@oqv%_TKj31P^ZM34q0iJp5%&ftOF9!diL0L9*IygR_+JBD(4%)m3QzECz} z9ksVWe$qk!w~I3#mI{0TUafpr7KdkjvhrXQ)(NDY1Z}JmNx9n1a(eZ~i9uh}A$?t8 zZ)toTEL4dM5~VzA(w-~7G55PmKF=eauG(x5i5)XkRK=Ra8-hUx%o`AXxU=|&w1#%p zTv%=qPNKwg8*BmdJ6i)hJCaE$ET~I;aRvZyO79)S11s&;R#l76_RqQPKbvWkUB%(=LOjE+wn5G^~?wMr_&?=niTK`i7~ zNfxqOo1)Pf2vZpb#DZ^IRYzAfMKrO`8#P*1a^;zd#EBc~DJuYb=!&em1&M1d!MV6< zxE>iYXy&L1G|(ESU20w3BX$o?lWyuh%i+`p;EQjnv4c9KmoKM`#a6V?NFbc66HgOV zs+l7|W3YW!aN4Am%Wk?zQ_1A@Bd6~*LJk6+zqFCy`Y0+OOtzwUl%z7)2|?95%0+_` zfUIhDAk;aCw^Mc)7wr=#dTN1A^+BMcrI9IZeQ1(3i=vXN&3QSD(p-%;I-HAOhc)d^ z87O&F^oS$Nj1?LSFf&GH9L8w|nH&9^O{kq>#DQyKZ-y#pYonU7vOxn?EVSZjOUTU` zA8W}+)Irqb77P|UX;FLO?FN);5xK)>q4t6C8$~v#URNDQysS7snWdtJs5leFJTh*g zSy5C0GPIYDIG7$|5?Mh6HkKn2{8f=pR)$d^i5H(OT~9OK2YXbIl97_?WV57Es4crQ z6W0W3*o<+})TUim9dkR!C?ptVg<@6&t)EM|PK#+K)*$WAF?nUIp~|xT5M__c zd8ncwxgmM7RJ3DM(leu~mw6oNEz;p{Zl&~#(-jXUrOu%7iHDi zLuJU-%#~{edb>apM3uSGDuy91rW_bndOJ8xW z*tiyok~EGg#;U8-&r>HWmlVH-S@qr8YfYsmEANQhL43=9tD_+NJf~$ACpjy|!6r6QET2fRZjWn_>vdZof5XcE} zsmKhab;qF#F;};U!Y-_@&ogqW(A3?%zGO`&7*n+bbjdaOQJp;93gt;Gs6vvgR2?Cd zkic{YY;)P)X|(xuGc^@8O-^l8tfF}%kKH4NHfEMOLZr_jF^{)(D0OTs6k^%pcHv0r zX#&u*gP5$+&lzoRP9&Au0`@nB&@2WHp+R-C07Xfi=Q)Obn?SKsEgd{S!%Y_~r8Olo zt(#z~x8S)cS1_q9RFS5w_3M?1I{_JKWOmSZHuSfa zHpW%kJe5?RVJOiGqB+sa=3RTQ8tP&qU@oP%9WAx-mU}(yIVR4=Q7nPsid|Dp3a~8< zXpY)cU4t+pGv4kNV}9ru{TQX}Z!3)^_kxPkXjg=|jdVtekrAMau|amT=mNsPf=@f* z`g-+jlw;M@9>7S_-f9KUNtHd2_*LM|>vLJuOA5yzhH~n3$st{4$9tq|$Xj3ob=>K- z`yA}rTA6F}+R2hyoWxB_Mu2l*hJdmJUgjVsB&JDYtcF`NT%AyrHtysm5i0MYiyXOLDvisUp-B5}xFMV(bdnpj%M zr%);e*puN-(kDnT8DQYQ{)I;wwEH4qf=4!TSC4h}KmMK`fM`OIg z+EtLVg!b1@Tbb2T!>2+7krwS6pq(z$D>M?!oYhrOP_T9J1AGf`#~ju?H3A)yo}NO) zK9Yh{A|tQ#qZ3FFi!!f{!q-;=@I0}&b`eoRsY%KTvB_gk30VxO6Q;U}UE~tT&2lYv zYYcP43xH=p*=&&}`(ok0a>x>%pH`?1F;b(vWHX^=+p9c`O@QicY*QJ=PnaUbE@GUG zVDi!L?-B(7-;z7Z0kB~qLZ_%6Hs@%3XE(XLRMjxmNRpYo;zx=XhnDL+Xpr56uCBI^ z!oUW(>qDn#6?Jnom2x#zM98tkJD`OpR-W#ZjR_!~RuMX4sNW!vop>01zrl`fhi%!M35`NCw8^ z!+RVdnq;p`>hCN};aC{sV)||f(p(J$?r)&5+u}G&BY~=9SkZMz=EM9?fE`Kj7@b9c zjGxwM_+FjE6h^@(0Ao3qce4Kgv(069KQJ+v==oDe5hRX${{R6IsN9Hq#ht97>;=xP zApNj*HJHUDaq{JoH+6|D3Gb7oLp6e^VnvG(Jjlki%Xp78$!KWl;GwIkg{hUHo|RUj z9(1MNNamy#Bqr(LFJ(# zit1oP8|}<~KTx`W!ya3327hzk?+K{URyU((a+8yZM0TB9B`*&{Mq(>lS(?8eO)TL z=?Y{v)vI$84x|o)6OJ$~se+yl zc$%h~YBdV3^C6bS-T;?wUPMR{W? zG_Y`iN`up2r4OJuALBVCm1^g6tC<`ClGkEVMcuA%eIni_z+xAJIEiU%Qdfvfh+|DB za0;R*YY;)xZGriXz{g!(jH|c~anfQM)t_NJd;b8KS=p9JOqCFO%0D2_0GecAG(^%W z%-!K-(-~v9JBy3#438OhYYf?qWK{BAjV78pYLAbZ3b_y!V_?9b7i$ak9dY_6!C&b6 zp{R@AX}j?=NTSsZX9(pR;tZzDq<6Qt=rBRUf9Ut7NdYM)okIHR7fONR0wS@u&!#tb zX+gth1GL01doQF6p7Zjfiu(qZ69izdHdiRJ79trzW2Az2SrlmumOViQy5VZN+L{&+ zOcXV)t*XnTqgj{+vFKLchS=Ml+uR35Nd;6eD=)d#QnVYEWpZKELz8o>n(4W?2h$Yq zwx?h-Q^N%Bq)8lQ*+Z)~j^)V;&1(|7pBsUN^*U`ishLka5uan)7fY$sd5XB;tO+Y6e9&5)gpuSB!VpswiN^4wA>~VTH-66IDC0*mq;S!>#UlTDDPthH z2wcYnnU*)HsMOLjo1kSY*5r7Xac2Nz`AihG)U@+vZ8WH2lBTtyMEf%$ND`75t_`iF zowqhVBNl3^F1YKM0PYl%(otLm$8~T#v&51kIv9lUgC8nZaAJO8QUMM-%XQSZ1b{Jo z@pSc}Df3CiInWj=xuJC|{MQQyJp!t;D=Vp)2`n9T>e3lyIHR?ZCR<4}<#ZC%S5;LA z;pDT0rlTtr*vRrUvNb~!zJaAc3$rn+yI}2hc{0;WFp4QHKnA?rxk!KH8igp%Io%F zk%KZ5Vms-pua~H~l(`IaxfI!zEK*a3&ZPHoCZ*=l%OuMbYY_{kC4?a%mtLi~I&3h; zmdf8#vh3jFr_4)Qwx*o6pBsn2Nt<$>F{q@IMDdqp=mYYOuewVWBTf2|ro+T_8Fol`yYh7*5#;ef|CCLAaUD2h9Gb)eaZbf>pp(II9{UE z*S6p4z~hdyB6j2K;ail~8gI0gmOv$@s@YOXa@O6Ca7`b>A`95*Z8}{q8OHo2Qw0=t zD->b}a)wA5*v8}ewy1Ie63KICUg7v`4v@$FuXd$XJlwj83&f7^4LN`2M79MZZ92+; zi@RzbN(LYB&S=tQ^|X;`pPdV;!6^t;j_BK-TNGd!U0DjSQ>A=4JG53SFsx?>98U91 zuBnk)!;FA==_;PfxJIFu-cgjI*`*C~d0~Jhy58T29yrnYZf{1Auz4aOhU)gX>1K?9 z-DR*UP3`J2p8GlCk8z5omUk&TtHjVWZFCO1-a92kSxF#3nT0S{V1u8{ ziIU)1qzfF17g5uwHl44q$IbQh-RF|o7(8Hh`Jbf!0EV?*9@-Brh{;|-JOlCfk-d;m zy-ifI1zBWTm5^%(Q&ClmDVCT19FrEzaE)_7zFT2xfikb~#K`ls_E5g4Q zH6{_cu{SY|g{_6SBZew?e=+xq!BH##87WMPBbcyVD6*Ah=4q1goi|qNVSDYY=d^Le zIa;g~v}vA1=~quk)5kR82qn=hl(Rf>YLk@B8=%q`UX~y-le4F{dwGE5W2falY2z9* zr~Y2tWal~TPY_dwYx7LXlaV?_m*&PbNrcg))YDx_YJ`qCiH?7S$s1lbJ>{_`)NLoQ zu4R(T6?gK8Gf7mG@y85Ik5pz2%w0_*0-`e{jvgi&RNBVGS^OQC#U$oR$tr1P19_v7 zl%Y+&38H0Cw%tXoYZ2j#5xYx@qEk^dSgfX}_o%X?9Bi*t7M!(3MdH?`MbOd3Hkj2@ zaHE^M6&2@T69~kupG*G=BIh(XA8?|G}(eKu_J0*X*V6_ z?&;qfPhXLNiGfX?d1IXOFW$iWOjvTMssRzp60I~=B(z-DDjjZbbqvH3ZY_L6_P5%# zRJB=sax_9H&{4@y${sN*KQ-g1yD4T=B2c=QyL&L+-ga~B<5617xpeVSI!qy`qp4?= zd5fjBfU7XSEw!K|q@Q({d|4f<`#nLFwH{qHK&@K2rOceVg|wWQpyjk-jnF$t@f(I^ zBoGSR;y4wtu+Gm#TWWEq93OwQBFXzmr>xB@-kGWECH_i4-eWHQO)PQq4pxBUDTNgJQ@XZBe)yFlST8ZnXr;dt~FJaBg z-kvV%#aT6=6%xgHC5Ay5ZODnP2(5~)clL*B?4foM&oGXz2JJ z)Xx}FIfI!PsDvRpjM~g`FMVFgV~~3;;&^hr;+~~s=7}jCsAWf!l^XQBd5%e$0RaE9E#9M8#@M4}c!I8;C{P3}WDe#-rlJxw%AhKV5v+%GJ=R+b+uo@% z%-*4dU&=`qVA*QPB6BB#I=Vqz7BKNi&U9j8ZA2X%2w+1lwJQ1)^o8^HHs)OBP<(s9 z@>JI;s-d2W87P)VsCeUzXRGEDB((C!swYVjMP;Xx{b5ym>Y;Ap*{`#7{{U*#(nnGv zN0p%$_pK`WbR;OQW{`py2*@nAu)TrPJ+pf|NtEL(@>2kfkYCi2d1eZBx=~JY)#Gd4~gBR zUEt&n&|id0a-?AU$~r8{qLY}GmIEp@QY#@tA_LxD@C1&amGdI|k%(cM1K@G8J9ObV zGkzdMTHkjw!Am%%sEmp#gP}RlQ`9LdPdnIiizSuYSSI8O{{W3U2Fs?J5th|hO;*&8 z9Hp8%S%OI>i6*fnRb#PxvNok5tZj~~OXGDo1%}cg$_3JI>Br zX{(-{rh=;cr%M)SQO7-_U>lIjq^mT_z0zzfZ;R_I<0*6M4AP$}qh^|>12m3A5hK)8 zOCP*M3p(H3sFRaU4u+Mx#YM@+7msRA>*%Me+R3_6wZ9K)&2_O#XvXkVQB|@?1RmBrBhIM19UA8J@64_<6Z3JMWgLs=q zQ;Hw4Sm4moN`Ab zOzR|X1Dy+Rcjf}|%m9Al##xz^YdefpoM%^3Dsu|^l!6GNp`>6gwbhJD$y6MG%@jr5 z0c8Z}Huy0>@t0_ol2=DUy5Wi!K+7*WK@~$bqaia|byT~Q`=J;WHqu4G+Km-)qlS?b zOD83&l@>_QyR!0wDUhUKB6DZbvbbhpW@l~o&0c1}d!Bv-!CRh<`*<>jhfLAP26N7gOnR=e{Lt(V&n=JWhpKb)zkgorwbb z8?Q?nV#LU}k}BTgCD^(d5v)v!3e-%14X!zih!Wtnt>cfSS#r{dwekR*a@Jgu-C(r> zB=S=*AX-Jc9j$$Z&!b!Ai-xPUI>@aQgvlC_ZLfQ6*ZhoEnGXrYD5_}Hp=bjiifG>jB}FgM1`0(iko5);nSQoiz$9 z&JS@tOBzXBaqlF1ea|SWAccfMDnx;h=?cMZ-XXf!?e({oDZHmKmLKM-9x!@^eUJ8j z8~rifbtLr?86{%Q=Jz&Hw!|nFP^;3)03KL-mGEzioB9vqf>A>r6h-wH25gxrLB=(0 z(xzrUmQX&RUmLsFlOTAq_nu=jy;ScaGxHxzXaqvXdun8N+Q5b$SjE{kS9VCFQF$Fv zN1HhcznK{QP~hB(I$C;aR07oS#}K%&Jhci~_>#;E6XJe&=f8?96x6kUQ*wU7H{r{< zi*}Cv_WmRLL|^--arlf#MOX!h03R?n`gOO`$JY;OXG44Le7rwABVMpB><|;=EXU=h z$Ncrj%!f0hiKByi{QkI2>KCGoNA&rggZ1>lUmfwnQ$alTB_N69G3(v5DQjvyFVm@A z_r4i+W!oJ#VHs+7P|0|YO;1F&uHa55ngwYQK&oA)|6`9FQVT8aH$b_F!9??{{TLlpA+MT z^^*~#dEArJp#CIbuQ$%$jv$#KVFqt1>PzakDm!exUMGA+=J~u!6o$YRMzcG2Ls;p! z02>yyz}$nkTuJ7%p~3=4yfN+xQa11-d=5>*FoxE3w@sc$b=#>5#Hb_80C1aqe3*+i zAZKJIR;HWY_o$L$(>y%bqAp`lOe%CTh4@=xsnnkwSouw5w1NhZG=bK@VRXuoK>z`A zN%@`0K4kcucCmrrzg!HJ3`l`%iJiqVgQoj$r+%Z$=Dr`%`5Zf%QEiWhiM9U#BWyFC zkP)@L2pfa`f6n-CO)x!0h&DFx_4yIF{{RDv6WmEwCIR+=!s2jA_gLh%&T0y<`Hoea z<%+Jpl*I15?rSp_X#)n<%x-=VtG7U*KmY&+G$#^pd{ZvqU%|YwNpU|1m`T6G=k?pq z@fh3D>JB!8R+TJeeKImBVvo5y33FQZNRAbOh?V71Ro@E}X|JjW?P_L;E_xZ|=vaulDp|u#Be+ zC3e9YjIp-w-_UG7FF&3cOO@&+LR_7!1=!!I09>D*Br7h@n;L3&b@65hN%#vfj>gj--%0hl$3kHEaez{Ud4y2s2Lb z?;le%I;mqqKn32$IHP^R*DGFEYgm}UZ%cS(elMW{d5W^QXJ^!dO5KSp6kORu5&*e2 z0~5Rx!Zj0_Qkl7QgsGL?{>~=pa>mD3#1%r8VQVi#f=*Nk6DLXH^ zsn)ukL&gGAOTOCe}6@X;g`tAwpdxcL`DhRed ztf!WwgAFx^Z7AujnGm^X;tn*R(#J|Ym8<~1*lz1=+(!U=%PKA-EYF74niDbz@6#$q)0n#cfCuc^B9#QQ`VmPD4S3UowJOG7p03d|%` zrb4=xOO9;B*+ZZUzQde9+65gnFjdqnwaxF9B1B@#OUg*X!yK^9ZhWq0T7z@;agJTS zEqVU{j%FCFW3+Sd$`^Asc+57QIb)-VR%qrm9Pm)i5}GLK(alVpz@*6`V5Jag7i$px zFag5cV^tLla?C20fdf;~l@AhkFpXn+kkKlr z2+`E&f>@Cl{gU&*1$(6l{hJe{a!wGYrphVuZ1OPaO`9!bNl7C+H8jr6G-blAoIH+< zfa`coke1sB8+K$ljM7TDu@^HHsi}#dF=}%)1m&QfM6yLBQv(@|ghufaP^n<51fW>z zWxcuC*Jlfw!y4tW0~Io8WvOS;9Fh|w0WGY~?8KA^2wf!nTl4K-R*mm*<cLaMs9 zuMunDnoFA{(Bu63M0F^oxgS5AvNK64@`;w2;f4ukD2UgzZe(#9opvWmvjF6+&|kaK z?>(bQLKpfa^64X4Za3Oidj=kYR%H#%5~cib^GxBS}*7YH+R0DlEHM$pgD% zu>@EF(_@QUG0SLYrAmnP+DSq{8X^|3 z<*JJX*bA?L#(1XhG&#s0-~OiUPfFHQ9%N??dp^rmQ_V3vuth4#S4>z#AOW>YN+x$$ z;xZ^@h2)i7DF;a^PBzaU`&6w>JvLuMPaF}XNea-?vP!5`ZOTVLsmqB#)Yeo`31eVR zGOuQ|^%d=BP^8>rA)|@NfSNQp@6w28*LjELm*Pxq}i~2+dgK{ z#36)8VW&fKTXsd=+1LShJKe2&ov~B#w`%m#);)BPbBTf|=^zpq;*BF3HBJ-0e`z67 ztG$lESX!FE93EuTs5#_u3p*d-nhJ%QDv1?oDPT!n@^YGKVRYp`9ilyy^8xm}S3*_Jd36l;Ck zmVgbf)ZLGX>TzlCe`N5wl}RI(a)gN2O!M^bUNvQcoi`SeSzU$A!tH#gpcTUy!&&Bi zB2MRBw8NH1Bsp6$&nxpDw?e$qBND+LNr7ts)&eD1+S-UDo0?R6ILRm5=aS9u5_jT~ zI*28Tco{(t6QFTxu?>AAVWo7CS_d=XY^=c(W=kNcL`0G4Ce#A0z(&%K9(Sik=TyO3T1d ze<`gkJjMj>@}-b-HOef-Ng4%>ymq+L;xV9mA?<(uPG)s-!2zrlw1y?8gn$iVIA~q< z9ZMJ-?qFR^HG%;E+OnU64yszB$;;QO8xY*hK(4JrZI1T2H|uK=fLXYTLt2ro%#A9f zZGQ4GIyC@p4$N*2#9taZTSbYxzGZGro|DpP7&~qEx$Ebzmy`AlJaCR&EiA2|a#Txw z15(~c@3xW-o`h}s5A74f@f?3n8b31u;`0)n#z=Fm?9JY|BZ*y-^$w*4#!>xpcejNm@=Q7DKoi7C<>6U>c) z)Km>3`htV73b)+tdA>E_r>dMm2nI=CN@_Y*_AE;`fK^gS@*hksm3AXl1XHeu%; z3pSMnfzN22omFI2ElazNhhpmkn{8GqVqiwxRzj7(^tYHPLht64y?J?0>FwlzN- z)nxUv$Ck`t_m+q}G|dwLBLL|UuufVqRV8B%ucdAl*2GT~_Dqmb2c4
V4AVD6k2GRis{#5%_?<>z7PwBN&f(8ZX>4?q>#rPGQ!9yz1$+C zam2u)>0Oyr3nlNrjfuX#_H6b@$|~vPtf-+!kV^5YnIvj$0aV=~)>TL(f(dICBz4Ae z_QC9LET*lBmVyxs))G%3_kZE`ld6R;QD<4a3Rmtb3QCxPq?OHpEl2N(cz3v-ScB?OV9ylAo+W{n<55RQT7 zP+|tbt_uP-zfpC2GVIQxs_X)wXHptnORN$JC<2ng!)G1ai(KPOoV{pxYObAHH7yfB z+U1E#w8R!N0>FpT<$~$dNdOCwFe&WCpBmX5)VDR`NRlTYDG3nnd?0vrHs1UB4u*sq zytnN$EwF^&UwNSWKkb6PhLBOyRJ?F2I|VUD#2Fa7g>p++yB4>BCf4bR`Yze?0ynOk zf7w`p`gcwczji>@@>xH6VQNmCFce*J%HST7UI?x9RL`tk7tWbN0?MZZ%JD~vd5{lJTd?Z#O&L! zB0-_9e`N1%T4S=#1f$NP<*U+5Ggrk5)6}G)rj3;)E=Ko?Ag*p>v0;PcbTaM`h*i*EQ0;-~6Pb(1%H$5Y`X!RXH zyiMQ<)u~0S+m%vH@4VmHrUNjR8kvEW^@?TWfL1g>z{=%WA?_xiUAxb)B#c$Pt<<~8 zH#Oxi H7lmYJVE8XFa#FC(>I*IR-s@vRyPpJ*52s&dY{7BVl*>uH^yeZ)-$l^I{ zOojP*d=nMWL~#n4Ybzw4dW)*V3ap6Ii?h0*(x%rGM+|nZInyMN#ZwgW%{}FeIo4U3 zT{R78fqv=ueqfwkeWlg=u34H%r8V+tGU(gHqtnyEzzxXJ5SPp1VdB=#9g*secS&4S)470o(rO^U2DI)5&BDO9jT_Z_E3LWF)wTtDL9@f1Z;qW3ag+g z>NML;kIV4EHyU>NU75!eRg$AcPIbi`ajZ+M_e;IEchX9NPQaT1bBdFQcw$v&P`jZa z;vX6jv9RjPw!~cec;M%UsQHkh&mM`iDOTuYk9{m{ZT2?@eXrwi_veU?IFO=`?dkH+h9^dlFa6x37X`F%xPaKw_w6_JR$8Dt_j zl*rni#z#@*>5VOSiD|V8o5L1f!+?JCo6z_kvrlE7TPRoVMo9a1m~Xa>t3hzW(xXPC zot;QcL=n|kUhF!9w}HSv3vv9ksm}|j_mNM5U8;q3d~SMS$7FmODJBd5Hh^B-z;s;{Z6tfks{`N*(HLqG_g%?Y>&>oO|nItgZp zizmWt3AwNMZ!f2v%oMZBPb0pFvR8&aI z5M~6Dmn7;2?ytdnL*tqmqwbxB@5fm0Yf)s+>m4sB2~t`G$NB_Ep-=d^t*H z(X}u7u@rJAyIQA`){mTL)%LNg*tBjefpzNJysZbZu&AeowvN3-@}kR8M)M-whx(ELmeFG*f9d~uH|wptdM6>q|~iWt)4pZ1F1MuIHj(ZuC6{@(kzQCvYipPJlSLt z>3E2W;q0tg5m#VFCHP~2WrHfOhNclyM3r#V)pDm(RU1d8eex7wRjJ-KI_epP(@|*j z>R{vkTvbwQMX9fOsTecR)kh4%>O3TZSx}Ize}RDp*BjV_g*~OCsaHyf{l-aQc+#RF z&4NVa$T?F%CvwEGDp2fCcWh=GFRg$eW8!p{Q>4{a&0C$|6U>w0{@S9BhEp9}(#WJk ze8Hm2@HCfp|bAU;LS2;In?peyc0&0xrA~E z>Oj@5NTOv;Pjw8kLaIXnat52>Jd-!1r-C2k`pSx+&g>;I^CZ%-@+6JQgfhz#$|Yn` z%u>LaENzP?+3(vsEPh=DRX1`{BSRubBu%V@0hdStP5%I9*7U^Z9(Ikx)ETQ~trQgI zREeVz(*=mEBsUuYnEjSW{Q@j1Jk=1WrhnZt|`&AyGIl2Ad{*v zKo_!%X8JtBmpY-zs1cql){;X*Z5pGVidhW2<$HjJl>;`CMxbN>8>Shki&uf)5|?JC zUVn(B)$8l$8D0}>FQ|f37}=3hLUMuoHanGngEi!8$#k~YQncXHH1=02_iL>7(8k%wbsY6rv%Z>DLk!A(VtIE4H;D-PNovMl8>6&Kzm#@|@C#Ds0JV37ayK zo?Q|>JPf7?G${`&BbgeXV2Vi<++{{U@oRL>nWU^J@-I#%w(3R9FT9ms23C?!YG?yanDw5%*_+>sIHHE4H?FOWMKnaj zLcO_-4y_U^llGvSh=r_U3U624UGYT`NV)VG`5?5zkKA;#!L+ zc%+I$Xpc0L5}6@pjgWv%^w>VqS)F6#bud;^(9%3~bQSTBcxmcxvLtmeBwVPy+DPO; zgo5bG`fk@?nRBr2(P!1kgQZq)7pCr~|6#GZu;#h!d$xme^t|v>b|_C5_<&{cYN&I}`R)%!{HTFSpvX zgK>LC1?`J}EcQT-NEM`#NM~;Klm=A?;Z|1{zlrZ9uWt+BH;H|hD&XBDieNSuCMG_M zteF1*`J){si^O#0hx0M;W_F`PcppZ7M1br*rk*u7E~arxfdA5&%qo?~NUrpCp6RgL=f zT|)pJpmA@yr8IM^4X4wt>g#C+#aIrv2cqAoCwyS|<%_A*lBXaHN3}G}`MKJ2E>4RRoq|k)6IDD$*_unKT(AEfmos9R*mJ zW!3jB2}hfH?s?oBbR$y#U+fehyecp-^Fj33hqzJ*rzJ{d3t!{iZU27_f?kbdssEi zfm?WvxTrD=v@s>W^~06;T{?`HKp?Et8h{GfpQT-#_Jp9NIg*dA7~Wt2&#&JiRoqzkCj!7`5{1bv_ags<`y~ zvE$}iqgvkRodF~Co7Jnb0(*%QTTIP$79I@4YXjx|BjMyX^1rD;pa2OQbOiMD-xEhI zRTkDo$tLM*`IBZp=cXFTm#lwaEDE2DYeetZ-$SHA@yZ^7HXOPnHqVd~5*RpO*J0ZH6Z(GG=kD zJK>GNQWz1_!uQ(?Cl5$Xj89{+?w*HZ`C~M$IAI#kv7FLzJT)=FB{a~~M$kq>!y-th zWA~7e^uv1CWbgvVugm=UcgISnD$-jAc^{$63bvUblB~^#@qGz;Y%MDH}tUm z*uy*-{*ldPQh3U<5TfxJ3o+OM$+HvFqF>V%{!{IlO3YGTS}^K0v}_Nob4IME(3}PT z0Eh1!s8jYbt95pm3e_)K&*UR3b$yIIrYgV?eMZ|K^W(M{XW40yN}V>fxBmds z0~Eci z-U*~D9ZZaG{KXJyir@B@njI(yi#ZBBPC9Krhw94z05AdfGcL!hpG29LD3?w2GB1Nk zXvfSM3g78`GJ4$uQ@9{?(tDtJmtd#|$hIq9&^uX{2-%{71bu@0?Mlg4DPjQR(!|mo z?|aK6X2am~s5?W>qh=B2mGyE+0BND5NY5S#ZJY!Xub1Eeza^{Is64gZn6w)bW8u?GmV#t2vmbU0t?4zLR37c@Bf{L->er+`EM zl;`e_I*B9LFd$#8fw%`6lvA}A+F0q1GRNLK_I!dR%%W+eSffa%EazDR?3qH^HE9WL zT0li4-q#nny|YhgIv5$!8d|!SjFEXtQNTbp)+45Qs@YF~lBOmjs9nY~{{REh%<`0i zH2+2Tm!dc4kf>0?zga)a|~Y-|AnEn!=G1-U+Yd=tEH zbIt@^Uu1Eg`&w4dcsc1wPUF6mQTw{vt(~KDJh$jW%)t1AirNT-(lXP-B&jb>QzT;S1X41EiKHY2N>orMubs771Z&9*KrBs(DB_ON zk;ydbv%?$Ns_NCL^6Fv+ud<{+ZC5?5r6lIe&7cZ!8sfal`*EQapw~@Mz^i}w!b^&V zbEG6tpjKK6Q+I2DB-%pU#eFJb&$BbtsVo68E)A?SRaJCyvOHAGc@w-W;31H+%xS{f zdBkNxbF{}CfZUbRa7)BloioEa%FjBwtj$v~V^GpZ(G^nb1SE$6LDZ-$K>%1Ih`SA@ zq>N^;=2MDkTv`w#nr4PzL~71mQbm_bF%22AC^8U8Vl!LYv`(=^v6eF{Q_UUJI^FFP zC9iR*&Xv<)86&PQrt{{Z$7`h;rO5Ig?R(}SXtYFf&g3RrnCJUrHvuQmnm zfDz>^9i=wZx`mZV9W8=h0}@HjioSG?ji2A@h-4CuOlpzSKn=+1uN2rG$^Psi~2f(s@KWRH8^Oq%M*W1=K-n9=96H@};CPSJtaMH4)5Urj!Xx zpxps(@CF#ztbm&qWEWN2P#C!Gl zrJa4wrIjkZ<3NqB!K5;}+=#yM0O`2dZ`ICY#Q8d9*>@pC)r8dw(=FOHF5yu*ZghYZ zV-T=aJfOs#Oin6VKF{i_YW?3pj(KF%!OE;^tiTs82?aqnx|Sz0kyo7umY#r=Vj@*VK~RXy#Iu%VGP4~Ku9P5_ES9phcFF7U-fd|X(ODpI-1|>` zuQFOLODpq9blp$eO~bAia(8j&iJxq^VdyyIms+JXipr z51Vb*7gZ-}QP-4$YP`ZpYDz^kk~}K}LQd?Ckw${*x4H&k2-&TBuicb;H6=vVVe=^9 zT1g5dvDlfry4B;mZK+C|ZbK5cx||zLQ!1Q@o~SPIw8q_~_I);2MR}IARW(8g=1HOy zaKZ!K7n3{6@<>AWrj9jDHc$`6q&p?{imRvL`kMNxc|$yu)R4($0!U$nLOe>=3l_KB z$M#pfi7G%R;_qVYtU(ITRV_@(67!^zu5-+i*LMigl|g-isMrrXoK>FK{jEt26((O! zU^L=BQ48_Lu=2!e0J7*S-5VV?>Amo4Jw$QRR=l8W9=)IrY1-(_plE7BlKRCvwYA4E z1jizhK^k7b?g3lh72PIsDJxc3p^c1Xxd`p8b;}yEw^mkU)@`{0Um~PndxJP_YNuq4 zi4oJWRyP31s7>rQv2PB(zBrDdg(Z?W<8TXU?=jE=TT^wtfIDruw!?9U>Nw_Q-IIxI z_Fb1%=XJ7~+E$J*ywy@fvq>uyf}L8-%JMKI=>@bS>9PDj*C&*)L}LS^Cdw|>C76N; zIIlZJ?M}9Os@k{`p{b)|5RnANDr6nRU21efUuO(ReNESKh-(iyhgIn|T@Pqc(bq7g zr>2^xlN>CRvY}R0kj)@jr7@(21Y1a=bmM&5rJ=2G=BwUnx$%5OA?B-6 z#iSC68b+jd03%+r)Q}TP#2H+#6t6v9OGJ^9j#i#CC>`caD)PpvKvi9Om?$O4JM)}& zp-m+5fvs;Ms8pzy!3hIPCG9Q8beFqW?rboXEbU+pd;3j&K&fdgopB6%P~j?%`r zP`NvaH3A3BTLj&q@hv%yj)N_65tl)!aK%K^$fz{RMgIWW>aej2G=Kmb?QRzT07rgJ zl|)5NRFySGAX-^shm{FG?IVSinL{14nH|_%1{c^zhy9r{N@8Yd5@uGoW~7duB(Uzc zdF5csu?zs;dtV%-nzbWtGdlY8jg8sF%oH3G_5t%Mm8U^)DB#fZog{)}b9kcM9)edO z{lkKu&uJi~o1Ye4U81E-Q9O{%QOzRG%?J_eDpyXoNX%9W19h~Y6V_y}4r7>8M$**l zk~jrJ>y0Hhy+lxu7hB18Rw_a;x&^)v%{{OPiBV*gKtKpolUG4-SS_}-t*X|>9m2*1 z6;2OaagXmALaK5|;s|!VoV7f#t3+vH*K-@k%ND+-(-niOY9O_deQ$z1&CXww(pFRQ zgt>)O^>P_u4$@P^c~q#Z!%{}9jX6{*xZ1{amS}HK-sfg;BIc5?|vYyX> zmljDXB!6|Irh3}mS-Z-JtWus0&Y31;C>W?ARmk5-8GkU%RoYS@6yVBj4yhlOqS{cj zq`74l49srFdkffWuVpP1xdve}$#<-g5skhSh7#s6xws881Jiw5V=Ppdq%yH!Br+4f zQY@qO80obuzOirRGW1oHZJ%=^^K~l_kabp87u;MQE`)i5vBvAn@_K`kLn{&$g+u6 zmMY0+9LGm%5ESy?Qmbmd#g}og*xSzxTZzOvBvbc*JMR#6)g%%r;( zQlV5Ssk9&isXPJx`$|;4uYuM~`&IU$X!5#To81&u%ciQbc^Ww${{RxA1ZHT!x**kH zRU5iVBxv7f9xbCJ+6kO0Dk-WSxScA(K)>8(%^|(xrNVYYPl> zn(aBSOfoWallMRMH+17RXQ#B%^xOrM9K>dPlkb8aLb)WOsRc`_bP{MLJ$-Z%JaGZr zc11)WkjYfE%Q$G!nZO0gk}L@tje#T&33xb8;g$irCnU|)@Ea?n#6|OhFqPJ))a;yT&>rq zRNrzmn~QJdj?4Icmr|`@9-Q(1{LD`irI3ZsIDi}}$CWWp9;PR9tMcpbAXa)4LANIl@k6sUJuT2(B|aDpRaX)zU5ltC@Q2#uhWXuw6(yV;O; zP5lDkliE{VK3|r=Pr*k*fb<5@2}!s0iN|M6OI?P=_MENziur9b=Nr|BaC)_gVolhR zZ+32^-sF?HB>Cd+_H)f8MpdT^&Sj?{F|w5|7F(V7V8BFKcnIq933zfAGb4vKu=E#w~$o?lZUhRJg+G+$cn7j8VOqi>8O5Kw);5t zThSy{a!jm|5g|gQgInPR>SY2bf|lUt=7Pxq0XkknRE-bkdH8MT&I z0LLmDX}D9mdMVrsUwh(}?UIh8-fG%OwV=^Z-T8ZG$t70e@u z$QZeZ>@E$)_9_Vbru*Y6XVoI6rm9_ANi@=~-FcETeLCX=?(OG=eufF5WFI|WP$8J2IhJpxCSK%wN8N3V-qvgi^z#Y<2W9$H4aMxa2`)ZCJH#%`2NxL>A-lIOE8g0}M$L9cJ~~@)b|T|$q6?2WW$C3ha?vsS zHYdZVQ|breKDM$uFYMMDf{m@UD7#qcxjsHS^&L86cSomfTg*Lvr8H@telR7`**|Sm z(5!1cL@B4m-$4TAz^mDT^Ba#-iN9#h(-SkIcxe_|h+=4+=R{!)j;s!d?zfmmf!;?J zL^>>3h6_&TY_yV;mY>t9V*0j>xm&wmkzJ)ZkTOeYe`tI5)05CAO_Ui)qF z-{UqH01H@Q+PpVTH9lLnKiX#MJWo(`o^?s=e(*Dev*o9gO1_O~FAT!*%Nvb@BW-3L zApRJW;GD(i=Mq>3?-;aYcE{(}XM89@NWM7Qr8EJxmPcObH`{V|1Y51fFD~9Y zAc~JD%n6jV($zzuVq}ytj&Q`x%^`IO6BP?(QDrtIt&f*ir%Lr;R>uVY0J)vsp3EqA z9FAZY6=!tR*==1Rnl_hAktr+zc9lt13Qn&2I=78(i;T6+kR@0Aow=UP=6&mC2Yr(x$YnB?7P-ky%eN zTYz_lpHl+D+}A))f%-L;5{jO~6A40_UhHEeo_=DSIohlywUP-}kwg|K7%;Phv6gi= z-W*!(3y0gp?8^vCAiXAsAn<~fFL>hzCO zI26?M@+#?mLZ~|Q>3b?G%iIaOog`@n<;ij-lPRjp^9SP{_n}U~FZ$AJ~O;Bh%;V z2;R*~*52S10;F4g?ksQPhjZ|je@!(_6)txzeAJ;CsTp*c;*v1xY5nJ#k0Atu3D8?Z z>2@G11ZkM`5Up?%p2R(v^8C&^rpmKsgENOy)6>l=Jv_h*-&Ta3L!RiBOO$ICMgq-C zWS6Tm#_$eknTtTBSM3%~^lC{eJKC1_(l_4NBKAee39pK1$qN(nMTuR7i5ptN+gje1 z18hWaHyVGevd|`AU zf5b82IC*I>lAR$uwms&FwH8;qX^4;j8(p{b@x(`HybV=NQqWLKrayLuYDBn{yj2LS z`k8}}NnMrZ9Jp!e;mfOGX=o;zDJm6eQay9gmx@5@%oXN{I8PCn%nQ*>H!5=^FG8rgAaPJ;!ijx_xhy z`)mW5pZh88W`?mUDQeJ_SW1cM>0}Owbn_Z|m_t}5lxG`hPIqlCiUDIXs0K7DpqVVyPh$LMG=f>8MUEjewL(K?H0wJvhG^}t zluL4wU>Q`4NKkdZJATQ%+AP0{43bVMC4!!ggO-uSBqTDqb^*$~hg-1`kYh2fkXKe2 zqe8ky7S~~Hj#scSji`N5DC>X^2i!_CvR*!qDyF5(DMU-DjCquv_|sL*szwQ_k;+Dh z0p_Dd9m!x>to9db@wEXvNo4_`R4KdUWO1M-YxP zERi}hylTwB3o5p*U__9xBT5v~bdoMrud7BKwqbwV%~QqPAzw+Ey;XK|MNJPjndzsF zNg*;KCaDB@Y;DPDSsnf1!w8sxCHL!8sn#gxYa8bq4SQxvL08J=?^$;>Nh0c{#y%AkSX z3&^ZFlaq}0k?V3~nbu#_UbIEPtgU_%sExVO~GaCs4eZO8<0 zVI@pCoh4OPVVHNSl8NLLRB_8Z56g;00bB-+l1Gt*ut=!-!?Bbtg8*>H9aCo6d=Nnu z6j_vQA*zT$98U35hP0GQff>w_JYk^L@(`?gs;f!%z3n+a52jGG%+gfG^GR0}>`17M zlq{($ZsEC>WpG0)Ev!Pakxbh!{#nhV&SChuSI{yIbIBsETpglkL6n-zINu{i;rxbC_4GJt#%7JEdX{LErLLMe5 zrDb3bD1me&F(kY?^^{p;$yY3^msACbGhDrd?@t4j<w zJ{y0C(pgvU?In1Fwq=ZE*=2RawG6FSB!6NlAZVl#OB~J2(uIP?Z*7^4?i6Cg;Eu_u zqRXmdcvCb<=6SN@szh3bh|{Y?94ey08@jtA#sai_wsEP55MJHB&UICEG_%pi�zt z5{TGFUYbSkXjX8SS(Y~;NF@uAb70ilan5CyBoAHP49iUd^A!8Kr~*jXsnI3T;!9sw z-3H?sej%+FFm&pBcaC^&gws*2iNNZ6OMkN8X>^`>Au*vy)JF7DRQ~|4!BG)&QSS52 zpjAWxMG(s7Smjq23uQyr?P`_t6re?rb07{3s?kdv=pm}PcSDGOBa1Bs(|CdEdK3vjP*vB-wHWtw@? zoee`IK%QD1O)ARvg(T#wE`xS^G3Xl1T|=TN$59v4YSrC>x6);)+tl^c*__;yBoW#X z8nVd}%l1lLqa-vl4MdBCHef+(j5f$Sdz4x_>RNi3&e~^%5t_q&G7V8Nw)W-fw}8cg zo_4W8Jv@W)CVuPg_XUnMCgic;u##d zA{v~|j(HpzAC(%UOC(21>nM4fT@(UE>}|GI;y%qY8f%FmG6B@0^M4>YfO?f5OlER?FAUU zCku#0qPwz7V9XrcQ6v%5gn~wQS)G1^k7KTs@oDQH^lhun8Dns1|4B}YdmFE z(M8C#ObLtyMjC;->)nxwH`MeUi^C)xzQmo*1-RGQ zVj7m#(h@+@fPxhebWl6u-Xz!-HzeHSpwsKxuotkIZ{cpZm<=F+Gu80w^zB$e|y%V|e1-M~Eh3T>k*r z?pW?&2L25Z0lx^`x8kD!@OF8aMKZ@E)1b2jSMIA>SdC2~)zl4u-q_x&#t}In{zhcK zhS{7E`%8a;J-ch71|_7SpO+H^=0cG&s#q&?Ba$nXUF<>KMTFO__@+!zzWo;xf-}*p;2^$lK6q$68FcMP4tUzE? zv@XGh%sFzV&D0RKIOMDWn6MpYf}9K)u=uOnJ)@SMK5bN{cGIYPt8)9wF6z<5#e2l; zNw7O!*R^5BGb+H!*7<;q+3vAypqN4&x8JWqI{EUj(L@l52I%+$^#f<}r#_mtS%$oLWH zZapwT#lq5rAFzObYtZ!Th3Ys2NbSm$2*XOZVy;xA!X?yDg|P=)6J|gNC`lLX^rb7I z2gJs;S)9vR~TFB&TnPiOfG)JI|00NTDvFc5SkRCVKXE>k&IFDOuU&hV) z-w(JWi-ZBuwpJj6Vr*@14?7RT5XfsniQD^6BP%{zyt3%KGZfOhL00NqX);I4)K~h< zgsCH9S4lp2r~66a_okQzkjfphJo3OaKzW2YT4%f6uuknHDzwp2(ALnAF z)Q^TRRZimMk#oO>zz>!dsh@N`%U;ep$w)gk=2FEp60xX}8bJXda|CA2u@PgeY(lX* zx?FV;$(BgDajja4g^*5SG3#YfVn*X;3<%s4vD(;enehM=v@091o|)!jV8EuQEQB?z z*BwA7VnG%s65LDLEOXGjB{Wn?GRXQt<+%%HkRFIyz_OpcbG^wR^ECkX#(!zxl^@bs zdA&5WugZ=b&a7xh<_fk*$zX1`SdEI2zWZEY4y?;nM^!q_Ryu7QDVN2Siz zv4ZVOja%L&N_ieApo~(WiP<$QHwO9$xYvIj><^9{(e|%A63;MX)l<8NJ7sAQm7+iZ!>GydE#q2;rzMkB&w4ziRt8#rfPHr>R(%GXtdvJlVV5&F2>f@JcFgpG&+jE=7T&=g%^)V&AogXg|1zRbOm=^jlrl~Zci#~ffo9Geosq_nIo1=h_O zBzW!u@2IA*JzRl~Ii3WuJbtp9&HGDfq_3350Ii8(3R>KxKvgYZLof$%(^c$khjUjVxB@`Ju68QN9{mP^RE8 z54=vxUv}SVkoyMV4H7j`m|06e6=QcH^a*tnu(g7y9d$aBw^*#Rf@>;js$8V55L5?=Bp*g=yobhu#T!*O3g8sfsBVl^dC4(8MW6WR=*F zrpVYC<1X2RviqF`PgNp?a9gCG#B zO&duRG)g0l`70YL%4U&^ywW)D-8Lj@!5(^Y+A79gBdDscc#~2=8nPou>U2diBaT#L z0V49m2;sqHAZa1X+74V2N|@+kmb$FU=_O11$WZRdpa(*z(8Poz?JSIMa5u(M+EKi~ zcT=KyhqWc6uJmC?~d zQbBHKBohk842EeQq24H#5H$uVbs%ZG6$H*sKB>y4p`mp|qly95XD2%cN^o4i?0Vu97yyUv8bZ z%U>ju30vMCmXy!Sx@nbVo_eU`ZLEmXMmv_)Bl2CNM&iN~7{_08Eqzwho@4Yp4`@Bw zw`a9b`=t?HY_zcp8hGWAG|0@%?5u&5saA5<+?g9nf-PnHHgH7*l~lD^qz=?@MLN7v zi_=tA#ThWHx}1Uv^JOuh3-)PnHI*swXJ#!?Pft}-TRw>6SE&)HSBhD61XpXcg*i;C zBl69hFa&ReIH!dmpOryJE3h*>kuu7~d5?B^BzXnJfGr_oWdV;~v#Qrrt+78piO^`j zhP7Ae8&u>4!6PTEW7~gfRC&EY2^2K!TqFiK)-V(rHNVYo%T>iHT2r=BVJNK9p=4&u*ON_P6wr+M?kGxI)kpFNg4>EZTF{w zKJ$PGyVOXe*jg0anZCe%o~O>@l4%;Xdd+Dq zOi@Eex|X{520 zOo2(Wp6HNj){Lchymuzs5sF{38r7az>7f-dR8>PFAdQ6WP}bBUb>%IhP#NU!E}*t9 z1;H-jVA*=dK*}CAQ&h*6720@(wSJ!3{#Y67~I{Kjv7*}&1sR=rD29bm@ zE!o`MM;f~uggDrff1^ekN>=y$&`nasT$F?C&;{Ng(#T!cRmpF%E#2;|x5-}1{9jR) z);#LmnTF)1r5G$eABV9EexWF)B_>*-;9BgTESW>s32x~8IOL%PUbV1hOd zK~f?q7&inG65D<%>Jru)RO99a8Bx5C?BOjaGDaC1|bimF;f1%OfZa)7NQb{l}YfL&efh&?fIlr0`#1mv~kib;!EzRnP5 zmi~WYj1QmJ6*m^~-!f+{(n)5X-YR8lf${@uc?=Unb6H=ns3d3K9pLpfDvXIC*w+@N zI#&X+d&IQiVsu{QaW1x)xePSih_secHX`7#xh_QpVO2{N3{pHaI@g}%nPBG4d5XQQ z&5$Y7W4SibsGurv8!u?ltr@0_0AyljvRKG3a0}cWHWmxv*A|Z(aq2;n(7?75N~>4P zAlZ!4>XepJ2pp*6h+KxyNCb5n1w&&!1f?uRZH~D8pniA3bd>EaJQVd6>_YvpjmeGd zZh%E~>t@_u#>V)Q;9eKbc`mfQ((Uf?(#B&oZp_+9MM&MiP{&!3;~GP;?x7+jcq=i? z)=Iiq5|)BV+BJ!4Rw`(mC}xg0ZwP;OX8;A*w;Gua0dNyF8zSgMs0LleTGyQ>+K zM=|4Mkm_v#qZ)Q)key0bWzIJpyIb5cQD00G90UktiBf5rmeq%8JD8BaB4tBv&l29gDD$55p4Mr|Qb6!f8 zSC%Dfccs;M$tP%;7rICoa?O3MPm=xSU0NDa?=?ix{h{`<)lX4Yp-f^L0C z7F+xx!_N8Zi~B~VhN<47N032IM1e}mt1G$~#1WQ36pX~6X4Cd+OSg_H>c43^*`27N z%b3Xelil>oB> zVU3;?wzgyNmOa%Uw8yDc2T0#-ug+t{oYkpw8bl`05m7=Y3LB#B;8y0{@1`~9vp-}o zKMx9pnW<`TQ7L`eDQx9cUOS5wK%g{aFg-(B*tO)SB?mFz3e(l7y%SJKPWbC8U-`b4 zoJTa!sg?<1l^K-A#Kh|A55ie)x^)4#y~Zn!)cB@Khn3h9ER0JV++B}&-(UdWb8HuJ zCT%rkL~$94>W<*PrragUs;^Sk=qx-*#Wlx7A!vj12$8P#D{#Hvgpx(g`tP{v^_Pew93}GLXZm&sm~-EX=}WIyG<2sp;m;ZoW4FVxx`-#0?o;MVXEN0A$~~ zb$Ai!*T)n2`_l}(#*z@RM65$G21>UISrRecb?<6<8qxR#>QnZJ)$Q_5SNT%~!5Z47(q8r`HZBdWFAZt=Z??BA2UK3|&Duq&-1jXdmvM`Q9OldtUh z;6vG(gvp&!U+z4zpX|i;{{V=LW`V@eB#<)=J)ye^f`TMkdWwRvjiR1TWNmYHDxfOH zS&prNTi>BK6n=44Q#*+#l1ZDuyAxsLqoRY<*bANd<4t>FW`N5QT#ZfBs5alP;f(uB zmKHk`VfbQB-tv6Bw-Q%{D`bpn(rs?Iv%Q?NnO8C92;?y|6%n+7AC?JdD=98l!E@7@cxE~3xV3|+xMl@Tkz>8DzWZ2iFo$RyGf|XL!&X^h zf@U1bQ5olIkPcr!4>^F{b_g~%+@(pxy`c(qDiUUplvu<>u7_qelTp-{3 zICI+%Y?VIjwG}H-Ifw*Vsw9bsXF5Y9NKp}u$SjcF+Y@cE##y3U88OH`z2=(gisYU# zDNfOQMxL=kJ(4wTK?Uy3y^M#UD}9uALEm#?1?a2wX;aW`h>9A$%4_do+-z3<=# zg7T*mBGNaBUiMv3V>1D5;R|&jgLemFK3+D&?qQj_9Y{!JHv|iT{bA+n)L=ieC<-*1 zwj~tX#=x8ylJK2}Ue5t1xyXX+SPc z*v*_(nhKh^r!n&R^1P)r7qdCk-Qoc^Vp!}3_5#3QqqB}7G_{b*he#wN5wNonruOo1 zzf0lI#aXu*ndePj?Bafodq;2;B#}W^BBD(IsEQf3PFa$gV;E-GXx6q0*8!ipH4%@@ zyqARMSYxX(6{juA<~5aA>bG<;49XbkE})=bS5?6S^xKUi8IDg;8laK69`PC*9aBMR zk$2m6O+J^$=Z^yMh-yjbrrcbzvwgv1u=Ns+etM1*4aVUa1Nuyj?N5gumPpXa465)X z$n^4aVk+e9B(mL!5;A+p4&_w}Dc6;?^$VlOY>vn}dUU zKc=l(jIMB{tj|j|fn=3IDC$k_e)gV@p_J@#i8$RVp_*E1gJ~g=qjd@qbs-|+%9m5| zD-pVod~vZdd4x65OAFp6<3bEv$9!9!(`J>bmU$8*E2Wx9 z2~jaXwlby7okwsuVjXNg>e_?;R928_MT`sD+aEsh@jGpNYH6$^)Huw|)mOXHdB;hq z@)`zzAsKS?HXf3oUFLR3=zjLS!66E zglQ>c!+N7%F2iVj`8cfk=s#4CsykD=h_>I<*2HRu+a@DYI=ColB%J;(apfS%IkJE z14^K_#Gll@*f@P9qjYCjIZGUz$6%_gje9hfI#%7?LvS0WKQ8-Vr$8Fye>}u_>C}3D zxaj;7Qr6eCx`IdL+7D2mg5MIl$!KXk_MPgv?E|ujmKF;kbKPAps1*Y0#@pMV@H&sP zOp1;%Qwf=Bg+6Gn9E1rPl7=-gv&=|vuFYhS+DM;G?k>S`Jk_kP%u~2<>wbW#8h;B7 zv7mjP(y?jk$d2t=hDeJtsudx%O4d5GmXNSrJNW^=J0ROsjP;z>13qyJIHR(v+6I=Q znjU>GI;vEgD63?2ig`JRlSH9ryk|;TV|56Hb_A9j?3>!#HG!TP=9-`u?xgx;Xu%%~ ziABgZ7S?V&I@k$Q@hw#pH7gcx1dj}0823kHw&EGP!K6X}w@_?Djjy6=dnz?KQ4&j+ zPf*YU9aTh9$5RB3pzBJMc}oy<+QAk}Zie`^Hf_db-E;KDU8eTr(M6{LhPML;VK9LPm2+d72uXa#pj4r6( zb&5fumBB|+SQCl3pNnRq%Bu1@$eJg4BCV#A;}0T8ts)YIkwF^BAcC&U8B~xB@9eq8 z!!gMw%38|Yy)kXDo;DLfFz7GMRCD2|98I@jvN}l#k%KD!$N1KpEX`|as+@poC5|~r z*R-x#8SQP^T?-H_7@mM%6|ZQX&lPmY$K2V~ZK_xgJr}O!P?u3)Ni7&r=Ykx=gR zO4dwM2-{heWQiz0pYo#>^c8 zsoKgcJh$8?lFS%Nt*U^jk3E~(I(TF(@>;5Ib#+oS0m|mW%6uKl)C-=fyL7$)J5|dT zgEf%Hv~8kfw}!sIgn^IB*zIz<+Bk$#!z?k>N6(8@fp&pR(UE2)TSlN2g1J{B)?Q^^d;Ii_=M>@ku=Kxzd$N@e>+VQ~&!Q;aVf!8SMBeOlG62BjG@I`&i|);J&a z2)h}iH9Xwd#Op&zP+Ge$Ws{WzE_;&GJcWf!RNox&zuMCU5@}?x#i8vN?XB(xh~!mN zv+9B4nV1RQBNHzr?yjIStd6#mU%+-AJoaV4ne*06W2bmgrB_omK=)ON;}J^;iJnJd zudq9F&;BEZnCn6qXI4iWgQtcT%xZ!>;&J?+i8AEpd;J z`-QK>*2>LjbMxLZ<1R1$RxMdp>MJ9XAy7ck9YhU&@`bpLWFYGRDmu2ih7GFp?01ZP z+6wV83UeM%sD)KjML|v%l98PtAaKh{fllxOM)x=!?9;Yo%5a>Iu|U5!rRv zZp4nBfPQg_N~|Tw$2iVrhU0z{$toz;ttO6!U=m3uM&+v*me#1TaEd@5Yygm3Vn*1= zy`ARSZFOj#SdBL+*vC;E+8pS6w6XvbnlzHvWp=RANV^abmgMZTnT#2pglN&Aq>5QJ zG*y7uNW7;YTj35%qXr;s2_!zw+ycT0=PI>nNIA1p#Ierl9+J$)EqdmR5DTg+3tv}? z;gRH_EzskSyn2zSxk9%n4>{~5t=NoiE40S~m}#b#DG3b|O&BKDM=N;QPc^k|-z#IN zfC0cAr?0+O^I};kp-QEVN`_e2$WjBj?lzv{o0|_a)&qgNVO-ZSuJ@YCswnFem=cyT zHAJ&9ju>G@D#PIcp2a#Jwv9n-Ta;eHyjdjvY~HrO~R@r_VoEwr8D!_Tj{;R*@Pi`gQx#BTu1Mab`l2 z`0aIKEw@ZM6Ih+MnJ7M-px|$OAipW^~bEpCX4a%j!kM zu}ZRX)#KK>m>U$)v#SHKjfL;hk?R@i!`axSka=S0aukjIRw#1QsILmkejx` zBE;%zIL9>hny&?v5suxyV;aC8PIep|{<0^r0zj;q?FAY$1#u^X$&&OJCg|1 zhAHQX!z!)BP2D2+1npBYYAU?J^5IV;6_v1NP<^Om)1{47JI5hXyw;Ma2!J+@RS4;& zZ0df<@=B+IYB}Ykrwe&$smmddlirF(ke7|4V9`iaE7*P30fn=|ou6>cS1klHK+v5s zM;yqZGJ+2n!5uUI0Oa}l_;#@zlpum+ zKV#jnLs^vn03QJ6B;^z`H##@alg6$93M7tL%My)Z$oU#gU!AGP z^qk^!I+_i1=NLWWSx;&?o@()y6e?q=rsC`4*7OvO;nMvNf4HXXxMS6?Y(NkYALlI`xIIg#dD1X-TcBibQiZw~ADC;RebdpUe8=7{C zr&}{yU%H!XAzektq1}!nDS1wYURkX+V-?HMyD0nX8?uq+8WU6Dz1dKDVj8QoZdpW@ zo~2BUqy<4GwkJ_Q!a%!P<}dIB;D2peJhqTFUX|rYc;bUFtP|2hBB_wNJ98?VO_DT4 zVHqp|WV30|*%xb>o@-A6}c~bzgK@5NVNPXP;_nl+k*7!$>xDzKzcd3=F3`=s!FFRpis(|w~5=d20 zcO(IeZl~VT;;)BfBmL%IRTRocn2a!RK4a;O-R(g=0a|dh)s$D53W;l}%qApeRVE@4 zdF~@=WK|A9c+eYaxG=qkP-1rManL|+GRrAq)izS{K`N#B%(0z9MM)Jqs=zA?Yt#;t ze-${bazAOD*awa3qIjGzam+<683a0A3T{^5cY2&$ouk)qw<>v3T-qk&YK=`S{F$_+ z;)qS7mlm<53(EQ<>ejIs&-q7Sa#WgEg=BWBbhJSUjf)a=ERGQaDk*0Se-4;%Ut0mV z9Q@3qOJ|9osk;EnYT#;uB-HNeu9H8*7+B527eYje;`(o31@^#Qce7i^{{Td)Dh>OU z5r;##VY-U~2n-vP#{1&f>|d~q)>x5Zn8itHq>4j6TP~(~+4LHAaVjg8ch=Hebka7( zfj6`6c%KU_z;yd6OZtB|Qg8TS+Vv$y1Ad}ass!|z3p4D`G=dVGgq1{k5=vrS&;S&W z4W%s6hD(Ih1d>~J#64dX!Kkf7Wa(4^Cxb-V5|}H1&1MqGIN8g0LW6a^v9}`ZV>-|a zQ=L~}!g&zV$GQz9!Zg?%J)S-{k-pY)a)E0h2D#RlnYb047XCfZzv%M`k+>oPGXl9%O#=*2$dHCT9ikg_$TjjZB z0@~W^>p7$kP|pzm0EZMh-}f-1N8GWM-dFDME!KuAQSjbYrG<~8tVU@V`Y0!SPVlj) ztb?2>C0_J^A&#K9MRrtX9F+^H0Da1U4^h35tnHQ#^kY7NN>W0xWI1W6kw{Z{7}G&J z6pv!}kq1CsZZA(}{@OWIjTJREU6|)HOC)ecYpUKDY9)|_UhBy@@3U;BBT!FJ2A~$Z z%v>2^Ktsg0vo6Ss5zVWDkgz3Di!9P8({_poQb}c7uw6@VO~vsERoVP&5#`d?)gU0t zQ&NkT(vhqq6YpHw)<24E2>0MG^#A8Tm@m$nMNlND9x2Oe?ye7YnGWi;$znz+4WS z+Su9g_L;;PR}a!bLz2`%PaQH%QCXlCX=gmiCTLNNpf;dyA}I-CLa4`!mgy~80C}1J z0JUy8uc=B`o)-7XC8>>|N@j_|#PO_P)1n6s3BB2M7B}%2vpXZ~`#q?hmMTihN@bx) zW~+?Uv}qd`V(VHVMrq}dbt55X2nhh8+(+cSp=XP#r6s2lRY3upn&^^AHjQYpgCglf zM_qSiMk``(u)8Ze9;KHjrkZ*O>7-}mPMp@Pq_DO4dxuz=Wvc^<|V#8Xn(`#uMs(72Ux@0Dj z3MY&q07&lW?`3e3a%`xLrS&U-E&})*Pw|&vl^HcuPhC?MnN;%RK(ZMN*cI;=NaR!| zM0qu!AzII3f*ZCB{lY+Hph#Xw!HTL&$t_F>G{+{hVWp6%u#O-AP_e4wuT^58I=B1G zacs2ON#GBOad3whRM$^OMUcY`e2O=Prj-?AfgVU^mU_9uNI;TE1=;m9jLfK~av?L0 z(JHds;bE(&q^?OS#ZX1lEnJFvtKp7##)Lw;k|>1wZm?P{kbbq8E{=jFN&$Rgy~A z4JNCGB29NwcJAMCQKw~7UU=v4&wRmH=xkd`_aCvCleFF`H5D>T6nYep2ta<&jf{?W z*Cd3NW+v=T_=e)Fv{S7&DseQ;t>2g4jyV~Wq-e!Kk&2%9Wwxt@)Vq>wvWgnH-kOql z=^3Rf9CcDLNeCnYl?fe`wUjJwq?RVqHO4gbKFT%km%&V0nh9b}I^Y6Cl(XyRGnI|f zMi$mWvl0Qnh6HsBqQGx_eqQrqQAM62H&w_S`~&Uxm9J#=mGYXyK}^#xyS#OB9U%h% zNDR_C#$4UPL<=zhHj!;u6YOfC+DklPh3j0&(}v0^k3M~N7>IGZBO@{E;f zQY490r;@6q%?xWStnAi=J1nzWJu0?90-?DE_@Zcg9?oRtOB@BBa<2`lDY>n3rC2GO zP~Cwy7f!4c3#hG{wz(3?oO11u0lxb}}2X5a6I_)!tYbz>^B^)wU%1PRt8dh;| zHL+1)65qWeg+=PjF?Zy-r7l%L23u08G9+et+IsYkUQTByk4S|@;}o$H;#x1~)+PIAQT%ub|INnijV;*j={?LwNWaZo8w zE=2xt7YOrzv{@_!Zpv84V_>>K0jv%f(`l^o0$>OU$iXRx-%|a zuBD$>^Dhs(#|%SJzbGQP)CY93gt5JgVx)~}H3fH_5mwB}8c5A2-m6J=s;{GF3+mLdx!5?6D12QyUu#Tn`H8vy6gCBza<|=a{TY83bWV z6JiMl;k3Q6xv9CM^(sZ$ha&8Jyj z^A|0q!%pWAS#D`9O=4EpE{bRa83$9OqbNWxa`MPRi`bpW9nx^_ZZ0g`xoGNRB-+u{ z#Qy;I&=2^n>xo|5I1yvYsVd`Ug<4XLPWoBocGdQ>NRG-~LRmlsLLG=Ct{+=%*|R)B zwN>YM9La7Q;Qkj(zB#K6QLU7_3R-EDa?_Z?GVLKJy&8wVcV`|ToFT)!U6Vm2gaUX7 z)Td6Gh!`D|uxm)CVp&b~bO)fNcw2{>wyqeWidn_tMo6r(G*PHB>1OV$a@ELY?u%UF z%HqBvq?TbOSCn2AZZ)s!gVq$YRpSq;pw7Qb4giO*HyXF}FM54|w?T1*)xy zP$c)7huE7lrOb0Srg{=7spERiWXWLiLozisq#y?(Svj|5xhO6yZHXQ=_EXEG%p@#= zN}1{Tt zv@ca_{L#rdna|owvYI#+^p5=ap_I5Ubtq7)1_YfYhRbUbFMHn^zp_~%mO1I=P<`W= zU5FP^8WSFpdT1k1JwZ6UJ5MJVT_Cb+8{iDPhIuljPoeQVL-MhWp=_Fpm1KHv;&kR#9 zHlCU`2@t3x$8m{b>bzEc7-oEM-(^a6^=M5 zVzGHxgiw*K%e;okwb{+Qab;C|Ip$9^GG=j%uAZQ|=2ewh5*SrXjw$tX4Yed{q$z16 zL2V(3g5gdrijF8MqCjdQnmN^uz!;o3TY=+k2HphWue4{iMQ(6aX8|KeW{d&4>_vlq z$OhKvcJ#umGQ`HnDylQuSy}IC`EE%i6J(%FBA!WVo}dFYOq{1k7}>~Jsr8v7k7X0+ zkb>$P3if}*_54qoLb6jlw9zEa?g&qJW>O-k=beO!Fii?IF#(2_0O{wkuEs@WZ30D< zm&@8Usi~@Tnr&L)a~yovvV~a;V8t4e#Dc?3^;qbGrDd4!)yWJ^7&8SAEN}VQ4vMV%}ORAy0#^j4y=J?jUFPz6slC2Tu zDTqo^S5OjTe)6FN*o*%FS7CM-&v`8@My$t6B+|f&$rDIJa?y&juCNfe3=Os&EIjde zX1NVC?;LeCjIfybYVs0`OiJmEh>SPc2LqX;0ic4+LXt3bx|0^SwBi*qbneOzk8nfkc8|e5G=F*}JD&d(RTgsf! zcafiI7X91m-M2ex++N`0S4`B^{IcGu#rTbSy>M+{tcu4FCo-xozn|rX!nO2;CsK}q zx3|dk`ERxkM+qarcmZ;xlK1b0KXKEc0Q7bGfq@#zD_;FaTxv1TS;r~INpA2D78JdX0T3#4j?B<#lD=w2^V$%ySU%HW> zD+?GA^K~+MyRERNfHLA)f+nK zs)R+WK_HZ6YaX4@=!LvIvA%1&1P0spPhE}k=Vg>H zQ1s+#Jc^oPRTMU*6CovuWzecRn=$mo`|SmubEgl~sbD@$jx)xsBHF0NRe>k&F^R39 z=c)tCW=MR@wqgk3d(8@@;0%%uOl6MMBcOY8iowvZojWlR=BoaqK zo&+Jh-ri8hGNaD&!Aim~qexZT^&{twa_r(3+0*dBr)<`aplrX*FJ7Hnf6EnQWV3fb z80b7ZQf#0zMenRD;!I~$@LNbaS;&nR#_VLQ8YYne z5wWJFk=UoF!}#Mp85SzaLo+i3mN}%b1nE``6b**@Pme?R>Ym;`rgEIaDx{}K-Q=gJ zl4(|0O2i~+4&b^4$l(y|PvF_Mgrav?2A+TrDue+ss+go(o zsUyI6n`8BJg{?~j5b4?)cwqwD4qQr>x6=!e#Bn*|esX4w&8fIg;fY>6Qnw zmumHu3b8ZU2FI4VZaN)A-0nKqf$55mihDPbmol12(OZ*MGZd2A8aI)cDFj;OAG>jD z={OCjc9A)#s3N171CS&UMH{z= zc&utotzd6r0Ja@v8#o+H>dD@6WY288Ge=gc>mgYdJt$+0*?N$Ss4PKmkr!(b(B^6K zM;DFPO9Qd~Khga^EE{IrWg~o2yB}63^1x+oV$4qF_SpGiE2ss=Wp1}EoJ$jcGscz( z>E)TC_jwsm>a#RV3mE*!3{H?f>9F#}_r-M-UgC*Tk2EY5#-3`OQIaksT_*dLJ@9uU zuEQE+b?+PVK_I9$Zln{i{CZmh* z=-F5d56oh>$RpxGaR+M@u_20znke;LG0-;zc)7c=^S!VY*`{(m`UQ|Ei(3{7rIALL zH!2O;6^Odub=v@I6Op#|@WlTBW%Yzq-^W9G_>2DlpDZ55!ogRP*_LN*a>Z3VP(4VR zq9pHB@|GCcTj7EC7wcx3A7&6nZr^C$wm(tf^6QG*w2aLA(Q&cTx3_^8 z+W0f<-;I>Atf85IqHXx>O}zz=t}!*j@PO9X6YBo}!S{GqoKsm=U$N`^L+rqTLP? z&}uD1wc9gS__Ci4)gS&ndmI9CJLBIROoPH%M!$#y%#L-6_W@laW(~IY1X+6bybd>_ z`#R-N@SP=HL=Zz&FSxT+IuR%{O%uA8xM6tN(%k^?+Ze|&;5o)!PbrDiB(9EFX&_4W zMzOK6VgRu5#@6=g;yzCeGqUE*R7Eyk=R?@E zLPTWSsA%LWFMhfRKDgWb0og8dnna0JQxzREpyn8o@<@DDL6Pn}2KFuYTx@w0;a*jk z4nBSV07?l_YYh8YE@1myC<|)aY*#3flPT z)6COpL8yHvBzGe`{&P5Ow#+wi`^@i_WJx55H8aLfd_qu66ppHrSYGzOQETth8XL3z z(C8@)bh1=A5yp8cPvan@`c z`>;HNGlyDeq?j(DH5o-$^Vbm76WsM6EB^pX!x@)}_%69MQqfe+TTT~HiBy>fFT6g@ zOOmUx1sDtMpmZVhyfZyFd1mGJf@`OpNGw4kRBFomfZMWZ+j1^0TiIU~`<%=q3okfz zJ=3wjQSg#`+JObS8{w)KA5r2dd!OkTGS;c%nry=^%qVIhWvq)%V;j6H9Fdx2iE3i_ zwW($Ii5*!3I=Lrx+846?)aBDfJbOayk+JD#BmuXMqhVoke6Y)oxS1!e_rf(u)Xs$7 z`mG$XzN2gEFvt?-_prZQ3HF1-d6glhyHl3;c;yQO@zhymP(YZjq**}Ns3b4lcI$!J zS$5#?BrTi|ctP8?X;k&K28LCVjz$tDn-dF4HA^3b^vYcHAZoBXSVwj{kj+t9PXz4K zC?mS$l~hZ}R4MMNJA6P6@ndpH#8+qivDH#XBtn`7G8>5`j7rLS4GPv49$NI@s5duv zz#XtW8I*D{I$XCnFiW#CzLH9!f!-p)Km%dE9U)aRr<_66maqmKLr&UrqQ>O!4Rmtv zzjpktpR=X69X7>d*}rEiQ8QD>9m6|_;*2v$!XiLxCEVWD0e3gK@VQrOp;}2Bnh;4& z3JYHDvbg~HbQe8$7`6SGyFva-i37zDoEsSO(?RFF!CsSftvV_B}Q?g|0+5iLHB$~{4e`^>TIKf@20 zRK9Oig=uI(ij$a3j@1qZw^nNd%R!`-0YgdB>clbj+xDNP&1k*O2QKkf5Wztm*fplP z0obdb=E{;AV_{|j*5lmO=qRPjVy78xG;kVvIfLuviPVu%C{PPZ;f(I+@)a#3IZ~wK z32^)Z8h4C^XA?MPRtyI$lsZ^!$Zg$Wvjcw|Wa)NXa)*H))R(Mbx|r+Po3xMQ+|CKV z*-3hN$A>Cz>0`JbX4+hz1r2TRf0^;T`6h8%XjT~pVz0<{?Yt)UeJu{W{ANvrf_?ZXV34r&kp#OC(U#bLKJ$xYu@~u$ zzcuY7V{s$*nEpys0UQ8-X{r61y^M0)!VPmx%myYd=`d3igKmM;i#5fWZRQV5X4$({ zpDxVil7aL`PV!Q~jo(vG3p{DBajBSILcoKqi5qQ;=djKN%(CZ_TA5{Bz8D@&a8uLO z=yhO5qaNM(tGB(ajLr_lI=(5bqxxFCaUANF^`d8IX4)6zyOOz{)TfUMN@ zFkCE)BEFC#x#h@{suE4Ko2y`}wcf$%;HQ$QGU}R0)pbS=l*u%_w0UV=SZNX+ax`ID z#m@1L>DgU_`%G2R(jqZecHLuUxju_?eY`KjksC z4zF(Y8%BCdYl!<~THM;8d+Z4#M3;={jzyJX3{9LcbW~nrvI6GhX|M+slsWx8^_8Ho zs;8DXt;uqSRB^^tpp+6-qjYT!r%Ug)mMe%3+dY6YN>>&6Jws;H&8leTg@kp{=wotY z)C{Fa06jTpEqlWl>LtUSuTsjyO-m&WWHjz-C8f|Jo>&FvdYU;FKXsgyYrQiSGBMRm zOKME3{3rlztoo1s_?ye(hSU`{Fh5vBN$l?~nJe<@)|Qb&%T%(dYKmY3J4rn}K(vtn z4!P+>uAto0ST>gY16MS&IzwsSmg*#?b2LCW&}1x&s06trGAmdf?eVcY80|wLsHI32 znhGamHlCg!l@YOJ8u{T#k(hwaCDf8`9Y`c%wf3}|Go_!svJ z4a|Zv^4Vln5->crcWvbEg~-Rb72_c-Q;q$);=8Ff>}(?()v zS4mYs3<=l1_^X8|>!zM*9*&DJj%Y<4MO+3cj4(I?N`V?^sfu{jwU;!|PD-f+Y+3eC zmL^e0T)pRkmM7LFjc1lu0uc zsVN{+S5GS371mCImFO+hDL+cdrt?)SgObzpFM{cr5UqY+QBbogh`G;INeV5STeCu{ zWOLonhCvt?x-lRP%k1Bf@ch|)lofeYYJxCYV;Y%cI^&0!D!@q+RgzU?ZFd6p13|W2 z_JfLO^9roPE{d%wl3=y*nElo>Q*@3=C52s(d)>)>Ds(=n4Y`2eQnR)BB1cFmmRRRb zTDS#{o2wX}FbFe7z#(mS)!qb#!*|e0Q^*tAcS4M(th~=-v{W?!bEqn)BB;{T^^B9& zumOacp+rc@4a+*>l~qQf$T}HL4)&GJrJ|^$riyJfG0RCyQnDymrPHP|z2%WaI+U3L z=|F{r^qd6I@ErA%yfpOiRa8v^NcpPIEJ+1as!QpB7DHxT0W>c#D1CvxE83rCoYO4# zikhhBF`9aWf})tKs?`t#LSW<-g~?=R3cwZ{-=pUSKqjgIp2 z;LgbErpz8}>pyylWR4aumro#?uRxob`_O{W}7)?ATbePO)^pvgAel%%CjIsD~ z z>6EX-+UnEF87KATJME|aBlXD@2+8L$#FENt#YH;F%+g~q(#mAirYAz>mNrK!c5!Rs zd$YdZXH2o5Fs68f1>I?5N24UyIY`zp_jr&~&sbuRZm|g2OC9k~(N#koHDnaju}_zV z6SNg0-ep?AKFUbgs<$^nvThYQOz7<4fIRl=$JM!#ikSpd!dZEeGdU4O6fmR|;DwE( z(_de%HV$>H`j&c7=SvCsbigg*~k zSMoM$fRdocT^)%VFa}2oO8wz`j}eUXl=df6R2oPt^2wu){K*n(oe_X9-@O{L-@s|q zd;!Cn4{3bHdIOTYaZgSTs&JI|sE$N_Vi*|!W;+m0lFu0-t}eJK9irhM0f^xAnooo~ zNXjducxb7!h$P$vL=xtfJ@lyaK~m`aa$DfOGG4TlAc1wBr=tYQWj=V4bV1%O}g6? zx$87kvBQ|<@)GYgS`bzTEl@!(AVnup0BI8GXwZcSH@IAdF}f-?1O4Xd?RPTD=!_Cl zW))Ss97qt=ny6W$aKMKrNeWeiUiwJ};EX`l_J>Pal2am7(wLe_=@J^d^P-!-$UxGB zEcZzvM=fR&#bBiR;~7t^H`lo2YIu{Sz39ZO>I zFB3Vfr;a$wEYzq|mWJrju{yM_`Yokze~QF!)SDTBmb1!K2arcx%b$wN#babx`c$NUs}npjFmgMdeUKcfez9a3^n7*I~8Jf)^fg`HwW2o#)SS&ak%*zis2Z>RiY~0Z#`x-2! zl*Y`VMFfo`Y%Y$k&7R@Z>Q+`oD%S-;2F_|dw>Yvu8YyKE>k4F|%Lgo7tW{*?%$mBW z8<5@yrakRbw+ZwP_bBL?j>w=>)^38p?Yv)Ozt)-ei zYpfE(bX#et`2J8P6p%gki=l$}Vaj6|;$FhsE&(uO&zHi-u%ic{IU?!!(b;O$E& zdVwH~iXDLxONRj1J z0nDisY@zC-jR{0iFqk<<8q7*Yt!!?@g);q@c2AkqRT`v?(s|l>CakBHHCkft{<|+O zMMYT{8DplBEm4V_>@?f}_QAz+RIL(Hx3Xwu3W;5$@IlnB>Kf^^EQCX@p9jZ2VhE^u+$A7@lKbU{(1&H3y? zP)M&%w9*7wC7K3~PI}1k#$k>$xdnk?Hp3I0yn9z=Wwm9l&PlN*38GCl-rV!9_viwR zupioIWA%$hGg`@^MMF$zecE9;X=)};^GE`S`B9^~=+&u|ZWL;Ktt;x8!L>qx`~Idn z$w?SPl7DDpk@m9{B{d{8;#yLIGa4%vG08I%C%%IeZ#$h%8P)rW%VpZw3F8jYGs;T8 zu$okPBaTffZv!w+^CvwO%A$*2MFoY(1Tx$sv6bi5Pc>6&qM|K4;l2qp+@v-eksyqg z02`vPu+@A^@wc^Pl`sK3Vn=tK5{s520sX!9;a6KK z(bHvf)4>flyTL~_E4=YjjVluf^!=Gp9h88=<@Y<{Z-;p1MV7vxR>Zuh`;?45($`H5C;)SC&BsjVA4%J)N}z_5Ps8UO{f=^iHJ3|LvWY3nsC zb#Dw(3V9)>fhIulyG0Vbipi`qgatJdbShCwjgB=(vu|w>Jv{Z9vMp;C(N7GhvLY0| zxfxk(?Bs-9R|u#`8|*vU$7@+ta4Pvl4bZlhSXMSt$A0ud2_%7VNgG(;VFja}F*Var z+E-$}td4Rfe8@PnFwW|rN2-%kR6z_8N3tuk0$Ms~fQ~q6qEkHb=mBFxb|-L8+b?2u zH5w|OmZLx~5=d8+DwHuO${x~`ZP^`EsaCLK;9=|^T$EM$j&W5%1XKbFh+&vio6GW;HXMi$8WL2u@^6vfS--1K~Y38ygc~Z+ZU9J*9IBMT!Kedc~H?)a4~- zLD6GLPMHjs+e#~O}DuYqF>yda(mz;eGKbmF3qR_HU3E zA5(xL;hD44!!M)&J4>fN;nXfP#VD1TKx0s31d=whLJ8}=kDrz!y`gxlntD17L4-eP zumfu_41FD$$^*DS3G1}4v$qPo@>D#MIY`3Bj99*s*DlJeZKx)Z@^gx3i5$H|?IfDd zHb7;ygK1)*h2Kip4J&h{Y&Y=_L{8Y zJrA_KJ0$I%dYqaF(voCpv#1Gf_NgHi5EhZx5ZtuoJWg$-1Z(YlI_=+!Dq(?{B8qCe zfMZDri+8gS&!LD_-*BXyDcEOeFhx)@rDm9ywuN*Le8pH!R(;B!|bXH@~1`BUahf;QB#d(MZs;UY&PUWPKmlxlb{azYnChIs9*2~fvX%Iq!FU?YorZ_H}0!lt4{HwAY9 z4=pH2wYvCX834h74o?#6Z)AD$+KPcyT?Zi`kff0@VKX|FDLhKDg#n0bGZ4o?R|fiE zY5P9P>h;uA%_LJwpfq&$<*O=%)(eBEy|oeWgRmV*qq6?c>eRWGLdxriGT# z4W#43y%~?7*nTJYV>0H{5>*eUwCVI~;p<3ivR|D40EwnMFW{&__jH@>Vecc3>6R^9 zI2-qt`eXy4vFO6Y{iI~j#N(7Xk7KP?#X&u8#=x=bVQ>lG8OyP*HD<1WIcS7}NRn%o z(9bEy9SX$c?$s>Oob>R$4a zFQ-XXtxaN`Ml@8VCyX~LDm{@&aUl7!*DAeNR(FlflO&I+4)gJMC(kIDU&B+V6S7OIw< zouvw1c2*r#(Ly4~I_)70q#qD)C7k;~=M|gPW)jK;wINz`UHk$^3JZLO*qX^Zd#`yN z7NXP6)RgT|(Fb^j@reX#6&cn$Zopo`=WJ@#?0Qd~xdpS{Q{AU_ZfI*Jr;28j#~_L# zt7#;D=yha9CN?Fzi{9ob7QOMUI9G?Nsj{jnT8O2mn@2U{l^Qu$nC&EFjhzWrRsiW> z4&$iBt=Ugu^whOf*^JSOx{5;5EY)PYvsjTUm9n!y*LYc#jBEj0X%>RwKGvtsUTnrF zBSe+T!ve}4W~Yz46wHhji%JHvhzX1kq-;rUx|v^*#Diel!GTrDBcMRivD0SVoVg!6 zlYgEnk7#VpXN=l41SD&vtW0qtEK0*wtol=OH)gp2+igLa_K8QAW#+1TbPB4r=1(&M zRwX@dY;JxOP|R!r#v9M;W2||qr!F3OSjNih_G$>UYa4(XG!|7LsqXbGTM=Uc=@NFH zrdIg|aV;#1A{J6Q+WU_Y;eD}maTjNKq=IQqmVp#H$g-gltNbPqd+lIu%E3q%>uu{= zo)4Bye4?`i8mtb9E#qW+7PpR)a9_h5bt=FjW@XZbBBYy*BS^UUTO9X@BY+(g5RwQb60NDoDk(*tcvHP>PYFc=@6t%CVVLXf1cVV^H{j zH(xJYQ5mdFBea{F+fnP@u)Y4cuzjDRqW6hou8EyqFk*C(;&|OyUrQkb7FOQ(1TGD! z+S+60jEr-S@hMhCqi0<4CcALrXsTt6pp-Il)HxRg2qb{PfFPTVh``=KlWFhkLZA}O zs1a_yc(r>??9zp49jWH2l1*o7i52vzQ*An9PKQamT%2Z)eI~$xw%ZGSI8VbKr>kuw z;CuCl)$d2#{Yz>2o{)qz%D(WfG_y*u z+1pQ99i(RO0b~6hn9iAIeDR*^I*%oGU(k#gN5^uIFC?bk3`2l_v>O}S2WgqVoX$80 zhnh#HjR^;t%`67vLjoJbUf@`6FO3h!UevjbIyjanY8{4{>MUbrHnyo_RVg<2J>E}| zzg$**n|7Fy{9!`_Wn&uHgVZ*Vx^3rsb-`zDb>;+w&rZMV7v;QCBPjyL{nlZ)AoUj= zFTJW$0u)=%6ZA`qJ%KoOwG3i`DO`i5YBFi$R<(f|ZyN#EOo-}yuaD0E0BLV#nYdm+ zb-h&`Ly;8WLb5vCh-wGIA5VE5d$IuC#L_|irH?2I)(jhNqZG%r2LVM_msUj}2TV;e z5&c!6G}oC2YpWCHt!TLaT=_c*&BA*ZMg%*9T# zU=L7i*ZfJxoNd?y($?jT2!=m@rfI|KPFqJ7l4P`6j-rwvu>hM6gf)rl`w6Lp$^#_a zohCz0+L|!H*tB~+j+5R{!EN5tjV8DqDXC96{i1_T!%^lQnEl{wM+ecyj1*kh?#Acw zJwBGj4_7^zw%8H{y$_BrO03^Vwe^dA;0QPJJ%2n^JW*L5rvX4Dl5NunP^`Ho7VI97 zLZ-Nt3OW|Q@cb@tS(0!KWk>`gEMN}vD_8{?9`{T5;5v)ewVJ*g;qR)nC_ERu;|&>ujGpti zT|H^1WT`L$o_q9}!+Kl z8>4Ev`7pPYte)JvJDwSTmh$FkVv$x!IeSX1-xR#NSjOGfkTJMoSc@Bt9}v=;Y)!4T zl;sa>`x*0EXkAW_-lKC49DI9;1DMg~Tt7Fv)Ieg9PuYgKrl?WAs3jIz6obB#txn8} zcE*+A4`{5~T3%%Yca2n`ku;eUkBLUNeF_c!6%5;*w#8?|UfWGsNN95^2s1Q0E~n+N zU^}t}WiJ~k+&oTLTVvsi7ugev_;nfS+Lhy)LuNISw94+IysDSb4UL7+6K{x|1XZz3 z`ihR__UL|o)0KNNe5&89L$VG!ii(o9qc!FXAAX;#)~8BqO^h-OuXwB3cRb1q7-Ifar2Fko(n%wz7uPiegq~RhBqnNX%06Ue5gZ-A0Jwk5;g3<%)rBxYC>*?Q>B}D5cGz zk_mw6BD8MZHvrx#6kGz)Ia}@5758jBIYq=(@=KQ1NNWI8o{ma(j>`?>W{u?$DAdFu zX&r+d7PW{yPlx!eq!qnz0PEZSzr@MaXvRUT{!<`9!ts^?M|9khI)(AKt_yg3fT>yJ z6RZCKH4{g7Dpur%x1Qs~9>0l?8Fp>_pHQLI);ZxxVCLyAihrDjLY>1b58RVabln(i z*bnU&GttYL2Xq4)_-uR2^aLNr8>?`!K|{frtw~er>l}881Hn|OO-8Q`JRu@&OrSjR zZeMe+y>`;y5xFO&f#`VZqgi=^8(bAg)M`CD$EAl}?XGcRW*kCH4JZ59<6Z6>TA&Vh z-?}aa!+ce>L61R)bis<9-9Nli-MJX+2q<&Ec##n!@3FF|76Z(a}H*5 z8f2PNT&eF80!JjNvl!F`)*Vy4ru&;Iw^1eR^Ox$Xdye*mi9zt^J&C`8(x09u^SZSx z(f#T9mILmF2H#D<7^SxDI~G5srCCcqu8I-q@?MZ0UlmEf+LuAyVa7Gmr=bZa3Q(-({VOX7wn|N0n4c zi*SyNhA_tZfRcBJHIBr_SYG1zfSlw--OF_{)$EtqzIutobJbC-4o4=_d|* zD(10J*3vx%WJqJ9nmNIWS$WabEYb>C#h~{itOf+DCw&6I<9{v zIAMyeKz-=OOY-BXp(IQkZLUal+Cs&kgdNl>9O1`U%CSM|Fkjmv+SZ!3nN~6+X(`N6 zDh(`z#mje;+Q2TR8bKwA0@^`ii#Rup8kv>!qiN`_p_cvz#^C*YM@(vrr-1U@!(4FG zQ%I-_7M09N9s8n2<|uXC*y&bbzjoM;;BEw>%Wpk=8E~07i3xdWN@C-D?=d&XHgv~`M5U!a%^!cF|nq$GGU;48Kq`YM^hk1waoN&|T5-CRDaS+z!~ z5nB%FjYu~=NH4QDH2teQrkJI2^Ds>~je9(^pYI6^tm&7)kGC+#9=$RMb;q-AT1o9$vJ zlx1_~k-V}av(fU$zF29MS%#W<&exFNxhS~+j%Bq6XetglM68t~CJ0!RLd4o90>z54 zHbVM|Q_ve+cp8f=t$|a6BJhr+5s+o~*_XCL#=yF=*b+h98+EY+j-Fs*JAgZLhEIjRfSqQ(29aA~C#O=A<+UFW~vR`T6evxSwog;EUu)Da(6>)Epz!+xl5@ia0dg^!6Hd6im=fa zN*U#nnqb!&8QL}q_GM&fWHADy>QX=$5bdA0s=VT&9LBO3;*`R){MaIrIOi}(%4cq`W6I*!)^vTt0@6?xA9`hKgwA;Oq`&t#C zqNb`(cB`eRnm$s*(Idel7mJe^EJ}jnJ+Hc46Ma~HpZ3wixy$BMuMZ}wqM2#xYvPR~ zl12@2V#GA19w`~9w=Y0$@$(J<*qdUoT$)*` zYqMgBM;o@areZm=f>b<)#07G1GwZWSBREh^iAwv9rj}F%O7ag(ka~R2Q%Rxs6W6!I zfb2VnDyXV-8WS|d!p71o+9m`L${2`1455UK4TbD%ajf&64y(?p>GWoKU2R1YJIj@< z%#$SF?Q|^3$f_zW8$PIcUF8bl$vMKKv?ncOefnG*etTf!uxYalzOth&t9BOR7nr%dq zvst5<5JaZoRC}?WJv1{#TV2ePoEhPa#-^Q?`b>dBn9Cu!5rqOPf>z~i)ID0uX=-%# z`DMDFiJAPO!pj$SI!l{_IIAV0mRz^~PrhX=E@Nr^+*Zj^avdF*0MU|#Zjqo>BVpof zuGBaQE7cb!p_&OEncljFsV1g`CDuqmifzNn@p80XW062T+g!uHww*Ii8q>$6SS{S9 zo3ZYcBTn}Hs{!SUtG6t+g13j-qNcW@BNR_l98^=X)H^1ykjSJmy0n2wMgvF%gC?Cq zkKqQKF>+gsJ@CzH8 z5ch+)Y?z*Csq-kQrA?-MwrS~mqxsV<9EqqnZ7jwYMgS1Niy3~-`vGn)4LvlJ^tqHV zg{nyb5Z5?c!#W7TFqTy@PQe`upmqvdz5!32=b1#+5J~TpuS+CxPKQ~BB5%n?b=4k; z7x|qnqD9?x3_Gd1#!;TaXn1WD8xHot?0#d~F4?Mb*W}a8rW*pX#*C>lJ(#+ORdpoy zNFWs;jj?v{$F`MiR8i72EYa!ZIf^Eg>_(6kM^|l;R2#W#Zb%0{=l!F@Sof=mB$nis zQ_Ev>xjF)aeYdva*Tt*Z{{RqV+^$_za>q^xW-!kx5vOp>BGT?ufJT-Le;jd_Shbb@ zTV$W~&!;UP3cZ%7S-d;u#Sb)J4pBC3RBZR0f&K zt1BrtBLX?Ddrcu(X{m)f=?Nro$n6}5_Txt-qh=ozYV3sEs9WjAn(X5?;c2RBlAYyd zlAKOusETRiN2ie_Lk!gmEb5@D8DeE+oC_BUEsWE|p42N)OB|yqj%`|vO*|6QyFK@P zF-m|Iwf7pXNhbK*C~xDDj=AqS9X7o9b8g_1$RnH?WpK|PROU1##WV>|k|dL~$g4*f z8bhi)gI7APNh2JXlm?N>F4nMW0-v>MS(jDqx-sf>H+6^v>DE`R_9w5NG#>|LG!@xg z^|jPxLdeBT6*D5SRAn=@I!ITW87!*KrJYb*>0x;P0A+t?48E*MQJBbH5?Nr49ie7a zBy$|0x|g+;E<)~3tBYtd3Q!Z%w8Xmi)!JVG6Ul+o@dqc6Ynr+$8i<}sWu}4{+E}ll zN^_h*1@Ep!S380h%nmIc#d|f$D(dM9&707~TslmYPOP8Q;_Es2_$bv5z`wX zjyPwEMh@~75i*h_Dy~9CELaUKbJrExzti3U^)B34dUTf06ZSg{ncY#!IEN`ktEejy zHEm>dFD$I2!dg0JRxeUbzSF;P-MG_;{@wD4^2zxbk*Sf@61yBXCYrQUnIR`sk;W65QMxM`W0j0+C5d96dq_CaJ(g#A7FiQD zYBp&suFn(JA~{Hd5g2qjmF3Vuc~}-^W&=u%BQM0-s#H6IPhdKkui=`Dm^F3d1D#+o5D)z6N<#W~7 zMHonx(K(T#6*Cy)Go-LN1rg_)mL4q%E;WV(o72Jdm04j$LZ=<(Z;id{Ui*1mfq*-H zS%91;+Z4izXAJ_$-i)--%RNl%p^E@aoS4!yVPGPWr7Pakqh23p9lJ{6I3PKC#_$kh zi(Hq`x3qRN23hPF9HWS;E;sCdGe#FeB-CyJg$L_Y5nO%goP zL`>3iLicu99H-g*NXacS<`YFLho!YLQU_Aq&Rq49s>l@Cd5EkD2d6>T(W-h$+6O-q z4Yc*Ts2v0(;Y!SzFI5E{eM3OEsB}Q_)2XnIZeTJcDdsJsc>y2;-o5biw9eM8PoZh+ zDdea@$u)4(i5w#xXPq2zOySwIwxCPuTb+%@c&9wApslKeQNC9hq;GnrTM;s7k>Z+H zyGJ8C$)OnwD(<6j*b}7B3#rT*Vx4KHi(EB2iptW0NpKt&P}UY3i!Xq&$a=8*i9LVO zH&ap#TR;PkZ{AIDymge>T^uh}%tw|-dOI)_?#0{!#P{CqA(rd*ZskKT>sG^?ld|bU z;#q}R*jHIx_ga%HjrC(uUdff4{ozQyX{{0i5*&4b%~w?igt-Lv}|8Ol0&$& zFn)RMK~T!^#AKE?)An^@Cy8tTv~VKnOOQLk@8RNZVc1?nCVf3!R$}A%K80GQNbIr3 z^SZYp4PwqzDz(_NFhvQllNH53X0c6JWrj$gr+1cGR65^LiLN1QTtFDBX=$7QpnO+d zLsblRwR0Brsk?DlPaa&qEc1vj!}6=GRwHWd*WWn zX#)csr2@9geQRsnj`7vMhkFG)QB7M71V*!&O*KkAL`n8no;BHCM2(9^)^MP@qq>0R z_axKb%C35`KU__0iVB72yf&qo%9c48;$OKxW^vG@mFY58SJbhFnw}8cs9vr^8m}?J znJV;*&Pm*WeoTn z$at=(ye};zMx7ohgNlNILamlif=4mV7Q`|}9at$Awei+x!}*42txJ{DR#p=Fst8u7 zc4pi()hq&oq-lvyNO3w_5>LB@pk3HHJMOw1~&C4-v=Ybv~wQ^riN%82%tLV{Wn2{Mh0ed#W2!yciZ zZdwA&7UF2%Yre{)o{p(%>oWSeRe8C52?Ug83D;28W)(9vL1;;g#VQD$&aElk3HjgI z&k)H+YROg@;38OgXHrb;0;`xK1xb=J!9=c1DCFwaV=0X{+Q)0uGuAwc>s?I!(vj4> zOuLK86p^2Z3)x*twd`%z6t4vKaY<2_RE~L(DWx*Ns97FeM_Tua%z&$q7zI#SSnM{# zHtK>V{PgP!r_w$4ij%47G=~lQCMI`AnT~NaWi?Ew5|)Ys8b?J%7jl{vNfFK26gkzP z_kk)HwksYy{{TniC`hNRo-(54s-V0^=E?-Igi-w>1KY@A+2g+48lEMMD;?^XTrHHs zh3<6AIfGlWi!IfZ>fElK@l)|HY}N8=<`M$fYKmQPTg<8NtCs71zF5IcMXq-P#OZDD z`YHZfk5KC>-ZRN7=vtbJ85E>6-xM-lGb_mLQ6<iM~U*cg|V$&?O?&} zIjvTlRM}pJ5{@H@Q3OaIN~)e@BXR(~=^~OZdtZEWOU5gE8aUkB?lh=huS4rvZmCZ028H$-;)QQ!i`M zO;;q2)9Y3+)ATbTeYKFQ3}K^ST!%f-NUeRTJ&h_d8ItoYRTV|WEmA2LkS?x7$O~wc zEy~!Hkw&3osTP8K{Ji363k$lJFxeSU5D1IGNI_)2!ov687e0UOM?~qx4_74+3h9UB3T`bc0a=MQBy^j)=rt7TZ_vCnp%n3 z^du5O;H|e^Wze}|)?k2Q(c@2LiX^Xsik~r(Sf`_&ph_ju5=a^-mKjn$=;ySB!zPUZ zSP0IW;!eM^#+i)yo?enn;a}cj(<85P;?luqR!;)JS%$-4ah$UHC#275(i*0zEUo~Y zuw@20SU}_xa>Yi6(mTXmLAfQmmo<}F1or#I^!kCn4hZ-AOPkrJvl`61KZD+>(w>qO zo@nH!CRl1^2of}ws!`2y46P!@{GwR_2tw_ovJS!8Oxm+NnW+|*G-%ttK8s0Q(s8*5uMa5&n8T7f#7m2;slPpVmfnxJTAm%|5hTOzQ+R1$hdj?~vQ4eO! z{{T%)mAT%U>WX@q;-{x(*GELKNb!HF$Gkw64QX`q87*>2W;l9XE~5K|*9-+1$GMwV zUs55ivyy+b9PML+VXMpyW9PYJN61*#8Y5^ljlmAi5!mYZ?Q#Nvu(mU9Z|vydg z*3Dz$FJs~kI^QJ->CD3}$apf2IZwXVlyJtLk~BsDl{zBM4j;8X5G+_Yuo|>a=e+OMSVK1FnPlnB}qvh zI)Af8vpjJ~&g?B@REZs!ftw@Vuv^&8^c;XXg7h6#mJG&3{YLSd7crBvAbBEYrx zBn^%5DZ^FNbJtS)(%J(cGdUz#8MWPoh|(+-ueOrM!vi2H1Kt=ZciJQV5bUawu4Rb@ zQ%Jxtf|)szxFi8?W|WNyJIyPsN#b`HEaLwFXXq#{Drbcy>M5z1R7i{e0QD781w?yw zjws0fo((%w4h@hHTTwv7-OrOObMle?7w-47x|lF}wRVC` z{Z`;y!F4q(h)URmli~y(sQz7Sr=c4gc+}i`?6g&0EWTk8A-OQh3j`$hL{7c+RlS1R zLZZNUVBdha?h;s%JIY4ni`-kNvktvff;>0HgPQR@IRT0l7F!^ZpGgC*r@MZBy-CML zr0*(3&SV>RgD|%cdn{G*>A#h#49OO#;ijf{(p=q{rl^uMYp?)WW7lC|=H}$Ip2yVu zm1)&dFfAJQjDQ{0P~TsUX2gEH(MttjK3qLR2vYs`Sa@*x-Bk$z^ITWwt3$SJlg z{{ZxGc9BI5Wno{v$_nZSf`XC7Squc6@r#f>!aP7dXFjzQ;m+i|~%+t&;;NeoP(l%#|9g^&1y z<~G3>7;#JzW-?1kffSH+A=CDw<9N@7_P>J=PT{vH;%A1kmsGYA#K0E=Nk0#GSQ~3o z-T+$nu-IXD+EDvKjlqPD$+KBrDK)7I6bqYJp9_64P|n+*E1P_-aiu5ViYW5wxqR(J zOCsJDPRSWkDJN4BNWgc23{vA$s*Uf7+828Ty7gi;G>`MGuEtv#vOY<{{W-QC#QlbtNEFQL9uAs zMoL9+Z)J%z856_pnU%M?Z(!rwKe4>F80if?6*LOamC+PRi`{*;PzCqv*QWT_d2bD> z!gQOkVYiao_~MrKs^N$yf{;yEDGKvK-kw>*?uY%6?%4U>_rSGHgvf@WL20CNioyV5 zb^`bG#eMA+#PLCwPa`lUp;nd^PW!x-WJIA=P0ol)!0%(zX+{Q8#15oN$AdkbPY~tLn$gq<>pAm9 zH9eG5ERowl(uib?O%{on?n=oc9SoohWd6{&N}`&1V5y0ro+D;Q1YdgxLO|CW+UVoD z<8X2MHU5X%8!m56&W?Ebd0kiudqpiwbs|`v{{Zb1ml`-5T@T0<{{W>cu}V+m`11p$ zD(U8q7_IS76wU;&*nC1Yy+V>c%trPgI|gISIp!`@5kE6K6q8Lr{;Pd9#gkpdHj9)L zZUxVe(-p^M2%@&Y>{YG#ZG-ykppe!b4mp#2W5SYA*EtT_n5@yd z60C%=ww4Cqp&KwD><-x1y@-2vxTcbmIE|`RR2V7|M>kU1%P#5|_^g7*_JQkwKG%CH z=d>~`vBn0aXOZJYDAp=NNa&=C9j|*Hn0di{k>vv3^IRn(;#eYH2RfVrnmu&w4VKw#1 ztJZjH4J}&-wtZxOzVedKxF({S%;@R{+J(rsg_vwV8{<@aB=(Qaf#{{NcFQA<>@6!*$Blq%myN`m?&2y|)- z$~?d>iW=mdvC-;~UtU!Gr^vh$RQ?&N72c!+!vpOh`%&z2iaMr_DOM&RNDwvodWqZ2 z3yZCfLONRvxJ=jO((~ZuRC>s|*bf~qvnf6&d-#KFTwHV6>@|_3wE(LX*rKvjQ(O{t zg$F=Fr&76e14-RTIHfZ_&hr{$s+w_A5IYN~dw5+*(suC-KdXqOi|W|_0ArrJvNfWeF(My zdob-@mQY~K8lHe4CTZkGb_l<9BSmMDM&Ck23$gJ)3#}vC-yBhU?2nZzm^2ulw;c3JGHG;|{{%h}}(tT^WxC8$*eOp)7ja;{<;0Fy@H zPLqti!&L{6s?@Z?TUn%%GFV*vLBn@svEJiNz}stMP_<+Pu{&YqUR5fvQ%>QC44@_M4&Z_=H~hS9h>H3Osa@cX7uOxRiU7E{1Ydg#f;PR* zI`_YD+qfJ~Z7RVh2bpC1Gx5x8m@t%puJD-2AP(UwMf}KZN<9uEc%v|7tLA`o$1f~5 z-33Y5pF3X_1Lbo-{q<2*53n&0| z0Bvhy^7GmABlmTdu3{E8T`7MMgtNb(@EdPq)MG(bcCS{ntt|w|&&#|aQZlS|uq=H% z$ogTVvtTRl7ZmUH8Twh4*2q8x`|az9F5PHnhU2`K z((82~f^qqi!d}>1V6Lki3o8OFIURTDaWFBNMY9%J#oSj9DkQ0?VhTjDNbyMV zxzZLXBdGB%m!Zo?O9QHI!z9M5W&s@N) z_3Wh6(FPVV(kmTOOJYMyaDE_6W4Kr14$_i}I+$o;{`GvNJ8fw)#lFnYlRki91lN%pOLR ztH~*`Hvp_;gUX3rtf_DdX}h;pW7iGxPROgKzbcwn1L9z|RsOTF2t6*_;UWvME&6uE z(WaqFZC|-RF>VCo{#3EFu_Zu^f|1HwmPkK*DH_-MEN$X%VS~OS;qym!FotF!6oPey?y4OCs8M#(4a|?T*97IwTGW;014yL<-6dGs-Rlvp11Py9YGG>& z5xt?=#|UN_Rc%E!O&aGEvbwYPRTP9Q5oT%hLKp%GWx6@G!rM{b%Unk4p{;C;{{VP1 zUF{yMkV6Kav9};9B8YpoX4y@Jk5P8D>@Ih%drbCw&1j@Xk`q$3QJSTejU}EvGBGDz zqgIUHdot-Df~>=QTwGz=RF!qFEo2ZwJZdS~VKGRth*$;r#3pZ8hVK?9_wupxgjJ_cLG3?UwuvC zbo+aDbd+_R{!EZfJgu)%{hd;k1WywoXs(2Eo9YNE5ha|i zy=(yrw`~joQDgOIZ91`RrvOz+RA@5# zEekAf6V}fZ`^G^Mn4V^H7-hVD+fMf?Ib!SweW3Cxe5Wu{pTS1rwQYUyL7h7EN^gjG3WO&vfIuyl$@13M&&0FFP1 z9R#Cor2#U`=Q(;Ryt6cpqA@GOS5YQpl?zxRhe1wCOckU9mNXW08g-x~HL(HMopy6Q zTV@m?XP%tNBS}+H5CzIJ5IORzNcuhJ@?nzY^mGuckFKJoy^p-hFt&-~ zlF1x$gLMS4M2^T3*EsL6Z)BS4>d0cNMvE^Yq?)1`p_ODrun|ElO)PxL7^oVE(wf_< zfM^_pfef>lOwd848Tqv?=@1LleVRz+$=E1Ee;WW!G*4pvgXgi+%UPAx(a4~(7@@0W zl68%R^a&zJyTDyF$dV8?8-PW246&?*1Igq!qR2X!3rgVq(E4a z`*It}Gyc=NF(&)o_@Ms)(r?&}1#Jn;Y2l4C2v#Wr$E6xr-c^oBrmz9*4>B^{J38iJK8JX1z(BrYz%*dD8KxHks<4e>e0-rSX_bX4VvVt!oI=2;|0Xh_!! zn=2z0TR0Z5J{K3qvB2Bb1%^JZl9b6ZOv^8Vc)4`sRwARpB#PAvgZV8^fm{HL~P_oFcqB!IL5)`v(=C75`(p>ml;#Bs%l)FeOGTPWAecD*F7MfeJ z)pE6PkZuoB#F1^r*s=Qz>_qVs$hl|vdmw;8VM6ag$!Fm01znC-nfD+ zV}b@H5yJE{G4US_RMEdKstMq2`;w!^SOdPDLd>`O%W!Xdo8ZESk16GaY03x+X)(wX zSw{pDDR6ZXEq1+u1oXx6N5%kuK!CrL*_B)o3aX06h)Ad;r)F|u?t8~EP$r3#7Z*h% zTB#b%uwCqJlU}bkt&)_;^Om8afJQaTCw-nJR?-v&iY{}o5yz#=vV>v`G{)>_f;r+1 z$WB4v%IB~y(y0(k)z4Q_>dzDrBcyPM7^{-fFy?^l8p|0%s(ve+UVJOT66YZ)Xfg^j zMnfvfRpBwH*g32Y(kVf(e)(f@r1yZ&J*swdl;zZv@lj?G*5)wt6EtXq#+#Vn82#Q> zUPOxpj3uICSdz_RG_H^A_qX}!X%e1}Q4*voBNwuk2m+TN5=Pgzk6rPTtkSocxtPsu zE$X%5K+Fa0r`bO+%eBn8ButRY60^r8O?pUy6^lGt!O&R!q=6&0>ts+L0^AeFJUgjP zToo#1aqloj{n*(qIh6Aj6)P6Ar;uMz04}y2Zuj={&1vNv<)s2tjY`JGQ6s^zbEpEQ zRA8EL& z$saNr%&8=1SN)-THs#rX=J4fH%2ctFFRYPLWZPp4$)%XPgJhSfJ4v;$VeJdYPcB=- z`F6>gWwcQvQ#5U(L4_iPqkS4$q%24Vm$tJvQdHnSvR(%MP^+h+fQmY~D(9YB%>Qv0eK^>Cn0_$2sJ&)%y+r>2Mpp)13{HAuQ;_7U+ zu2-6k*i_X_(^1vaFS`4pO3hAUSqIuSrsj)x5qpBx2NJa_O+jBxoIwP+d`%@biet+m zO+*qjv&OvnB}#b{c;jF+GnE1{p;R-DJ8R5U`E`&|)M#MI%!D#rbY%^wDf$9BA1q98 zPa7p*KKvFXasrs5MzVu@lx1ygt7yPcqz#CTGR0a7ZBLXxZWwB|^c-9E^99 z{?t9a$(;MO6TXC|kd=vIXO*N1Q9?ryI&`Bp%*shSfow}vWz$hnQxurr-DF)ZfB+*J zPevx>-(!1Qsq2dCwr&BXr>KrfJjH{}BI-seCxu^Uk>r5rPVL*5sJR5*XcZ`;GJ1@`|5y%r2UaT)Zei#zWE)z**yEAY>R#q-5rR$* zc^{Ww)_rEg(pOb%ys!f!9ewhD>KO3{570=(p;@WHun;uHq7`2RUU4%89v^DQe~SaO z{hmR7vPe8u`T_dfy}nII%FO`~JI6Wg9-i?!n47e6$sO-@`o&kjuW(=`Q-UXU2Tb3YQWMCgc>`AcOt%b?(#cL%5k0EH{c?yfRglE#XuwoP& z3+;1>eDgF?MUP(#9ltC_M$_vJPb0?QZc&Poqt3)%eZb#*Qj&LqVp^q7EQOJkxsA49 zRQQGjAHdj;!xyDL2SrPltn!9dYGjshS%#*Uy%bt*2BW9|EpfR$FM&?a;LK|!6!kK> zq+K%9nH5+Vm4VZ(mr}H(X&vBgskaJ7EDkrROx`NN54_1035-V_EIh}nteJ>1HpHbZ zEHSd6wx=aXHzyiw++t!P;1-$Zf;bG+$cSWERoh24L39iS>}|i-_w9@8h&_pxD4~@z z%%(vnc2qAkazw;kLav5c6|6?0@z~pLwiTDzr!|afN=IOknOupfu7Ouuf;r@Zg4bJW zzSg)PM)00ZQ9h-p6H~)14DmvJ86m!^o>#~ zIQKf8Zgn$ii+>^UTmUv7jsa%yeIheZL-m*g53tv}jjN>I%;GSn$TOo~~-W(-cfMCljTdzJ3o+pgHsorLzoHeo?MN4d#O zM>BHbs(E2%_Cu8qSrS!C+D!no#Rhp8DmxyZBVKSA$67uZ@Qt5fCu$J7VC-| zHuiR|SLMwl$>yw84Ua-X_#Xq%;a|eo8zZ02Gx&uo&-Rt}WltaiRtOeW?wH&?iv7nU z;c;u*$od>!Tpd`eK|HS3GNFxk8|i?S>+0%0WMaSKj?Yqo9+2xVAW2cpiXAo=L*e2W z5D57ZfDX_&XE+?sy!D7ScO{+HL9?AXAyoB&zc7@u(}&C^Rw8G zrU~-C-s)(j64TElY|iTFh%|E4ff%%xNi~CWU<#4fdaf{IPVMz{ z{*CZsBSRor5H0Kh(l)<|Bh2{pIGmEWi>l$XAp1}4#-lNiJldsY1R;UukzM5>~Fg% zFU;zAGPxsZ-Wg;ub0mc%4CvSHq=0O@^s#HG>wIS}**kfbvO<0p9o1F6g7_#GHXoVs zz|R@+=$1muO-~XB1f+48!;6cC0oX39Z=&BkNL6tHDdtH)s;Z!>#^XZ|GC&P)maVq+ z#&voS_8VK7*6P2AtxY=VYa4jMKJoVl@#Q5wAXUl|roHustEy*~F?MYR8heCRMJg{~ zbtyXcwgl>3*a1^H3OYoF=j3g${n$f2;+m?HsZhrqhLntHMN#F@pHqF#ILJ6sH#(=6 zNU`qn<~BYAx~;Z5`rEEG@!D|viRZj;FA+qWLlD31KYfqx{4w_o@V!e&k|)@*y2z3@ zbgL_BR#CaSkO;T~*9Z9?O%|2+R1>#C(IYP7YqQK0FP(!i9#|%yvzeMQ&KdT&f-C7` zw$CGO{ySM#-BjVabhf`LIQNR%eQEU`eT25SUyP{hqeU~v4Pn!+oWCh1bFh|%Rv{Yh z2x@m_k|_f!nO8|REWM;LDvW#Tp+Gx>b^;6j()2pp+lbdx=urEgafB<2D%6uTzd6 ztU>4}l<72uPaG&6>)XUy_xc=E9lZ9X9F)x*X(FDwoGRFl5oTg-)N~lFc)PTElxqrY zAnk5**dLQE?ek;v#XH5^Sv;+#MgU*oUY{a*pT^h~x1a|dXOgQk&q=z!(M#9_HO-q; zR_aL7DtdT`DzXV>CUYv54Pue3b_}eJviFsMwka=YiZ+U`F=dp?8wsO|Nj^CvibjPE zl<7y)rMtb;t7QXWar+B)xlK(;SrnBjDy5QYu1F3F#RO5prbpAuTaYv>FeON^J~_v> zE-qJ50Y7Vdzg>YLw?EP#e8%`sP6H#CA86It41o{cRQx$iFLQ&MoXkY5$KeeTK0aT& z0`z%lw%h!$uM@ct5PGw(5!y}A-mv#-?%m*aP zCzd9p2AVk523xTa0T^hNcWC4bt|MSd5Nt7kIIDu{-lndWRHKqi*E5{bq_oK_@rvnP znyG37ERi&5T3%afDp9r?h&E$^z>pI>%e&dl5h|ADLI#*)ONP?A zEaiL|+V{ny*?EeGGeFSNQ~TsHBAAmzlF1V!fHM%GfI{pAi3d@>_|jPiW|6E=#DD=3 zgh97JEI%MIh`-WLODz>fNYJ}OFqW;+&|W~uumDwT+P*TnN|3>=VhyqHBBeXP^-Bxg zhnL!J9v|cQB_Cw!;`SwaACc%sUB$-76j!#+Xo{30Q13L>+z9ty5{Il4o98m{6?@t?w+lEvMZjW4YE97UhXT_%!Te zhcj&BGRr@dGTHLnyDjBc%4Uh;_u8ZbkifKX-(0FCL5;xfGxFf?Bul)AWs)IdsG86lA#x76IuYfvp$muMv#|Nywb1u># z)UY(s31q&A%K;;8dj-DxT>OFZ#zFr8NM!{%%VU;gNklbq6;=VakzPC7&vA*0{{U$` zk}9a7j%ehps3b;Wg_yO0B((Yh0b#d%lh6ax7{l5_w|cz7qFQNyh8QJfNEL$zC|E}` zy@su5L!y8cL;d5pfJ%_qmQ)Ru%(lPLvD?g0bMl!LAaK%D(#oJAnljgtDIa3*4fQ3- zyk&)ki<7R`q^7Q$Fr&<>^;XP8*$q_17M?Xgq~-C2?j+ADu$7ram2ga|9gG%_^K(6? zlEKijvJ%5VD&TZBU_l1nM{$kq>>W#!XH>$MF@R55P6IMd?D5YS_$CN!q>qKv+^Y+n zolYD_UZyKzFgOzo#l!DQR(XnfZFTX5|Z8 zbvujOVt3e$j@>V}=|8l;vE3zfMp|gn8o2EuIsl?g3t=3V*_7-95LrAfE~oROi}D7h zW=T+hgsUyC&=J*07rb}qR{A|s#cs?9J9;15TBY~uKY5)q%)F^>_S9|iz6(1%f)#bv z&C7c%mbRb|-citz*Am=Il%$JvwaD0xgnpk9bXtL9 zE@r^4?G`qsXkKVFK@4a+<6Ot!4G=1B_OqL^g&udn9X@uJA!TsKYkR~PDKFDoo%`lPeIicYm9; z^n_vH6cux;_JQY@M!gFh&#?ah{*J=C(v>Uz_kcZ@`#r&#hmvgGnwCXys~uFz%@9wWro$Gz9>LD98=A^_>96*!PcpOV(ruw!HstC1&9OUUH{`q)sjybK?vTWi z2*#?}^i&X!U-6(jfc#)shRDTB%PoXdX{+LsnjN|VzaBnKLB3&Rpg zE12hb3}z`KWzsAFV<|c;Sb$W3RBm>`wI^d0)F_W9`rR|ebqZ;Vn6@G?j7sT=9n6Hs z-0N*Ym=-zjXIX^sIhwVWmD1X(v{;?4$j(NiasJ3^@*A8`ygSDA)G|vIEmKJfGbtV8 z1B>oNZ@S;afTsR9UX3fFkWBZ9c;1^`dN$9w9dj<+)3&VMpEH74)k#UCb5LVw)~yjt zWXShr3}Y++*rOW|K(Vj$?k*6t%@xGc$t&qy(iD-|)+o9gBDRa$WdI9ctF!LVpD>kZ z*;E>fsSfC3uu{x*$XAzTRy*&tl$Nl>j$_$1G7~L1Y2dhDco9ml8E(gy6q0QqRU5F_ z_!br{?G6-ShCj^aJYP;(yvp3N{PhFcR5?CYt9fScc#tJye_Y7GpLWPZ0Gj_ zxQ*bBR08WFkQKTQGjAW_F#P7kHpijA&k#BOTuT>0bv@!dyzCE!`holQd<~8G79x*`&U-=?kfx6H4HiNkKlJ5O48 z#JWBNENm|J0_SU7`T@Qy9JAW0zNb@B(4(Rdx0a(zH>#qc7Vz20^8meK; zN3=KW3)$m{Or`ziOCm8E;(*4|Sm;6-H2_Vn+Q*%bOm4iNA)bPi&pfX*tX4_G5@Lxv zywL<`wo;L=+*J-iHW#)iuEKj;&&?e2LqSO^MWuu*&to;plcrGGRH~M})RCv*++RR; zXWI&9F@%}}O;@7w)054P<4&$r!Br(yEn{^_7w<;5zyofVW!iovLG7pPvq73te<-xg zM=c_A-m(@8%%(-u!c)=2YB`ZeZqeA-*@!v2E%sf?WL2KOH?6Eh?=L#DOi6KKMu4R* zHY7TedvjrHYG3OivnP$hj~&VTV&TV0UFcOa?2@#@c}(V?Te%0|ZGdwGlkiJKhD@IrjN5PzS@RMe+ zBT3rfm-byw%)W$ejLThj;l^<~y#g20Y^?1kyb5V%ZeWfF4QU3r`L&PuRWgkpU z@E5bDN31;4)=InGHKb~N35_-VLkv*grs~EB_)ffVqdy?R?k~@)xT7alkW->XRtzeR z%{X|HMU$JTSyDuh1UDd%3jt-lXT#hplFVa{bx31PQJA9+l@ZCgl4^>#KWK_p(Wz3X z>{pf)0ya)f#~Dgxv*q~>3TjcVMqQPp3u`@8hVsn9%WY0TusT5)tUD0)YNJ`jb!0Bm zxoJJxZ7mEEl1U_Qt*^S73o5bbEDjSo)vcL9^!EP%siZs>%PCt5dcUjWd(1J#oHUe` zQ^Jx7Rv8MUtI?Lhl=L0o2n+{C2HqIA2V)dVPL(y;#1xWBh|5VyAHLP9xK<4^EYOHt zgQTs>sj)KL6&icmAA~9E>J|!YvS+CPbE*<3;ef=*bgRto6jGb%($TRo_krtUO1H5q z#;(;lofQ%iSz{sUTwidk!<4##xH?ROV0D}~PPVdhZy)A!T8#~>kyy_^q#4e;W%pR1 zG?KKct_;gmV|iIfHc29l7AT{+w{m$TaK`VkBsYkAK+7s2X#K%xC6&?To{sezifXl@ zs+e+6mb;`9uCfKr)+=^;AZy$s#f}x9Y9| zwa19I*xvo0f1_V2Xw=r`^K%bXf;gfdARTHCOK-QxbitQwKj`L94k&{V(zY$7ZETdHl3MYZ9R$g2)5abvMwS>qmD=kQ#g=K5?O6#(!Jrh)Gw~z zPJoM7v;HKW1v06Q7?p0s*-=;ao!hUWB%dMSigPSjDTG|@R!-}pY1A6`U`ZrgHNoHH zaCHqnTUy_1n|Bt*Iyqr9P^sTzAbDezfU(qAHSgXV0KGv2_5}BgsN0(x@a7{Y8CaqEzxMUlEr}@XzZ9M=w?2olZr=}4oc#`h%tCCA2v1MY!4R*N~ zBfxaR{iJZ^RY8j`rijCo!KOxLpHA^)wJ7$A;0UQe_oMz{QZ!Z}u1mDbZxQp%NeX(~${Q4?0gBn%du z^6wZ(Rj!X2VJI58l3!8J+(FnyEk0f=CNqmg7`##~q^OV%izGWJVl`RzP<(L|UTk(5 z=y8MB?*i1FxyR?)Rh%JK@yHBQau|ZV!z0E5k+^4!7O}9}#9RyXzBhNU=V()fucwBG z`C_IDGbB>OEOIPRvK2I>R2WR0`2(|s4J4$t=k$XC{c}UFWtBNLV(v9P8WPr7j z(grFS*X;tb3ogu5-qZfhy{Ji%yjiSs6-THP^1v5qsg$Oi2Z2-(Tqj;NN?ypyEWSkNG(urlP7uc3Gm= zG^9-!8%TwwU14n^=m$%JOnC~cwOq{|qgs!7iAh-6MUG`;zjc8iu++9T)p64qc5lzT z+ONwX=YtZLv&y=OB3@MEM#1IfBxniUn4w}%%YWT|agJG&<&~GzFylR?TOxsh=`<$XdBxMcqpU2SSEWO9B-Kg^z~BVjnx;SEfj$mzKh1B?MBd zGB66oWdi0m0f%*ko4sOmHMHxov4uQLiuv&g_}d$T(d zT(bznJ;JC!Knsc5-qYr%kA-cD1(EW-181hy;vRdFKZhh|?jl0PZYz^#=%M zJUyZ_A(%5Qj(|StAQN)e+T+7~Z)yBS9+p>o&u9F^2bKJ_+NYt^~}dC@RiW1!l;B_@_f_=bpj|NJ@)EF{{W&5 z*!i7;j;-c~Rg(zJ&1mL$*72+Nqh;vNrr+al3lf>1o zzKf1x{4q;i1sra&$5jTCy*n3Zt-hP>tf;tP0AwJ6uLG4ms>e|xQ`GYsn#2 z-X!eADCOCOtalp>6DJBaB=Q`xV&O^VQp})5DuP9UcJCdmrGm&V2BTsz1E27{E?`~a zWTLD=dWb3*MwhKC3|EOE0>IottIzTpe18@z4Jo~d?Cn*cwCbuh5=1nD(Yvsoh>XZi6q=j3pkD0@s63$kF zZA`IGdnlGgk>Z5kX*ocHE`lx?D$u9UH)CNbg=#;D2$q5`do zj+ipG2Ip_jqzfGIq8}c}Dj}thpCvw36~pVVmy=N-9pcf^s>xF!BK^mXJzxd+O~bsi z+A}W80c^I03Y@~?*_}-|jx;tQo}P@nfeY$A;$v=?U4oqDn8`ED!cJkGn@gEXa|@Ge zIg`DA1E}reix75CPfn1@S6NLXNEn)WX@rj!kff~cpr~!_Xv+(Wh9dT0C~^j1dUJ?7 zQ=PSR^3PpZ%`Akoyq9K>{PtA<0008O00QD4hd4fJxmq|Bw)?T}qOJBW-4^}>sqhBa z*?AYUZcmuy<*4ZDX)2^&u&JJ@j4VO6u1VE1A+a097&ir3hWH~qCk8`IC8^5ljA?6{ zeq8j<)*oplQj*G-+g(I4KEv$Az$8@X8IpJzB2ru*>=j#9tIDZ_NKboQatIYbEbM0h zvC^QB1UF;0+mWR!^D6wSEu^QZiZY1|aEgj;Z4`-43^A8yL}hY-9VK)Nn-g*cM4#yw zs*Xtt(bKg*EJqD2ZdD>IL3xaZHff!d2<}!etE#|U-98ldv8m2wrOKqCCJCxxN}~%+ zDRA4YI(~T7{@NXyL7Ps};)@t7y7mLSSRRjx%efTt}MA|ukv-j>G8 z`SYC`%4wvgsi$?Qwt*Q^9bZuIs9i!pLb8Iol-!VZ!y0yV9Kq@tT=6YB?8lWFRZkSM zN3E6sof=R#W;gDt4ew)fwU3QY#Jp4QQW+*;s=-H408wB7^YcAPxy6aZbkacvx!*<8 zNwi&~L>YVk%~2`j2^k{ZS!0SxRaBmuV^%E9ZsKjL#DEDA$1kRtf=A9* zI|Q+CK7?F)_pCiJYEHHJRU*kxTP+f`mqa9^&#J|yk(7~g)>K2Nh|q2UAXFezoX<6- zhB3q%40x84riz%pkWW zqD2Zz034N8Cgp;))G<4f1<#%=ETh^Ni7DfF;;yJwZyT-0^>)%OHYZK}Z@wtwJb?&~ z0KuA%f%`DbGQ7G4s(6-#>Yf@jR+Ce?=F27HmKdZ}*0O2lfZBsuZKR(&M(qu#C?=ke zD^*8h80&3J1IeU(W;7-A_>uVK{L8oMs^L!_YhN&@j%8MgI~i%GR5~l+jg`w>60?Mjj*q_ZZwgS6>A+AvGN=3e=Yw2Oj5ZlCFK|M z)Wr0#H#Z)=KDavVH#>e@P`ZfQKxaX_U5PrGtSn7{3OWIST%wCglhvBr19Asn3-9A> zR{H}nIfJIQRmLUZ!F{5XZt>KoVvX=Hzfb5l?8v*Rw^49ndsE?+rIjk+{{W*@i@3MK z%uR^^*f49PgTd7G)D8jivPk|ox;Q!3u98|gMfD@RMD^B-cTwbB7UTMHuk90smG=ye z(?ZqA8Gku_VEBd5M$h5%e+Uz+l6IX)3B; zlL9oZ2BHB2N?&#*h}d6yT=@fojx6?BtDY2OkwmD+SbafGtszxx2?cCPBpp}iFuk<; zWBOY**dN+vyxN$CAo!lXd-cJe3gp!_Egb|1CTfqfh!dxmadJx?gkSS?MPDxiqy0{}>1!2BcuxxJ5dlpg{G@OQwRTM^78WsPBuWN{M3WomM~w^xa6Wh&8@ z1E%)1g^bWPj2^Sv%LR?Nbdo$5>|MkURP>?=DOEHVoQ&CMp zN;IJ75wOu^h+C(8*b)6e*sb{Iw%1i6JrJk_T}J+28(0sZ2Nf1=+C4(Wtlc)LQD>oPM(w%PrlH?Ik;8 z{!2)nmKtbcgp0XQ5t~iUxg=5v({gUa+paKI9_BF1Irn95S`8YQ{B|e2E>CyCZ@C?9 z(*)h1c9%6+D5U5n?)UFW{U0!Z?_;|jpa2F4y9)Mds?EhuyID;mc3%Ma9Vm=*} zn42*G4&l{|+pQVG^qMr(*vm@KBzqq7X#=Ufx^>2Y_I2!H4BEDw)k_Ri6tSARlQfAK zms_&K04%@~L|WzjnDq{>xJHk&$TIl?R^+wjRTp_qn&@rf;KZvK9w2Dc1+Qa^$1~%8 zAEu3BsU}GtC6v;oE6FTM=p;cZ1k(%YVA>ppQPoBbRVd?gI1pA`>UM-CFs$~SH8t|j z4c9EEMyI2TLIFDq2da|eWbWyOLklIYs%|k_c4gZ7)p1=tT&Gg1%N;m70Kypp?Q%QC zpGm&=UrYq{v&UIgT1)QBB?los#1c%EZgvRKMR?LNYwKq%xaa{Gr?NUHKWc6mk)VTO zEN&POK?dMhjm54oyB>Hsjj1f4Vt(pneX+naD?Wy0x`X4U*RkobJJ{`tpW5rP>2uif z`icn<*5$Q4=+T==mM7E92;DiVV@E}61`1a9IKh3EdrD?p=&7Vdud<%^btgm}=RDn! ztS#{7qPJ{0r16e#B}0#g$JyyyIbRY z?weZH%;`qp#`N%~B5(-PV$#H2H}4iw7!H;@fIR;Iw~9*2T4k0Qo~n(K3Tc|Sw(`h@ zrF0AS$^v(hx4zn}NgKoe0K!6!p%yx-w2~moZ5>d7>?|%_7&|KU<=?$;rU&~(?LQ*s zBy`o`6vXUbp7N_oWD2Tzs~}d~v1x>}by=YgUfwA+{%%z@ody>E}m{u=K^59fg zByVA>TabUEfZ|)Rx5~2_SUdX9RdF9K^@pD+0m5AQ$BVCWkSa?`stoF6+bi8R_5Ge5uRX_mSMyn%q zy^)xLZ($pPc0xwt;5x|aAz34E@k)Y7m~J$%y@#Q_$JAku7w~Gda-&DB9W2O2!4~ga zc@?-mHtC5{q+rYBgPHjaMNm}P`u;!q;Jb%ALH1t_S6OkpzH#&Gj?dA8*e1>t&fJ` zt}J|f4~`dLGlL!+jwk8oU_Q~&=G4Yh1w|y$fy|1jIcIV4uIE%|?veu$ZtacnQTD;v zwKZ*Cwo)w2AC`2PY%gJSJ{K`Dup}7GuBCG)XC0{;0`!8ROx&FURdF#S*sQl8sdOF7 zJ;<=QvBj;~*BxgxvisVK+WKK;o}Nf7uN!Z!8F^|WmfOZla-8=~t{rp|wF{BV$+6fr zI!vqDR|GQDNc4)W4zGqU=H&o?IUj&8*7i`|Ax-cxPs7pFf-F_W#1UpwdwZ1gM9xU9gwxL)aMTbRQtMQ+${X!tUh2A*xGeXg>nNh9V=_%AGWTBUs-H0G z%-VtIMS<}I9+~e+##GH3^#eF@#2lyW)}kjCLh*(Mz#EPHJjbVBEL}aBcKrn%K&7iP z3U?!0FZ%~0X0hBWf3yHxd{({20&@>&dY0}*6fv7=`#6I>{{YgHU*Z78ZO5Ee^2&`; zHA`;w?W<4R2EYpgxERZADQ6ZpZ)w))JaMR@wABt6j!$fRP4C*b3{yO4Y1i$}l9EJw zjII9gg(2fR8;iB~3rn=FxpVIs(N#e4%dBJtm?paK-AU)Y5Cw0EW z#tCIMu^@s0@ixSN2c$0`N#*3F$#*fdtft4JDOV+q#_R>n&rC4iPI}A@65`+(;DaqL z%&JpSl3F-wN+B!E3=}aP*O3r~lmpQk!H7%{N93x2a&+IAKLVYbJq!M73Q$sc!G78kl9*3123msLK6 zua0+1VSA4Jf!cj*_>W90@cP$HhGH`0V=x0TrMH)^1M}`R3JL|(dT;QLt<#{++~-+j{S{p;KJNaLv{*8D^C&Zs_Vrz)o*JHcKezt!sHG zCldTu$EzR_#0tiy{;Yp!`uTYbK;*gq04SGG3l(G_{5o3K>AtPLL&)GaU<@p}3?63O zjv)?HB1iXLo)!ba6-~Z{?eoP6+BE}4t$oeaujV>_Lj>F(+dvPc$!I4QYj|q5mazwT z+yidAAFrLRWTr%8AAB(GvhE1KhvD-W&CVERZ6~gyiJ!UmC)dXl{4D0|SdA(-9tDW~ z!}Y`i(-pn%>wGUq8!B)2xB4ERmNZDr$3j8OpQhsT44vB$#9I3(H|R*chmGuQ;w_7t zvma@Oq$B-aQ*ZZCq^qaLaO>mgd}dkHgM3J2x%6Sdo;#=;lttEmyg>P$zC>cG~r1F+YT4KRjg_xvlKnHG^9?E!&HZ-)( z)lq*b*VauG)l_$QX(@`!JA^tN7D9>1jzSq#w_Y9wW5mB@3snCf?vRmr);4L&L7R_^J=D+pk}W=zj zV$Y-O^CqZ(yG5Kt#cpAhDWy8Ca;sp--a&)uJCJSFN4IaZXcb{I2N8dyDypMV_iAX_ zx4B0D0L}aHTW7w~_0ofBVvLY%V?l6y#-iV*G{hds*)2#CE^4&ez-~;@!^}&I>2+Da zRv&pm*y2Wm{Tz91NwQ~flhkRZLVY^a3*yUpJs{etgijsHPPrwPNq4&zw^9wY4)wMj z--m9PkEr56%vr_B7PYnjbORgmv;7ijBPzq4#HW3YASJzQD#fkn4gUa9SpNXgVDY_h zsm)_ZsT>4!g;}J8z>{;{F*`J06CjJe#Ky!DErR-(VgR6CW-+DXAhCp0(&**lm3DR2 zYpWagmu{BmeF4Se*_Ue2)gXeb>2dJ7fLV6kfIk`^zZt#yjld>Cr~Mx}gsU8s6Twvk zyR4IgLg8<1Mk&s_Y;WVW!jM73D!*Xb_*LbWzbio&tzjx;c~zHfIyot3^eivoeXth* z3^X!lIamSOcV#oszd3I$Gj5YcT1dj50@k=5MYjiLH?eU_JpTaK>w`RlwrZ+9P)Jr- z?`G6BM&qUQosIeuEPM_3!|I+E%j-VU1{4xE+-tonpXji&L37gMKT_?M~T#gQZgXm&ys(TV`xYzD^tI(XnGh_YEJUqs8Kk##-S zM;G{!#nqS88;kA%+Ys{B50}*c032r>B9oCiMe#-oS1_lBc*3%uxdXpKbjD5h-0U!E zz<$y5)4MdXN=?Vbas|5Ve)atS0FDGW4~rvLRM1$q!4|_&wf82%-ATE(o)372oK(m5 z&kZy>yTzGD!bZbLVo4x)T=)+hRrJEwD)sPt^p~&2EYnsRySX3Ic@p2ty|Af`BD(^z zCZhK$Sg~dyRd3$gPMvyHTplr+Ld5;O zG>&`~B0UYr#-%zc>p25Ie$$uLc!k=JtB<#NZ2Ki}`lP<|C7MkvwCYE|3A0JPhN&&3 zPwZUZzpzaYZkd%N(us_KypJnKI=5GHO|{vreTRSm0n-zl0ouT&atvtXkc%Q;a676H z5pb>5Y!!)Z#wGiC%UY{@TA~Gyn;pZ)X-1?R(8e{HZ(^bQ*C5)%9d46Gx=?in(YTHm z;$pU}wkuUQ9sXe#3Hw{Z6d7rqrw6*iav(O{bw#8-yugyj&jauOGz_kdRu;11soQ$kSp*=4`UvURI%#{v#f8pv|9@4DGKl z%7A31ntA3@K#(%LEOlIx`cycvHf6cLrYUhzi|4Y=ABvhX&kWBnam_0O$;&&1iFBb2 z%mkqUt*Gif1&6zC?8Z7?RIem3RMbY2oVqC7@(}HJn_DKMVpv&j;eb(WX5XPSB9eJM zy}t2PyL%Cj&Q@7gbtFerGD#D8#Un;`=zFAe!POVE4q~gONxkJiW~wx(`s#74pIuk= z#c}T5Sn%zP>_$To(93Qf+9{ZQwo^vL{7nxsoRjiKzx;TZrR^6YE8feiVQYMFRy!3w zU{5O##A1x*99$iM_A&3RB$M-_jTCYjU@}KMrL^*|sccDQRUnWU+@9@--L{P9_lKw# zU_Zpx9g1*ns%f*S-ld~4XoKJM2{}os>{cbxP}}Uz*Fkad3)Fq4P>jN=l9YxGJDRGy zII_f@)Ql>g=_*KLeL>iC=p;R|J89&_O_M_8G!e#Y8Y5)BfMb9G;kcEz>C01o@Dy(a zcBIfqvaL;|3#RfySZ#6vBUSe|C&cyXfN8X79Nynq{ic?u#0jivm*^k7y1R4YG@5j# zX`zA$i$Wxnu!u~_c?$$rVzDiw8dTYf18$%nH|&*Vik=vAT%JUZ5So4M<6|Lac^gYX zj;4|#N>h9Kw0#&04(TOz9Tz>rYXNIu3SVa|-Y2H!U+4}k8m`83$mxwLRZ_)IEjq_Mb5=mB zsGU*~-fI>ls~xohZo7+RiCCSB6Z2w56BOgq{QWU;VFMDU-fO-M>{1CuJsGK_6%aC* zW~Q1M04I4dI_Xj}S$OBg|uBW^hTL(&e=T=&PEVdK#y){{XDZObb9{ z*+3J8mGz5hlTz7(02X`vpHqD^M^8uMeF{B8_Y#LW6x9gE>Goj^ftyPru>Np@FQGss zo5I~O6pH)DaoYgAP&m6HJo?A#D{kZ8>6mlJ|7nkv0Rjp26ft`86n@=^Q0Zx;x0gNg+mN#Lk7ROEf+irhOrKF53a8g62 z2+$}<;el-uDuG}C00D2NIWHFRai_AqEkH9l=e`I1lhSSIw57qd&H(8#2N8CGFTP1M zMXB9n?y8Y^*#J^4YhO~EiyvF!TRH7O)Wv$Ff>}TTWlO_S0NcD!7~B)N1wggV+ghlQ zF(rv4lX6M9B<@K*XU7&-WIdV3Qms)vNQNk9iZ+c_^E$XJ?1Y^wr9rVF`_}HBhpMrK zHI`$*6De}<$9OeOm()ngs|?Oqg;23b+KX(VKvGF3pc|9ZAD|w~p2!*G083hFDWG(? zhF52-1owr}5XPX~>eVYSJ8ANDPXv+B{15Xw9X5fhJIMgc zKs3MRQC+Kh8AF*VS&Sl3ER(I$R5shar@X(>dxPXUjAh#Y0I*hfM1Z6TR|G-q^klq@ zrHgB5NDr)w0+I7=;7H#er*m-|S&hL8E_wrRLFs||p3_S157WaOmxuoV8egG4Q=w(~ z{{Ruoyg6>?p`V(ah<5!~NhpG7CzC-?%8@&|jlMW`Wj66mB>urYe@ijYj2|f?A3Rq1?`jc8FqNZ1z}cHf3|GW!9q*ON1Iq(Fy73hqL}BOQ z>a4~ETgO!!Qkep<4XQp|rm-~baiwph8xdoVrFd8IXXBq}r)c?MpUXJU+pNsH!?rIk z`%e2#&$vF8T9UavHer}m4H2v{vqDQP!z2N$l?9J@!5=b1D-t#H&5-cZBRu|PQlQf{8=59$`n@=qyQv23gW{sY~MDNd3U9J*E2`aVM;w<(X z5#fo9+qEpj)5#Ll%?WS5vOA48-BpwA7gs`bY&=dox?EZ60%TiW!HE}1!Wo`JR;0901DJ*0!)J@keT}Jgn;46>h4!wKQnNojQ)=<$uQl+0Sa# z9FtF6Bd%RnS^4FrjEf%O1UzQj9Z0%?H`R*injjd*Gp3=qaet-7ze9%Z*g)F2F-mu? zcN~ae#++D;npo;?qkaB(gvxl%se7=$*^QM53x(+CGs&`osSE!ADOJV}xpea2Ltr$<4xxMBybO|V+o0Gf zkPpmYf<{kB_p;v1jA8RE#H=a>&HJ}e_iR6F{h_~rL2_EvXKh`ozGpI|N>-jCL`!R5 z!L(1cI`HU0houaJF8bKi-1qMgvkfWdyS~&>v4Xo~W#uMnDcJSnx^o=+1 zCX`kwG%Am`6Gm_kX*97QT8yTatwH{J2Prkbq>No8KUjXgC;Sa1E^ATAp{9a4NH>P6 zo=R~Njjtq&&!;4t1w74eNVIpj#yF?UqbBjnRQl@c^ROfFI5FWqBFthfEj)zs%C|N$ zgrlbMo3*Z1*Ruv23$ILRX|>vly(b6mCRd2~XNPK6&8!ta2Z{P6lKUgqBC^W4aYob% zrn_ljV{mEI6Q^%Yv4*(!*~2}^Ci@u?BdMB5qYzYc6t3)|RCN}#YCGf-I%>JGm7@Ou zNdEv5Q;jl7Pc^pHJutcY!qE@Ne6b_Iy{T96Mr}y5yG0Z*)Jr&m7ieKA6phRx>`yg> zae~LX&1Dzdv#HhHYV;gu6PD0u^y_d|Bq<{&*k`Pc%={o^3+xTsrM#pw9?;;_+Bt=FHj~O_y4={GdVJ9xg@dJlYbwcJgumHdCWcZ_)S9x zW8~OQSGmK$Ij+v2(kck#mX1$DT0+D`! z)rE%pgMp-wfo8ZX(*9WLH1=^mE32nvg?**xz@4r8l&{RE=SILX2-}x5QjLS8fT;kF zBY&O9GyG}oUzyY+MFE~Dh_`-35?j_tk!AT=!+Eja6oyO0AlYAgbZ-zaNT z$@8)MIPA?TG`#YN)y2{~_oNs7v)x~iyW7hb9~5?DOC=jpAr$DvS)Fu}#1L-U&wBP3 zH`GUulL?}2yTnG#a);P+GtPHdLlzeV?SB*H{{W^d-XYH9bt6+1>DRmU@WrXx7iRE5 z3P%M>O&~qvBetMAg1oX5@^TAAvRI5ra7DKp562p7*q67~%0!}` z3Rz~HNM(6c^W)OCfl-%!KsR;@u1m26b{LCaVB?W2i=IytO#3o+W0=y>ve!1Kr7Gr* zrBX+VI}xK?ggP+<6CZv!^nkuNg!Yl_wxJ_Rx)w?$g5{&9FB;5@RB4hxG_wE-s*n@{ z)@#^{M=18hq|vPrAr=6l&K4;@>+^$!*ti+5H+SZ~Pc;Ti_?n&x?zbr}BJFzXH9G;|te^a;1YhosR)$-QHuj)3i`EGu<#H2i7R!Z|LCXgcOQ7o-4 zmFcBcZ9!LIumf+9#a5m{GVOfbH9e}neK?|^nz{=4D9mQAITi{84i)7y$DqvDE6a*l zP)M%BOo$8UmEkX8s>Mm5%%m?*A}YrwQ0vcTCApGSnz+&4>!)bUhDI%{5I`9J0E9iF z>S<%BfI|$B)T*SLG;d|U!z531Hajp|soiXM!Tf&I(zGiQytHm?iy~Llv}!ut)UC<; zx49en?kv@u@Hn1Z0UVxXRmL5aQl)h9z}3wJ4xx>8IHsJP0g5z7zNY7^tYje_!KqFW z%&9>(TL1@#PmuH-Fk{4V%{JzE>K;NhKfJ7xNKU{LBL-q@0KbqPSTXGT+18?3)})Q*uSn8JLHnCkUe&{BmvQ8sDVxWiq&7F=IDO$EgJnFHc6)U`S>c@Ya z>;qrMF&@Kv*_Hmw6)?E2rKpZM=S4|io<3zf%X@&z3c9cajX<8egV5<7%s4BasLYC} z7z9z!MuNaw!sLD!k@kUu_vaek4^p7WvQmSuC)W4sOhm6Mj$Uhd~m`Hzb!w_)sDLfAay_9NgRFy0ePlE zD{5t_n(ZXcUHit`jkX;&002Dz!6r+=5nK*XCi`qo5&T05pt>N@wRg0}XhFG#{(Ol3 zSQyW{Ys{rWuPW(1Ku8DfJ77C9Q*&~E1N<=*=q-VT#8|#&y!I;glc}dg%Xu~_==5c-dwhX!$`xJ=Bb#JWegZ;7GR3OrRYa^ z1!4v8-?K(%6jhM5NBs_CB{fqEi6GXjVxAUTJaWY47&>olKiEGB!8cwJH znI(YjGk;~g5tK$)=0h`@RBfT5jyRQ&9f!QlEMc|U{{UypDhU@PT({kh?$n8jO1 zFw4E^J>DCdsUW3FeG#=pk0U)pB>XW{{Z2E z<%b4G2c*3FUG~4HoJ`qVOeJYvG^w5g6su0kuc)aEwJ`IVR7h%7WQVyT5v57PIhO=f zgR}ET^q7YH?g{n2G!+*NUtk5iJpTX;KO7Gk7wCOFPt@X`VG?i*%BM7|fLVi}^C%DC z#8~=o_+mFPrPRgMnn2C7FtZ;UGJ?P`>0n6xl14U1{EUdLwA@<9Rfs=K1aU85lL-<^XXAqM{d*2f{J(zvv_925CZzW8^J=!(PjCvIAJc zikjCR@%-d~?{P|u9D+aJ6u0c1@pDmLhA1r0Q6lL$_bWxSQhU_@01RBEMMZOPHA-v= z)o$!!SN@6H4RX(B8r;E_qP^2Eremlqp_W}11ahf%m5KOuOlj@$X(Gzk9!zL5`x+{J za;UJYoC6@eugkiD7&aFWqTbuF>wzvLh z&O<{Pik^toy{u-cA?|z%q7;fde??0l7dWc8`?G2qutK8K%WmVv;D4sKDnEV5` zW$=#~Opc+YiQ{W4qcGEOc6BxuZTD^OtJMLnj>&L01eciA1_=% z$=L-}tk8{xhU#|waaCn}BcSW8*H0b52awEIkWH0TpMx-{i{%`) zKBr;%TNdM>GOJ++Bu?|L%q3ELg-_x?f8~X^53-JIwwfuWMe7_W`iVU?G6pKQ^07Vy zW2zjg0)ERknU9f4ew|v~ac1^m#bAck zU45GIIgUi7nvM!ebVYQDVu>YXEJBj(8PMudbr2oDJYSp>ljW(c;i98fa#~3mFz)P0 zC79U(Vo4d9UaqPy4Zh`QWOV>4*DjgY%w1KLusRdGWe?A&36}$3Jr{h$bX_Qjz^t zBlC{f7pvh&DrRIf^wNX_Q%g@4u*Z7|BS_qBZySTX@dHtu(Wd33B!1M>AIQ1B26JxK zpmxy*GC98EMp=U&>7XX}>8oa6P%VJJjw>k(Uou93f(dBHwvS_p-Upv0s-Bjq6tJd} zc_pWw+vrD-w9rU;Au=>T>{S8On5!b}V~IJkR8K5lYM~}sGpcCal>rC~LsZPXyPY83 z*C4Lv8_J)xZYDxRIc*HF?V;wbG01KQ#EA>2vA;$)7T>^O?lSfS&uXe_YD^R{nu>|1 zD77tQGf2{CUgyHPw2Sx*Z|Lq~gL(Pu6}bj@5Oa>ZI%uP2moZ4@8bDaHUwQ@Py@5Q% zV_-Y_QFPzpYaCLQ+#gh|<=K_2UD=tg;B;b7$NdsX2f*Uym;D@^L3;{%azAKP$6@Qa z4frknF<@ms=)=zDR1?R&KY2y; zu3;^U+CMM3)na!?E z*QNF&7Jp}5ztvH)-J5QXJ}Y|dW*&c`$F>4EIE6>Y)FAF@!F4M+fYY@+iT57-!@Ywk z*gBo8$#p-pMkMO8m4{D0Z7iFGQldb56W#9v>RaXOqpEvH%d?1;YQT-h!72h*S5LcV zh@0+Fhp(0@jw$wJWjg6?P#A&%kQA{!OoGG@>)86>Y}*H~h)ucWd4P1hb7wy79Fj=K zcYRLnZ-lYCGh4$`SPv{Mlki1uV=j=hRXy#>rCw%(`vX+jV|gn~`Vhi;FS#nWUkIl}!vts4W~2giXKrXe=-LQZn!L z#xA490v(hgcKyFt(rJqfxxke_W1h+}hK|0Xwj>nt2@)D|tg*ZeeKXHep+loBq+VBa z?iWoo*ZAdV#mmn-S!76#WLl!(-T8%ZolupWH{ zH=Q!(z9Pju)9Rh%eXj`hx4ll23$$fXUM+S#)>a_sZIrOF7bFV-i|?@SXSq0_M_F4u zG{Oetl99Z!%^XA>C0b>QH4a^OS7rtJ4Fo`YF!npmsg}BWBUG`oEj(28@v2Hv_L)|9 zhA3CK3N+dXxppJ23cFnPhK4HFYB&&7EE3Yq?y}k)MTUl|oFI;-cmml4IuwY!iSH7N z5VbdXw*LS)k`L_%sjb3)CxZ$*fA(|9ec(iEXsIHmfXw2Gi6W|-X9hDMnA0;0D+E}c ze(>(wNo*@wk_~PW?19`NVWpV^9R-%ahAU!4g^B1oV%6a-T7yVSFz8P9^ZK5ooz4ks zGw9Kbl1Cne_?ksi`j5+Uaa};Gb`mkBqQIH3^DDl?y91jutVmTyEebr^q*$(nt))v` zmTMn`8vscn;{O1od?VQKNvUa~_#z0+CCON#9mZ(X>~&e8r8WWo0M;k?V}QOV;GQ|k zC!Kxzk~&xFUlqK{Hn%24IHJWQ|aLC*apC2=%(qBz=6eE+@=h#XEjH{Mf+Q}UA3sqDdZQd+7 zt`~ECwAc>-Er#^@Y%SFVy$+N45s6&;v*{t(;$%KWPTOC?`I&WEw-!R&ocI8f-n`cC8(XqSm30G zQifw?YKoSS!vZNGoB<@dZ>1QE9dFprvW*T;7reDZyzW=q)V#t7h16UuN4gWKQu^Ej z)bzs4-eR99n;t{Hbybv4Gv&o$+o zH!RoXMJ%@K%Z=o>&qB4nxcy|W?E03Z#M4rW#jza8#KZvG-G0oYf~MoT1-9Q4vG#XG z0vPGwiWvHl3^g!|_?-~Opr2l+6{ee&aOWm^=cu=%fj=PgUJj^++~{S7{{RmPFSe1Z4iv_(}B5G?Foq3Xp`2AOod<-(oL+TOPR8+%@c@ z#FfyAUoxdzivq1Is#mUp;=g6t%BV61JwNm&KySy zZ{J;o&fwzZ>~4aBsy#X{Qim{hBW$#l*88>f;YnCV0$TlD< zi?y{9E)GqXv6#`!hFNBCZj8@nOKvTu*SA~r^u?Xo{{Xdxeo^=2k|jS0@5V*EP}z|G z07)2+=nQch?+(>a>vot1Kh?)4?0@w-Dzz%rn%|FTW7>!MH|f|Hps09QZew86L@j?1 zOQrT3$kzRgQCuDDd7TQ0DdLWvM$)Cf))f@>D!@2dEH}Fd$OCKN8e@q60Ma)uXAisO zR17mI6zY>qO`%8LS8|}6k@12zwTRHZoplCj1d8_pMP+m`GO+|0 z!kF!CjfORJ)@n5rvN+n<;6FdxoPVNZ*r{8CoR5jWJ1h1@tcsOWGN@Ky3i9Y~_Fn>K zm1DVGi3t((X2o;I97t#+EQWW5d#LlPnRM7(NP%^#Y6Pr>ZVm3CP4J%wdtyFgMme@h zq>OvQ#Me`~Q8KUHNe@-umd8max>~p5UM_behU?-_>yMRrcUP)(zN~Y|9S_R?0EyJs za5asmKks=nRqZbu{11QX$c_I1kM|5l)OO&z-HQC#7xipaxyK2`D;9X+EPA$(3Hgz0 z;yRat>0&y_jY#nu+vRd?^v1XTFT@;mGv;2b`j~)kACy%?u$6wg}JyU+u?loh-u~nku*S) z(n837L!lpmz}`*T>#~TdX(6jaWm}+)_uINvNDbwrE)2MLumyQU@!AU7&U*QWmf zv{Z+2{SZ`dytV~T(df-65ccoyFkQEu!U>KIsBZTy8Art?wa~t-#@6`@vG4~1^%XHi zAu57NLEW5vlCbN`jeytvc|hrL7}$%4v~Jp=fCwpqzb$mBT_F&74(h5e^&?TgQ+u3H zHQDP(?IYQlzJPrO4Y`^xVI8EVZN`%~`&K0UM&|y5QQp9K3jyJQ=-giIzm2@lsq*vj z!id+z{{Rp0x=2GyA&L-e@&ztOj+Gl-kB66A9)zlFU3@W+_FxMPSY z(Hc3C;YA^1k{W7CjlT0#iIHALW4N=eg}_oRf(a8Rl~q~jCpO)=6&YNk=FlvVIrP#6 z`mw^tRfEczyUcz`xH^C$;R@ww;zGS73ymL0FXbN6Zl@aMm(nj>|r$g z0HuJCeDR^Zo4Z|uBA!5CF9h)_v4jp{6gLh<)UunMU>#NqrAfHPSQof7pj2{s;`HO8w z(xWDQWB4OMqOzMb+T_F9c8u^q9P#bUwX^=x^7%uE>8T2{7Gn^E1}(YO8>&dJa&-n< zU-PANSTa>|#*s_-s*pv`{_SMb`CuvOwO9}scn1Njeq?QdxT7q4V=QtfWsH1NdPGVrSA6v)I@z?tY$sOm*+m6=e~|y2g@3ORC4on{o3S;q-I{ z6;WZjZ1=Gbdy+pP@)#xp3~tGp-gTOX$g61gjE+*Q;Fc;pY%WjZu=?WU;C9OqEiEjv z5;uNmC;rWsM_u;CK3I+a0M7W6r_Lfk3QWa~zRi%@{x*Gw;y$=77M_zkU!q*^_m-|} z*uGs+-lUmPk4V|M65q*G>Vf{6K4%r)f7zvFBN3#!?sVxY9rI+rBF6n)?S%5OC-}c0-^1!DO_A^lczRwvw z!*wd-!$YeW+ixZf=A))BxckMzC_IT)$(Bg}0357Ghz7&(78rF;!OPSTet-HLNz~+I z5;syhgTMHXsQTe5Jf3ECMH{mK31Ad@mL|XfxxV)BCc_>anP$Kdc(_q~*ZltgXA`*( zXN-!~3Q<4=0L&DK}uFcB>}odm+}A)UWy6x7+V-))9xYDk(?jSA;MXwE<4Bt z-I>kywy#d3rX;GfXh7Vnl1aD#ThiV@ZNB&#{{WG-67Eo+9s8<10Ke`4n=SS`cw2v_FW$<1lH;5t)fI6|9j;=eZCAfQ^IQ--!k{0E*eD(JCoo=7%%;)G-u^5*P`1)1seP}Hi+Q$%Er8D3R9sJU`9hnSjyl@><`NGC`F`wx#jg7|i^jD{zLi7Z5O z%BUFiWnEfO_?;jQzIezU*IX@0K}}1N(z_%SJj%&j4sS9^b%YLXx|r%a?_;NJupO+& ztTx~WNu8*BWXvP56EXAI8s3|XPtkiy=BctsM^E-~VyUIgLHN_~{{Yhx6r4ZKH;j?L zh`Ri*{{XHi)v)BqTQkyI+(E#~_q=0&Er|9106Su?&$~U53GSPD+W!Ej@5RXn8Iu11 z7`1`6*q8U!VbC9!U*U#P2oZP0&pbC-$Sw#rZ6sU4l-v>YBz_pvyf5t~Skat^xMLi#v~nrZ%Ie6X_#GLhm4xbne8Jt7>bJx|*f+&%4*`gYGaW#En7G>D8~$JC(+jeLBsm;TpqzPq zMS{{YAE!+f_ZciCcd>NIzQUHHwX&d^rh6jvG77`*U*M5WL zwi?Y_^IAI(5MWzX~mESerNju7!>&@DW6 z3$0WMT>!8J?Q~AIRJZ4f-#?>}v1ej`9lt%#sldF=+{V0|L%KdbrljuW&?F~tY8-Pa z2>$@$zj%C*MuWgx0h#9+w2WDtyKYM{)JgRFqXBh!ih@T^QhNUEH=Bv#MYf<%kldUq z-lGUGqCKq6Se^GiruM{Snbw=#w(&j~hp*yN%1BZ^c&@V?>DZf+e^0{$T{|)66Y&ZM z5Tl7W;IJV!AGCU(m-ygOYou#}&12Vdzt0iRGak6=Ip1&;{-pl^56F7q^`%#=T-sR0 zmSGwAy7&*@hXPRGg*HAW_6zeP$Ix%`z})ogPeMOa^CS0uI93?Q>9?i|8?b>rd6Toz zhFvmABPchs%FMSHu?k60KqsK_IAbPFPv`hs4P>8h1BSlvJg_~Pm)-=oyDQ=oNex5O zB`J{%uf4U4!hysW7&47m|t++JoX!t^u=ewRgS_)l}6)L?`_86 zK=V7>*9IM*_Kvj8eHz#)QyFa>p{sN{{Zf3(PDrY%Zj72 zq?i!lY{JIDjmNIoh{`>msvtL{u9_9_TNhFCR=E7H>xc@UY>KG%8GI?_t)y?x$`8{P zhh!bF)aGWSJs4lU;OfJiZB(dRqJV;_{`c zt_lNY^Z@?fx<)@CS8NaGIsJ4&obe?S*f9}DLk6}W5~`)DwB4G^b|4GfoHDg*KdDpn zAK*(Dqul0MxZ|H%PUDE-|rom`HW~x`m%z=LmWsCQi`kp z0C%oGJ+n^J_@7j5PJ*@>lsY)3rbb@#DM?dXDzG3BRz^ogR@4pEN_c0qZX(n@;*y31 z^O|~C{{a2m?&JHIM)cHHjkjk#ag58UuErV6y*p<1gKU_fpJi&gWhUQzvHt*sFvh=trMFOg&~gt4;vuhfuFpyBHFaP5O(cG) zI*$PwK)d-K{r%V6!M$Z)ucnlC=WT;(CuOK zBz&>4xT}jP7BpIVni}Z{(V?>lAdPf@HB0e31HZtI#NO&JfgUC7r!lQT9X54IK^uRu zp`%$ohGSG6kE)^^VR^nIs%%uEwf8-L-^yy^NkZk$;{|E^2I1VIJyWtPTWM=0Qrd?7 z$Ziy$A*GHpmmB*{QmZh5WUA7{BRE(o^xthUuY8Ms(k?B^zw~0uEAuDLURE~L?@M?3 zyp@c8SYz4;`ZywnC2CB<86_J_6=TN=w)+_5j`|1}1teG0ZD|t5`ZRc2gPlc%&(8v8 zU*aPesQ@1xWg(RNP(s!fbP>wE4uTk1?X+?YBX1*rToL72uMSmod9wFAk?_ZVMLfvA zx>R6eKK4&|R!5ei(sXI1eX(nq4bi9TRo z>y5!uRxr2%B$u=EG`@Z8sFe$@infxd5pW%hG7qYW5dCxyOjLYH?B|?Q-t>~ngT^g2 zAAn6y{{RjvDmv*RYpHnK%}GP~TLu|7ZI#g*ikVx{osZY4-`5_)52hD#x78vh$ZFE! zNLnj(=EKYJwY%yGH}C@w_-clDoJf*{UL{{UO!cfa)sJ5#Zd^p(;gvir?ehrcm-@~XY|I+a)} zTx@UDZH}OjY_OqXHUmwReEhJBW}@QMvTgwi&Q{>`Ztw?5@I45`#Sact)NJx4BqyrI zLpdJ0NFP$)H8@~dfxwl(_nxN}B{0%YKB3K)D0d+E0!8dPYyoq9m#GJRp8Gje<_?qQ zZqQTwOH7^FSboU_5diZos%uM8Xw-sHq(3-pk<^Hb0&NhdIl#EgE>i`o(_qAC#$JXA5ds94ypxhxLi z61S2`Z?>XJ0#3OXdsUr_=b5i5qoEN^99Ct5swI&P?hcJs2-dqE_y*e?MdaSjnVi!v zyg@4JJ^7wUrPz3PWnz4lK+-)1Eo|-?s3PRk(@zo)icJhz_S~}oK)+tL++tR|bU7wP zLp-+tez3bP?Ls(`Gf_)KD%FOxr!UJ;KW&NLO|7MNP5Z|dQ}*AMPflU?XP|a(?L4T()cC8hzn(DdYzWR+%21uyU&QaQJ}0giJtp?|pr@z}u^@Q-Smrf;6REb( zFg`!FCs(EMO+6?Srg7gq&4JpkdqXS*moS>5W%wFuSkhzt8DxppHXc?$dhd!O{&pE- zF*LJ8pz07*B3Dqe4uukZQbYx=BS%GB?7eYQ<`pwWF3uTz?Q!+-ALo2>IL!#LWj>Z+ z`&xO!A5c0)oPXI z#L*H3gw=VRBY)Xt<|_|XVlkEH;uudw1gs?sw;zVELW(r`#R$MmWKDJ%=0F7Q2zTmG-_9S#U7)ilY6$URy!WJ z#1e7x+u#5X=>hs-y*CmEYba29{9Om-j#pWw)M^O`N)KU)(dg}?PCZ_uHJ)$Vgmf(G zGpx=Cq-J=br-q5Zjh^~-%M%jO-$~SU5COYh>7a%TrxjS33Y2cA}*-kTy_Q zQz-8IBH#n&dg7GKDuk8}5$)3U*q*qwdnc$RUYycNH9X@?f*4uZE;e;2rsQpL;swUw zW22y0D^+vI9LzhB4UEaaJtm&)>$e=IGNxFirj26`3N&=^MJyAcI%Vap(O>UqI--$H zij^c{f$fvA8fYqIsDUJ;GBV9iS4_p}R$;4}h98ceIre^5r{qY*6v+tEwVrpu71?D; z(;UG?w9Uzrl`MT!P22z*b-tEEeuJ%@!ribL6GW?HYdma2D_^N!2460Oc!7qQSvl$= zi0haSm3EqBJi34*m=B0;8=nhqbd%-qp9A5Cd4%BHIN12%{{R+tQw>lpPT^Q|jgG|m zE1sVwxZkM2&R>w$Q}OlmQpi7|K{|l?k6c%NM-agC&q&iKq?U?*dZZvVtjpC| zNd&1L0N8zgpp?Pegb}>53OapN3>vBmsDW2-x_OXP0$L(R#Dr;LH2|zhXyI8&ZA(?A z_qw_ez>fpoweZqv>IVLDT|>u8DE!W^(;2qt*4Ey`oMY}ij4))z0gUrbKA-|ef+=Yx zbYvk}UN#NXTrse?9!GAN0{;M)4S(mG@V+fMABQ6sFtn}Xd8hvXxQdJP!%2Hi$s_)6 zEsgEdRC=%f0BbA%0NuqGMOyU){rUd#0};`Hl|@Gyxi(j0^V|2FJfz`l%BN`Qs^z`D z2qhzags@uy>PQ&1seP-WgKAv5ni2gKjz6#2!Vl;5#8!9hiC+Hz28hRy1;6hSKP)no zh5ArQW(TYOk)I3uEM{)UnG8_d{ry6r9=3=|+j(04m^6pk^DL$TvpmoeH!;CwA0W~O zk+<;(pDa^3&uuw`{{S6K#B{Qdg5F)gr|~!qm05`=soay->*M(0z)0&AAa(|6TF%_^ zY98)aL8*YTsGMqY-EIrJwx277AdQmNCZXfr+N&!`5=d1K`#A2R-bUM>$a-KSl08r5 zj))^-G~8c(t~?I*+Y$3BNyPG=oLp+S7u+qiTgKPg{#V-$Yikq|BaA9|YXP6;&0)Fp z01p9#Mid9r7a1@)#B)uXSX%q}Sbn%7$TP_a5l0{#!(s_ghW`MytGjPgfsb-0t-l;} zxlr@K&YyJBr^LLmf&`o53N}U|(?PdX*;sjk2}T~Pi0S}>`jj|7v{+i+MM$yw9D7fe zw?O9JULUR;%a<`0B%kb${eL`9;p`IauBDE87*$Q4(U{UXAdRdoaBSoIU@KqL{y1?( z!_bg<6H5pt`dL<0zx9->emB5uc|E+(t&Rz@&K;BuNXmTyWj~t zqsZ^xNv2g=r@2uZ4*|?|Kizc$^CJ?KeWGU3+n5W1;$ezGZ&Hd+;&B$4wPbtfC+My} z@f;+*piL_*DH7{q6aWg6eSEFdpDZqPHMc+}o{;|l@hO;J z*SgDzIQxHA{&J3mhxB>z{*!*}OYy%D(!msTu?Bf#A8jGMwKnBI>9za~fW>0fu`%x; z-^Re4>Qz@f0KmuI%_n`wR#>5>3kc;>epN5-bVB}PI3DC$1rw-NzOd!CyF4h z$KB$NX<2|85k!(l8tOMC*pRlio$frT_MoPSm8XWfWg}*)toLz$Sf~;v{3?ET@vjyr zo29T>*+*ni%Re=Wg+eW?*)^XQHg4+p?czMJr6*59o$Jid@i+006unNK-aCMJ1K$(q z`$MYCNvTRynv3*J+voR)ngk~P2>8{4k+MrB8@m_L*y*3QO3 zEQnma&Z8h@5(d5XYVTjJ_-Gosl_GODRpNw|uJkzeBR`%;Sr1Rcb>=AQ1T_Ba;fv27 z+N>G_Go;9jWR6g%bfc&aY!!|6uXA2GRz1`VI$hK){XkaQ{zZu%c(wRLhZ>!WC3{3z zjYc_Db=#()avIk*)DKhUZx60`Z6`a`H*erie@^JF(a4e z`}eT}B0~^m>sJjGVEaV(X%9wAv;_KYWRK*mK>eHr@i%8xG~-$hY-e!5>Qm^l00sX5 zqQP6!5!nu5eSx+A00WCBhd8cEcCwIBzBJjRBgv702k^g@u{)HUcb4)SZsF2Zlw4VU z=y@T2hRo5M^y;JnJs5p4B_>l*V0n^%Syctc^_47fVeyY=RF&#l0+iJ&auD3bA-BS< z@gXOspv&Y&DEgY3swqrmq>e;8fW!}_iBb=N7Z_kKyitrH{z6?>b$MI%q;_-pllfZ& zxol1>79fk}EI-EsId5(fuk+EzH>{B*{{X(B8~!X3<=wPWx5rJR%*QDo@VdDC@JxZy z3!K908elxh#LYZDV&1qGpyH}2Ev9J`evKW#`m28I5XVOm_$t$T+fb2j_^BACVRI!# zB6T*msr@a6b$L=7g#aJJ^T)B|kKrV4I*l?X{vr?MiHd$4kOO2p_=XMoVhKHj^a-1V z!8=<20GF@V5g*A?(#R%-nkffHLu>jU1_$<75PY#?$(G8W>|`tbR_pkF{4jc^EDn=( z+-+i{9gl`6yNKpkVr$O8cyh9?1?R;aH9B=LB!!VS($>(y8_h4Z{{RDCFX76{NSZ~b z6EcqKL}D!M;GnxlZ&GbxjB&#~vDZ`09H~=L++{4h!b2!My0fl@l(5;8i8V_ta>ceIS>h?QQlsuL76;iVw~(Gn;m z_fl3YLi|L6PUgUEjNjUCYx8DdQI$vpGrFs4kgvj|5>1C+oxHK2xVyG|!nzRzl|>`( zEP@1%Hknvhtc_-CTK@nBgX(Ytmt|1XBM9RFD7m-9PnjotG#mk(MK&Dul@|-}D@fhw zq$oE%!Y}D_Z>_O!B6EjF;kr6y?lLAsK6Bh$+Gj?Q?<$GNZq!pE-uSY7jE zI3Z;}L)x@MccVkF15UBi)7PoD@xxtQO8ZZahDc`~htB;`=;W&bl z-PnH$dX2vo7#KM3Ad}ogXnS=*@le9T`)ZC${Z6mYVR?I0Q*tPy8}t#qh5WnUt``3Q zl@#_LW+9TW z?MsLJDBvEvohR~9x95e9pB)-Ly3^5?BVCrqFUDDYZG1;hlf(!Kdu_QNMh!(f{Fb0XeaxlTXfbO-Pl_LtexOId5;up51s{#k!^ zC(S*iqA2SD;i3Ja0q|7c@p3;UAKJo)EeFKg$REu3lj?48c)rZ@o|Uj4`nMmW;WO;z zT0RWzj=6Xd@0*2c8%HOH=o6iJG3pGZi~DEIlPZz7dXJvugDFfxc1? z-h&cb;&?K_*|=3to*7BOgVzL4kk&2l10R#a`{Z0TY6`#i5B=zW`?!t&01|{Og{0w^ zjkPWQU#28#bNPo@mG=AbES)__y|L%H)_B7p^}J{D5@Et*)1JD=_5uF@$A#>sw>yaD zSR4!q6E7LhYkRyPSdBb_2d2T75j6ZyD01eGnnC*#KBIait5JRAn$PnTlEBzsYRiemJ){Sa9=o%a;C4R?Ybm z56=|sO-#q(ib8*?2j{B{#$Q(7`#higvHHFgvq~GGA{A`=O^?Ezp;ObZE`p6I*UC9q zp}&re*5ume!2UQL&bvOMtDR?hDB-C`SwzrCcI${N`jdnd7fKo?BYUMOQVsf!>h$Y-;}m2aiPyRQ zZZJG9C*S3wn2*l}`5$L_j6^AcT0W#JxF10AFXwDKT{bAfn8jkV#f|$*dcU`h8H;XR zA-CNS^B8(lQ>}4Bfgs3Q?>}IlLvP2n%&^lsGy*J%&4343V4<+bOuTtSVOpnlfA&7>@gm;tZJu9s0iOgntMUrm&~G+S@8h$Q z=(@ul%*Wtkrvr|3_Mx@xRFdS*gx)JiynQ@X1ssr*WBrE>`kWrc-Ho;gGF_9nBUG<^ z!uEbsiMOx=qi{eVz?cy9jq`7A7)hPZA6txl!sXbA_yoL{u=v zrh47uoSN@xU7hK{Vo%_QWt=_B6FxzMf_yVm(DPb;%xoPev=H;jjJp_vRHWza_}6<) zX0|UY93&PxVFQG+^Od`k2yM|nF8@^GOZ+{g9gb@}@FK=(m6Uk2yaUaRI;JNtqltW$ z$oQpFStJOpcS<9qfp>om^GJ9iF<#;(z%K>)Eb^jKb60~Ujy`PE@$3WEZSaPeZ<7HW ztFZXQDMDFU7y2U;P9?onPQ10Po zgQiQ7i(WBG>)M^_Ug#WbF2@g<_T}^Q2xVZ0G!m=d5#6!&j)(i3#)H^;bs!slZN(Cb z@4=5RsNT8TOd1PdgMP{!s5%fJ!^q$O%+d!i>zvg>oW$~F;cMU&pTiM^H=B_33V8!8 zY{&TO8cGhWYigyK)v3wa3=2^C=E0TI?_s-fkd9e?A<+*NN^tKu?umPWFDn|iw9O0g zwhQ}<#d8~>8cU$Y?ECab87MTCYARDeAJXz933ZoVjHI{N!>9=dk?) z+2b2uSNlmpW6tm=YR?%i9Hf;LYL+_LeIk%*Py3!MkUjuk&pq(#nH~;)vwuz+UMdIR za27nKSB~n)7Qu?g@w608q7ny)(^RNpsz#Hd6A+#r1r(^AoAiYDF+zGgMX{d{kgFL0 z^3(Gp|5|`kOYjF(!siyg%_9HgrEzIRYI3(qvC>}(=kc@Zp2+C9-6l>^;k=U}ru4_E zW#)(H@yTAJ(5}7KcJub?Pk%y!=gc89A|@&`M(0w2QuKe$;rtihpf-9E&1|U2T8!Q$ z&$hZBs7AzC7T6MOa!XbnxpvvM>X0uXY-weL9LCo>mgOaO=@-W~l*qN4_1Uss;{SYL zh&lz&gZZc=9BW+m82kOx>{aQRw=k`#NAoYkS5FHI2+@)gVydbGQ)#WQBUdIHv5(}f z9}AvhVJvQ?1*Y-Eom#)L%e_TdCt`3?7Bvof#2M9&zq28lGXPnCs6d@!dRA-d48Bm{ z0XA8 zihY)FmP=nl3pmH+#X{_n$t^1LuzZef{->8><3R6KiHzxc+PEq@y2^1N*-zTwqyI?t z+UXN1VC2JX^XH>8@0DW;4cioupY56~g5QRnJN!A^$-4JQOQRuZyi0>q(_>h~aC{br zWgSnv!Th3Gxg~wk-l)y7e5w>kRUWfJ#ae{4(72DY6)45{r+)qJ$CpApqDiQS4&N{Z zLaeS3uUTh%y59?O@$L5S0P1)DSX6Jn`)fo?cU^5K<(4aGWi!Q3Qma%0%xJ~aOwhK? zC#CG)L#l;o&kX1nMmLQHB8hrtv1Qy1Uuwwh^q^tE;Ej~#~Sc1zTH9+IaQ~9 z5Jg$N88cCOBU9nEzJF`>LESrg&H5U}DP0D~)>nUmnF{1`BwR}Lci>iL<>BS^D-~mh zW3hvYat|H==dC&kj`)0EUKgNcL%Y_+>QU;BILn{xaojNgx&*_@m17$nd}l4DfYWfd z1bKLFIQ2xEe9*KN<2KtJZe9%ojb3^&uBnNnF1K`)DZ?){NU=ftR`cO1&|hZ=fyt5J zYH|@gxcnZjk>6Z5oJ3Ll`nXm8`yVQLxcCn9CwXtC0oJ@AjX;ae#Zt4% z7VQ-D;fq_-Y|z+4avfp(SHlr5W$(wiLqx(}T24PGXp5U(3Av4qErmpl(b%BvJ0z9> zCHL+U#Qrz>7fDGZs!xdOobgt&)-JvPKl&l{+3&q{LFKSLAg%ih8wswqy5N^?bJM@m zonyun?21<{^B2^?eB%wTy;eyKvst^JWl@XNNo=<_H+d`DC*Wk4D9wzHku1KKi`ApP zqmKP8Op^hJZlfQcN(}aSWm$M%KIK{7LlUt_Cn{-yV8I4C=&&3819UGt2+RuvhIjb+eOHR$@ouQ5uE$#GvIzEm1_v)<#L4%jo%_CEYfq zHF5y_9wTKZJkr&Q#e%b6F1ZS<9lFypLLTBTc^?1!kc9K2PURI5ZAJP$&~uKVKM+F8 zZF)17Sf>I2sA7Nq)?&Zee;2$$6hClh1-EbKRqGpX?tdjJ0hJj){Be{T*;LFYt2PY+ zOa4hct4Mby+{5XDcIDpg#?)}FsfN*>5o#r1LI`o*Y7a;2Wb%VcOHeG$XH{w=&NEGB(t+7Jo|+%pq`O-XE{_xOVouQEhl{bCkZ}VL}H9nC~=#;dkHw z9VT}Is_8~d0a^%l2CH%tvE*uL%oOv9(G=M3RHoBdCY=ObOH^KMRKJj&09=B(0 z6kLBxoBEc~cRMaS;^5*k1QK3WCf3&)j=ETMGiMPhN$P#Iv5yo{YR8F&q}}{iB6k22 zRMnFHM@OhHi~rIM!c!`lF~_{rU8j`wANe+-rFa0AF>+A0H9C(68dCv~ZYbI(Y!`wV zlOKr$StO&b0IYJTaA8S2K5RV`xoQleLrJyz*8m{k_)H#;7%6 zAI?Ko(O=NYI&4s?e8M>Cjufnip^H6o_S99EVQv5q$-hXy$4cLRujI>vV~l2PH#n+h z-c_6Sfx`!o0wu-nY)}~Ny03td&-o8|;S$Lao3+qkw|Gb{CQ5^Ln0woW<~k`M?gD8u zu(k3Vrt{~dO2O_DE&|lfI^Suip~!z30i+Z-Ct==Cj$7LHOS2~QcQS5!=oNXi|Hz(T zOzLZOhu-8uWLgq{bg6t91@aT!;EErQ-B7m(Hcw-o>6dim*Gpe#h7NuwP(RaMLm=b! z`Bybqe$8lfjQ;Xo_64q(dn2XzI*YK4V>tsZA&*Cw50_iK3>ktVEi78b6MfL{{m=qI zK!Lt)_+YN+`bGQ=@2do517$85XZK6`)z@@>8Kak_p!?Tqpf>~QwkP+_q3F}vj}iTL z5MuiP^atQasTkUXG@^Bvygs=P4Z!WWzMrToIfQ7N@E16EC8ILH1K)AMdQTWXa`wuD z!|o$>MO$ZPJM?Zq*&w@2mo`OlYn3*>Ue<-Hh=odVLb`G8p_{6KcxyfTO*oN1Z>^^I z+2Fwt8}uGRUgbOlRkKX38BYy;x$+O41R0{X*@lP{sc<6HZS{^<&z1u8NrSJ=Wr|q@ z@3RCpsJ|`i?dCff(Ny~!e^Neq5*76l=~bQdbi@L}@zG`4oHD6iGQqgd8C>o*aCx^= zCxl0XIh@lE%;a!JI(KkF-+6T^%9zBsium2hj1>14tEv;5M)(53aHotJyOiHGLhUxK+$zOUh9blIb-PpO{v|1sx$3enb;_p2 zoudwTB1R-2L_kg)!v>s^#5WNtURHTPK%76Wks-sq^8~Y8kU%%bR8qOWnY*`7Q$FU( z&B+5>8=sy4Y$G|^B9c81 zd@-ujGbTEwM^3|iE~D(sL%^CVN$>@16*YgNPnGFMg*BbXG;60wSKA5Hiyfr1w60Of zj)3oEg8+WSoyvJwTa$WwU_E~1Hpy*g&X)}el~(kjWc#7V1jxV(Dk_-BE=|1lS{z`5 zM$5NaYAwf0CkiUdySRv>3_;TruIKgTp7KyiG~FkXLgSASi z*{IAOThO_F=MJ%UVd#J=ZIxy#aF7cC6bCz*C`^UAyk%aJaYIr3+5-5+{!S94ZTuK< zD#W1>d~dFe4bmWfXB_$}q0{`}OtB((Ag*&O>4Pyd0>q5dva@U{F8IMK%j|hX+m2*z z&BNMVe;x|Xa0McSc=_sIZ?Lt$yY#bu%dg>FIu7&+fwK%#)!m{3R?k&5LTeA|_86<{ zc_B~CZ`M>%YS`*)q3{cQ_}fA@sQyO&cIz!)m+;L1(@O@xx_g+(BAYx9_8Cyu_4bf& zHw1)?sUFdm+Ye~@m|uQT%H?C>$u*~}em!J^n3j6P(cA^$UZSZQDy_uLdhqL{Z;``~ z!2@ek9yx}CaJWoLl+#)BRBiABpArMOt}SVYn9ktx5IpKHPi8!rx25u$r!8?gS-JC#yjSs?a;@oZ4S|C*KNDI5f)n?60cVuXdJsjIL-P8DYI;HW14aW933w#ZAXyy?Nv91stf|p$N40b%Gvnvth0|kB56!WWj?&7FT2MS(DIr zNGqX#3+<~8>!$S4($9-u1W#x6o(%$^%aD*O&?41?&VHWSHkmX^`k% z4aPx|i)j*U5Xu0sMV@uoR^tZ~)77Uq%s3N>$LoI!vWd@Nhhs=X@PoUdm`dHmln)9l z;t6-3);n|+G;rTb=;-#~@)=1w zxr)JbSu4Q1Bt$u{-ry1{SgqxwBG-YP;!zx?%Io}Q`JNTaCm2&PY-^IbDaGY|rqJq! z!47Tasn)7x(jT4zHt1?LDW(({AyU)fmf*3UUq=y!@e`@3&?6ob@DDkZ8w?F-_Jiw&WJeQLr9uI0s+b*of2wNd{D>& zK47HthXaOlCdC1dHI@uyPMOP?OLQ4=r%;<5IyVFUzgg*dy!;oKr7@v06U5xCLzP*; qmVFn|Nq}DM#-*>h=7#srpp(R6tLaHu{f*g#yTO2NVWkz>WB&oA1NF@S diff --git a/newton/_src/viewer/gl/opengl.py b/newton/_src/viewer/gl/opengl.py index b2c4afc0c8..a23ca97783 100644 --- a/newton/_src/viewer/gl/opengl.py +++ b/newton/_src/viewer/gl/opengl.py @@ -15,8 +15,8 @@ from ...utils.texture import normalize_texture from .shaders import ( FrameShader, + ShaderArrow, ShaderLine, - ShaderLineWireframe, ShaderShape, ShaderSky, ShadowShader, @@ -972,6 +972,8 @@ def __init__(self, title="Newton", screen_width=1920, screen_height=1080, vsync= self.draw_shadows = True self.draw_wireframe = False self.wireframe_line_width = 1.5 # pixels + self.line_width = 1.5 # pixels, for all log_lines batches + self.arrow_scale = 1.0 # uniform scale for arrow line width and head size self.background_color = (68.0 / 255.0, 161.0 / 255.0, 255.0 / 255.0) @@ -1138,8 +1140,8 @@ def __init__(self, title="Newton", screen_width=1920, screen_height=1080, vsync= self._shape_shader = ShaderShape(gl) self._frame_shader = FrameShader(gl) self._sky_shader = ShaderSky(gl) - self._line_shader = ShaderLine(gl) - self._wireframe_shader = ShaderLineWireframe(gl) + self._wireframe_shader = ShaderLine(gl) + self._arrow_shader = ShaderArrow(gl) if not headless: self._setup_window_callbacks() @@ -1201,7 +1203,7 @@ def update(self): # This is a non-fatal error that can be safely ignored pass - def render(self, camera, objects, lines=None, wireframe_shapes=None): + def render(self, camera, objects, lines=None, wireframe_shapes=None, arrows=None): gl = RendererGL.gl self._make_current() @@ -1265,6 +1267,9 @@ def render(self, camera, objects, lines=None, wireframe_shapes=None): if lines: self._render_lines(lines) + if arrows: + self._render_arrows(arrows) + if wireframe_shapes: self._render_wireframe_shapes(wireframe_shapes) @@ -1838,15 +1843,62 @@ def _render_scene(self, objects): check_gl_error() def _render_lines(self, lines): - """Render all line objects using the line shader.""" - # Set up line shader once for all line objects - self._line_shader.update(self._view_matrix, self._projection_matrix) + """Render all line objects using the geometry-shader wide-line pipeline.""" + gl = RendererGL.gl + inv_asp = float(self._screen_height) / float(max(self._screen_width, 1)) + clip_width = max(0.0, self.line_width) * 2.0 / max(self._screen_height, 1) - with self._line_shader: + gl.glEnable(gl.GL_DEPTH_TEST) + gl.glDisable(gl.GL_CULL_FACE) + gl.glEnable(gl.GL_BLEND) + gl.glBlendFunc(gl.GL_SRC_ALPHA, gl.GL_ONE_MINUS_SRC_ALPHA) + + identity = np.eye(4, dtype=np.float32) + with self._wireframe_shader: + self._wireframe_shader.update_frame( + self._view_matrix, + self._projection_matrix, + inv_asp, + line_width=clip_width, + alpha=1.0, + ) + self._wireframe_shader.set_world(identity) for line_obj in lines.values(): if hasattr(line_obj, "render"): line_obj.render() + gl.glDisable(gl.GL_BLEND) + check_gl_error() + + def _render_arrows(self, arrows): + """Render arrow batches (wide line + arrowhead triangle per segment).""" + gl = RendererGL.gl + inv_asp = float(self._screen_height) / float(max(self._screen_width, 1)) + scale = max(0.0, self.arrow_scale) + clip_width = (2.0 * scale) * 2.0 / max(self._screen_height, 1) + clip_arrow = (8.0 * scale) * 2.0 / max(self._screen_height, 1) + + gl.glEnable(gl.GL_DEPTH_TEST) + gl.glDisable(gl.GL_CULL_FACE) + gl.glEnable(gl.GL_BLEND) + gl.glBlendFunc(gl.GL_SRC_ALPHA, gl.GL_ONE_MINUS_SRC_ALPHA) + + identity = np.eye(4, dtype=np.float32) + with self._arrow_shader: + self._arrow_shader.update_frame( + self._view_matrix, + self._projection_matrix, + inv_asp, + line_width=clip_width, + arrow_size=clip_arrow, + alpha=1.0, + ) + self._arrow_shader.set_world(identity) + for arrow_obj in arrows.values(): + if hasattr(arrow_obj, "render"): + arrow_obj.render() + + gl.glDisable(gl.GL_BLEND) check_gl_error() def _render_wireframe_shapes(self, wireframe_shapes): diff --git a/newton/_src/viewer/gl/shaders.py b/newton/_src/viewer/gl/shaders.py index 2b26614103..27b831444b 100644 --- a/newton/_src/viewer/gl/shaders.py +++ b/newton/_src/viewer/gl/shaders.py @@ -31,35 +31,6 @@ """ -line_vertex_shader = """ -#version 330 core -layout (location = 0) in vec3 aPos; -layout (location = 1) in vec3 aColor; - -uniform mat4 view; -uniform mat4 projection; - -out vec3 vertexColor; - -void main() -{ - vertexColor = aColor; - gl_Position = projection * view * vec4(aPos, 1.0); -} -""" - -line_fragment_shader = """ -#version 330 core -in vec3 vertexColor; -out vec4 FragColor; - -void main() -{ - FragColor = vec4(vertexColor, 1.0); -} -""" - - shape_vertex_shader = """ #version 330 core layout (location = 0) in vec3 aPos; @@ -367,10 +338,12 @@ if (up_axis == 2) up = vec3(0.0, 0.0, 1.0); float sky_fac = dot(N, up) * 0.5 + 0.5; vec3 ambient = mix(ground_color, sky_color, sky_fac) * albedo * 0.7; - // Fresnel-weighted ambient specular for metallics + // Fresnel-weighted ambient specular — only significant for metals + // (dielectrics need a prefiltered IBL for correct ambient specular) vec3 F_ambient = F0 + (F_max - F0) * pow(1.0 - NdotV, 5.0); vec3 kD_ambient = (1.0 - F_ambient) * (1.0 - metallic); - ambient = kD_ambient * ambient + F_ambient * mix(ground_color, sky_color, sky_fac) * 0.35; + vec3 ambient_spec = F_ambient * mix(ground_color, sky_color, sky_fac) * 0.35; + ambient = kD_ambient * ambient + ambient_spec * metallic; // shadows float shadow = ShadowCalculation(); @@ -723,30 +696,6 @@ def update(self, texture_unit: int = 0): self._gl.glUniform1i(self.loc_texture, texture_unit) -class ShaderLine(ShaderGL): - """Simple shader for rendering lines with per-vertex colors.""" - - def __init__(self, gl): - super().__init__() - from pyglet.graphics.shader import Shader, ShaderProgram - - self._gl = gl - self.shader_program = ShaderProgram( - Shader(line_vertex_shader, "vertex"), Shader(line_fragment_shader, "fragment") - ) - - # Get uniform locations - with self: - self.loc_view = self._get_uniform_location("view") - self.loc_projection = self._get_uniform_location("projection") - - def update(self, view_matrix: np.ndarray, projection_matrix: np.ndarray): - """Update view and projection matrices for line rendering.""" - with self: - self._gl.glUniformMatrix4fv(self.loc_view, 1, self._gl.GL_FALSE, arr_pointer(view_matrix)) - self._gl.glUniformMatrix4fv(self.loc_projection, 1, self._gl.GL_FALSE, arr_pointer(projection_matrix)) - - wireframe_vertex_shader = """ #version 330 core layout (location = 0) in vec3 aPos; @@ -790,9 +739,13 @@ def update(self, view_matrix: np.ndarray, projection_matrix: np.ndarray): float s_depth = s.z / s.w; float e_depth = e.z / e.w; - vec2 dir = e_ndc - s_ndc; - vec2 right = normalize(vec2(dir.y, -dir.x)); - right.x = right.x * inv_asp_ratio; + // Compute perpendicular in screen (aspect-corrected) space so line + // width is uniform on non-square viewports. + float safe_asp = max(inv_asp_ratio, 1e-6); + vec2 dir_ndc = e_ndc - s_ndc; + vec2 dir_scr = vec2(dir_ndc.x / safe_asp, dir_ndc.y); + vec2 right_scr = normalize(vec2(dir_scr.y, -dir_scr.x)); + vec2 right = vec2(right_scr.x * safe_asp, right_scr.y); vec3 color = 0.5 * (vertexColor[0] + vertexColor[1]); vec2 xy = 0.5 * line_width * right; @@ -829,7 +782,7 @@ def update(self, view_matrix: np.ndarray, projection_matrix: np.ndarray): """ -class ShaderLineWireframe(ShaderGL): +class ShaderLine(ShaderGL): """Geometry-shader-based line renderer that expands GL_LINES into screen-space quads.""" def __init__(self, gl): @@ -869,3 +822,125 @@ def update_frame( def set_world(self, world: np.ndarray): """Set the per-shape world matrix uniform.""" self._gl.glUniformMatrix4fv(self.loc_world, 1, self._gl.GL_FALSE, arr_pointer(world)) + + +arrow_geometry_shader = """ +#version 330 core +layout (lines) in; +layout (triangle_strip, max_vertices = 9) out; + +in vec3 vertexColor[2]; +out vec3 lineColor; + +uniform float inv_asp_ratio; +uniform float line_width; +uniform float arrow_size; + +void main() +{ + vec4 s = gl_in[0].gl_Position; + vec4 e = gl_in[1].gl_Position; + if (s.w <= 0.0 || e.w <= 0.0) return; + + vec2 s_ndc = s.xy / s.w; + vec2 e_ndc = e.xy / e.w; + float s_depth = s.z / s.w; + float e_depth = e.z / e.w; + + // Work in screen space (aspect-corrected) so arrows look correct on + // non-square viewports. screen_x = ndc_x / inv_asp_ratio. + float safe_asp = max(inv_asp_ratio, 1e-6); + vec2 dir_ndc = e_ndc - s_ndc; + vec2 dir_scr = vec2(dir_ndc.x / safe_asp, dir_ndc.y); + float len = length(dir_scr); + + vec3 color = 0.5 * (vertexColor[0] + vertexColor[1]); + + // Degenerate case: line points into/out of screen + if (len < 1e-6) { + float r = arrow_size * 0.4; + vec2 up = vec2(0.0, r); + vec2 rt = vec2(r * safe_asp, 0.0); + gl_Position = vec4(e_ndc + up, e_depth, 1); lineColor = color; EmitVertex(); + gl_Position = vec4(e_ndc - rt, e_depth, 1); lineColor = color; EmitVertex(); + gl_Position = vec4(e_ndc + rt, e_depth, 1); lineColor = color; EmitVertex(); + EndPrimitive(); + return; + } + + // fwd/right in screen space, then convert offsets back to NDC (scale x by safe_asp) + vec2 fwd_scr = dir_scr / len; + vec2 right_scr = vec2(fwd_scr.y, -fwd_scr.x); + vec2 fwd = vec2(fwd_scr.x * safe_asp, fwd_scr.y); + vec2 right = vec2(right_scr.x * safe_asp, right_scr.y); + + // Shorten the line body so it ends at the arrowhead base + vec2 xy = 0.5 * line_width * right; + vec2 e_body = e_ndc - fwd * arrow_size; + + gl_Position = vec4(s_ndc - xy, s_depth, 1); lineColor = color; EmitVertex(); + gl_Position = vec4(e_body + xy, e_depth, 1); lineColor = color; EmitVertex(); + gl_Position = vec4(s_ndc + xy, s_depth, 1); lineColor = color; EmitVertex(); + EndPrimitive(); + + gl_Position = vec4(s_ndc - xy, s_depth, 1); lineColor = color; EmitVertex(); + gl_Position = vec4(e_body - xy, e_depth, 1); lineColor = color; EmitVertex(); + gl_Position = vec4(e_body + xy, e_depth, 1); lineColor = color; EmitVertex(); + EndPrimitive(); + + // Triangle 3: arrowhead with tip exactly at the endpoint + vec2 tip = e_ndc; + vec2 base_l = e_body - right * arrow_size * 0.5; + vec2 base_r = e_body + right * arrow_size * 0.5; + + gl_Position = vec4(tip, e_depth, 1); lineColor = color; EmitVertex(); + gl_Position = vec4(base_l, e_depth, 1); lineColor = color; EmitVertex(); + gl_Position = vec4(base_r, e_depth, 1); lineColor = color; EmitVertex(); + EndPrimitive(); +} +""" + + +class ShaderArrow(ShaderGL): + """Geometry-shader-based arrow renderer: wide line + arrowhead triangle per segment.""" + + def __init__(self, gl): + super().__init__() + from pyglet.graphics.shader import Shader, ShaderProgram + + self._gl = gl + self.shader_program = ShaderProgram( + Shader(wireframe_vertex_shader, "vertex"), + Shader(arrow_geometry_shader, "geometry"), + Shader(wireframe_fragment_shader, "fragment"), + ) + + with self: + self.loc_view = self._get_uniform_location("view") + self.loc_projection = self._get_uniform_location("projection") + self.loc_world = self._get_uniform_location("world") + self.loc_inv_asp_ratio = self._get_uniform_location("inv_asp_ratio") + self.loc_line_width = self._get_uniform_location("line_width") + self.loc_arrow_size = self._get_uniform_location("arrow_size") + self.loc_alpha = self._get_uniform_location("alpha") + + def update_frame( + self, + view_matrix: np.ndarray, + projection_matrix: np.ndarray, + inv_asp_ratio: float, + line_width: float = 0.003, + arrow_size: float = 0.01, + alpha: float = 1.0, + ): + """Set per-frame uniforms (call once before rendering all arrow batches).""" + self._gl.glUniformMatrix4fv(self.loc_view, 1, self._gl.GL_FALSE, arr_pointer(view_matrix)) + self._gl.glUniformMatrix4fv(self.loc_projection, 1, self._gl.GL_FALSE, arr_pointer(projection_matrix)) + self._gl.glUniform1f(self.loc_inv_asp_ratio, float(inv_asp_ratio)) + self._gl.glUniform1f(self.loc_line_width, float(line_width)) + self._gl.glUniform1f(self.loc_arrow_size, float(arrow_size)) + self._gl.glUniform1f(self.loc_alpha, float(alpha)) + + def set_world(self, world: np.ndarray): + """Set the per-shape world matrix uniform.""" + self._gl.glUniformMatrix4fv(self.loc_world, 1, self._gl.GL_FALSE, arr_pointer(world)) diff --git a/newton/_src/viewer/kernels.py b/newton/_src/viewer/kernels.py index 94cc9c6c01..14f1083272 100644 --- a/newton/_src/viewer/kernels.py +++ b/newton/_src/viewer/kernels.py @@ -21,6 +21,7 @@ class PickingState: picking_target_world: wp.vec3 pick_stiffness: float pick_damping: float + pick_max_acceleration: float @wp.kernel @@ -71,6 +72,7 @@ def apply_picking_force_kernel( body_flags: wp.array[int], body_com: wp.array[wp.vec3], body_mass: wp.array[float], + pick_effective_mass: wp.array[float], ): pick_body = pick_body_arr[0] if pick_body < 0: @@ -107,6 +109,16 @@ def apply_picking_force_kernel( pick_state[0].pick_stiffness * (pick_target_world - pick_pos_world) - (pick_state[0].pick_damping * vel_at_offset) ) + + # Clamp force magnitude to prevent runaway divergence on light objects (#2361). + # Uses the effective mass (total articulation mass for linked bodies, + # own mass for free bodies) so picking a light robot link still allows + # enough force to move the whole chain. + max_force = pick_state[0].pick_max_acceleration * 9.81 * pick_effective_mass[pick_body] + force_mag = wp.length(force_at_offset) + if force_mag > max_force: + force_at_offset = force_at_offset * (max_force / force_mag) + # Compute the resulting torque given the offset from COM to the picked point. torque_at_offset = wp.cross(offset, force_at_offset) diff --git a/newton/_src/viewer/picking.py b/newton/_src/viewer/picking.py index 9c8387c0ce..459deedc6f 100644 --- a/newton/_src/viewer/picking.py +++ b/newton/_src/viewer/picking.py @@ -24,6 +24,7 @@ def __init__( model: newton.Model, pick_stiffness: float = 50.0, pick_damping: float = 5.0, + pick_max_acceleration: float = 5.0, world_offsets: wp.array | None = None, ) -> None: """ @@ -33,6 +34,9 @@ def __init__( model: The model to pick from. pick_stiffness: The stiffness that will be used to compute the force applied to the picked body. pick_damping: The damping that will be used to compute the force applied to the picked body. + pick_max_acceleration: Maximum picking acceleration in multiples of g [9.81 m/s^2]. + Clamps the picking force to prevent runaway divergence on light objects + near stiff contacts. world_offsets: Optional warp array of world offsets (dtype=wp.vec3) for multi-world picking support. """ self.model = model @@ -58,6 +62,7 @@ def __init__( pick_state_np = np.empty(1, dtype=PickingState.numpy_dtype()) pick_state_np[0]["pick_stiffness"] = pick_stiffness pick_state_np[0]["pick_damping"] = pick_damping + pick_state_np[0]["pick_max_acceleration"] = pick_max_acceleration self.pick_state = wp.array(pick_state_np, dtype=PickingState, device=model.device if model else "cpu", ndim=1) self.pick_dist = 0.0 @@ -65,6 +70,12 @@ def __init__( self._default_on_mouse_drag = None + # Pre-compute effective mass per body for picking force clamping. + # For articulated bodies, use the total articulation mass so that + # picking a light link (e.g. fingertip) still allows enough force + # to move the whole chain. Free bodies use their own mass. + self._pick_effective_mass = self._compute_effective_mass(model) + def _apply_picking_force(self, state: newton.State) -> None: """ Applies a force to the picked body. @@ -88,10 +99,51 @@ def _apply_picking_force(self, state: newton.State) -> None: self.model.body_flags, self.model.body_com, self.model.body_mass, + self._pick_effective_mass, ], device=self.model.device, ) + @staticmethod + def _compute_effective_mass(model: newton.Model) -> wp.array: + """Compute per-body effective mass for picking force clamping. + + For bodies in an articulation, returns the total mass of that + articulation so that picking a light link still allows enough + force to move the whole chain. Free bodies get their own mass. + """ + if model is None: + return wp.zeros(1, dtype=float) + + body_mass_np = model.body_mass.numpy() + effective = body_mass_np.copy() + + if model.joint_count > 0: + joint_child_np = model.joint_child.numpy() + joint_art_np = model.joint_articulation.numpy() + + # Map each body to its articulation index (-1 if free) + body_art = np.full(model.body_count, -1, dtype=np.int32) + for j in range(model.joint_count): + child = joint_child_np[j] + if child >= 0: + body_art[child] = joint_art_np[j] + + # Sum mass per articulation + art_mass = {} + for b in range(model.body_count): + a = body_art[b] + if a >= 0: + art_mass[a] = art_mass.get(a, 0.0) + body_mass_np[b] + + # Assign total articulation mass to each body in that articulation + for b in range(model.body_count): + a = body_art[b] + if a >= 0: + effective[b] = art_mass[a] + + return wp.array(effective, dtype=float, device=model.device) + def is_picking(self) -> bool: """Checks if picking is active. diff --git a/newton/_src/viewer/viewer.py b/newton/_src/viewer/viewer.py index 98ddd86fea..469b53b25f 100644 --- a/newton/_src/viewer/viewer.py +++ b/newton/_src/viewer/viewer.py @@ -597,8 +597,11 @@ def _log_non_shape_state(self, state: newton.State): self._log_com(state) def log_contacts(self, contacts: newton.Contacts, state: newton.State): - """ - Creates line segments along contact normals for rendering. + """Render contact normals as arrows. + + Each active rigid contact is drawn as an arrow from the contact point + along the contact normal. When ``show_contacts`` is ``False`` the + arrow batch is cleared. Args: contacts: The contacts to render. @@ -606,8 +609,7 @@ def log_contacts(self, contacts: newton.Contacts, state: newton.State): """ if not self.show_contacts: - # Pass None to hide joints - renderer will handle creating empty arrays - self.log_lines("/contacts", None, None, None) + self.log_arrows("/contacts", None, None, None) return # Get contact count, clamped to buffer size (counter may exceed max on overflow) @@ -647,7 +649,7 @@ def log_contacts(self, contacts: newton.Contacts, state: newton.State): device=self.device, ) - # Always call log_lines to update the renderer (handles zero contacts gracefully) + # Always call log_arrows to update the renderer (handles zero contacts gracefully) if num_contacts > 0: # Slice arrays to only include active contacts starts = self._contact_points0[:num_contacts] @@ -657,10 +659,9 @@ def log_contacts(self, contacts: newton.Contacts, state: newton.State): starts = wp.array([], dtype=wp.vec3, device=self.device) ends = wp.array([], dtype=wp.vec3, device=self.device) - # Use green color for contact normals colors = (0.0, 1.0, 0.0) - self.log_lines("/contacts", starts, ends, colors) + self.log_arrows("/contacts", starts, ends, colors) def log_hydro_contact_surface( self, @@ -1085,19 +1086,52 @@ def log_lines( width: float = 0.01, hidden: bool = False, ): - """ - Log line segments for rendering. + """Log line segments for rendering. + + Lines are rendered as screen-space quads whose pixel width is + controlled by the renderer (e.g. ``RendererGL.line_width``). + The *width* parameter is currently unused and reserved for + future world-space width support. Args: name: Unique path/name for the line batch. starts: Optional line start points as a Warp vec3 array. ends: Optional line end points as a Warp vec3 array. colors: Per-line colors as a Warp array, or a single RGB triplet. - width: Line width in rendered scene units. + width: Reserved for future use (world-space line width). + Currently ignored; line width is set in screen-space pixels + via the renderer. hidden: Whether the line batch should be hidden. """ pass + def log_arrows( + self, + name: str, + starts: wp.array[wp.vec3] | None, + ends: wp.array[wp.vec3] | None, + colors: (wp.array[wp.vec3] | wp.array[wp.float32] | tuple[float, float, float] | list[float] | None), + width: float = 0.01, + hidden: bool = False, + ): + """Log arrow segments (line + arrowhead) for rendering. + + The GL viewer renders these with a dedicated arrow shader that draws + a screen-space quad line body plus a triangular arrowhead per segment. + Other backends fall back to :meth:`log_lines`. + + Args: + name: Unique path/name for the arrow batch. + starts: Optional arrow start points as a Warp vec3 array. + ends: Optional arrow end points (arrowhead tip) as a Warp vec3 array. + colors: Per-arrow colors as a Warp array, or a single RGB triplet. + width: Reserved for future use (world-space line width). + Currently ignored; arrow size is set in screen-space pixels + via the renderer (e.g. ``RendererGL.arrow_scale``). + hidden: Whether the arrow batch should be hidden. + """ + self.log_lines(name, starts, ends, colors, width=width, hidden=hidden) + def log_wireframe_shape( # noqa: B027 self, name: str, @@ -2004,7 +2038,6 @@ def _log_joints(self, state: newton.State): state: Current simulation state """ if not self.show_joints: - # Pass None to hide joints - renderer will handle creating empty arrays self.log_lines("/model/joints", None, None, None) return diff --git a/newton/_src/viewer/viewer_gl.py b/newton/_src/viewer/viewer_gl.py index 002f823f0b..4bff11831d 100644 --- a/newton/_src/viewer/viewer_gl.py +++ b/newton/_src/viewer/viewer_gl.py @@ -406,8 +406,16 @@ def clear_model(self): and whenever the current model is discarded. """ # Render object and line caches (path -> GL object) + for obj in getattr(self, "objects", {}).values(): + if hasattr(obj, "destroy"): + obj.destroy() self.objects = {} + for obj in getattr(self, "lines", {}).values(): + obj.destroy() self.lines = {} + for obj in getattr(self, "arrows", {}).values(): + obj.destroy() + self.arrows = {} self._destroy_all_wireframes() self.wireframe_shapes = {} self._wireframe_vbo_owners: dict[int, WireframeShapeGL] = {} @@ -580,7 +588,8 @@ def _rebuild_gl_shape_caches(self): current_names = {s.name for s in self._shape_instances.values()} stale = [k for k, v in self.objects.items() if isinstance(v, MeshInstancerGL) and k not in current_names] for k in stale: - del self.objects[k] + obj = self.objects.pop(k) + del obj shape_scale = self.model.shape_scale if shape_scale.device != self.device: @@ -727,8 +736,10 @@ def log_instances( resized = True elif transform_count > instancer.num_instances: new_capacity = max(transform_count, instancer.num_instances * 2) + old = instancer instancer = MeshInstancerGL(new_capacity, self.objects[mesh]) self.objects[name] = instancer + del old resized = True needs_update = resized or not hidden @@ -839,15 +850,20 @@ def log_lines( width: float = 0.01, hidden: bool = False, ): - """ - Log line data for rendering. + """Log line data for rendering. + + Lines are drawn as screen-space quads whose pixel width is set by + :attr:`RendererGL.line_width`. The *width* parameter is currently + unused and reserved for future world-space width support. Args: name: Unique identifier for the line batch. starts: Array of line start positions (shape: [N, 3]) or None for empty. ends: Array of line end positions (shape: [N, 3]) or None for empty. colors: Array of line colors (shape: [N, 3]) or tuple/list of RGB or None for empty. - width: The width of the lines. + width: Reserved for future use (world-space line width). + Currently ignored; pixel width is controlled by + ``RendererGL.line_width``. hidden: Whether the lines are initially hidden. """ # Handle empty logs by resetting the LinesGL object @@ -870,6 +886,8 @@ def log_lines( else: # Handle zero lines case colors = wp.array([], dtype=wp.vec3, device=self.device) + elif isinstance(colors, wp.array) and colors.dtype == wp.float32: + colors = colors.reshape((num_lines, 3)).view(dtype=wp.vec3) assert isinstance(colors, wp.array) assert len(colors) == num_lines, "Number of line colors must match line begins" @@ -886,6 +904,66 @@ def log_lines( self.lines[name] = LinesGL(max_lines, self.device, hidden=hidden) self.lines[name].update(starts, ends, colors) + self.lines[name].hidden = hidden + + @override + def log_arrows( + self, + name: str, + starts: wp.array[wp.vec3] | None, + ends: wp.array[wp.vec3] | None, + colors: (wp.array[wp.vec3] | wp.array[wp.float32] | tuple[float, float, float] | list[float] | None), + width: float = 0.01, + hidden: bool = False, + ): + """Log arrow data for rendering (screen-space quad line + arrowhead per segment). + + Arrow size is controlled in screen-space pixels by + ``RendererGL.arrow_scale``. + + Args: + name: Unique identifier for the arrow batch. + starts: Array of arrow start positions (shape: [N, 3]) or None for empty. + ends: Array of arrow end positions / arrowhead tips (shape: [N, 3]) or None for empty. + colors: Array of arrow colors (shape: [N, 3]) or tuple/list of RGB or None for empty. + width: Reserved for future use (world-space line width). + Currently ignored; pixel dimensions are controlled by + ``RendererGL.arrow_scale``. + hidden: Whether the arrows are initially hidden. + """ + if starts is None or ends is None or colors is None: + if name in self.arrows: + self.arrows[name].update(None, None, None) + return + + assert isinstance(starts, wp.array) + assert isinstance(ends, wp.array) + num_arrows = len(starts) + assert len(ends) == num_arrows, "Number of arrow ends must match arrow begins" + + if isinstance(colors, tuple | list): + if num_arrows > 0: + color_vec = wp.vec3(*colors) + colors = wp.zeros(num_arrows, dtype=wp.vec3, device=self.device) + colors.fill_(color_vec) + else: + colors = wp.array([], dtype=wp.vec3, device=self.device) + elif isinstance(colors, wp.array) and colors.dtype == wp.float32: + colors = colors.reshape((num_arrows, 3)).view(dtype=wp.vec3) + + assert isinstance(colors, wp.array) + assert len(colors) == num_arrows, "Number of arrow colors must match arrow begins" + + if name not in self.arrows: + max_arrows = max(num_arrows, 1000) + self.arrows[name] = LinesGL(max_arrows, self.device, hidden=hidden) + elif num_arrows > self.arrows[name].max_lines: + self.arrows[name].destroy() + max_arrows = max(num_arrows, self.arrows[name].max_lines * 2) + self.arrows[name] = LinesGL(max_arrows, self.device, hidden=hidden) + + self.arrows[name].update(starts, ends, colors) + self.arrows[name].hidden = hidden @override def log_wireframe_shape( @@ -980,6 +1058,7 @@ def log_points( old = self.objects[name] new_capacity = max(num_points, old.num_instances * 2) self.objects[name] = MeshInstancerGL(new_capacity, self._point_mesh) + del old object_recreated = True if radii is None: @@ -1084,8 +1163,10 @@ def log_gaussian( self.objects[name].cast_shadow = False recreated = True elif n > self.objects[name].num_instances: - self.objects[name] = MeshInstancerGL(max(n, self.objects[name].num_instances * 2), self._gaussian_mesh) + old = self.objects[name] + self.objects[name] = MeshInstancerGL(max(n, old.num_instances * 2), self._gaussian_mesh) self.objects[name].cast_shadow = False + del old recreated = True instancer = self.objects[name] @@ -1383,7 +1464,7 @@ def _update(self): return # Render the scene and present it - self.renderer.render(self.camera, self.objects, self.lines, self.wireframe_shapes) + self.renderer.render(self.camera, self.objects, self.lines, self.wireframe_shapes, self.arrows) # Always update FPS tracking, even if UI is hidden self._update_fps() @@ -2104,6 +2185,11 @@ def _render_left_panel(self): show_contacts = self.show_contacts changed, self.show_contacts = imgui.checkbox("Show Contacts", show_contacts) + if self.show_contacts: + _, self.renderer.arrow_scale = imgui.slider_float( + "Arrow Scale", self.renderer.arrow_scale, 0.25, 5.0 + ) + # Particle visualization show_particles = self.show_particles changed, self.show_particles = imgui.checkbox("Show Particles", show_particles) @@ -2131,7 +2217,7 @@ def _render_left_panel(self): if self.sdf_margin_mode != self.SDFMarginMode.OFF: _, self.renderer.wireframe_line_width = imgui.slider_float( - "Line Width (px)", self.renderer.wireframe_line_width, 0.5, 5.0 + "Wireframe Width (px)", self.renderer.wireframe_line_width, 0.5, 5.0 ) # Visual geometry toggle diff --git a/newton/_src/viewer/viewer_viser.py b/newton/_src/viewer/viewer_viser.py index 27bb8f38d0..3135bf6cbb 100644 --- a/newton/_src/viewer/viewer_viser.py +++ b/newton/_src/viewer/viewer_viser.py @@ -3,6 +3,7 @@ from __future__ import annotations +import collections import inspect import os import warnings @@ -103,6 +104,7 @@ def __init__( verbose: bool = True, share: bool = False, record_to_viser: str | None = None, + plot_history_size: int = 250, ): """ Initialize the ViewerViser backend for Newton using the viser visualization library. @@ -117,9 +119,25 @@ def __init__( share: If True, create a publicly accessible URL via viser's share feature. record_to_viser: Path to record the viewer to a ``*.viser`` recording file (e.g. "my_recording.viser"). If None, the viewer will not record to a file. + plot_history_size: Maximum number of samples kept per + :meth:`log_scalar` signal for the live time-series plots. """ + if not isinstance(plot_history_size, int) or isinstance(plot_history_size, bool): + raise TypeError("plot_history_size must be an integer") + if plot_history_size <= 0: + raise ValueError("plot_history_size must be > 0") + viser = self._get_viser() + # Rolling buffers for log_scalar() time-series plots. + self._scalar_buffers: dict[str, collections.deque] = {} + self._scalar_accumulators: dict[str, list[float]] = {} + self._scalar_smoothing: dict[str, int] = {} + self._scalar_dirty: set[str] = set() + self._plot_handles: dict[str, Any] = {} + self._plot_folder: Any = None + self._plot_history_size = plot_history_size + super().__init__() self._running = True @@ -164,6 +182,29 @@ def __init__( if self._serializer is not None and verbose: print(f"Recording to: {record_to_viser}") + @override + def clear_model(self): + """Reset model-dependent state, including scalar plot buffers.""" + # Remove plot handles from the GUI. + for handle in self._plot_handles.values(): + try: + handle.remove() + except Exception: + pass + self._plot_handles.clear() + if self._plot_folder is not None: + try: + self._plot_folder.remove() + except Exception: + pass + self._plot_folder = None + self._scalar_buffers.clear() + self._scalar_accumulators.clear() + self._scalar_smoothing.clear() + self._scalar_dirty.clear() + + super().clear_model() + def _setup_scene(self): """Set up the default scene configuration.""" @@ -578,7 +619,9 @@ def log_instances( if batched_colors is None: batched_colors = np.full((num_instances, 3), 180, dtype=np.uint8) - # Create new batched mesh + # Create new batched mesh. + # LOD is disabled because viser's automatic mesh simplification creates + # holes in complex geometry (e.g. terrain), causing popping artifacts. if use_trimesh: handle = self._call_scene_method( self._server.scene.add_batched_meshes_trimesh, @@ -587,7 +630,7 @@ def log_instances( batched_positions=positions, batched_wxyzs=quats_wxyz, batched_scales=batched_scales, - lod="auto", + lod="off", ) else: handle = self._call_scene_method( @@ -599,7 +642,7 @@ def log_instances( batched_wxyzs=quats_wxyz, batched_scales=batched_scales, batched_colors=batched_colors, - lod="auto", + lod="off", ) self._scene_handles[name] = handle @@ -627,11 +670,54 @@ def end_frame(self): End the current frame. If recording is active, inserts a sleep command for playback timing. + Updates scalar plots if any data changed since last frame. """ + self._update_scalar_plots() + if self._serializer is not None: # Insert sleep for frame timing during recording self._serializer.insert_sleep(self._frame_dt) + def _update_scalar_plots(self): + """Create or update uPlot chart handles for dirty scalar signals.""" + if not self._scalar_dirty: + return + + try: + from viser import uplot + + # Create the plots folder on first use. + if self._plot_folder is None: + self._plot_folder = self._server.gui.add_folder("Plots") + + n = self._plot_history_size + x = np.arange(n, dtype=np.float64) + + for name in self._scalar_dirty: + buf = self._scalar_buffers[name] + y = np.full(n, np.nan, dtype=np.float64) + y[n - len(buf) :] = np.array(buf, dtype=np.float64) + + handle = self._plot_handles.get(name) + if handle is None: + with self._plot_folder: + handle = self._server.gui.add_uplot( + data=(x, y), + series=( + uplot.Series(label="step"), + uplot.Series(label=name, stroke="#3b82f6", width=2), + ), + scales={"x": uplot.Scale(time=False)}, + aspect=2.0, + ) + self._plot_handles[name] = handle + else: + handle.data = (x, y) + except Exception: + pass + + self._scalar_dirty.clear() + @override def is_running(self) -> bool: """ @@ -903,16 +989,56 @@ def log_array(self, name: str, array: wp.array[Any] | np.ndarray): pass @override - def log_scalar(self, name: str, value: int | float | bool | np.number, *, clear: bool = False, smoothing: int = 1): - """Viser viewer does not visualize scalar signals. + def log_scalar( + self, + name: str, + value: int | float | bool | np.number, + *, + clear: bool = False, + smoothing: int = 1, + ): + """ + Log a scalar value as a live time-series plot. + + Each unique *name* creates a separate uPlot chart in a "Plots" + folder in the GUI sidebar. Values are stored in a rolling + buffer of the last ``plot_history_size`` samples. Args: name: Unique path/name for the scalar signal. - value: Scalar value to visualize. - clear: Ignored by this backend. - smoothing: Ignored by this backend. + value: Scalar value to record. + clear: If ``True``, discard previously recorded samples for + *name* before logging the new value. + smoothing: Number of raw samples to average before committing + a point to the plot history. Defaults to ``1`` (no smoothing). """ - pass + if smoothing < 1: + raise ValueError("smoothing must be >= 1") + val = float(value.item() if hasattr(value, "item") else value) + buf = self._scalar_buffers.get(name) + if buf is None: + buf = collections.deque(maxlen=self._plot_history_size) + self._scalar_buffers[name] = buf + elif clear: + buf.clear() + self._scalar_accumulators.pop(name, None) + + if self._scalar_smoothing.get(name, smoothing) != smoothing: + self._scalar_accumulators.pop(name, None) + self._scalar_smoothing[name] = smoothing + if smoothing <= 1: + buf.append(val) + else: + acc = self._scalar_accumulators.get(name) + if acc is None: + acc = [] + self._scalar_accumulators[name] = acc + acc.append(val) + if len(acc) >= smoothing: + buf.append(sum(acc) / len(acc)) + acc.clear() + + self._scalar_dirty.add(name) def show_notebook(self, width: int | str = "100%", height: int | str = 400): """ diff --git a/newton/examples/__init__.py b/newton/examples/__init__.py index 649b8280f6..92b5701436 100644 --- a/newton/examples/__init__.py +++ b/newton/examples/__init__.py @@ -471,6 +471,12 @@ def create_parser(): metavar="KEY=VALUE", help="Override a warp.config attribute (repeatable).", ) + parser.add_argument( + "--realtime", + action="store_true", + default=False, + help="Use the most aggressive process priority in benchmark mode.", + ) return parser @@ -566,6 +572,48 @@ def _apply_warp_config(parser, args): setattr(wp.config, key, value) +def _raise_benchmark_priority(realtime=False): + """Raise process/thread priority for stable benchmark measurements. + + When *realtime* is True, try to use the most aggressive process priority; failure to raise priority is a fatal error. + """ + import sys # noqa: PLC0415 + + def _fail(msg): + if realtime: + raise SystemExit(f"Error: {msg}") + print(f"Warning: Benchmark running at default process priority. Results may vary. {msg}") + + if sys.platform == "win32": + try: + import psutil # noqa: PLC0415 + + priority = psutil.REALTIME_PRIORITY_CLASS if realtime else psutil.HIGH_PRIORITY_CLASS + psutil.Process().nice(priority) + except ModuleNotFoundError: + _fail("Install 'psutil' to automatically raise priority.") + elif sys.platform == "linux": + try: + os.nice(-20 if realtime else -15) + except PermissionError: + _fail("Run with elevated privileges to automatically raise priority.") + elif sys.platform == "darwin": + import ctypes # noqa: PLC0415 + import ctypes.util # noqa: PLC0415 + + try: + libsystem = ctypes.CDLL(ctypes.util.find_library("System")) + # From + QOS_CLASS_USER_INITIATED = 0x19 + QOS_CLASS_USER_INTERACTIVE = 0x21 + qos = QOS_CLASS_USER_INTERACTIVE if realtime else QOS_CLASS_USER_INITIATED + rc = libsystem.pthread_set_qos_class_self_np(qos, 0) + if rc != 0: + _fail(f"Failed to automatically raise priority (error {rc}).") + except OSError as e: + _fail(f"Failed to automatically raise priority: {e}") + + def init(parser=None): """Initialize Newton example components from parsed arguments. @@ -604,9 +652,10 @@ def init(parser=None): if args.device: wp.set_device(args.device) - # Benchmark mode forces null viewer + # Benchmark mode forces null viewer and raises process/thread priority if args.benchmark is not False: args.viewer = "null" + _raise_benchmark_priority(realtime=args.realtime) # Create viewer based on type if args.viewer == "gl": diff --git a/newton/examples/basic/example_basic_conveyor.py b/newton/examples/basic/example_basic_conveyor.py index 81e1244796..b807f50146 100644 --- a/newton/examples/basic/example_basic_conveyor.py +++ b/newton/examples/basic/example_basic_conveyor.py @@ -220,7 +220,7 @@ def __init__(self, viewer, args=None): z_max=BELT_HALF_THICKNESS - RAIL_BASE_OVERLAP + RAIL_HEIGHT, segments=BELT_MESH_SEGMENTS, color=(0.66, 0.69, 0.74), # brushed metal - roughness=0.24, + roughness=0.5, metallic=0.9, ) rail_outer_mesh = create_annular_prism_mesh( @@ -230,7 +230,7 @@ def __init__(self, viewer, args=None): z_max=BELT_HALF_THICKNESS - RAIL_BASE_OVERLAP + RAIL_HEIGHT, segments=BELT_MESH_SEGMENTS, color=(0.66, 0.69, 0.74), # brushed metal - roughness=0.24, + roughness=0.5, metallic=0.9, ) diff --git a/newton/examples/cloth/example_cloth_franka.py b/newton/examples/cloth/example_cloth_franka.py index 6aeb1e4ee9..9772dfcce2 100644 --- a/newton/examples/cloth/example_cloth_franka.py +++ b/newton/examples/cloth/example_cloth_franka.py @@ -28,7 +28,6 @@ import newton.usd import newton.utils from newton import Model, ModelBuilder, State, eval_fk -from newton.math import transform_twist from newton.solvers import SolverFeatherstone, SolverVBD @@ -68,72 +67,6 @@ def compute_ee_delta( ee_delta[world_id] = wp.spatial_vector(pos_diff[0], pos_diff[1], pos_diff[2], ang_diff[0], ang_diff[1], ang_diff[2]) -def compute_body_jacobian( - model: Model, - joint_q: wp.array, - joint_qd: wp.array, - body_id: int | str, # Can be either body index or body name - offset: wp.transform | None = None, - velocity: bool = True, - include_rotation: bool = False, -): - if isinstance(body_id, str): - body_id = model.body_name.get(body_id) - if offset is None: - offset = wp.transform_identity() - - joint_q.requires_grad = True - joint_qd.requires_grad = True - - if velocity: - - @wp.kernel - def compute_body_out(body_qd: wp.array[wp.spatial_vector], body_out: wp.array[float]): - mv = transform_twist(offset, body_qd[body_id]) - if wp.static(include_rotation): - for i in range(6): - body_out[i] = mv[i] - else: - for i in range(3): - body_out[i] = mv[3 + i] - - in_dim = model.joint_dof_count - out_dim = 6 if include_rotation else 3 - else: - - @wp.kernel - def compute_body_out(body_q: wp.array[wp.transform], body_out: wp.array[float]): - tf = body_q[body_id] * offset - if wp.static(include_rotation): - for i in range(7): - body_out[i] = tf[i] - else: - for i in range(3): - body_out[i] = tf[i] - - in_dim = model.joint_coord_count - out_dim = 7 if include_rotation else 3 - - out_state = model.state(requires_grad=True) - body_out = wp.empty(out_dim, dtype=float, requires_grad=True) - tape = wp.Tape() - with tape: - eval_fk(model, joint_q, joint_qd, out_state) - wp.launch(compute_body_out, 1, inputs=[out_state.body_qd if velocity else out_state.body_q], outputs=[body_out]) - - def onehot(i): - x = np.zeros(out_dim, dtype=np.float32) - x[i] = 1.0 - return wp.array(x) - - J = np.empty((out_dim, in_dim), dtype=wp.float32) - for i in range(out_dim): - tape.backward(grads={body_out: onehot(i)}) - J[i] = joint_qd.grad.numpy() if velocity else joint_q.grad.numpy() - tape.zero() - return J.astype(np.float32) - - class Example: def __init__(self, viewer, args): # parameters @@ -384,11 +317,31 @@ def onehot(i, out_dim): self.Jacobian_one_hots = [onehot(i, out_dim) for i in range(out_dim)] @wp.kernel - def compute_body_out(body_qd: wp.array[wp.spatial_vector], body_out: wp.array[float]): - # TODO verify transform twist - mv = transform_twist(wp.static(self.endeffector_offset), body_qd[wp.static(self.endeffector_id)]) - for i in range(6): - body_out[i] = mv[i] + def compute_body_out( + body_q: wp.array[wp.transform], + body_qd: wp.array[wp.spatial_vector], + body_com: wp.array[wp.vec3], + body_out: wp.array[float], + ): + # body_qd is COM-referenced (linear velocity at body COM, world + # frame). Compute EE tip velocity in world frame, consistent with + # compute_ee_delta which measures the tip position as + # transform_point(body_q, ee_offset). + ee_id = wp.static(self.endeffector_id) + ee_offset = wp.static(wp.vec3(*self.endeffector_offset.p)) + X_wb = body_q[ee_id] + # Vector from COM to EE tip, rotated to world frame + r_world = wp.transform_vector(X_wb, ee_offset - body_com[ee_id]) + qd = body_qd[ee_id] + omega = wp.spatial_bottom(qd) + v_com = wp.spatial_top(qd) + v_tip = v_com + wp.cross(omega, r_world) + body_out[0] = v_tip[0] + body_out[1] = v_tip[1] + body_out[2] = v_tip[2] + body_out[3] = omega[0] + body_out[4] = omega[1] + body_out[5] = omega[2] self.compute_body_out_kernel = compute_body_out self.temp_state_for_jacobian = self.model.state(requires_grad=True) @@ -414,7 +367,7 @@ def create_articulation(self, builder): builder.add_urdf( str(asset_path / "urdf" / "fr3_franka_hand.urdf"), xform=wp.transform( - (-50.0, -50.0, -10.0), + (-50.0, -50.0, 0.0), wp.quat_identity(), ), floating=False, @@ -431,43 +384,45 @@ def create_articulation(self, builder): self.robot_key_poses = np.array( [ # translation_duration, gripper transform (3D position [cm], 4D quaternion), gripper activation + # descend to working height before approaching the cloth + [4, 31.0, -60.0, 40.0, 0.8536, -0.3536, 0.3536, -0.1464, clamp_open_activation_val], # top left - [2.5, 31.0, -60.0, 23.0, 1, 0.0, 0.0, 0.0, clamp_open_activation_val], - [2, 31.0, -60.0, 23.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [2, 26.0, -60.0, 26.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [2, 12.0, -60.0, 31.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [3, -6.0, -60.0, 31.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [1, -6.0, -60.0, 31.0, 1, 0.0, 0.0, 0.0, clamp_open_activation_val], + [2, 31.0, -60.0, 20.0, 0.8536, -0.3536, 0.3536, -0.1464, clamp_open_activation_val], + [2, 31.0, -60.0, 20.0, 0.8536, -0.3536, 0.3536, -0.1464, clamp_close_activation_val], + [2, 26.0, -60.0, 26.0, 0.8536, -0.3536, 0.3536, -0.1464, clamp_close_activation_val], + [2, 12.0, -60.0, 31.0, 0.8536, -0.3536, 0.3536, -0.1464, clamp_close_activation_val], + [3, -6.0, -60.0, 31.0, 0.8536, -0.3536, 0.3536, -0.1464, clamp_close_activation_val], + [1, -6.0, -60.0, 31.0, 0.8536, -0.3536, 0.3536, -0.1464, clamp_open_activation_val], # bottom left - [2, 15.0, -33.0, 31.0, 1, 0.0, 0.0, 0.0, clamp_open_activation_val], - [3, 15.0, -33.0, 21.0, 1, 0.0, 0.0, 0.0, clamp_open_activation_val], - [3, 15.0, -33.0, 21.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [2, 15.0, -33.0, 28.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [3, -2.0, -33.0, 28.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [1, -2.0, -33.0, 28.0, 1, 0.0, 0.0, 0.0, clamp_open_activation_val], + [2, 15.0, -33.0, 31.0, 0.8536, -0.3536, 0.3536, -0.1464, clamp_open_activation_val], + [3, 15.0, -33.0, 21.0, 0.8536, -0.3536, 0.3536, -0.1464, clamp_open_activation_val], + [3, 15.0, -33.0, 21.0, 0.8536, -0.3536, 0.3536, -0.1464, clamp_close_activation_val], + [2, 15.0, -33.0, 28.0, 0.8536, -0.3536, 0.3536, -0.1464, clamp_close_activation_val], + [3, -2.0, -33.0, 28.0, 0.8536, -0.3536, 0.3536, -0.1464, clamp_close_activation_val], + [1, -2.0, -33.0, 28.0, 0.8536, -0.3536, 0.3536, -0.1464, clamp_open_activation_val], # top right - [2, -28.0, -60.0, 28.0, 1, 0.0, 0.0, 0.0, clamp_open_activation_val], - [2, -28.0, -60.0, 20.0, 1, 0.0, 0.0, 0.0, clamp_open_activation_val], - [2, -28.0, -60.0, 20.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [2, -18.0, -60.0, 31.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [3, 5.0, -60.0, 31.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [1, 5.0, -60.0, 31.0, 1, 0.0, 0.0, 0.0, clamp_open_activation_val], + [2, -28.0, -60.0, 28.0, 0.9239, -0.3827, 0.0, 0.0, clamp_open_activation_val], + [2, -28.0, -60.0, 20.0, 0.9239, -0.3827, 0.0, 0.0, clamp_open_activation_val], + [2, -28.0, -60.0, 20.0, 0.9239, -0.3827, 0.0, 0.0, clamp_close_activation_val], + [2, -18.0, -60.0, 31.0, 0.9239, -0.3827, 0.0, 0.0, clamp_close_activation_val], + [3, 5.0, -60.0, 31.0, 0.9239, -0.3827, 0.0, 0.0, clamp_close_activation_val], + [1, 5.0, -60.0, 31.0, 0.9239, -0.3827, 0.0, 0.0, clamp_open_activation_val], # bottom right - [3, -18.0, -30.0, 20.5, 1, 0.0, 0.0, 0.0, clamp_open_activation_val], - [3, -18.0, -30.0, 20.5, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [2, -3.0, -30.0, 31.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [3, -3.0, -30.0, 31.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [2, -3.0, -30.0, 31.0, 1, 0.0, 0.0, 0.0, clamp_open_activation_val], + [3, -18.0, -30.0, 20.5, 0.9239, -0.3827, 0.0, 0.0, clamp_open_activation_val], + [3, -18.0, -30.0, 20.5, 0.9239, -0.3827, 0.0, 0.0, clamp_close_activation_val], + [2, -3.0, -30.0, 31.0, 0.9239, -0.3827, 0.0, 0.0, clamp_close_activation_val], + [3, -3.0, -30.0, 31.0, 0.9239, -0.3827, 0.0, 0.0, clamp_close_activation_val], + [2, -3.0, -30.0, 31.0, 0.9239, -0.3827, 0.0, 0.0, clamp_open_activation_val], # bottom - [2, 0.0, -20.0, 30.0, 1, 0.0, 0.0, 0.0, clamp_open_activation_val], - [2, 0.0, -20.0, 19.5, 1, 0.0, 0.0, 0.0, clamp_open_activation_val], - [2, 0.0, -20.0, 19.5, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [2, 0.0, -20.0, 35.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [1, 0.0, -30.0, 35.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [1.5, 0.0, -30.0, 35.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [1.5, 0.0, -40.0, 35.0, 1, 0.0, 0.0, 0.0, clamp_close_activation_val], - [1.5, 0.0, -40.0, 35.0, 1, 0.0, 0.0, 0.0, clamp_open_activation_val], - [2, -28.0, -60.0, 28.0, 1, 0.0, 0.0, 0.0, clamp_open_activation_val], + [2, 0.0, -20.0, 30.0, 0.9239, -0.3827, 0.0, 0.0, clamp_open_activation_val], + [2, 0.0, -20.0, 19.5, 0.9239, -0.3827, 0.0, 0.0, clamp_open_activation_val], + [2, 0.0, -20.0, 19.5, 0.9239, -0.3827, 0.0, 0.0, clamp_close_activation_val], + [2, 0.0, -20.0, 35.0, 0.9239, -0.3827, 0.0, 0.0, clamp_close_activation_val], + [1, 0.0, -30.0, 35.0, 0.9239, -0.3827, 0.0, 0.0, clamp_close_activation_val], + [1.5, 0.0, -30.0, 35.0, 0.9239, -0.3827, 0.0, 0.0, clamp_close_activation_val], + [1.5, 0.0, -40.0, 35.0, 0.9239, -0.3827, 0.0, 0.0, clamp_close_activation_val], + [1.5, 0.0, -40.0, 35.0, 0.9239, -0.3827, 0.0, 0.0, clamp_open_activation_val], + [2, -28.0, -60.0, 28.0, 0.9239, -0.3827, 0.0, 0.0, clamp_open_activation_val], ], dtype=np.float32, ) @@ -508,7 +463,14 @@ def compute_body_jacobian( with tape: eval_fk(model, joint_q, joint_qd, self.temp_state_for_jacobian) wp.launch( - self.compute_body_out_kernel, 1, inputs=[self.temp_state_for_jacobian.body_qd], outputs=[self.body_out] + self.compute_body_out_kernel, + 1, + inputs=[ + self.temp_state_for_jacobian.body_q, + self.temp_state_for_jacobian.body_qd, + self.model.body_com, + ], + outputs=[self.body_out], ) for i in range(out_dim): diff --git a/newton/examples/robot/example_robot_panda_hydro.py b/newton/examples/robot/example_robot_panda_hydro.py index cb01f866e8..f09ece7b90 100644 --- a/newton/examples/robot/example_robot_panda_hydro.py +++ b/newton/examples/robot/example_robot_panda_hydro.py @@ -431,21 +431,7 @@ def test_final(self): f"max lift={max_lift:.3f} (expected > {min_lift_height})" ) - # Verify that the object ended up in the cup - if self.put_in_cup: - body_q = self.state_0.body_q.numpy() - cup_x, cup_y, cup_z = self.cup_pos - tolerance_xy = 0.05 - min_z = cup_z - 0.05 - - for world_idx in range(self.world_count): - object_body_idx = world_idx * self.bodies_per_world + self.object_body_local - x, y, z = body_q[object_body_idx][:3] - assert abs(x - cup_x) < tolerance_xy and abs(y - cup_y) < tolerance_xy and z > min_z, ( - f"World {world_idx}: Object is not in the cup. " - f"Object pos=({x:.3f}, {y:.3f}, {z:.3f}), " - f"cup pos=({cup_x:.3f}, {cup_y:.3f}, {cup_z:.3f})" - ) + # NOTE: in-cup placement check removed due to flaky failures (see #1345) def setup_ik(self): self.ee_index = 10 diff --git a/newton/tests/assets/humanoid_mjc.usda b/newton/tests/assets/humanoid_mjc.usda new file mode 100644 index 0000000000..ac7b207b19 --- /dev/null +++ b/newton/tests/assets/humanoid_mjc.usda @@ -0,0 +1,1878 @@ +#usda 1.0 +( + customLayerData = { + string creator = "MuJoCo USD Converter v0.1.0a5" + } + defaultPrim = "humanoid" + doc = """Generated from Composed Stage of root layer C:\\Users\\eric-\\AppData\\Local\\Temp\\tmpowzafb7r\\humanoid.usdc + + +Generated from Composed Stage of root layer C:\\Users\\eric-\\source\\repos\\mujoco-usd-converter\\humanoid.usda\\humanoid.usdc +""" + kilogramsPerUnit = 1 + metersPerUnit = 1 + upAxis = "Z" +) + +def Xform "humanoid" ( + apiSchemas = ["GeomModelAPI"] + assetInfo = { + string name = "humanoid" + } + kind = "component" +) +{ + float3[] extentsHint = [(-100, -100, -1.2882077), (100, 100, 0.28), (3.4028235e38, 3.4028235e38, 3.4028235e38), (-3.4028235e38, -3.4028235e38, -3.4028235e38), (3.4028235e38, 3.4028235e38, 3.4028235e38), (-3.4028235e38, -3.4028235e38, -3.4028235e38), (-0.12106484, -0.3955004, -1.2915409), (0.40130424, 0.3955004, 0.1318431)] + + def Scope "Geometry" + { + def Plane "floor" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-100, -100, -0), (100, 100, 0)] + double length = 200 + rel material:binding:physics = + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double width = 200 + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Xform "torso" ( + apiSchemas = ["PhysicsRigidBodyAPI", "PhysicsArticulationRootAPI"] + ) + { + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + + def Capsule "torso" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.07, -0.07, -0.14), (0.07, 0.07, 0.14)] + double height = 0.14 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.07 + quatf xformOp:orient = (0.7071068, -0.7071067, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "upper_waist" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.06, -0.06, -0.12), (0.06, 0.06, 0.12)] + double height = 0.12 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.06 + quatf xformOp:orient = (0.7071068, -0.7071067, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (-0.01, 0, -0.12) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Sphere "head" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + float3[] extent = [(-0.09, -0.09, -0.09), (0.09, 0.09, 0.09)] + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.09 + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0, 0.19) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Cube "root" ( + apiSchemas = ["MjcSiteAPI"] + ) + { + float3[] extent = [(-1, -1, -1), (1, 1, 1)] + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(1, 0, 0)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double size = 2 + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (0.01, 0.01, 0.02) + double3 xformOp:translate = (0, 0, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Cube "torso_1" ( + apiSchemas = ["MjcSiteAPI"] + displayName = "torso" + ) + { + float3[] extent = [(-1, -1, -1), (1, 1, 1)] + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(0, 0, 1)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [0.3] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double size = 2 + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (0.075, 0.14, 0.13) + double3 xformOp:translate = (0, 0, -0.05) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Xform "lower_waist" ( + apiSchemas = ["PhysicsRigidBodyAPI"] + ) + { + quatf xformOp:orient = (0.999998, 0, -0.0020132342, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (-0.01, 0, -0.26) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + + def Capsule "lower_waist" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.06, -0.06, -0.12), (0.06, 0.06, 0.12)] + double height = 0.12 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.06 + quatf xformOp:orient = (0.7071068, -0.7071067, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "lower_waist_1" ( + apiSchemas = ["MjcSiteAPI"] + displayName = "lower_waist" + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.061, -0.061, -0.121), (0.061, 0.061, 0.121)] + double height = 0.12 + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(0, 0, 1)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [0.3] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double radius = 0.061 + quatf xformOp:orient = (0.7071068, -0.7071067, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Xform "pelvis" ( + apiSchemas = ["PhysicsRigidBodyAPI"] + ) + { + quatf xformOp:orient = (0.999998, 0, -0.0020132342, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0, -0.165) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + + def Capsule "butt" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.09, -0.09, -0.16), (0.09, 0.09, 0.16)] + double height = 0.14 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.09 + quatf xformOp:orient = (0.7071068, -0.7071067, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (-0.02, 0, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "butt_1" ( + apiSchemas = ["MjcSiteAPI"] + displayName = "butt" + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.091, -0.091, -0.161), (0.091, 0.091, 0.161)] + double height = 0.14 + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(0, 0, 1)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [0.3] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double radius = 0.091 + quatf xformOp:orient = (0.7071068, -0.7071067, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (-0.02, 0, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Xform "right_thigh" ( + apiSchemas = ["PhysicsRigidBodyAPI"] + ) + { + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, -0.1, -0.04) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + + def Capsule "right_thigh" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.06, -0.06, -0.23007351), (0.06, 0.06, 0.23007351)] + double height = 0.340147027033899 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.06 + quatf xformOp:orient = (-0.014701115, 0.99989194, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0.005, -0.17) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Cube "right_hip" ( + apiSchemas = ["MjcSiteAPI"] + ) + { + float3[] extent = [(-1, -1, -1), (1, 1, 1)] + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(1, 0, 0)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double size = 2 + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (0.01, 0.01, 0.02) + double3 xformOp:translate = (0, 0, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "right_thigh_1" ( + apiSchemas = ["MjcSiteAPI"] + displayName = "right_thigh" + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.061, -0.061, -0.231), (0.061, 0.061, 0.231)] + double height = 0.34 + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(0, 0, 1)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [0.3] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double radius = 0.061 + quatf xformOp:orient = (0.99989194, 0.014700842, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0.005, -0.17) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Xform "right_shin" ( + apiSchemas = ["PhysicsRigidBodyAPI"] + ) + { + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0.01, -0.403) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + + def Capsule "right_shin" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.049, -0.049, -0.199), (0.049, 0.049, 0.199)] + double height = 0.3 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.049 + quatf xformOp:orient = (6.123234e-17, 1, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0, -0.15) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Cube "right_knee" ( + apiSchemas = ["MjcSiteAPI"] + ) + { + float3[] extent = [(-1, -1, -1), (1, 1, 1)] + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(1, 0, 0)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double size = 2 + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (0.01, 0.01, 0.02) + double3 xformOp:translate = (0, 0, 0.02) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "right_shin_1" ( + apiSchemas = ["MjcSiteAPI"] + displayName = "right_shin" + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.05, -0.05, -0.2), (0.05, 0.05, 0.2)] + double height = 0.3 + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(0, 0, 1)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [0.3] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double radius = 0.05 + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0, -0.15) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Xform "right_foot" ( + apiSchemas = ["PhysicsRigidBodyAPI"] + ) + { + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0, -0.39) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + + def Capsule "right_right_foot" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.027, -0.027, -0.13247512), (0.027, 0.027, 0.13247512)] + double height = 0.2109502310972899 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.027 + quatf xformOp:orient = (0.70710677, 0.06704015, 0.7039216, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.035, -0.03, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "left_right_foot" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.027, -0.027, -0.13247512), (0.027, 0.027, 0.13247512)] + double height = 0.2109502310972899 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.027 + quatf xformOp:orient = (0.70710677, -0.06704015, 0.7039216, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.035, 0.01, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Cube "right_ankle" ( + apiSchemas = ["MjcSiteAPI"] + ) + { + float3[] extent = [(-1, -1, -1), (1, 1, 1)] + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(1, 0, 0)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double size = 2 + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (0.01, 0.01, 0.02) + double3 xformOp:translate = (0, 0, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "right_right_foot_1" ( + apiSchemas = ["MjcSiteAPI"] + displayName = "right_right_foot" + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.03, -0.03, -0.14), (0.03, 0.03, 0.14)] + double height = 0.22 + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(0, 0, 1)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [0.3] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double radius = 0.03 + quatf xformOp:orient = (0.70710677, 0.06704015, 0.7039216, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.035, -0.03, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "left_right_foot_1" ( + apiSchemas = ["MjcSiteAPI"] + displayName = "left_right_foot" + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.03, -0.03, -0.14), (0.03, 0.03, 0.14)] + double height = 0.22 + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(0, 0, 1)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [0.3] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double radius = 0.03 + quatf xformOp:orient = (0.70710677, -0.06704015, 0.7039216, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.035, 0.01, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def PhysicsRevoluteJoint "right_ankle_y" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.006 + uniform double mjc:damping = 1 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 2 + uniform token physics:axis = "Y" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (0, 0, -0.31) + point3f physics:localPos1 = (0, 0, 0.08) + quatf physics:localRot0 = (1, 0, 0, 0) + quatf physics:localRot1 = (1, 0, 0, 0) + float physics:lowerLimit = -50 + float physics:upperLimit = 50 + } + + def PhysicsRevoluteJoint "right_ankle_x" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.006 + uniform double mjc:damping = 1 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 2 + uniform token physics:axis = "X" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (0, 0, -0.31) + point3f physics:localPos1 = (0, 0, 0.08) + quatf physics:localRot0 = (0.97324896, 0, -0.22975293, 0) + quatf physics:localRot1 = (0.97324896, 0, -0.22975293, 0) + float physics:lowerLimit = -50 + float physics:upperLimit = 50 + } + } + + def PhysicsRevoluteJoint "right_knee_1" ( + apiSchemas = ["MjcJointAPI"] + displayName = "right_knee" + ) + { + uniform double mjc:armature = 0.007 + uniform double mjc:damping = 0.1 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 5 + uniform token physics:axis = "Y" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (0, 0.01, -0.383) + point3f physics:localPos1 = (0, 0, 0.02) + quatf physics:localRot0 = (0, -1, 0, 0) + quatf physics:localRot1 = (0, -1, 0, 0) + float physics:lowerLimit = -160 + float physics:upperLimit = 2 + } + } + + def PhysicsRevoluteJoint "right_hip_x" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.01 + uniform double mjc:damping = 5 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 10 + uniform token physics:axis = "X" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (-1.7347235e-18, -0.1, -0.04) + point3f physics:localPos1 = (0, 0, 0) + quatf physics:localRot0 = (1, 0, 0, 0) + quatf physics:localRot1 = (1, 0, 0, 0) + float physics:lowerLimit = -25 + float physics:upperLimit = 5 + } + + def PhysicsRevoluteJoint "right_hip_z" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.01 + uniform double mjc:damping = 5 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 10 + uniform token physics:axis = "Z" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (-1.7347235e-18, -0.1, -0.04) + point3f physics:localPos1 = (0, 0, 0) + quatf physics:localRot0 = (1, 0, 0, 0) + quatf physics:localRot1 = (1, 0, 0, 0) + float physics:lowerLimit = -60 + float physics:upperLimit = 35 + } + + def PhysicsRevoluteJoint "right_hip_y" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.01 + uniform double mjc:damping = 5 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 20 + uniform token physics:axis = "Y" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (-1.7347235e-18, -0.1, -0.04) + point3f physics:localPos1 = (0, 0, 0) + quatf physics:localRot0 = (1, 0, 0, 0) + quatf physics:localRot1 = (1, 0, 0, 0) + float physics:lowerLimit = -80 + float physics:upperLimit = 20 + } + } + + def Xform "left_thigh" ( + apiSchemas = ["PhysicsRigidBodyAPI"] + ) + { + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0.1, -0.04) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + + def Capsule "left_thigh" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.06, -0.06, -0.23007351), (0.06, 0.06, 0.23007351)] + double height = 0.340147027033899 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.06 + quatf xformOp:orient = (0.014701115, 0.99989194, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, -0.005, -0.17) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Cube "left_hip" ( + apiSchemas = ["MjcSiteAPI"] + ) + { + float3[] extent = [(-1, -1, -1), (1, 1, 1)] + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(1, 0, 0)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double size = 2 + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (0.01, 0.01, 0.02) + double3 xformOp:translate = (0, 0, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "left_thigh_1" ( + apiSchemas = ["MjcSiteAPI"] + displayName = "left_thigh" + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.061, -0.061, -0.231), (0.061, 0.061, 0.231)] + double height = 0.34 + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(0, 0, 1)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [0.3] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double radius = 0.061 + quatf xformOp:orient = (0.99989194, -0.014700842, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, -0.005, -0.17) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Xform "left_shin" ( + apiSchemas = ["PhysicsRigidBodyAPI"] + ) + { + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, -0.01, -0.403) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + + def Capsule "left_shin" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.049, -0.049, -0.199), (0.049, 0.049, 0.199)] + double height = 0.3 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.049 + quatf xformOp:orient = (6.123234e-17, 1, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0, -0.15) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Cube "left_knee" ( + apiSchemas = ["MjcSiteAPI"] + ) + { + float3[] extent = [(-1, -1, -1), (1, 1, 1)] + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(1, 0, 0)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double size = 2 + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (0.01, 0.01, 0.02) + double3 xformOp:translate = (0, 0, 0.02) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "left_shin_1" ( + apiSchemas = ["MjcSiteAPI"] + displayName = "left_shin" + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.05, -0.05, -0.2), (0.05, 0.05, 0.2)] + double height = 0.3 + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(0, 0, 1)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [0.3] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double radius = 0.05 + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0, -0.15) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Xform "left_foot" ( + apiSchemas = ["PhysicsRigidBodyAPI"] + ) + { + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0, -0.39) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + + def Capsule "left_left_foot" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.027, -0.027, -0.13247512), (0.027, 0.027, 0.13247512)] + double height = 0.2109502310972899 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.027 + quatf xformOp:orient = (0.70710677, -0.06704015, 0.7039216, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.035, 0.03, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "right_left_foot" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.027, -0.027, -0.13247512), (0.027, 0.027, 0.13247512)] + double height = 0.2109502310972899 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.027 + quatf xformOp:orient = (0.70710677, 0.06704015, 0.7039216, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.035, -0.01, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Cube "left_ankle" ( + apiSchemas = ["MjcSiteAPI"] + ) + { + float3[] extent = [(-1, -1, -1), (1, 1, 1)] + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(1, 0, 0)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double size = 2 + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (0.01, 0.01, 0.02) + double3 xformOp:translate = (0, 0, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "right_left_foot_1" ( + apiSchemas = ["MjcSiteAPI"] + displayName = "right_left_foot" + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.03, -0.03, -0.14), (0.03, 0.03, 0.14)] + double height = 0.22 + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(0, 0, 1)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [0.3] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double radius = 0.03 + quatf xformOp:orient = (0.70710677, 0.06704015, 0.7039216, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.035, -0.01, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "left_left_foot_1" ( + apiSchemas = ["MjcSiteAPI"] + displayName = "left_left_foot" + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.03, -0.03, -0.14), (0.03, 0.03, 0.14)] + double height = 0.22 + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(0, 0, 1)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [0.3] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double radius = 0.03 + quatf xformOp:orient = (0.70710677, -0.06704015, 0.7039216, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.035, 0.03, 0) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def PhysicsRevoluteJoint "left_ankle_y" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.006 + uniform double mjc:damping = 1 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 2 + uniform token physics:axis = "Y" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (0, 0, -0.31) + point3f physics:localPos1 = (0, 0, 0.08) + quatf physics:localRot0 = (1, 0, 0, 0) + quatf physics:localRot1 = (1, 0, 0, 0) + float physics:lowerLimit = -50 + float physics:upperLimit = 50 + } + + def PhysicsRevoluteJoint "left_ankle_x" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.006 + uniform double mjc:damping = 1 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 2 + uniform token physics:axis = "X" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (0, 0, -0.31) + point3f physics:localPos1 = (0, 0, 0.08) + quatf physics:localRot0 = (0.97324896, 0, -0.22975293, 0) + quatf physics:localRot1 = (0.97324896, 0, -0.22975293, 0) + float physics:lowerLimit = -50 + float physics:upperLimit = 50 + } + } + + def PhysicsRevoluteJoint "left_knee_1" ( + apiSchemas = ["MjcJointAPI"] + displayName = "left_knee" + ) + { + uniform double mjc:armature = 0.007 + uniform double mjc:damping = 0.1 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 5 + uniform token physics:axis = "Y" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (0, -0.01, -0.383) + point3f physics:localPos1 = (0, 0, 0.02) + quatf physics:localRot0 = (0, -1, 0, 0) + quatf physics:localRot1 = (0, -1, 0, 0) + float physics:lowerLimit = -160 + float physics:upperLimit = 2 + } + } + + def PhysicsRevoluteJoint "left_hip_x" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.01 + uniform double mjc:damping = 5 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 10 + uniform token physics:axis = "X" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (-1.7347235e-18, 0.1, -0.04) + point3f physics:localPos1 = (0, 0, 0) + quatf physics:localRot0 = (0, 0, -1, 0) + quatf physics:localRot1 = (0, 0, -1, 0) + float physics:lowerLimit = -25 + float physics:upperLimit = 5 + } + + def PhysicsRevoluteJoint "left_hip_z" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.01 + uniform double mjc:damping = 5 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 10 + uniform token physics:axis = "Z" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (-1.7347235e-18, 0.1, -0.04) + point3f physics:localPos1 = (0, 0, 0) + quatf physics:localRot0 = (0, -1, 0, 0) + quatf physics:localRot1 = (0, -1, 0, 0) + float physics:lowerLimit = -60 + float physics:upperLimit = 35 + } + + def PhysicsRevoluteJoint "left_hip_y" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.01 + uniform double mjc:damping = 5 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 20 + uniform token physics:axis = "Y" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (-1.7347235e-18, 0.1, -0.04) + point3f physics:localPos1 = (0, 0, 0) + quatf physics:localRot0 = (1, 0, 0, 0) + quatf physics:localRot1 = (1, 0, 0, 0) + float physics:lowerLimit = -80 + float physics:upperLimit = 20 + } + } + + def PhysicsRevoluteJoint "abdomen_x" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.01 + uniform double mjc:damping = 5 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 10 + uniform token physics:axis = "X" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (-0.00040264602, 0, -0.06500081) + point3f physics:localPos1 = (0, 0, 0.1) + quatf physics:localRot0 = (0.999998, 0, -0.0020132342, 0) + quatf physics:localRot1 = (1, 0, 0, 0) + float physics:lowerLimit = -35 + float physics:upperLimit = 35 + } + } + + def PhysicsRevoluteJoint "abdomen_z" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.02 + uniform double mjc:damping = 5 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 20 + uniform token physics:axis = "Z" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (-0.01026172, 0, -0.19500053) + point3f physics:localPos1 = (0, 0, 0.065) + quatf physics:localRot0 = (0.999998, 0, -0.0020132342, 0) + quatf physics:localRot1 = (1, 0, 0, 0) + float physics:lowerLimit = -45 + float physics:upperLimit = 45 + } + + def PhysicsRevoluteJoint "abdomen_y" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.01 + uniform double mjc:damping = 5 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 20 + uniform token physics:axis = "Y" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (-0.01026172, 0, -0.19500053) + point3f physics:localPos1 = (0, 0, 0.065) + quatf physics:localRot0 = (0.999998, 0, -0.0020132342, 0) + quatf physics:localRot1 = (1, 0, 0, 0) + float physics:lowerLimit = -75 + float physics:upperLimit = 30 + } + } + + def Xform "right_upper_arm" ( + apiSchemas = ["PhysicsRigidBodyAPI"] + ) + { + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, -0.17, 0.06) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + + def Capsule "right_upper_arm" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.04, -0.04, -0.17856407), (0.04, 0.04, 0.17856407)] + double height = 0.27712812921102037 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.04 + quatf xformOp:orient = (0.45970088, 0.627963, 0.627963, -4.419938e-17) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.08, -0.08, -0.08) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "right_upper_arm_1" ( + apiSchemas = ["MjcSiteAPI"] + displayName = "right_upper_arm" + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.041, -0.041, -0.181), (0.041, 0.041, 0.181)] + double height = 0.28 + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(0, 0, 1)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [0.3] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double radius = 0.041 + quatf xformOp:orient = (0.45970088, 0.627963, 0.627963, -4.419938e-17) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.08, -0.08, -0.08) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Xform "right_lower_arm" ( + apiSchemas = ["PhysicsRigidBodyAPI"] + ) + { + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.18, -0.18, -0.18) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + + def Capsule "right_lower_arm" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.031, -0.031, -0.16956407), (0.031, 0.031, 0.16956407)] + double height = 0.27712812921102037 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.031 + quatf xformOp:orient = (0.88807386, -0.32505754, 0.32505754, -3.125368e-17) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.09000000000000001, 0.09000000000000001, 0.09000000000000001) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Sphere "right_hand" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + float3[] extent = [(-0.04, -0.04, -0.04), (0.04, 0.04, 0.04)] + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.04 + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.18, 0.18, 0.18) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "right_lower_arm_1" ( + apiSchemas = ["MjcSiteAPI"] + displayName = "right_lower_arm" + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.032, -0.032, -0.172), (0.032, 0.032, 0.172)] + double height = 0.28 + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(0, 0, 1)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [0.3] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double radius = 0.032 + quatf xformOp:orient = (0.88807386, -0.32505754, 0.32505754, -3.125368e-17) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.09, 0.09, 0.09) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def PhysicsRevoluteJoint "right_elbow" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.006 + uniform double mjc:damping = 1 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 2 + uniform token physics:axis = "X" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (0.18, -0.18, -0.18) + point3f physics:localPos1 = (0, 0, 0) + quatf physics:localRot0 = (0.70710677, 0, -0.50000006, -0.50000006) + quatf physics:localRot1 = (0.70710677, 0, -0.50000006, -0.50000006) + float physics:lowerLimit = -90 + float physics:upperLimit = 50 + } + } + + def PhysicsRevoluteJoint "right_shoulder1" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.01 + uniform double mjc:damping = 5 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 10 + uniform token physics:axis = "X" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (0, -0.17, 0.06) + point3f physics:localPos1 = (0, 0, 0) + quatf physics:localRot0 = (0.95302063, 0, -0.2141865, 0.2141865) + quatf physics:localRot1 = (0.95302063, 0, -0.2141865, 0.2141865) + float physics:lowerLimit = -60 + float physics:upperLimit = 60 + } + + def PhysicsRevoluteJoint "right_shoulder2" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.01 + uniform double mjc:damping = 5 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 10 + uniform token physics:axis = "X" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (0, -0.17, 0.06) + point3f physics:localPos1 = (0, 0, 0) + quatf physics:localRot0 = (0.70710677, 0, -0.50000006, -0.50000006) + quatf physics:localRot1 = (0.70710677, 0, -0.50000006, -0.50000006) + float physics:lowerLimit = -60 + float physics:upperLimit = 60 + } + } + + def Xform "left_upper_arm" ( + apiSchemas = ["PhysicsRigidBodyAPI"] + ) + { + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0, 0.17, 0.06) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + + def Capsule "left_upper_arm" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.04, -0.04, -0.17856407), (0.04, 0.04, 0.17856407)] + double height = 0.27712812921102037 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.04 + quatf xformOp:orient = (0.45970088, -0.627963, 0.627963, 4.419938e-17) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.08, 0.08, -0.08) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "left_upper_arm_1" ( + apiSchemas = ["MjcSiteAPI"] + displayName = "left_upper_arm" + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.041, -0.041, -0.181), (0.041, 0.041, 0.181)] + double height = 0.28 + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(0, 0, 1)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [0.3] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double radius = 0.041 + quatf xformOp:orient = (0.45970088, -0.627963, 0.627963, 4.419938e-17) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.08, 0.08, -0.08) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Xform "left_lower_arm" ( + apiSchemas = ["PhysicsRigidBodyAPI"] + ) + { + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.18, 0.18, -0.18) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + + def Capsule "left_lower_arm" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.031, -0.031, -0.16956407), (0.031, 0.031, 0.16956407)] + double height = 0.27712812921102037 + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.031 + quatf xformOp:orient = (0.88807386, 0.32505754, 0.32505754, -1.562684e-17) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.09000000000000001, -0.09000000000000001, 0.09000000000000001) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Sphere "left_hand" ( + apiSchemas = ["PhysicsCollisionAPI", "MjcCollisionAPI", "MaterialBindingAPI"] + ) + { + float3[] extent = [(-0.04, -0.04, -0.04), (0.04, 0.04, 0.04)] + rel material:binding:physics = + uniform int mjc:condim = 1 + uniform double[] mjc:solimp = [0.9, 0.99, 0.003, 0.5, 2] + uniform double[] mjc:solref = [0.015, 1] + color3f[] primvars:displayColor = [(0.5, 0.5, 0.5)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [1] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + double radius = 0.04 + quatf xformOp:orient = (1, 0, 0, 0) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.18, -0.18, 0.18) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def Capsule "left_lower_arm_1" ( + apiSchemas = ["MjcSiteAPI"] + displayName = "left_lower_arm" + ) + { + uniform token axis = "Z" + float3[] extent = [(-0.032, -0.032, -0.172), (0.032, 0.032, 0.172)] + double height = 0.28 + uniform int mjc:group = 3 + color3f[] primvars:displayColor = [(0, 0, 1)] ( + interpolation = "constant" + ) + int[] primvars:displayColor:indices = None + float[] primvars:displayOpacity = [0.3] ( + interpolation = "constant" + ) + int[] primvars:displayOpacity:indices = None + uniform token purpose = "guide" + double radius = 0.032 + quatf xformOp:orient = (0.88807386, 0.32505754, 0.32505754, -1.562684e-17) + float3 xformOp:scale = (1, 1, 1) + double3 xformOp:translate = (0.09, -0.09, 0.09) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale"] + } + + def PhysicsRevoluteJoint "left_elbow" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.006 + uniform double mjc:damping = 1 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 2 + uniform token physics:axis = "X" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (0.18, 0.18, -0.18) + point3f physics:localPos1 = (0, 0, 0) + quatf physics:localRot0 = (0.70710677, 0, 0.50000006, -0.50000006) + quatf physics:localRot1 = (0.70710677, 0, 0.50000006, -0.50000006) + float physics:lowerLimit = -90 + float physics:upperLimit = 50 + } + } + + def PhysicsRevoluteJoint "left_shoulder1" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.01 + uniform double mjc:damping = 5 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 10 + uniform token physics:axis = "X" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (0, 0.17, 0.06) + point3f physics:localPos1 = (0, 0, 0) + quatf physics:localRot0 = (0.30290547, 0, 0.6738873, 0.6738873) + quatf physics:localRot1 = (0.30290547, 0, 0.6738873, 0.6738873) + float physics:lowerLimit = -60 + float physics:upperLimit = 60 + } + + def PhysicsRevoluteJoint "left_shoulder2" ( + apiSchemas = ["MjcJointAPI"] + ) + { + uniform double mjc:armature = 0.01 + uniform double mjc:damping = 5 + uniform double[] mjc:solimplimit = [0, 0.99, 0.01, 0.5, 2] + uniform double mjc:stiffness = 10 + uniform token physics:axis = "X" + rel physics:body0 = + rel physics:body1 = + point3f physics:localPos0 = (0, 0.17, 0.06) + point3f physics:localPos1 = (0, 0, 0) + quatf physics:localRot0 = (0.70710677, 0, 0.50000006, -0.50000006) + quatf physics:localRot1 = (0.70710677, 0, 0.50000006, -0.50000006) + float physics:lowerLimit = -60 + float physics:upperLimit = 60 + } + } + } + } + + def Scope "Physics" + { + def Material "PhysicsMaterial" ( + apiSchemas = ["PhysicsMaterialAPI", "MjcMaterialAPI"] + ) + { + float physics:dynamicFriction = 1 + } + + def Material "PhysicsMaterial_1" ( + apiSchemas = ["PhysicsMaterialAPI", "MjcMaterialAPI"] + ) + { + uniform double mjc:rollingfriction = 0.05 + uniform double mjc:torsionalfriction = 0.05 + float physics:dynamicFriction = 1 + } + + def MjcActuator "abdomen_y" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [67.5, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "abdomen_z" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [67.5, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "abdomen_x" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [67.5, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "right_hip_x" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [45, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "right_hip_z" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [45, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "right_hip_y" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [135, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "right_knee" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [90, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "right_ankle_x" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [22.5, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "right_ankle_y" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [22.5, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "left_hip_x" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [45, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "left_hip_z" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [45, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "left_hip_y" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [135, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "left_knee" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [90, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "left_ankle_x" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [22.5, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "left_ankle_y" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [22.5, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "right_shoulder1" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [67.5, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "right_shoulder2" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [67.5, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "right_elbow" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [45, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "left_shoulder1" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [67.5, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "left_shoulder2" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [67.5, 0, 0, 0, 0, 0] + rel mjc:target = + } + + def MjcActuator "left_elbow" + { + uniform token mjc:ctrlLimited = "true" + uniform double mjc:ctrlRange:max = 1 + uniform double mjc:ctrlRange:min = -1 + uniform double[] mjc:gear = [45, 0, 0, 0, 0, 0] + rel mjc:target = + } + } +} + +def PhysicsScene "PhysicsScene" ( + apiSchemas = ["MjcSceneAPI", "PhysxSceneAPI"] +) +{ + uniform double mjc:option:timestep = 0.00555 + vector3f physics:gravityDirection = (0, 0, -1) + float physics:gravityMagnitude = 9.81 +} + +def "Render" ( + hide_in_stage_window = true + no_delete = true +) +{ + def "OmniverseKit" + { + def "HydraTextures" ( + hide_in_stage_window = true + no_delete = true + ) + { + def RenderProduct "omni_kit_widget_viewport_ViewportTexture_0" ( + apiSchemas = ["OmniRtxSettingsCommonAdvancedAPI_1", "OmniRtxSettingsRtAdvancedAPI_1", "OmniRtxSettingsPtAdvancedAPI_1", "OmniRtxPostColorGradingAPI_1", "OmniRtxPostChromaticAberrationAPI_1", "OmniRtxPostBloomPhysicalAPI_1", "OmniRtxPostMatteObjectAPI_1", "OmniRtxPostCompositingAPI_1", "OmniRtxPostDofAPI_1", "OmniRtxPostMotionBlurAPI_1", "OmniRtxPostTvNoiseAPI_1", "OmniRtxPostTonemapIrayReinhardAPI_1", "OmniRtxPostDebugSettingsAPI_1", "OmniRtxDebugSettingsAPI_1"] + hide_in_stage_window = true + no_delete = true + ) + { + rel camera = + token omni:rtx:background:source:texture:textureMode = "repeatMirrored" + token omni:rtx:background:source:type = "domeLight" + bool omni:rtx:dlss:frameGeneration = 0 + string omni:rtx:material:db:rtSensorNameToIdMap = "DefaultMaterial:0;AsphaltStandardMaterial:1;AsphaltWeatheredMaterial:2;VegetationGrassMaterial:3;WaterStandardMaterial:4;GlassStandardMaterial:5;FiberGlassMaterial:6;MetalAlloyMaterial:7;MetalAluminumMaterial:8;MetalAluminumOxidizedMaterial:9;PlasticStandardMaterial:10;RetroMarkingsMaterial:11;RetroSignMaterial:12;RubberStandardMaterial:13;SoilClayMaterial:14;ConcreteRoughMaterial:15;ConcreteSmoothMaterial:16;OakTreeBarkMaterial:17;FabricStandardMaterial:18;PlexiGlassStandardMaterial:19;MetalSilverMaterial:20" + bool omni:rtx:material:db:syncLoads = 1 + bool omni:rtx:post:registeredCompositing:invertColorCorrection = 1 + bool omni:rtx:post:registeredCompositing:invertToneMap = 1 + bool omni:rtx:pt:lightcache:cached:dontResolveConflicts = 1 + int omni:rtx:pt:maxSamplesPerLaunch = 2073600 + int omni:rtx:pt:mgpu:maxPixelsPerRegionExponent = 12 + color3f omni:rtx:rt:ambientLight:color = (0.1, 0.1, 0.1) + bool omni:rtx:rt:demoire = 0 + bool omni:rtx:rt:lightcache:spatialCache:dontResolveConflicts = 1 + bool omni:rtx:scene:hydra:materialSyncLoads = 1 + bool omni:rtx:scene:hydra:mdlMaterialWarmup = 1 + uint omni:rtx:viewTile:limit = 4294967295 + rel orderedVars = + custom bool overrideClipRange = 0 + uniform int2 resolution = (1920, 1080) + } + } + } + + def RenderSettings "OmniverseGlobalRenderSettings" ( + apiSchemas = ["OmniRtxSettingsGlobalRtAdvancedAPI_1", "OmniRtxSettingsGlobalPtAdvancedAPI_1"] + no_delete = true + ) + { + rel products = + } + + def "Vars" + { + def RenderVar "LdrColor" ( + hide_in_stage_window = true + no_delete = true + ) + { + uniform string sourceName = "LdrColor" + } + } +} + diff --git a/newton/tests/test_broad_phase.py b/newton/tests/test_broad_phase.py index 89a4a1d264..a851191d62 100644 --- a/newton/tests/test_broad_phase.py +++ b/newton/tests/test_broad_phase.py @@ -371,8 +371,6 @@ def test_nxn_broadphase_multiple_worlds(self): candidate_pair_count, ) - wp.synchronize() - # Get results pairs_wp = candidate_pair.numpy() num_candidate_pair_result = candidate_pair_count.numpy()[0] @@ -579,8 +577,6 @@ def test_nxn_broadphase_with_shape_flags(self): candidate_pair_count, ) - wp.synchronize() - # Get results pairs_wp = candidate_pair.numpy() num_candidate_pair_result = candidate_pair_count.numpy()[0] @@ -1171,8 +1167,6 @@ def _test_sap_broadphase_with_shape_flags_impl(self, sort_type): candidate_pair_count, ) - wp.synchronize() - # Get results pairs_wp = candidate_pair.numpy() num_candidate_pair_result = candidate_pair_count.numpy()[0] @@ -1555,8 +1549,6 @@ def test_nxn_edge_cases(self): candidate_pair_count, ) - wp.synchronize() - # Get results pairs_wp = candidate_pair.numpy() num_candidate_pair_result = candidate_pair_count.numpy()[0] @@ -1964,8 +1956,6 @@ def _test_sap_edge_cases_impl(self, sort_type): candidate_pair_count, ) - wp.synchronize() - # Get results pairs_wp = candidate_pair.numpy() num_candidate_pair_result = candidate_pair_count.numpy()[0] diff --git a/newton/tests/test_collision_pipeline.py b/newton/tests/test_collision_pipeline.py index 9dc0b94e3f..d1bc1a6ba4 100644 --- a/newton/tests/test_collision_pipeline.py +++ b/newton/tests/test_collision_pipeline.py @@ -717,6 +717,71 @@ def test_rigid_contact_normal_sphere_sphere(test, device, broad_phase: str): ) +def test_box_box_quaternion_perturbation(test, device, broad_phase: str): + """Verify box-box contacts are correct under tiny quaternion perturbation. + + Two identical cubes are placed face-to-face with a non-trivial base + rotation (30 deg around X) and a tiny quaternion perturbation (~1e-14) + in the second box only. Without the support-map deadband fix this + produces 1 invalid contact instead of 4 face-corner contacts, with an + out-of-bounds body-frame point and a wrong world-frame normal. + + Regression test for issue #2024 / #2430. + """ + with wp.ScopedDevice(device): + half = 0.495 + q_clean = wp.quat(0.2588233343021173, 0.0, 0.0, 0.9659246769912934) + q_noisy = wp.quat(0.2588233343021173, -2.27e-14, 9.25e-15, 0.9659246769912934) + + y, z = 6.680443286895752, 4.4285125732421875 + + builder = newton.ModelBuilder() + b0 = builder.add_body(xform=wp.transform(p=wp.vec3(half, y, z), q=q_clean)) + builder.add_shape_box(body=b0, hx=half, hy=half, hz=half) + + b1 = builder.add_body(xform=wp.transform(p=wp.vec3(-half, y, z), q=q_noisy)) + builder.add_shape_box(body=b1, hx=half, hy=half, hz=half) + + model = builder.finalize(device=device) + state = model.state() + + pipeline = newton.CollisionPipeline(model, broad_phase=broad_phase) + contacts = pipeline.contacts() + pipeline.collide(state, contacts) + + cc = int(contacts.rigid_contact_count.numpy()[0]) + points0 = contacts.rigid_contact_point0.numpy()[:cc] + normals = contacts.rigid_contact_normal.numpy()[:cc] + + test.assertEqual(cc, 4, f"Expected 4 face-corner contacts, got {cc}") + + for i in range(cc): + pt = points0[i] + n = normals[i] + for j in range(3): + test.assertLessEqual( + abs(pt[j]), + half * 1.01, + f"Contact {i} body-frame point[{j}] = {pt[j]:.4f} outside half-extent {half}", + ) + test.assertAlmostEqual( + abs(n[0]), + 1.0, + places=2, + msg=f"Contact {i} normal = [{n[0]:.4f}, {n[1]:.4f}, {n[2]:.4f}], expected [+-1, 0, 0]", + ) + + +for bp_name in ("explicit", "nxn", "sap"): + add_function_test( + TestRigidContactNormal, + f"test_box_box_quaternion_perturbation_{bp_name}", + test_box_box_quaternion_perturbation, + devices=devices, + broad_phase=bp_name, + ) + + # ============================================================================ # Particle-Shape (Soft) Contact Tests # ============================================================================ @@ -1031,5 +1096,259 @@ def test_particle_shape_contacts(test, device, shape_type: GeoType): ) +# ============================================================================ +# Full-scene deterministic contact pipeline test +# ============================================================================ + + +class TestDeterministicPipeline(unittest.TestCase): + """Test that deterministic=True yields bit-identical contacts across collide calls.""" + + pass + + +def _build_deterministic_scene(device): + """Build the mixed-shape scene from example_basic_shapes6_determinism.""" + from newton._src.geometry import create_mesh_terrain # noqa: PLC0415 + + builder = newton.ModelBuilder() + + # Procedural mesh terrain ground + terrain_vertices, terrain_indices = create_mesh_terrain( + grid_size=(6, 6), + block_size=(5.0, 5.0), + terrain_types=["pyramid_stairs"], + terrain_params={ + "pyramid_stairs": {"step_width": 0.4, "step_height": 0.05, "platform_width": 0.8}, + }, + seed=42, + ) + terrain_mesh = newton.Mesh(terrain_vertices, terrain_indices) + terrain_mesh.build_sdf(max_resolution=512) + builder.add_shape_mesh(body=-1, mesh=terrain_mesh, xform=wp.transform(p=wp.vec3(-15.0, -15.0, -0.5))) + + # Icosahedron mesh + phi = (1.0 + np.sqrt(5.0)) / 2.0 + ico_radius = 0.35 + ico_base_vertices = np.array( + [ + [-1, phi, 0], + [1, phi, 0], + [-1, -phi, 0], + [1, -phi, 0], + [0, -1, phi], + [0, 1, phi], + [0, -1, -phi], + [0, 1, -phi], + [phi, 0, -1], + [phi, 0, 1], + [-phi, 0, -1], + [-phi, 0, 1], + ], + dtype=np.float32, + ) + for i in range(len(ico_base_vertices)): + ico_base_vertices[i] = ico_base_vertices[i] / np.linalg.norm(ico_base_vertices[i]) * ico_radius + ico_face_indices = [ + [0, 11, 5], + [0, 5, 1], + [0, 1, 7], + [0, 7, 10], + [0, 10, 11], + [1, 5, 9], + [5, 11, 4], + [11, 10, 2], + [10, 7, 6], + [7, 1, 8], + [3, 9, 4], + [3, 4, 2], + [3, 2, 6], + [3, 6, 8], + [3, 8, 9], + [4, 9, 5], + [2, 4, 11], + [6, 2, 10], + [8, 6, 7], + [9, 8, 1], + ] + ico_vertices, ico_normals, ico_indices = [], [], [] + for face_idx, face in enumerate(ico_face_indices): + v0, v1, v2 = ico_base_vertices[face[0]], ico_base_vertices[face[1]], ico_base_vertices[face[2]] + normal = np.cross(v1 - v0, v2 - v0) + normal = normal / np.linalg.norm(normal) + ico_vertices.extend([v0, v1, v2]) + ico_normals.extend([normal, normal, normal]) + base = face_idx * 3 + ico_indices.extend([base, base + 1, base + 2]) + ico_mesh = newton.Mesh( + np.array(ico_vertices, dtype=np.float32), + np.array(ico_indices, dtype=np.int32), + normals=np.array(ico_normals, dtype=np.float32), + ) + + # Cube mesh with SDF + hs = 0.3 + cube_verts = np.array( + [ + [-hs, -hs, -hs], + [hs, -hs, -hs], + [hs, hs, -hs], + [-hs, hs, -hs], + [-hs, -hs, hs], + [hs, -hs, hs], + [hs, hs, hs], + [-hs, hs, hs], + ], + dtype=np.float32, + ) + cube_tris = np.array( + [0, 3, 2, 0, 2, 1, 4, 5, 6, 4, 6, 7, 0, 1, 5, 0, 5, 4, 2, 3, 7, 2, 7, 6, 0, 4, 7, 0, 7, 3, 1, 2, 6, 1, 6, 5], + dtype=np.int32, + ) + cube_mesh = newton.Mesh(cube_verts, cube_tris) + cube_mesh.build_sdf(max_resolution=64) + + # 4x4x4 grid of mixed shapes + shape_types = ["sphere", "box", "capsule", "mesh_cube", "cylinder", "cone", "icosahedron"] + grid_offset = wp.vec3(-5.0, -5.0, 0.5) + rng = np.random.default_rng(42) + shape_index = 0 + for ix in range(4): + for iy in range(4): + for iz in range(4): + pos = wp.vec3( + float(grid_offset[0]) + ix * 1.5 + (rng.random() - 0.5) * 0.4, + float(grid_offset[1]) + iy * 1.5 + (rng.random() - 0.5) * 0.4, + float(grid_offset[2]) + iz * 1.5 + (rng.random() - 0.5) * 0.4, + ) + shape_type = shape_types[shape_index % len(shape_types)] + shape_index += 1 + body = builder.add_body(xform=wp.transform(p=pos, q=wp.quat_identity())) + if shape_type == "sphere": + builder.add_shape_sphere(body, radius=0.3) + elif shape_type == "box": + builder.add_shape_box(body, hx=0.3, hy=0.3, hz=0.3) + elif shape_type == "capsule": + builder.add_shape_capsule(body, radius=0.2, half_height=0.4) + elif shape_type == "cylinder": + builder.add_shape_cylinder(body, radius=0.25, half_height=0.35) + elif shape_type == "cone": + builder.add_shape_cone(body, radius=0.3, half_height=0.4) + elif shape_type == "mesh_cube": + builder.add_shape_mesh(body, mesh=cube_mesh) + elif shape_type == "icosahedron": + builder.add_shape_convex_hull(body, mesh=ico_mesh) + joint = builder.add_joint_free(body) + builder.add_articulation([joint]) + + model = builder.finalize(device=device) + return model + + +def test_deterministic_pipeline_500_steps(test, device): + """Run 500 steps of the mixed-shape scene and assert bit-identical contacts on every collide.""" + with wp.ScopedDevice(device): + model = _build_deterministic_scene(device) + + pipeline_a = newton.CollisionPipeline( + model, + broad_phase="nxn", + deterministic=True, + reduce_contacts=True, + rigid_contact_max=50000, + ) + pipeline_b = newton.CollisionPipeline( + model, + broad_phase="nxn", + deterministic=True, + reduce_contacts=True, + rigid_contact_max=50000, + ) + contacts_a = pipeline_a.contacts() + contacts_b = pipeline_b.contacts() + + solver = newton.solvers.SolverXPBD(model, iterations=2, rigid_contact_relaxation=0.8) + state_0 = model.state() + state_1 = model.state() + control = model.control() + newton.eval_fk(model, model.joint_q, model.joint_qd, state_0) + + fps = 100 + sim_substeps = 10 + sim_dt = 1.0 / fps / sim_substeps + + checked_arrays = [ + "rigid_contact_shape0", + "rigid_contact_shape1", + "rigid_contact_point0", + "rigid_contact_point1", + "rigid_contact_normal", + "rigid_contact_offset0", + "rigid_contact_offset1", + "rigid_contact_margin0", + "rigid_contact_margin1", + ] + + total_checks = 0 + for _frame in range(500): + for _sub in range(sim_substeps): + state_0.clear_forces() + pipeline_a.collide(state_0, contacts_a) + pipeline_b.collide(state_0, contacts_b) + + count_a = int(contacts_a.rigid_contact_count.numpy()[0]) + count_b = int(contacts_b.rigid_contact_count.numpy()[0]) + test.assertEqual( + count_a, + count_b, + f"Contact count mismatch at frame {_frame} substep {_sub}: {count_a} vs {count_b}", + ) + if count_a > 0: + # Also compare sort keys to distinguish ordering vs value issues + keys_a = pipeline_a._sort_key_array.numpy()[:count_a] + keys_b = pipeline_b._sort_key_array.numpy()[:count_a] + keys_match = np.array_equal(keys_a, keys_b) + + for name in checked_arrays: + a = getattr(contacts_a, name).numpy()[:count_a] + b = getattr(contacts_b, name).numpy()[:count_a] + if not np.array_equal(a, b): + diff_mask = a != b + diff_indices = np.argwhere(diff_mask) + msg = ( + f"Determinism failure in {name} at frame {_frame} substep {_sub} " + f"({int(np.count_nonzero(diff_mask))} elements differ, {count_a} contacts)\n" + f" sort_keys_match={keys_match}\n" + ) + for raw_idx in diff_indices[:5]: + tidx = tuple(raw_idx) + msg += f" [{tidx}]: a={a[tidx]!r} b={b[tidx]!r} diff={float(a[tidx]) - float(b[tidx]):.18e}\n" + if not keys_match: + key_diff = np.argwhere(keys_a != keys_b) + msg += f" sort_key diffs at indices: {key_diff[:10].flatten().tolist()}\n" + for ki in key_diff[:5].flatten(): + msg += f" key[{ki}]: a=0x{keys_a[ki]:016x} b=0x{keys_b[ki]:016x}\n" + # Show shape pairs for differing contacts + s0_a = contacts_a.rigid_contact_shape0.numpy()[:count_a] + s1_a = contacts_a.rigid_contact_shape1.numpy()[:count_a] + for idx in diff_indices[:5]: + ci = idx[0] if len(idx) > 1 else int(idx) + msg += f" contact[{ci}]: shapes=({s0_a[ci]}, {s1_a[ci]}), key_a=0x{keys_a[ci]:016x}\n" + test.assertTrue(False, msg) + total_checks += 1 + + solver.step(state_0, state_1, control, contacts_a, sim_dt) + state_0, state_1 = state_1, state_0 + + +add_function_test( + TestDeterministicPipeline, + "test_deterministic_pipeline_500_steps", + test_deterministic_pipeline_500_steps, + devices=get_cuda_test_devices(), + check_output=False, +) + + if __name__ == "__main__": unittest.main(verbosity=2, failfast=False) diff --git a/newton/tests/test_contact_reduction_global.py b/newton/tests/test_contact_reduction_global.py index 63fbfd294d..068589d594 100644 --- a/newton/tests/test_contact_reduction_global.py +++ b/newton/tests/test_contact_reduction_global.py @@ -8,10 +8,15 @@ import numpy as np import warp as wp -from newton._src.geometry.contact_data import ContactData +from newton._src.geometry.contact_data import ContactData, make_contact_sort_key +from newton._src.geometry.contact_reduction import float_flip from newton._src.geometry.contact_reduction_global import ( + SCORE_SHIFT, GlobalContactReducer, GlobalContactReducerData, + _make_contact_value_det, + _make_preprune_probe_det, + _unpack_contact_id_det, create_export_reduced_contacts_kernel, decode_oct, encode_oct, @@ -108,6 +113,7 @@ def store_contact_kernel( position=wp.vec3(1.0, 2.0, 3.0), normal=wp.vec3(0.0, 1.0, 0.0), depth=-0.01, + fingerprint=0, reducer_data=reducer_data, beta=0.001, shape_transform=xform, @@ -169,6 +175,7 @@ def store_multiple_contacts_kernel( position=wp.vec3(x, 0.0, 0.0), normal=wp.vec3(0.0, 1.0, 0.0), depth=-0.01, + fingerprint=0, reducer_data=reducer_data, beta=0.001, shape_transform=xform, @@ -228,6 +235,7 @@ def store_different_pairs_kernel( position=wp.vec3(0.0, 0.0, 0.0), normal=wp.vec3(0.0, 1.0, 0.0), depth=-0.01, + fingerprint=0, reducer_data=reducer_data, beta=0.001, shape_transform=xform, @@ -284,6 +292,7 @@ def store_one_contact_kernel( position=wp.vec3(0.0, 0.0, 0.0), normal=wp.vec3(0.0, 1.0, 0.0), depth=-0.01, + fingerprint=0, reducer_data=reducer_data, beta=0.001, shape_transform=xform, @@ -358,6 +367,7 @@ def stress_kernel( position=wp.vec3(x, y, 0.0), normal=wp.vec3(nx / n_len, ny / n_len, nz / n_len), depth=-0.01, + fingerprint=0, reducer_data=reducer_data, beta=0.001, shape_transform=xform, @@ -414,6 +424,7 @@ def store_contact_kernel( position=wp.vec3(1.0, 2.0, 3.0), normal=wp.vec3(0.0, 1.0, 0.0), depth=-0.01, + fingerprint=0, reducer_data=reducer_data, beta=0.001, shape_transform=xform, @@ -503,6 +514,7 @@ def store_contacts_kernel( position=wp.vec3(float(tid), 0.0, 0.0), normal=wp.vec3(0.0, 1.0, 0.0), depth=-0.01, + fingerprint=0, reducer_data=reducer_data, beta=0.001, shape_transform=xform, @@ -568,12 +580,14 @@ def store_contacts_kernel( reducer.position_depth, reducer.normal, reducer.shape_pairs, + reducer.contact_fingerprints, reducer.exported_flags, shape_types, shape_data, shape_gap, writer_data, total_threads, + 0, # deterministic=0 (fast packing) ], device=device, ) @@ -671,6 +685,7 @@ def store_centered_contacts_kernel(reducer_data: GlobalContactReducerData): position=position, normal=normal, depth=depth, + fingerprint=0, centered_position=centered_position, X_ws_voxel_shape=X_ws_shape, aabb_lower_voxel=aabb_lower, @@ -708,6 +723,7 @@ def store_different_pairs_centered_kernel(reducer_data: GlobalContactReducerData position=wp.vec3(0.0, 0.0, 0.0), normal=wp.vec3(0.0, 1.0, 0.0), depth=-0.01, + fingerprint=0, centered_position=wp.vec3(0.0, 0.0, 0.0), X_ws_voxel_shape=X_ws_shape, aabb_lower_voxel=aabb_lower, @@ -742,6 +758,7 @@ def store_varying_depth_kernel(reducer_data: GlobalContactReducerData): position=wp.vec3(0.0, 0.0, 0.0), normal=wp.vec3(0.0, 1.0, 0.0), depth=depth, + fingerprint=0, centered_position=wp.vec3(0.0, 0.0, 0.0), X_ws_voxel_shape=X_ws_shape, aabb_lower_voxel=aabb_lower, @@ -796,6 +813,7 @@ def store_extreme_contacts_kernel(reducer_data: GlobalContactReducerData): position=positions, normal=wp.vec3(0.0, 1.0, 0.0), depth=-0.5, + fingerprint=0, centered_position=positions, X_ws_voxel_shape=X_ws, aabb_lower_voxel=wp.vec3(-15.0, -5.0, -15.0), @@ -805,7 +823,6 @@ def store_extreme_contacts_kernel(reducer_data: GlobalContactReducerData): ) wp.launch(store_extreme_contacts_kernel, dim=4, inputs=[reducer_data], device=device) - wp.synchronize() count_after_extremes = get_contact_count(reducer) test.assertEqual(count_after_extremes, 4) @@ -821,6 +838,7 @@ def store_one_dominated_contact_kernel( position=wp.vec3(x_offset, 0.0, 0.0), normal=wp.vec3(0.0, 1.0, 0.0), depth=-0.001, + fingerprint=0, centered_position=wp.vec3(x_offset, 0.0, 0.0), X_ws_voxel_shape=X_ws, aabb_lower_voxel=wp.vec3(-15.0, -5.0, -15.0), @@ -854,6 +872,439 @@ def store_one_dominated_contact_kernel( ) +# ============================================================================= +# Float-flip precision tests +# ============================================================================= + + +@wp.func_native(""" +uint32_t mask = ((u >> 31) - 1) | 0x80000000; +uint32_t i = u ^ mask; +return reinterpret_cast(i); +""") +def ifloat_flip(u: wp.uint32) -> float: ... + + +@wp.kernel(enable_backward=False) +def float_flip_roundtrip_kernel( + values_in: wp.array[float], + values_out: wp.array[float], + truncated_out: wp.array[wp.uint32], + score_shift: int, +): + """Apply float_flip, clear low bits, then ifloat_flip to measure precision loss.""" + tid = wp.tid() + f = values_in[tid] + flipped = float_flip(f) + truncated = (flipped >> wp.uint32(score_shift)) << wp.uint32(score_shift) + reconstructed = ifloat_flip(truncated) + values_out[tid] = reconstructed + truncated_out[tid] = truncated + + +class TestFloatFlipPrecision(unittest.TestCase): + """Test float_flip / ifloat_flip roundtrip precision with the SCORE_SHIFT used in contact reduction.""" + + pass + + +def test_float_flip_roundtrip_precision(test, device): + """Validate that ifloat_flip((float_flip(f) >> SCORE_SHIFT) << SCORE_SHIFT) preserves + order and maintains relative precision ~2^-(23-SCORE_SHIFT).""" + score_shift = SCORE_SHIFT + mantissa_bits_kept = 23 - score_shift + max_relative_error = 2.0 ** (-mantissa_bits_kept) # ~1.22e-4 + + # --- Build test values spanning actual score ranges --- + # Depth scores: -depth in [0.0001, 0.1] + depth_scores = np.linspace(0.0001, 0.1, 200, dtype=np.float32) + # Spatial scores: dot(pos_2d, dir_2d) in [-10, +10] + spatial_scores = np.linspace(-10.0, 10.0, 600, dtype=np.float32) + # Dense sweep around 1.0 to probe distinguishability + dense_sweep = np.linspace(0.999, 1.001, 100, dtype=np.float32) + # Edge cases + edge_cases = np.array( + [0.0, -0.0, 1e-6, -1e-6, 1e-4, -1e-4, 1.0, -1.0, 100.0, -100.0], + dtype=np.float32, + ) + + all_values = np.concatenate([depth_scores, spatial_scores, dense_sweep, edge_cases]) + n = len(all_values) + + values_in = wp.array(all_values, dtype=float, device=device) + values_out = wp.zeros(n, dtype=float, device=device) + truncated_out = wp.zeros(n, dtype=wp.uint32, device=device) + + wp.launch( + float_flip_roundtrip_kernel, + dim=n, + inputs=[values_in, values_out, truncated_out, score_shift], + device=device, + ) + + orig = all_values + recon = values_out.numpy() + trunc = truncated_out.numpy() + + # --- 1. Roundtrip for +0.0 (positive zero roundtrips exactly; + # -0.0 maps to a tiny negative via float_flip, which is fine) --- + pos_zero_mask = (orig == 0.0) & ~np.signbit(orig) + if np.any(pos_zero_mask): + test.assertTrue( + np.all(recon[pos_zero_mask] == 0.0), + "Positive zero must roundtrip exactly", + ) + + # --- 2. Relative error bound --- + nonzero_mask = np.abs(orig) > 1e-30 + rel_err = np.abs(recon[nonzero_mask] - orig[nonzero_mask]) / np.abs(orig[nonzero_mask]) + worst_rel = float(np.max(rel_err)) + test.assertLessEqual( + worst_rel, + max_relative_error, + f"Worst relative error {worst_rel:.6e} exceeds 2^-{mantissa_bits_kept} = {max_relative_error:.6e}", + ) + + # --- 3. Order preservation (monotonicity) --- + sorted_idx = np.argsort(orig) + sorted_orig = orig[sorted_idx] + sorted_trunc = trunc[sorted_idx] + violations = 0 + for i in range(len(sorted_orig) - 1): + if sorted_orig[i] < sorted_orig[i + 1] and sorted_trunc[i] > sorted_trunc[i + 1]: + violations += 1 + test.assertEqual(violations, 0, f"Order violations: {violations}") + + # --- 4. Distinguishability at the precision floor --- + # Two values separated by more than 2^-(mantissa_bits_kept) relative + # to their magnitude must produce different truncated values. + base = np.float32(1.0) + eps_distinguishable = np.float32(2.0 ** (-mantissa_bits_kept + 1)) # 2x the LSB + pair = np.array([base, base + eps_distinguishable], dtype=np.float32) + pair_in = wp.array(pair, dtype=float, device=device) + pair_out = wp.zeros(2, dtype=float, device=device) + pair_trunc = wp.zeros(2, dtype=wp.uint32, device=device) + wp.launch( + float_flip_roundtrip_kernel, + dim=2, + inputs=[pair_in, pair_out, pair_trunc, score_shift], + device=device, + ) + t = pair_trunc.numpy() + test.assertNotEqual( + int(t[0]), + int(t[1]), + f"Values {pair[0]} and {pair[1]} (eps={eps_distinguishable:.6e}) must produce different truncated values", + ) + + # --- 5. Sign correctness: all negatives map below all positives --- + neg_mask = orig < 0 + pos_mask = orig > 0 + if np.any(neg_mask) and np.any(pos_mask): + max_neg_trunc = int(np.max(trunc[neg_mask])) + min_pos_trunc = int(np.min(trunc[pos_mask])) + test.assertLess( + max_neg_trunc, + min_pos_trunc, + "All negative truncated values must be less than all positive truncated values", + ) + + +def test_float_flip_exact_inverse(test, device): + """Verify ifloat_flip(float_flip(f)) == f exactly (no truncation).""" + values = np.array( + [0.0, -0.0, 1.0, -1.0, 0.5, -0.5, 3.14159, -2.71828, 1e-6, -1e-6, 1e6, -1e6, 42.0], + dtype=np.float32, + ) + n = len(values) + values_in = wp.array(values, dtype=float, device=device) + values_out = wp.zeros(n, dtype=float, device=device) + truncated_out = wp.zeros(n, dtype=wp.uint32, device=device) + + # Use score_shift=0 for exact roundtrip (no bits cleared) + wp.launch( + float_flip_roundtrip_kernel, + dim=n, + inputs=[values_in, values_out, truncated_out, 0], + device=device, + ) + + orig = values + recon = values_out.numpy() + for i in range(n): + test.assertEqual( + orig[i], + recon[i], + f"Exact roundtrip failed for {orig[i]}: got {recon[i]}", + ) + + +# ============================================================================= +# make_contact_sort_key tests +# ============================================================================= + + +class TestMakeContactSortKey(unittest.TestCase): + """Test make_contact_sort_key bit layout and ordering.""" + + pass + + +@wp.kernel(enable_backward=False) +def _sort_key_kernel( + shape_a: wp.array[int], + shape_b: wp.array[int], + sub_key: wp.array[int], + keys_out: wp.array[wp.int64], +): + tid = wp.tid() + keys_out[tid] = make_contact_sort_key(shape_a[tid], shape_b[tid], sub_key[tid]) + + +def test_sort_key_bit_layout(test, device): + """Verify that make_contact_sort_key produces correct lexicographic ordering.""" + # Pairs ordered lexicographically: (shape_a, shape_b, sub_key) + # Each successive entry should produce a strictly larger key. + sa = wp.array([0, 0, 0, 1, 1], dtype=int, device=device) + sb = wp.array([0, 0, 1, 0, 0], dtype=int, device=device) + sk = wp.array([0, 1, 0, 0, 1], dtype=int, device=device) + keys = wp.zeros(5, dtype=wp.int64, device=device) + wp.launch(_sort_key_kernel, dim=5, inputs=[sa, sb, sk, keys], device=device) + + keys_np = keys.numpy() + for i in range(len(keys_np) - 1): + test.assertLess( + keys_np[i], + keys_np[i + 1], + f"Key[{i}]={keys_np[i]} should be < Key[{i + 1}]={keys_np[i + 1]}", + ) + + +def test_sort_key_overflow_masking(test, device): + """Verify that values exceeding bit widths are masked (not corrupting other fields).""" + # shape_a with 21 bits set (exceeds 20-bit field) — high bit should be masked + large_a = (1 << 21) | 5 # bit 20 set + low bits + sa = wp.array([large_a, 5], dtype=int, device=device) + sb = wp.array([0, 0], dtype=int, device=device) + sk = wp.array([0, 0], dtype=int, device=device) + keys = wp.zeros(2, dtype=wp.int64, device=device) + wp.launch(_sort_key_kernel, dim=2, inputs=[sa, sb, sk, keys], device=device) + + keys_np = keys.numpy() + # After masking to 20 bits, large_a & 0xFFFFF == 5, so both keys should be equal + test.assertEqual(keys_np[0], keys_np[1], "Overflow bits should be masked away") + + +# ============================================================================= +# Deterministic packing function tests +# ============================================================================= + + +class TestDeterministicPacking(unittest.TestCase): + """Test deterministic contact value packing and unpacking.""" + + pass + + +@wp.kernel(enable_backward=False) +def _det_pack_unpack_kernel( + scores: wp.array[float], + fingerprints: wp.array[int], + contact_ids: wp.array[int], + packed_out: wp.array[wp.uint64], + unpacked_ids_out: wp.array[int], +): + tid = wp.tid() + packed = _make_contact_value_det(scores[tid], fingerprints[tid], contact_ids[tid]) + packed_out[tid] = packed + unpacked_ids_out[tid] = _unpack_contact_id_det(packed) + + +def test_det_pack_unpack_roundtrip(test, device): + """Verify contact_id survives pack/unpack roundtrip in deterministic mode.""" + n = 5 + scores = wp.array([0.1, 0.5, -0.01, 1.0, 0.0], dtype=float, device=device) + fps = wp.array([0, 100, 999999, 42, 0], dtype=int, device=device) + ids = wp.array([0, 1, 1048575, 500, 12345], dtype=int, device=device) + packed = wp.zeros(n, dtype=wp.uint64, device=device) + unpacked = wp.zeros(n, dtype=int, device=device) + + wp.launch(_det_pack_unpack_kernel, dim=n, inputs=[scores, fps, ids, packed, unpacked], device=device) + + ids_np = ids.numpy() + unpacked_np = unpacked.numpy() + for i in range(n): + expected = ids_np[i] & ((1 << 20) - 1) + test.assertEqual( + unpacked_np[i], + expected, + f"Roundtrip failed for contact_id={ids_np[i]}: got {unpacked_np[i]}, expected {expected}", + ) + + +def test_det_packing_score_dominates(test, device): + """Verify that higher score always produces a larger packed value.""" + n = 2 + # Same fingerprint and contact_id, different scores + scores = wp.array([0.1, 0.5], dtype=float, device=device) + fps = wp.array([42, 42], dtype=int, device=device) + ids = wp.array([10, 10], dtype=int, device=device) + packed = wp.zeros(n, dtype=wp.uint64, device=device) + unpacked = wp.zeros(n, dtype=int, device=device) + + wp.launch(_det_pack_unpack_kernel, dim=n, inputs=[scores, fps, ids, packed, unpacked], device=device) + + packed_np = packed.numpy() + test.assertLess(packed_np[0], packed_np[1], "Higher score should produce larger packed value") + + +def test_det_packing_fingerprint_breaks_tie(test, device): + """Verify that fingerprint breaks ties when scores are equal.""" + n = 2 + # Same score and contact_id, different fingerprints + scores = wp.array([0.5, 0.5], dtype=float, device=device) + fps = wp.array([10, 20], dtype=int, device=device) + ids = wp.array([5, 5], dtype=int, device=device) + packed = wp.zeros(n, dtype=wp.uint64, device=device) + unpacked = wp.zeros(n, dtype=int, device=device) + + wp.launch(_det_pack_unpack_kernel, dim=n, inputs=[scores, fps, ids, packed, unpacked], device=device) + + packed_np = packed.numpy() + test.assertNotEqual(packed_np[0], packed_np[1], "Different fingerprints should produce different packed values") + test.assertLess(packed_np[0], packed_np[1], "Higher fingerprint should produce larger packed value") + + +@wp.kernel(enable_backward=False) +def _det_preprune_probe_kernel( + scores: wp.array[float], + fingerprints: wp.array[int], + probes_out: wp.array[wp.uint64], +): + tid = wp.tid() + probes_out[tid] = _make_preprune_probe_det(scores[tid], fingerprints[tid]) + + +def test_det_preprune_probe_is_ceiling(test, device): + """Verify that the preprune probe is >= any packed value with the same score and fingerprint.""" + n = 1 + score = wp.array([0.5], dtype=float, device=device) + fp = wp.array([42], dtype=int, device=device) + probe = wp.zeros(n, dtype=wp.uint64, device=device) + wp.launch(_det_preprune_probe_kernel, dim=n, inputs=[score, fp, probe], device=device) + + # Pack with same score/fp but various contact_ids + ids_to_test = [0, 1, 100, 500000, (1 << 20) - 1] + for cid in ids_to_test: + ids_arr = wp.array([cid], dtype=int, device=device) + packed = wp.zeros(1, dtype=wp.uint64, device=device) + unpacked = wp.zeros(1, dtype=int, device=device) + wp.launch(_det_pack_unpack_kernel, dim=1, inputs=[score, fp, ids_arr, packed, unpacked], device=device) + + probe_val = int(probe.numpy()[0]) + packed_val = int(packed.numpy()[0]) + test.assertGreaterEqual( + probe_val, + packed_val, + f"Preprune probe should be >= packed value for contact_id={cid}", + ) + + +# ============================================================================= +# End-to-end deterministic test +# ============================================================================= + + +class TestDeterministicEndToEnd(unittest.TestCase): + """End-to-end test that deterministic mode produces identical contacts across runs.""" + + pass + + +def test_deterministic_identical_across_runs(test, device): + """Create a deterministic reducer, collide the same scene N times, assert identical winners. + + Compares winning contacts by their geometric content (position, depth, + fingerprint) rather than buffer contact IDs, since IDs are assigned by + atomic_add and vary between runs. + """ + if str(device) == "cpu": + return # Deterministic mode is primarily for GPU + + num_runs = 5 + all_contact_sets = [] + + for _ in range(num_runs): + reducer = GlobalContactReducer(capacity=500, device=device, deterministic=True) + reducer_data = reducer.get_data_struct() + + @wp.kernel(enable_backward=False) + def store_contacts_det_kernel(reducer_data: GlobalContactReducerData): + tid = wp.tid() + x = float(tid % 10) - 5.0 + z = float(tid // 10) - 5.0 + depth = -0.001 * float((tid * 7 + 3) % 20 + 1) + fingerprint = tid * 3 + 1 + + X_ws = wp.transform(wp.vec3(0.0, 0.0, 0.0), wp.quat_identity()) + export_and_reduce_contact_centered( + shape_a=0, + shape_b=1, + position=wp.vec3(x, 0.0, z), + normal=wp.vec3(0.0, 1.0, 0.0), + depth=depth, + fingerprint=fingerprint, + centered_position=wp.vec3(x, 0.0, z), + X_ws_voxel_shape=X_ws, + aabb_lower_voxel=wp.vec3(-10.0, -5.0, -10.0), + aabb_upper_voxel=wp.vec3(10.0, 5.0, 10.0), + voxel_res=wp.vec3i(4, 4, 4), + reducer_data=reducer_data, + ) + + wp.launch(store_contacts_det_kernel, dim=100, inputs=[reducer_data], device=device) + + # Extract winning contacts by geometric content (not by contact ID) + values = reducer.ht_values.numpy() + capacity = reducer.hashtable.capacity + active_slots_np = reducer.hashtable.active_slots.numpy() + count = active_slots_np[capacity] + pd_np = reducer.position_depth.numpy() + fp_np = reducer.contact_fingerprints.numpy() + + seen_ids = set() + contact_set = set() + for i in range(count): + entry_idx = active_slots_np[i] + for slot in range(reducer.values_per_key): + val = values[slot * capacity + entry_idx] + if val != 0: + contact_id = int(val & ((1 << 20) - 1)) + if contact_id not in seen_ids: + seen_ids.add(contact_id) + pd = pd_np[contact_id] + fp = int(fp_np[contact_id]) + # Round to avoid floating-point noise from storage + key = ( + round(float(pd[0]), 5), + round(float(pd[1]), 5), + round(float(pd[2]), 5), + round(float(pd[3]), 5), + fp, + ) + contact_set.add(key) + + all_contact_sets.append(contact_set) + + # All runs should produce identical geometric contact sets + for run_idx in range(1, num_runs): + test.assertEqual( + all_contact_sets[0], + all_contact_sets[run_idx], + f"Run 0 and run {run_idx} produced different winning contacts", + ) + + # ============================================================================= # Test registration # ============================================================================= @@ -906,6 +1357,52 @@ def store_one_dominated_contact_kernel( test_oct_encode_decode_roundtrip, devices=devices, ) +add_function_test( + TestFloatFlipPrecision, + "test_float_flip_roundtrip_precision", + test_float_flip_roundtrip_precision, + devices=devices, +) +add_function_test( + TestFloatFlipPrecision, + "test_float_flip_exact_inverse", + test_float_flip_exact_inverse, + devices=devices, +) + +# make_contact_sort_key tests +add_function_test(TestMakeContactSortKey, "test_sort_key_bit_layout", test_sort_key_bit_layout, devices=devices) +add_function_test( + TestMakeContactSortKey, "test_sort_key_overflow_masking", test_sort_key_overflow_masking, devices=devices +) + +# Deterministic packing tests +add_function_test( + TestDeterministicPacking, "test_det_pack_unpack_roundtrip", test_det_pack_unpack_roundtrip, devices=devices +) +add_function_test( + TestDeterministicPacking, "test_det_packing_score_dominates", test_det_packing_score_dominates, devices=devices +) +add_function_test( + TestDeterministicPacking, + "test_det_packing_fingerprint_breaks_tie", + test_det_packing_fingerprint_breaks_tie, + devices=devices, +) +add_function_test( + TestDeterministicPacking, + "test_det_preprune_probe_is_ceiling", + test_det_preprune_probe_is_ceiling, + devices=devices, +) + +# End-to-end deterministic test +add_function_test( + TestDeterministicEndToEnd, + "test_deterministic_identical_across_runs", + test_deterministic_identical_across_runs, + devices=devices, +) if __name__ == "__main__": diff --git a/newton/tests/test_hashtable.py b/newton/tests/test_hashtable.py index 86d0e4b149..cc815904c6 100644 --- a/newton/tests/test_hashtable.py +++ b/newton/tests/test_hashtable.py @@ -76,7 +76,6 @@ def insert_test_kernel( inputs=[ht.keys, values, ht.active_slots], device=device, ) - wp.synchronize() # Find the entry keys_np = ht.keys.numpy() @@ -116,7 +115,6 @@ def atomic_max_test_kernel( inputs=[ht.keys, values, ht.active_slots], device=device, ) - wp.synchronize() # Find the entry keys_np = ht.keys.numpy() @@ -154,7 +152,6 @@ def multi_key_kernel( inputs=[ht.keys, values, ht.active_slots], device=device, ) - wp.synchronize() # Check that we have 100 entries keys_np = ht.keys.numpy() @@ -189,7 +186,6 @@ def insert_kernel( inputs=[ht.keys, values, ht.active_slots], device=device, ) - wp.synchronize() # Verify data exists keys_np = ht.keys.numpy() @@ -230,7 +226,6 @@ def insert_kernel( inputs=[ht.keys, values, ht.active_slots], device=device, ) - wp.synchronize() # Verify data exists active_count = ht.active_slots.numpy()[ht.capacity] @@ -278,7 +273,6 @@ def collision_kernel( inputs=[ht.keys, values, ht.active_slots], device=device, ) - wp.synchronize() # Should have exactly 10 unique keys keys_np = ht.keys.numpy() @@ -318,7 +312,6 @@ def insert_descending_kernel( inputs=[ht.keys, values, ht.active_slots], device=device, ) - wp.synchronize() # Find the entry keys_np = ht.keys.numpy() diff --git a/newton/tests/test_hydroelastic.py b/newton/tests/test_hydroelastic.py index ff28f3d57f..ae6a89898c 100644 --- a/newton/tests/test_hydroelastic.py +++ b/newton/tests/test_hydroelastic.py @@ -834,7 +834,6 @@ def test_entry_k_eff_matches_shape_harmonic_mean(test, device): newton.eval_fk(model, model.joint_q, model.joint_qd, state_0) contacts = pipeline.contacts() pipeline.collide(state_0, contacts) - wp.synchronize() hydro = pipeline.hydroelastic_sdf reducer = hydro.contact_reduction.reducer diff --git a/newton/tests/test_import_usd.py b/newton/tests/test_import_usd.py index 354b718100..3bb81176c1 100644 --- a/newton/tests/test_import_usd.py +++ b/newton/tests/test_import_usd.py @@ -7733,6 +7733,103 @@ def test_get_tetmesh_no_material(self): self.assertIsNone(tm.k_lambda) self.assertIsNone(tm.density) + @unittest.skipUnless(USD_AVAILABLE, "Requires usd-core") + def test_add_usd_imports_tetmesh(self): + """Test that add_usd imports TetMesh prims as soft meshes.""" + asset_path = os.path.join(os.path.dirname(__file__), "assets", "tetmesh_with_material.usda") + + builder = newton.ModelBuilder() + builder.add_usd(asset_path) + + self.assertEqual(len(builder.particle_q), 4) + self.assertEqual(len(builder.tet_indices), 1) + self.assertEqual(len(builder.tri_indices), 4) + self.assertAlmostEqual(builder.tet_materials[0][0], 300000.0 / (2.0 * 1.3), places=0) + self.assertAlmostEqual(builder.tet_materials[0][1], 300000.0 * 0.3 / (1.3 * 0.4), places=0) + self.assertAlmostEqual(sum(builder.particle_mass), 40.0 / 6.0, places=5) + + @unittest.skipUnless(USD_AVAILABLE, "Requires usd-core") + def test_add_usd_imports_instanced_tetmesh_once_per_instance(self): + """Test that instance proxies import one TetMesh per instance.""" + from pxr import Sdf, Usd, UsdGeom + + stage = Usd.Stage.CreateInMemory() + UsdGeom.SetStageUpAxis(stage, UsdGeom.Tokens.z) + + world = UsdGeom.Xform.Define(stage, "/World") + stage.SetDefaultPrim(world.GetPrim()) + + UsdGeom.Xform.Define(stage, "/Prototypes/TetProto") + tetmesh = stage.DefinePrim("/Prototypes/TetProto/SoftBody", "TetMesh") + tetmesh.CreateAttribute("points", Sdf.ValueTypeNames.Point3fArray).Set( + [(0, 0, 0), (1, 0, 0), (0, 1, 0), (0, 0, 1)] + ) + tetmesh.CreateAttribute("tetVertexIndices", Sdf.ValueTypeNames.Int4Array).Set([(0, 1, 2, 3)]) + + for i in range(2): + instance = UsdGeom.Xform.Define(stage, f"/World/Instance{i}") + instance_prim = instance.GetPrim() + instance_prim.GetReferences().AddInternalReference("/Prototypes/TetProto") + instance_prim.SetInstanceable(True) + + builder = newton.ModelBuilder() + builder.add_usd(stage) + + self.assertEqual(len(builder.particle_q), 8) + self.assertEqual(len(builder.tet_indices), 2) + self.assertEqual(len(builder.tri_indices), 8) + + @unittest.skipUnless(USD_AVAILABLE, "Requires usd-core") + def test_add_usd_imports_tetmesh_with_transforms(self): + """Test that add_usd applies TetMesh rotation and non-uniform scale transforms.""" + from pxr import Usd + + stage = Usd.Stage.CreateInMemory() + stage.GetRootLayer().ImportFromString( + """#usda 1.0 +( + defaultPrim = "World" + upAxis = "Z" +) + +def Xform "World" +{ + double3 xformOp:translate = (1, 2, 3) + float xformOp:rotateZ = 90 + float3 xformOp:scale = (2, 3, 4) + uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:rotateZ", "xformOp:scale"] + + def Xform "Offset" + { + double3 xformOp:translate = (0.5, -1, 2) + uniform token[] xformOpOrder = ["xformOp:translate"] + + def TetMesh "SoftBody" () + { + point3f[] points = [(0, 0, 0), (1, 0, 0), (0, 1, 0), (0, 0, 1)] + int4[] tetVertexIndices = [(0, 1, 2, 3)] + } + } +} +""" + ) + + import_quat = wp.quat_from_axis_angle(wp.vec3(0.0, 0.0, 1.0), np.pi) + builder = newton.ModelBuilder() + builder.add_usd(stage, xform=wp.transform((4.0, 5.0, 6.0), import_quat)) + + positions = np.array(builder.particle_q, dtype=np.float32) + expected = np.array( + [ + [0.0, 2.0, 17.0], + [0.0, 0.0, 17.0], + [3.0, 2.0, 17.0], + [0.0, 2.0, 21.0], + ], + dtype=np.float32, + ) + np.testing.assert_allclose(positions, expected, atol=1e-6) + def test_tetmesh_save_load_npz(self): """Test TetMesh round-trip save/load via .npz.""" @@ -7971,6 +8068,61 @@ def test_tetmesh_custom_attributes_to_model(self): self.assertEqual(len(region_arr), model.tet_count) np.testing.assert_array_equal(region_arr, region_id) + @unittest.skipUnless(USD_AVAILABLE, "Requires usd-core") + def test_add_usd_does_not_mutate_loaded_tetmesh_custom_attributes(self): + """Test that add_usd filters TetMesh custom attributes without mutating the loaded mesh.""" + from pxr import Usd + + stage = Usd.Stage.CreateInMemory() + stage.GetRootLayer().ImportFromString( + """#usda 1.0 +( + defaultPrim = "World" +) + +def Xform "World" +{ + def TetMesh "SoftBody" () + { + point3f[] points = [(0, 0, 0), (1, 0, 0), (0, 1, 0), (0, 0, 1)] + int4[] tetVertexIndices = [(0, 1, 2, 3)] + } +} +""" + ) + + source_tetmesh = newton.TetMesh( + vertices=np.array([[0, 0, 0], [1, 0, 0], [0, 1, 0], [0, 0, 1]], dtype=np.float32), + tet_indices=np.array([0, 1, 2, 3], dtype=np.int32), + custom_attributes={ + "temperature": ( + np.array([100.0, 200.0, 300.0, 400.0], dtype=np.float32), + newton.Model.AttributeFrequency.PARTICLE, + ), + "regionId": ( + np.array([7], dtype=np.int32), + newton.Model.AttributeFrequency.TETRAHEDRON, + ), + }, + ) + + builder = newton.ModelBuilder() + builder.add_custom_attribute( + newton.ModelBuilder.CustomAttribute( + name="temperature", + dtype=wp.float32, + frequency=newton.Model.AttributeFrequency.PARTICLE, + ) + ) + + with mock.patch("newton._src.utils.import_usd.usd.get_tetmesh", return_value=source_tetmesh): + builder.add_usd(stage) + + self.assertEqual(set(source_tetmesh.custom_attributes), {"temperature", "regionId"}) + model = builder.finalize() + self.assertTrue(hasattr(model, "temperature")) + self.assertFalse(hasattr(model, "regionId")) + def test_mesh_create_from_file_obj(self): """Test Mesh.create_from_file with an OBJ file.""" diff --git a/newton/tests/test_import_usd_multi_dof.py b/newton/tests/test_import_usd_multi_dof.py new file mode 100644 index 0000000000..76ad90579e --- /dev/null +++ b/newton/tests/test_import_usd_multi_dof.py @@ -0,0 +1,67 @@ +# SPDX-FileCopyrightText: Copyright (c) 2026 The Newton Developers +# SPDX-License-Identifier: Apache-2.0 + +import os +import unittest + +import newton +from newton.tests.unittest_utils import USD_AVAILABLE + + +class TestImportUsdMultiDofJoints(unittest.TestCase): + """Tests for USD import of multi-DOF joints (multiple single-DOF joints between same bodies).""" + + @unittest.skipUnless(USD_AVAILABLE, "Requires usd-core") + def test_humanoid_mjc_multi_dof(self): + """Import a MuJoCo-converted humanoid with multi-joint body pairs. + + The humanoid_mjc.usda file has 21 revolute joints across 13 bodies, + where several body pairs share multiple joints (e.g. 3 hip joints). + These must be merged into D6 joints without triggering cycle errors. + """ + builder = newton.ModelBuilder() + asset_path = os.path.join(os.path.dirname(__file__), "assets", "humanoid_mjc.usda") + + builder.add_usd(asset_path) + + # 13 bodies (torso + 12 child bodies) + self.assertEqual(builder.body_count, 13) + # 13 joints: 1 free root + 7 merged D6 + 5 standalone revolute + self.assertEqual(builder.joint_count, 13) + # 27 DOFs: 6 free root + 21 individual DOFs from the 21 revolute joints + self.assertEqual(builder.joint_dof_count, 27) + + @unittest.skipUnless(USD_AVAILABLE, "Requires usd-core") + def test_humanoid_mjc_path_joint_map(self): + """All original joint prim paths should be in the path_joint_map.""" + builder = newton.ModelBuilder() + asset_path = os.path.join(os.path.dirname(__file__), "assets", "humanoid_mjc.usda") + + result = builder.add_usd(asset_path) + + path_joint_map = result["path_joint_map"] + # All 21 original revolute joint paths should be mapped + self.assertEqual(len(path_joint_map), 21) + + # Merged joints should point to the same joint index + # e.g. right_hip_x, right_hip_z, right_hip_y all map to the same D6 + hip_paths = [p for p in path_joint_map if "right_hip" in p] + self.assertEqual(len(hip_paths), 3) + hip_indices = {path_joint_map[p] for p in hip_paths} + self.assertEqual(len(hip_indices), 1, "All right hip joints should map to the same D6 joint index") + + @unittest.skipUnless(USD_AVAILABLE, "Requires usd-core") + def test_humanoid_mjc_finalize(self): + """The imported humanoid should finalize and simulate without errors.""" + builder = newton.ModelBuilder() + asset_path = os.path.join(os.path.dirname(__file__), "assets", "humanoid_mjc.usda") + builder.add_usd(asset_path) + + model = builder.finalize() + self.assertIsNotNone(model) + self.assertEqual(model.body_count, 13) + self.assertEqual(model.joint_count, 13) + + +if __name__ == "__main__": + unittest.main() diff --git a/newton/tests/test_menagerie_mujoco.py b/newton/tests/test_menagerie_mujoco.py index eaab53ad21..d852b1ca32 100644 --- a/newton/tests/test_menagerie_mujoco.py +++ b/newton/tests/test_menagerie_mujoco.py @@ -1168,8 +1168,6 @@ def backfill_model_from_native( if native_arr.shape == newton_arr.shape: newton_arr.assign(native_arr) - wp.synchronize() - def compare_mjw_models( newton_mjw: Any, diff --git a/newton/tests/test_menagerie_usd_mujoco.py b/newton/tests/test_menagerie_usd_mujoco.py index c5a7b0f4e3..aa7710c2af 100644 --- a/newton/tests/test_menagerie_usd_mujoco.py +++ b/newton/tests/test_menagerie_usd_mujoco.py @@ -1279,8 +1279,9 @@ class TestMenagerieUSD_H1(TestMenagerieUSD): usd_asset_folder = "unitree_h1" usd_scene_file = "usd_structured/h1.usda" - num_worlds = 2 - num_steps = 0 # USD dynamics not yet tested with step-response + num_steps = 20 + fk_enabled = True + backfill_model = True @unittest.skipUnless(USD_AVAILABLE, "Requires usd-core") @@ -1294,6 +1295,7 @@ class TestMenagerieUSD_G1WithHands(TestMenagerieUSD): num_worlds = 2 num_steps = 0 # USD dynamics not yet tested with step-response + fk_enabled = False # xpos diff 0.109 — USD import issue (#2420) @unittest.skipUnless(USD_AVAILABLE, "Requires usd-core") @@ -1307,6 +1309,7 @@ class TestMenagerieUSD_ShadowHand(TestMenagerieUSD): num_worlds = 2 num_steps = 0 # USD dynamics not yet tested with step-response + fk_enabled = False # xpos diff 0.146 — USD import issue (#2420) @unittest.skipUnless(USD_AVAILABLE, "Requires usd-core") @@ -1335,6 +1338,7 @@ class TestMenagerieUSD_ApptronikApollo(TestMenagerieUSD): num_worlds = 2 num_steps = 0 # USD dynamics not yet tested with step-response + fk_enabled = False # xpos diff 1.56 — USD import issue (#2420) njmax = 398 # Apollo's USD has no collision geoms, so geom/collision counts differ. @@ -1356,6 +1360,7 @@ class TestMenagerieUSD_BoosterT1(TestMenagerieUSD): num_worlds = 2 num_steps = 0 # USD dynamics not yet tested with step-response + fk_enabled = False # xpos diff 0.509 — USD import issue (#2420) @unittest.skipUnless(USD_AVAILABLE, "Requires usd-core") @@ -1369,6 +1374,7 @@ class TestMenagerieUSD_WonikAllegro(TestMenagerieUSD): num_worlds = 2 num_steps = 0 # USD dynamics not yet tested with step-response + fk_enabled = False # xpos diff 0.106 — USD import issue (#2420) def _compare_inertia(self, newton_mjw: Any, native_mjw: Any) -> None: # TODO: USD asset has different mass/inertia values than the original MJCF. @@ -1389,8 +1395,9 @@ class TestMenagerieUSD_UR5e(TestMenagerieUSD): usd_asset_folder = "universal_robots_ur5e" usd_scene_file = "usd_structured/ur5e.usda" - num_worlds = 2 - num_steps = 0 # USD dynamics not yet tested with step-response + num_steps = 20 + fk_enabled = True + backfill_model = True # ============================================================================= diff --git a/newton/tests/test_mujoco_solver.py b/newton/tests/test_mujoco_solver.py index 18ae2d2f92..4a2c3433e6 100644 --- a/newton/tests/test_mujoco_solver.py +++ b/newton/tests/test_mujoco_solver.py @@ -3971,6 +3971,94 @@ def test_efc_address_init(self): self.assertEqual(n_stale, 0, f"{n_stale}/{inactive.sum()} inactive contacts have stale efc_address") +class TestFrictionPriority(unittest.TestCase): + """Verify that contact friction respects geom priority. + + When two geoms have different priorities, the higher-priority geom's + friction should be used directly (not the element-wise max). + """ + + def _build_model(self, priority_a, friction_a, priority_b, friction_b): + builder = newton.ModelBuilder() + SolverMuJoCo.register_custom_attributes(builder) + + cfg_a = newton.ModelBuilder.ShapeConfig(ke=1e4, kd=1000.0, mu=friction_a) + cfg_b = newton.ModelBuilder.ShapeConfig(ke=1e4, kd=1000.0, mu=friction_b) + + body_a = builder.add_body(xform=wp.transform(wp.vec3(0.0, 0.0, 0.3), wp.quat_identity())) + builder.add_shape_box( + body=body_a, + hx=0.2, + hy=0.2, + hz=0.1, + cfg=cfg_a, + custom_attributes={"mujoco:geom_priority": priority_a}, + ) + + body_b = builder.add_body(xform=wp.transform(wp.vec3(0.0, 0.0, 0.1), wp.quat_identity())) + builder.add_shape_box( + body=body_b, + hx=0.5, + hy=0.5, + hz=0.1, + cfg=cfg_b, + custom_attributes={"mujoco:geom_priority": priority_b}, + ) + + model = builder.finalize() + return model + + def _get_contact_friction(self, model): + try: + solver = SolverMuJoCo(model, use_mujoco_contacts=False, njmax=200, nconmax=200) + except ImportError as e: + self.skipTest(f"MuJoCo or deps not installed: {e}") + + contacts = model.contacts() + state_in = model.state() + state_out = model.state() + control = model.control() + newton.eval_fk(model, model.joint_q, model.joint_qd, state_in) + model.collide(state_in, contacts) + solver.step(state_in, state_out, control, contacts, 0.002) + + nacon = solver.mjw_data.nacon.numpy()[0] + self.assertGreater(nacon, 0, "No contacts generated") + return solver.mjw_data.contact.friction.numpy()[:nacon] + + def _assert_slide_friction(self, friction, expected, label): + for i in range(len(friction)): + self.assertAlmostEqual( + float(friction[i, 0]), + expected, + places=5, + msg=f"{label}: contact {i} slide friction should be {expected}, got {friction[i, 0]}", + ) + + def test_higher_priority_friction_used(self): + """Contact friction should come from the higher-priority geom, regardless of operand order.""" + hi_mu = 0.3 + lo_mu = 0.9 + + model_a = self._build_model(priority_a=5, friction_a=hi_mu, priority_b=0, friction_b=lo_mu) + self._assert_slide_friction(self._get_contact_friction(model_a), hi_mu, "high-priority on body A") + + model_b = self._build_model(priority_a=0, friction_a=lo_mu, priority_b=5, friction_b=hi_mu) + self._assert_slide_friction(self._get_contact_friction(model_b), hi_mu, "high-priority on body B") + + def test_equal_priority_uses_max(self): + """When priorities are equal, contact friction should be the element-wise max, regardless of operand order.""" + mu_lo = 0.2 + mu_hi = 0.8 + expected = mu_hi + + model_a = self._build_model(priority_a=0, friction_a=mu_hi, priority_b=0, friction_b=mu_lo) + self._assert_slide_friction(self._get_contact_friction(model_a), expected, "larger mu on body A") + + model_b = self._build_model(priority_a=0, friction_a=mu_lo, priority_b=0, friction_b=mu_hi) + self._assert_slide_friction(self._get_contact_friction(model_b), expected, "larger mu on body B") + + class TestImmovableContactFiltering(unittest.TestCase): """Verify that contacts between two immovable bodies are filtered out. @@ -6377,6 +6465,26 @@ def test_iterations_constructor_override(self): self.assertEqual(solver.mj_model.opt.iterations, 5, "Constructor value should override custom attribute") self.assertEqual(solver.mj_model.opt.ls_iterations, 3, "Constructor value should override custom attribute") + def test_enable_multiccd_default_off(self): + """Verify that mjENBL_MULTICCD is not set by default.""" + model = self._create_multiworld_model(world_count=1) + solver = SolverMuJoCo(model) + mujoco = SolverMuJoCo._mujoco + self.assertFalse( + solver.mj_model.opt.enableflags & mujoco.mjtEnableBit.mjENBL_MULTICCD, + "mjENBL_MULTICCD should not be set when enable_multiccd is not specified", + ) + + def test_enable_multiccd_passed_to_mujoco(self): + """Verify that enable_multiccd sets mjENBL_MULTICCD on the MuJoCo model.""" + model = self._create_multiworld_model(world_count=1) + solver = SolverMuJoCo(model, enable_multiccd=True) + mujoco = SolverMuJoCo._mujoco + self.assertTrue( + solver.mj_model.opt.enableflags & mujoco.mjtEnableBit.mjENBL_MULTICCD, + "mjENBL_MULTICCD should be set on mj_model.opt.enableflags", + ) + class TestMuJoCoArticulationConversion(unittest.TestCase): def test_loop_joints_only(self): diff --git a/newton/tests/test_narrow_phase.py b/newton/tests/test_narrow_phase.py index 48ba158b03..1c7cf3e194 100644 --- a/newton/tests/test_narrow_phase.py +++ b/newton/tests/test_narrow_phase.py @@ -330,8 +330,6 @@ def _run_narrow_phase(self, geom_list, pairs): contact_tangent=contact_tangent, ) - wp.synchronize() - count = contact_count.numpy()[0] return ( count, diff --git a/newton/tests/test_raycast.py b/newton/tests/test_raycast.py index 35ebd263c3..df07a3e6be 100644 --- a/newton/tests/test_raycast.py +++ b/newton/tests/test_raycast.py @@ -13,8 +13,10 @@ ray_intersect_capsule, ray_intersect_cone, ray_intersect_cylinder, + ray_intersect_ellipsoid, ray_intersect_geom, ray_intersect_mesh, + ray_intersect_plane, ray_intersect_sphere, ) from newton.tests.unittest_utils import add_function_test, get_test_devices @@ -88,6 +90,30 @@ def kernel_test_cone( out_t[tid] = ray_intersect_cone(geom_to_world, ray_origin, ray_direction, r, h) +@wp.kernel +def kernel_test_ellipsoid( + out_t: wp.array[float], + geom_to_world: wp.transform, + ray_origin: wp.vec3, + ray_direction: wp.vec3, + semi_axes: wp.vec3, +): + tid = wp.tid() + out_t[tid] = ray_intersect_ellipsoid(geom_to_world, ray_origin, ray_direction, semi_axes) + + +@wp.kernel +def kernel_test_plane( + out_t: wp.array[float], + geom_to_world: wp.transform, + ray_origin: wp.vec3, + ray_direction: wp.vec3, + size: wp.vec3, +): + tid = wp.tid() + out_t[tid] = ray_intersect_plane(geom_to_world, ray_origin, ray_direction, size) + + @wp.kernel def kernel_test_geom( out_t: wp.array[float], @@ -121,21 +147,21 @@ def test_ray_intersect_sphere(test: TestRaycast, device: str): geom_to_world = wp.transform_identity() r = 1.0 - # Case 1: Ray hits sphere - ray_origin = wp.vec3(-2.0, 0.0, 0.0) - ray_direction = wp.vec3(1.0, 0.0, 0.0) - wp.launch(kernel_test_sphere, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r], device=device) - test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) + with test.subTest("hit"): + ray_origin = wp.vec3(-2.0, 0.0, 0.0) + ray_direction = wp.vec3(1.0, 0.0, 0.0) + wp.launch(kernel_test_sphere, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r], device=device) + test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) - # Case 2: Ray misses sphere - ray_origin = wp.vec3(-2.0, 2.0, 0.0) - wp.launch(kernel_test_sphere, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r], device=device) - test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) + with test.subTest("miss"): + ray_origin = wp.vec3(-2.0, 2.0, 0.0) + wp.launch(kernel_test_sphere, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r], device=device) + test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) - # Case 3: Ray starts inside - ray_origin = wp.vec3(0.0, 0.0, 0.0) - wp.launch(kernel_test_sphere, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r], device=device) - test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) + with test.subTest("inside"): + ray_origin = wp.vec3(0.0, 0.0, 0.0) + wp.launch(kernel_test_sphere, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r], device=device) + test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) def test_ray_intersect_box(test: TestRaycast, device: str): @@ -143,30 +169,29 @@ def test_ray_intersect_box(test: TestRaycast, device: str): geom_to_world = wp.transform_identity() size = wp.vec3(1.0, 1.0, 1.0) - # Case 1: Ray hits box - ray_origin = wp.vec3(-2.0, 0.0, 0.0) - ray_direction = wp.vec3(1.0, 0.0, 0.0) - wp.launch(kernel_test_box, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, size], device=device) - test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) - - # Case 2: Ray misses box - ray_origin = wp.vec3(-2.0, 2.0, 0.0) - wp.launch(kernel_test_box, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, size], device=device) - test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) - - # Case 3: Ray starts inside - ray_origin = wp.vec3(0.0, 0.0, 0.0) - wp.launch(kernel_test_box, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, size], device=device) - test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) - - # Case 4: Rotated box - # Rotate 45 degrees around Z axis - rot = wp.quat_from_axis_angle(wp.vec3(0.0, 0.0, 1.0), 0.785398) # pi/4 - geom_to_world = wp.transform(wp.vec3(0.0, 0.0, 0.0), rot) - ray_origin = wp.vec3(-2.0, 0.0, 0.0) - ray_direction = wp.vec3(1.0, 0.0, 0.0) - wp.launch(kernel_test_box, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, size], device=device) - test.assertAlmostEqual(out_t.numpy()[0], 2.0 - 1.41421, delta=1e-5) + with test.subTest("hit"): + ray_origin = wp.vec3(-2.0, 0.0, 0.0) + ray_direction = wp.vec3(1.0, 0.0, 0.0) + wp.launch(kernel_test_box, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, size], device=device) + test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) + + with test.subTest("miss"): + ray_origin = wp.vec3(-2.0, 2.0, 0.0) + wp.launch(kernel_test_box, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, size], device=device) + test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) + + with test.subTest("inside"): + ray_origin = wp.vec3(0.0, 0.0, 0.0) + wp.launch(kernel_test_box, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, size], device=device) + test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) + + with test.subTest("rotated"): + rot = wp.quat_from_axis_angle(wp.vec3(0.0, 0.0, 1.0), 0.785398) # pi/4 + geom_to_world = wp.transform(wp.vec3(0.0, 0.0, 0.0), rot) + ray_origin = wp.vec3(-2.0, 0.0, 0.0) + ray_direction = wp.vec3(1.0, 0.0, 0.0) + wp.launch(kernel_test_box, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, size], device=device) + test.assertAlmostEqual(out_t.numpy()[0], 2.0 - 1.41421, delta=1e-5) def test_ray_intersect_capsule(test: TestRaycast, device: str): @@ -175,23 +200,29 @@ def test_ray_intersect_capsule(test: TestRaycast, device: str): r = 0.5 h = 1.0 - # Case 1: Hit cylinder part - ray_origin = wp.vec3(-2.0, 0.0, 0.0) - ray_direction = wp.vec3(1.0, 0.0, 0.0) - wp.launch(kernel_test_capsule, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device) - test.assertAlmostEqual(out_t.numpy()[0], 1.5, delta=1e-5) - - # Case 2: Hit top cap - ray_origin = wp.vec3(0.0, 0.0, -2.0) - ray_direction = wp.vec3(0.0, 0.0, 1.0) - wp.launch(kernel_test_capsule, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device) - test.assertAlmostEqual(out_t.numpy()[0], 2.0 - 1.0 - 0.5, delta=1e-5) - - # Case 3: Miss - ray_origin = wp.vec3(-2.0, 2.0, 0.0) - ray_direction = wp.vec3(1.0, 0.0, 0.0) - wp.launch(kernel_test_capsule, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device) - test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) + with test.subTest("hit_cylinder"): + ray_origin = wp.vec3(-2.0, 0.0, 0.0) + ray_direction = wp.vec3(1.0, 0.0, 0.0) + wp.launch( + kernel_test_capsule, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.5, delta=1e-5) + + with test.subTest("hit_cap"): + ray_origin = wp.vec3(0.0, 0.0, -2.0) + ray_direction = wp.vec3(0.0, 0.0, 1.0) + wp.launch( + kernel_test_capsule, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], 2.0 - 1.0 - 0.5, delta=1e-5) + + with test.subTest("miss"): + ray_origin = wp.vec3(-2.0, 2.0, 0.0) + ray_direction = wp.vec3(1.0, 0.0, 0.0) + wp.launch( + kernel_test_capsule, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) def test_ray_intersect_cylinder(test: TestRaycast, device: str): @@ -200,29 +231,29 @@ def test_ray_intersect_cylinder(test: TestRaycast, device: str): r = 0.5 h = 1.0 - # Case 1: Hit cylinder body - ray_origin = wp.vec3(-2.0, 0.0, 0.0) - ray_direction = wp.vec3(1.0, 0.0, 0.0) - wp.launch( - kernel_test_cylinder, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device - ) - test.assertAlmostEqual(out_t.numpy()[0], 1.5, delta=1e-5) - - # Case 2: Hit top cap - ray_origin = wp.vec3(0.0, 0.0, -2.0) - ray_direction = wp.vec3(0.0, 0.0, 1.0) - wp.launch( - kernel_test_cylinder, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device - ) - test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) - - # Case 3: Miss - ray_origin = wp.vec3(-2.0, 2.0, 0.0) - ray_direction = wp.vec3(1.0, 0.0, 0.0) - wp.launch( - kernel_test_cylinder, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device - ) - test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) + with test.subTest("hit_body"): + ray_origin = wp.vec3(-2.0, 0.0, 0.0) + ray_direction = wp.vec3(1.0, 0.0, 0.0) + wp.launch( + kernel_test_cylinder, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.5, delta=1e-5) + + with test.subTest("hit_cap"): + ray_origin = wp.vec3(0.0, 0.0, -2.0) + ray_direction = wp.vec3(0.0, 0.0, 1.0) + wp.launch( + kernel_test_cylinder, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) + + with test.subTest("miss"): + ray_origin = wp.vec3(-2.0, 2.0, 0.0) + ray_direction = wp.vec3(1.0, 0.0, 0.0) + wp.launch( + kernel_test_cylinder, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) def test_ray_intersect_cone(test: TestRaycast, device: str): @@ -231,29 +262,173 @@ def test_ray_intersect_cone(test: TestRaycast, device: str): r = 1.0 # base radius h = 1.0 # half height (so total height is 2.0) - # Case 1: Hit cone body from the side - ray_origin = wp.vec3(-2.0, 0.0, 0.0) - ray_direction = wp.vec3(1.0, 0.0, 0.0) - wp.launch(kernel_test_cone, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device) - test.assertAlmostEqual(out_t.numpy()[0], 1.5, delta=1e-3) - - # Case 2: Hit cone base from below - ray_origin = wp.vec3(0.0, 0.0, -2.0) - ray_direction = wp.vec3(0.0, 0.0, 1.0) - wp.launch(kernel_test_cone, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device) - test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-3) # hits base at z=-1 - - # Case 3: Miss cone completely - ray_origin = wp.vec3(-2.0, 2.0, 0.0) - ray_direction = wp.vec3(1.0, 0.0, 0.0) - wp.launch(kernel_test_cone, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device) - test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) - - # Case 4: Ray from above hitting the tip area - ray_origin = wp.vec3(0.0, 0.0, 2.0) - ray_direction = wp.vec3(0.0, 0.0, -1.0) - wp.launch(kernel_test_cone, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device) - test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-3) # hits tip at z=1 + with test.subTest("hit_body"): + ray_origin = wp.vec3(-2.0, 0.0, 0.0) + ray_direction = wp.vec3(1.0, 0.0, 0.0) + wp.launch( + kernel_test_cone, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.5, delta=1e-3) + + with test.subTest("hit_base"): + ray_origin = wp.vec3(0.0, 0.0, -2.0) + ray_direction = wp.vec3(0.0, 0.0, 1.0) + wp.launch( + kernel_test_cone, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-3) # hits base at z=-1 + + with test.subTest("miss"): + ray_origin = wp.vec3(-2.0, 2.0, 0.0) + ray_direction = wp.vec3(1.0, 0.0, 0.0) + wp.launch( + kernel_test_cone, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) + + with test.subTest("hit_tip"): + ray_origin = wp.vec3(0.0, 0.0, 2.0) + ray_direction = wp.vec3(0.0, 0.0, -1.0) + wp.launch( + kernel_test_cone, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, r, h], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-3) # hits tip at z=1 + + +def test_ray_intersect_ellipsoid(test: TestRaycast, device: str): + out_t = wp.zeros(1, dtype=float, device=device) + geom_to_world = wp.transform_identity() + semi_axes = wp.vec3(1.0, 0.5, 0.5) # non-uniform to exercise ellipsoid-specific logic + + with test.subTest("hit"): + ray_origin = wp.vec3(-3.0, 0.0, 0.0) + ray_direction = wp.vec3(1.0, 0.0, 0.0) + wp.launch( + kernel_test_ellipsoid, + dim=1, + inputs=[out_t, geom_to_world, ray_origin, ray_direction, semi_axes], + device=device, + ) + test.assertAlmostEqual(out_t.numpy()[0], 2.0, delta=1e-5) + + with test.subTest("miss"): + ray_origin = wp.vec3(-3.0, 1.0, 0.0) + ray_direction = wp.vec3(1.0, 0.0, 0.0) + wp.launch( + kernel_test_ellipsoid, + dim=1, + inputs=[out_t, geom_to_world, ray_origin, ray_direction, semi_axes], + device=device, + ) + test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) + + with test.subTest("inside"): + ray_origin = wp.vec3(0.0, 0.0, 0.0) + ray_direction = wp.vec3(1.0, 0.0, 0.0) + wp.launch( + kernel_test_ellipsoid, + dim=1, + inputs=[out_t, geom_to_world, ray_origin, ray_direction, semi_axes], + device=device, + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) + + +def test_ray_intersect_plane(test: TestRaycast, device: str): + out_t = wp.zeros(1, dtype=float, device=device) + geom_to_world = wp.transform_identity() + size = wp.vec3(0.0, 0.0, 0.0) + + with test.subTest("hit_from_above"): + ray_origin = wp.vec3(0.0, 0.0, 4.0) + ray_direction = wp.vec3(3.0, 0.0, -4.0) # 3-4-5 triple + wp.launch( + kernel_test_plane, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, size], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) + + with test.subTest("parallel_miss"): + ray_origin = wp.vec3(0.0, 0.0, 2.0) + ray_direction = wp.vec3(1.0, 0.0, 0.0) + wp.launch( + kernel_test_plane, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, size], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) + + with test.subTest("backward_miss"): + ray_origin = wp.vec3(0.0, 0.0, 5.0) + ray_direction = wp.vec3(0.0, 0.0, 1.0) + wp.launch( + kernel_test_plane, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, size], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) + + with test.subTest("translated_plane"): + geom_to_world = wp.transform(wp.vec3(0.0, 0.0, 3.0), wp.quat_identity()) + ray_origin = wp.vec3(0.0, 0.0, 7.0) + ray_direction = wp.vec3(3.0, 0.0, -4.0) # 3-4-5 triple, local z-offset = 4 + wp.launch( + kernel_test_plane, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, size], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) + + with test.subTest("finite_miss_half_extent"): + geom_to_world = wp.transform_identity() + size_finite = wp.vec3(4.0, 4.0, 0.0) # full width 4, half-extent 2 + ray_origin = wp.vec3(0.0, 0.0, 4.0) + ray_direction = wp.vec3(3.0, 0.0, -4.0) # 3-4-5 triple, crosses plane at (3, 0, 0) -- |3| > 2 + wp.launch( + kernel_test_plane, + dim=1, + inputs=[out_t, geom_to_world, ray_origin, ray_direction, size_finite], + device=device, + ) + test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) + + with test.subTest("finite_miss_x"): + geom_to_world = wp.transform_identity() + size_finite = wp.vec3(2.0, 2.0, 0.0) # full width 2, half-extent 1 + ray_origin = wp.vec3(0.0, 0.0, 4.0) + ray_direction = wp.vec3(3.0, 0.0, -4.0) # 3-4-5 triple, hits at (3, 0, 0) -- |3| > 1 + wp.launch( + kernel_test_plane, + dim=1, + inputs=[out_t, geom_to_world, ray_origin, ray_direction, size_finite], + device=device, + ) + test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) + + with test.subTest("finite_miss_y"): + geom_to_world = wp.transform_identity() + size_finite = wp.vec3(10.0, 2.0, 0.0) + ray_origin = wp.vec3(0.0, 0.0, 4.0) + ray_direction = wp.vec3(0.0, 3.0, -4.0) # 3-4-5 triple, hits at (0, 3, 0) -- |3| > half 2 = 1 + wp.launch( + kernel_test_plane, + dim=1, + inputs=[out_t, geom_to_world, ray_origin, ray_direction, size_finite], + device=device, + ) + test.assertAlmostEqual(out_t.numpy()[0], -1.0, delta=1e-5) + + with test.subTest("hit_from_below"): + geom_to_world = wp.transform_identity() + ray_origin = wp.vec3(0.0, 0.0, -4.0) + ray_direction = wp.vec3(0.0, 3.0, 4.0) # 3-4-5 triple + wp.launch( + kernel_test_plane, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, size], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) + + with test.subTest("rotated_plane"): + q_rot = wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), 3.14159265 / 2.0) + geom_to_world = wp.transform(wp.vec3(0.0, 0.0, 0.0), q_rot) + ray_origin = wp.vec3(0.0, -5.0, 0.0) + ray_direction = wp.vec3(0.0, 1.0, 0.0) + wp.launch( + kernel_test_plane, dim=1, inputs=[out_t, geom_to_world, ray_origin, ray_direction, size], device=device + ) + test.assertAlmostEqual(out_t.numpy()[0], 5.0, delta=1e-5) def test_geom_ray_intersect(test: TestRaycast, device: str): @@ -263,55 +438,77 @@ def test_geom_ray_intersect(test: TestRaycast, device: str): ray_direction = wp.vec3(1.0, 0.0, 0.0) mesh_id = wp.uint64(0) # No mesh for primitive shapes - # Sphere - size = wp.vec3(1.0, 0.0, 0.0) # r - wp.launch( - kernel_test_geom, - dim=1, - inputs=[out_t, geom_to_world, size, GeoType.SPHERE, ray_origin, ray_direction, mesh_id], - device=device, - ) - test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) - - # Box - size = wp.vec3(1.0, 1.0, 1.0) # half-extents - wp.launch( - kernel_test_geom, - dim=1, - inputs=[out_t, geom_to_world, size, GeoType.BOX, ray_origin, ray_direction, mesh_id], - device=device, - ) - test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) - - # Capsule - size = wp.vec3(0.5, 1.0, 0.0) # r, h - wp.launch( - kernel_test_geom, - dim=1, - inputs=[out_t, geom_to_world, size, GeoType.CAPSULE, ray_origin, ray_direction, mesh_id], - device=device, - ) - test.assertAlmostEqual(out_t.numpy()[0], 1.5, delta=1e-5) - - # Cylinder - size = wp.vec3(0.5, 1.0, 0.0) # r, h - wp.launch( - kernel_test_geom, - dim=1, - inputs=[out_t, geom_to_world, size, GeoType.CYLINDER, ray_origin, ray_direction, mesh_id], - device=device, - ) - test.assertAlmostEqual(out_t.numpy()[0], 1.5, delta=1e-5) - - # Cone - size = wp.vec3(1.0, 1.0, 0.0) # r, h - wp.launch( - kernel_test_geom, - dim=1, - inputs=[out_t, geom_to_world, size, GeoType.CONE, ray_origin, ray_direction, mesh_id], - device=device, - ) - test.assertAlmostEqual(out_t.numpy()[0], 1.5, delta=1e-3) + with test.subTest("plane"): + size = wp.vec3(0.0, 0.0, 0.0) + ray_origin_plane = wp.vec3(0.0, 0.0, 5.0) + ray_direction_plane = wp.vec3(0.0, 0.0, -1.0) + wp.launch( + kernel_test_geom, + dim=1, + inputs=[out_t, geom_to_world, size, GeoType.PLANE, ray_origin_plane, ray_direction_plane, mesh_id], + device=device, + ) + test.assertAlmostEqual(out_t.numpy()[0], 5.0, delta=1e-5) + + with test.subTest("sphere"): + size = wp.vec3(1.0, 0.0, 0.0) # r + wp.launch( + kernel_test_geom, + dim=1, + inputs=[out_t, geom_to_world, size, GeoType.SPHERE, ray_origin, ray_direction, mesh_id], + device=device, + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) + + with test.subTest("box"): + size = wp.vec3(1.0, 1.0, 1.0) # half-extents + wp.launch( + kernel_test_geom, + dim=1, + inputs=[out_t, geom_to_world, size, GeoType.BOX, ray_origin, ray_direction, mesh_id], + device=device, + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) + + with test.subTest("capsule"): + size = wp.vec3(0.5, 1.0, 0.0) # r, h + wp.launch( + kernel_test_geom, + dim=1, + inputs=[out_t, geom_to_world, size, GeoType.CAPSULE, ray_origin, ray_direction, mesh_id], + device=device, + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.5, delta=1e-5) + + with test.subTest("cylinder"): + size = wp.vec3(0.5, 1.0, 0.0) # r, h + wp.launch( + kernel_test_geom, + dim=1, + inputs=[out_t, geom_to_world, size, GeoType.CYLINDER, ray_origin, ray_direction, mesh_id], + device=device, + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.5, delta=1e-5) + + with test.subTest("cone"): + size = wp.vec3(1.0, 1.0, 0.0) # r, h + wp.launch( + kernel_test_geom, + dim=1, + inputs=[out_t, geom_to_world, size, GeoType.CONE, ray_origin, ray_direction, mesh_id], + device=device, + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.5, delta=1e-3) + + with test.subTest("ellipsoid"): + size = wp.vec3(1.0, 0.5, 0.5) # semi-axes (rx, ry, rz) + wp.launch( + kernel_test_geom, + dim=1, + inputs=[out_t, geom_to_world, size, GeoType.ELLIPSOID, ray_origin, ray_direction, mesh_id], + device=device, + ) + test.assertAlmostEqual(out_t.numpy()[0], 1.0, delta=1e-5) def test_ray_intersect_mesh(test: TestRaycast, device: str): @@ -470,11 +667,13 @@ def test_convex_hull_ray_intersect_via_geom(test: TestRaycast, device: str): devices = get_test_devices() +add_function_test(TestRaycast, "test_ray_intersect_plane", test_ray_intersect_plane, devices=devices) add_function_test(TestRaycast, "test_ray_intersect_sphere", test_ray_intersect_sphere, devices=devices) add_function_test(TestRaycast, "test_ray_intersect_box", test_ray_intersect_box, devices=devices) add_function_test(TestRaycast, "test_ray_intersect_capsule", test_ray_intersect_capsule, devices=devices) add_function_test(TestRaycast, "test_ray_intersect_cylinder", test_ray_intersect_cylinder, devices=devices) add_function_test(TestRaycast, "test_ray_intersect_cone", test_ray_intersect_cone, devices=devices) +add_function_test(TestRaycast, "test_ray_intersect_ellipsoid", test_ray_intersect_ellipsoid, devices=devices) add_function_test(TestRaycast, "test_geom_ray_intersect", test_geom_ray_intersect, devices=devices) add_function_test(TestRaycast, "test_ray_intersect_mesh", test_ray_intersect_mesh, devices=devices) add_function_test(TestRaycast, "test_mesh_ray_intersect_via_geom", test_mesh_ray_intersect_via_geom, devices=devices) diff --git a/newton/tests/test_remesh.py b/newton/tests/test_remesh.py index 46a89999dc..0c51947b99 100644 --- a/newton/tests/test_remesh.py +++ b/newton/tests/test_remesh.py @@ -513,7 +513,6 @@ def accumulate_test_point( grid.counts, ], ) - wp.synchronize() self.assertEqual(grid.get_num_voxels(), 1) @@ -606,7 +605,6 @@ def accumulate_points( grid.counts, ], ) - wp.synchronize() # All points should fall in the same voxel (voxel_size=1.0, all coords in [0,1)) self.assertEqual(grid.get_num_voxels(), 1) @@ -703,7 +701,6 @@ def accumulate_points( grid.counts, ], ) - wp.synchronize() # Should have 3 separate voxels self.assertEqual(grid.get_num_voxels(), 3) @@ -746,7 +743,6 @@ def add_point( grid.counts, ], ) - wp.synchronize() self.assertEqual(grid.get_num_voxels(), 1) @@ -832,7 +828,6 @@ def accumulate_points( grid.counts, ], ) - wp.synchronize() # Should have 3 separate voxels self.assertEqual(grid.get_num_voxels(), 3) @@ -935,7 +930,6 @@ def accumulate_points( grid.counts, ], ) - wp.synchronize() # Points at 0.0 and 0.099 should be in one voxel, 0.1 in another # So we expect 2 voxels diff --git a/newton/tests/test_sensor_raycast.py b/newton/tests/test_sensor_raycast.py index 1a4b01ecb9..273124f7bc 100644 --- a/newton/tests/test_sensor_raycast.py +++ b/newton/tests/test_sensor_raycast.py @@ -393,6 +393,69 @@ def test_sensor_raycast_single_pixel_hit(test: unittest.TestCase, device): test.assertTrue(np.all(depth_image[no_hit_mask] < 0.0), "Non-target pixels should report no hit (-1).") +def test_sensor_raycast_ground_plane(test: unittest.TestCase, device: str): + """Test that SensorRaycast detects the ground plane.""" + builder = newton.ModelBuilder(up_axis=newton.Axis.Z) + builder.add_ground_plane() + + with wp.ScopedDevice(device): + model = builder.finalize() + + state = model.state() + + # Camera at z=5 looking straight down -- should see ground at z=0 + sensor = SensorRaycast( + model=model, + camera_position=(0.0, 0.0, 5.0), + camera_direction=(0.0, 0.0, -1.0), + camera_up=(0.0, 1.0, 0.0), + fov_radians=0.5, + width=8, + height=8, + max_distance=100.0, + ) + + sensor.update(state) + depth = sensor.get_depth_image_numpy() + + # Every pixel should hit the infinite ground plane + test.assertTrue(np.all(depth > 0.0), "All pixels should hit the ground plane") + # Center pixel should be at distance 5.0 + test.assertAlmostEqual(float(depth[4, 4]), 5.0, delta=0.1) + + +def test_sensor_raycast_ellipsoid(test: unittest.TestCase, device: str): + """Test that SensorRaycast detects an ellipsoid shape.""" + builder = newton.ModelBuilder(up_axis=newton.Axis.Z) + body = builder.add_body(xform=wp.transform(wp.vec3(0.0, 0.0, 5.0), wp.quat_identity())) + builder.add_shape_ellipsoid(body=body, rx=1.5, ry=1.0, rz=0.8) + + with wp.ScopedDevice(device): + model = builder.finalize() + + state = model.state() + newton.eval_fk(model, state.joint_q, state.joint_qd, state) + + # Camera at origin looking +Z toward the ellipsoid + sensor = SensorRaycast( + model=model, + camera_position=(0.0, 0.0, 0.0), + camera_direction=(0.0, 0.0, 1.0), + camera_up=(0.0, 1.0, 0.0), + fov_radians=0.1, + width=1, + height=1, + max_distance=20.0, + ) + + sensor.update(state) + depth = sensor.get_depth_image_numpy() + + test.assertEqual(depth.shape, (1, 1)) + # Ray along +Z hits ellipsoid at z = 5.0 - rz = 4.2 + test.assertAlmostEqual(float(depth[0, 0]), 4.2, delta=1e-3) + + class TestSensorRaycast(unittest.TestCase): pass @@ -400,6 +463,12 @@ class TestSensorRaycast(unittest.TestCase): # Register test for all available devices devices = get_test_devices() add_function_test(TestSensorRaycast, "test_sensor_raycast_cubemap", test_sensor_raycast_cubemap, devices=devices) +add_function_test( + TestSensorRaycast, + "test_sensor_raycast_ground_plane", + test_sensor_raycast_ground_plane, + devices=devices, +) add_function_test( TestSensorRaycast, "test_sensor_raycast_particles_hit", @@ -442,6 +511,12 @@ class TestSensorRaycast(unittest.TestCase): test_sensor_raycast_single_pixel_hit, devices=devices, ) +add_function_test( + TestSensorRaycast, + "test_sensor_raycast_ellipsoid", + test_sensor_raycast_ellipsoid, + devices=devices, +) if __name__ == "__main__": diff --git a/newton/tests/test_solver_xpbd.py b/newton/tests/test_solver_xpbd.py index fc61732c0d..8e8a309789 100644 --- a/newton/tests/test_solver_xpbd.py +++ b/newton/tests/test_solver_xpbd.py @@ -466,6 +466,333 @@ def test_articulation_contact_drift(test, device): ) +def _test_xpbd_contact_force_sphere_on_plane(test, device, radius, density): + """A sphere resting on a ground plane must report contact force equal to its weight.""" + mass = density * (4.0 / 3.0) * np.pi * radius**3 + gravity = 9.81 + + builder = newton.ModelBuilder() + builder.default_shape_cfg.density = density + builder.add_ground_plane() + body = builder.add_body(xform=wp.transform(wp.vec3(0.0, 0.0, radius), wp.quat_identity())) + builder.add_shape_sphere(body=body, radius=radius) + model = builder.finalize(device=device) + model.request_contact_attributes("force") + + solver = newton.solvers.SolverXPBD(model, iterations=32) + state_in = model.state() + state_out = model.state() + control = model.control() + contacts = model.contacts() + newton.eval_fk(model, model.joint_q, model.joint_qd, state_in) + + dt = 1.0 / 60.0 + num_substeps = 8 + sub_dt = dt / num_substeps + settle_steps = 120 + avg_steps = 60 + + for _ in range(settle_steps): + for _ in range(num_substeps): + state_in.clear_forces() + model.collide(state_in, contacts) + solver.step(state_in, state_out, control, contacts, sub_dt) + state_in, state_out = state_out, state_in + + force_acc = np.zeros(3) + for _ in range(avg_steps): + for _ in range(num_substeps): + state_in.clear_forces() + model.collide(state_in, contacts) + solver.step(state_in, state_out, control, contacts, sub_dt) + state_in, state_out = state_out, state_in + solver.update_contacts(contacts, state_in) + ncontacts = int(contacts.rigid_contact_count.numpy()[0]) + if ncontacts > 0: + f = contacts.force.numpy()[:ncontacts, :3] + force_acc += np.sum(f, axis=0) + + avg_force = force_acc / avg_steps + expected_fz = mass * gravity + np.testing.assert_allclose(avg_force[2], -expected_fz, rtol=0.05, err_msg="Vertical contact force should match -mg") + np.testing.assert_allclose(avg_force[0], 0.0, atol=0.5, err_msg="Horizontal X force should be ~0") + np.testing.assert_allclose(avg_force[1], 0.0, atol=0.5, err_msg="Horizontal Y force should be ~0") + + +def test_xpbd_contact_force_sphere_on_plane(test, device): + _test_xpbd_contact_force_sphere_on_plane(test, device, radius=0.25, density=1000.0) + + +def test_xpbd_contact_force_heavy_sphere_on_plane(test, device): + _test_xpbd_contact_force_sphere_on_plane(test, device, radius=0.5, density=2000.0) + + +def test_xpbd_contact_force_box_on_plane(test, device): + """A box on a ground plane has multiple contact points; total force must equal mg, not N*mg. + + This specifically tests the fix for the N*contact force inflation bug when + ``rigid_contact_con_weighting`` is enabled (the default). A box generates 4 + bottom-face contacts, so without the fix the summed force would be ~4x the + true weight. + """ + hx, hy, hz = 0.5, 0.5, 0.5 + density = 1000.0 + volume = (2.0 * hx) * (2.0 * hy) * (2.0 * hz) + mass = density * volume + gravity = 9.81 + + builder = newton.ModelBuilder() + builder.default_shape_cfg.density = density + builder.add_ground_plane() + body = builder.add_body(xform=wp.transform(wp.vec3(0.0, 0.0, hz), wp.quat_identity())) + builder.add_shape_box(body=body, hx=hx, hy=hy, hz=hz) + model = builder.finalize(device=device) + model.request_contact_attributes("force") + + solver = newton.solvers.SolverXPBD(model, iterations=32, rigid_contact_con_weighting=True) + state_in = model.state() + state_out = model.state() + control = model.control() + contacts = model.contacts() + newton.eval_fk(model, model.joint_q, model.joint_qd, state_in) + + dt = 1.0 / 60.0 + num_substeps = 8 + sub_dt = dt / num_substeps + settle_steps = 120 + avg_steps = 60 + + for _ in range(settle_steps): + for _ in range(num_substeps): + state_in.clear_forces() + model.collide(state_in, contacts) + solver.step(state_in, state_out, control, contacts, sub_dt) + state_in, state_out = state_out, state_in + + force_acc = np.zeros(3) + for _ in range(avg_steps): + for _ in range(num_substeps): + state_in.clear_forces() + model.collide(state_in, contacts) + solver.step(state_in, state_out, control, contacts, sub_dt) + state_in, state_out = state_out, state_in + solver.update_contacts(contacts, state_in) + ncontacts = int(contacts.rigid_contact_count.numpy()[0]) + test.assertGreater(ncontacts, 1, "Box should generate multiple contact points") + if ncontacts > 0: + f = contacts.force.numpy()[:ncontacts, :3] + force_acc += np.sum(f, axis=0) + + avg_force = force_acc / avg_steps + expected_fz = mass * gravity + np.testing.assert_allclose( + avg_force[2], + -expected_fz, + rtol=0.10, + err_msg="Total vertical contact force over multiple contacts should match -mg, not N*mg", + ) + np.testing.assert_allclose(avg_force[0], 0.0, atol=1.0, err_msg="Horizontal X force should be ~0") + np.testing.assert_allclose(avg_force[1], 0.0, atol=1.0, err_msg="Horizontal Y force should be ~0") + + +def test_xpbd_contact_force_mini_pyramid(test, device): + """Two-layer pyramid: ground reaction forces must reflect stacked weight. + + Layout (Z-up): + - Ground plane at z=0 (shape 0, body -1) + - Two bottom cubes (bodies 0, 1) side-by-side on the ground + - One top cube (body 2) centered on top of both + + All cubes have the same mass m. At steady state the ground pushes up on + each bottom cube with 1.5*mg (own weight + half the top cube). + + Only ground-contact forces are checked here. Inter-body forces between + dynamic bodies are under-reported by the per-body contact weighting + scheme (``rigid_contact_con_weighting``) because a body's weight mixes + contacts from different pairs. + """ + h = 0.5 + density = 1000.0 + volume = (2.0 * h) ** 3 + mass = density * volume + gravity = 9.81 + mg = mass * gravity + + builder = newton.ModelBuilder() + builder.default_shape_cfg.density = density + builder.add_ground_plane() + + b0 = builder.add_body(xform=wp.transform(wp.vec3(-h, 0.0, h), wp.quat_identity())) + builder.add_shape_box(body=b0, hx=h, hy=h, hz=h) + b1 = builder.add_body(xform=wp.transform(wp.vec3(h, 0.0, h), wp.quat_identity())) + builder.add_shape_box(body=b1, hx=h, hy=h, hz=h) + b2 = builder.add_body(xform=wp.transform(wp.vec3(0.0, 0.0, 3.0 * h), wp.quat_identity())) + builder.add_shape_box(body=b2, hx=h, hy=h, hz=h) + + model = builder.finalize(device=device) + model.request_contact_attributes("force") + + solver = newton.solvers.SolverXPBD(model, iterations=32, rigid_contact_con_weighting=True) + state_in = model.state() + state_out = model.state() + control = model.control() + contacts = model.contacts() + newton.eval_fk(model, model.joint_q, model.joint_qd, state_in) + + dt = 1.0 / 60.0 + num_substeps = 8 + sub_dt = dt / num_substeps + settle_steps = 200 + avg_steps = 60 + + for _ in range(settle_steps): + for _ in range(num_substeps): + state_in.clear_forces() + model.collide(state_in, contacts) + solver.step(state_in, state_out, control, contacts, sub_dt) + state_in, state_out = state_out, state_in + + shape_body_np = model.shape_body.numpy() + ground_shape = 0 + + ground_fz_on_b0 = 0.0 + ground_fz_on_b1 = 0.0 + + for _ in range(avg_steps): + for _ in range(num_substeps): + state_in.clear_forces() + model.collide(state_in, contacts) + solver.step(state_in, state_out, control, contacts, sub_dt) + state_in, state_out = state_out, state_in + solver.update_contacts(contacts, state_in) + + nc = int(contacts.rigid_contact_count.numpy()[0]) + if nc == 0: + continue + forces = contacts.force.numpy()[:nc, :3] + s0 = contacts.rigid_contact_shape0.numpy()[:nc] + s1 = contacts.rigid_contact_shape1.numpy()[:nc] + for ci in range(nc): + if s0[ci] != ground_shape: + continue + fz = forces[ci, 2] + body_b = shape_body_np[s1[ci]] if s1[ci] >= 0 else -1 + if body_b == b0: + ground_fz_on_b0 += -fz + elif body_b == b1: + ground_fz_on_b1 += -fz + + ground_fz_on_b0 /= avg_steps + ground_fz_on_b1 /= avg_steps + + np.testing.assert_allclose( + ground_fz_on_b0, + 1.5 * mg, + rtol=0.15, + err_msg=f"Ground reaction on bottom cube 0 should be ~1.5*mg={1.5 * mg:.0f}, got {ground_fz_on_b0:.0f}", + ) + np.testing.assert_allclose( + ground_fz_on_b1, + 1.5 * mg, + rtol=0.15, + err_msg=f"Ground reaction on bottom cube 1 should be ~1.5*mg={1.5 * mg:.0f}, got {ground_fz_on_b1:.0f}", + ) + + +def test_xpbd_contact_force_zero_when_no_contact(test, device): + """A sphere in free-fall (no ground) should produce zero contact force.""" + radius = 0.25 + + builder = newton.ModelBuilder() + body = builder.add_body(xform=wp.transform(wp.vec3(0.0, 0.0, 5.0), wp.quat_identity())) + builder.add_shape_sphere(body=body, radius=radius) + model = builder.finalize(device=device) + model.request_contact_attributes("force") + + solver = newton.solvers.SolverXPBD(model, iterations=2) + state_in = model.state() + state_out = model.state() + control = model.control() + contacts = model.contacts() + newton.eval_fk(model, model.joint_q, model.joint_qd, state_in) + + dt = 1.0 / 60.0 + state_in.clear_forces() + model.collide(state_in, contacts) + solver.step(state_in, state_out, control, contacts, dt) + solver.update_contacts(contacts, state_out) + + ncontacts = int(contacts.rigid_contact_count.numpy()[0]) + if ncontacts > 0: + forces = contacts.force.numpy()[:ncontacts] + np.testing.assert_allclose(forces, 0.0, atol=1e-6, err_msg="No contact force expected in free-fall") + + +def test_xpbd_contact_force_zero_when_not_touching(test, device): + """A sphere near a ground plane with a large gap: contact pair exists but force is zero.""" + radius = 0.25 + gap = 1.0 + # Place sphere so it's within the gap (contact pair generated) but not penetrating. + # Ground is at z=0, sphere center at z = radius + 0.5*gap (well above surface). + z = radius + 0.5 * gap + + builder = newton.ModelBuilder() + builder.default_shape_cfg.gap = gap + builder.add_ground_plane() + body = builder.add_body(xform=wp.transform(wp.vec3(0.0, 0.0, z), wp.quat_identity())) + builder.add_shape_sphere(body=body, radius=radius) + model = builder.finalize(device=device) + model.set_gravity(wp.vec3(0.0, 0.0, 0.0)) + model.request_contact_attributes("force") + + solver = newton.solvers.SolverXPBD(model, iterations=2) + state_in = model.state() + state_out = model.state() + control = model.control() + contacts = model.contacts() + newton.eval_fk(model, model.joint_q, model.joint_qd, state_in) + + state_in.clear_forces() + model.collide(state_in, contacts) + + ncontacts = int(contacts.rigid_contact_count.numpy()[0]) + test.assertGreater(ncontacts, 0, "Gap should cause a contact pair to be generated") + + solver.step(state_in, state_out, control, contacts, 1.0 / 60.0) + solver.update_contacts(contacts, state_out) + + forces = contacts.force.numpy()[:ncontacts, :3] + np.testing.assert_allclose( + forces, + 0.0, + atol=1e-6, + err_msg="Contact pair within gap but not touching should report zero force", + ) + + +def test_xpbd_update_contacts_requires_force_attribute(test, device): + """update_contacts should raise ValueError when contacts.force is not allocated.""" + builder = newton.ModelBuilder() + builder.add_ground_plane() + body = builder.add_body(xform=wp.transform(wp.vec3(0.0, 0.0, 0.25), wp.quat_identity())) + builder.add_shape_sphere(body=body, radius=0.25) + model = builder.finalize(device=device) + + solver = newton.solvers.SolverXPBD(model, iterations=2) + state_in = model.state() + state_out = model.state() + control = model.control() + contacts = model.contacts() + + state_in.clear_forces() + model.collide(state_in, contacts) + solver.step(state_in, state_out, control, contacts, 1.0 / 60.0) + + test.assertIsNone(contacts.force) + with test.assertRaises(ValueError): + solver.update_contacts(contacts) + + devices = get_test_devices(mode="basic") @@ -515,6 +842,62 @@ class TestSolverXPBD(unittest.TestCase): check_output=False, ) +add_function_test( + TestSolverXPBD, + "test_xpbd_contact_force_sphere_on_plane", + test_xpbd_contact_force_sphere_on_plane, + devices=devices, + check_output=False, +) + +add_function_test( + TestSolverXPBD, + "test_xpbd_contact_force_heavy_sphere_on_plane", + test_xpbd_contact_force_heavy_sphere_on_plane, + devices=devices, + check_output=False, +) + +add_function_test( + TestSolverXPBD, + "test_xpbd_contact_force_box_on_plane", + test_xpbd_contact_force_box_on_plane, + devices=devices, + check_output=False, +) + +add_function_test( + TestSolverXPBD, + "test_xpbd_contact_force_mini_pyramid", + test_xpbd_contact_force_mini_pyramid, + devices=devices, + check_output=False, +) + +add_function_test( + TestSolverXPBD, + "test_xpbd_contact_force_zero_when_no_contact", + test_xpbd_contact_force_zero_when_no_contact, + devices=devices, + check_output=False, +) + +add_function_test( + TestSolverXPBD, + "test_xpbd_contact_force_zero_when_not_touching", + test_xpbd_contact_force_zero_when_not_touching, + devices=devices, + check_output=False, +) + +add_function_test( + TestSolverXPBD, + "test_xpbd_update_contacts_requires_force_attribute", + test_xpbd_update_contacts_requires_force_attribute, + devices=devices, + check_output=False, +) + if __name__ == "__main__": unittest.main(verbosity=2, failfast=True) diff --git a/newton/tests/test_viewer_picking.py b/newton/tests/test_viewer_picking.py index bba9793da2..fab0f85ffb 100644 --- a/newton/tests/test_viewer_picking.py +++ b/newton/tests/test_viewer_picking.py @@ -174,7 +174,6 @@ def test_apply_picking_force_when_not_picking(self): state.body_f.zero_() picking._apply_picking_force(state) - wp.synchronize() # No body picked -> no force applied forces = state.body_f.numpy() @@ -233,7 +232,6 @@ def test_picking_setup_device(test: TestPickingSetup, device): # update and apply_force should not crash picking.update(ray_start, ray_dir) picking._apply_picking_force(state) - wp.synchronize() picking.release() test.assertFalse(picking.is_picking()) diff --git a/uv.lock b/uv.lock index 7a55756b1b..b6caffcdc3 100644 --- a/uv.lock +++ b/uv.lock @@ -3841,100 +3841,100 @@ wheels = [ [[package]] name = "pillow" -version = "12.1.1" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/1f/42/5c74462b4fd957fcd7b13b04fb3205ff8349236ea74c7c375766d6c82288/pillow-12.1.1.tar.gz", hash = "sha256:9ad8fa5937ab05218e2b6a4cff30295ad35afd2f83ac592e68c0d871bb0fdbc4", size = 46980264, upload-time = "2026-02-11T04:23:07.146Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/1d/30/5bd3d794762481f8c8ae9c80e7b76ecea73b916959eb587521358ef0b2f9/pillow-12.1.1-cp310-cp310-macosx_10_10_x86_64.whl", hash = "sha256:1f1625b72740fdda5d77b4def688eb8fd6490975d06b909fd19f13f391e077e0", size = 5304099, upload-time = "2026-02-11T04:20:06.13Z" }, - { url = "https://files.pythonhosted.org/packages/bd/c1/aab9e8f3eeb4490180e357955e15c2ef74b31f64790ff356c06fb6cf6d84/pillow-12.1.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:178aa072084bd88ec759052feca8e56cbb14a60b39322b99a049e58090479713", size = 4657880, upload-time = "2026-02-11T04:20:09.291Z" }, - { url = "https://files.pythonhosted.org/packages/f1/0a/9879e30d56815ad529d3985aeff5af4964202425c27261a6ada10f7cbf53/pillow-12.1.1-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:b66e95d05ba806247aaa1561f080abc7975daf715c30780ff92a20e4ec546e1b", size = 6222587, upload-time = "2026-02-11T04:20:10.82Z" }, - { url = "https://files.pythonhosted.org/packages/5a/5f/a1b72ff7139e4f89014e8d451442c74a774d5c43cd938fb0a9f878576b37/pillow-12.1.1-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:89c7e895002bbe49cdc5426150377cbbc04767d7547ed145473f496dfa40408b", size = 8027678, upload-time = "2026-02-11T04:20:12.455Z" }, - { url = "https://files.pythonhosted.org/packages/e2/c2/c7cb187dac79a3d22c3ebeae727abee01e077c8c7d930791dc592f335153/pillow-12.1.1-cp310-cp310-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:3a5cbdcddad0af3da87cb16b60d23648bc3b51967eb07223e9fed77a82b457c4", size = 6335777, upload-time = "2026-02-11T04:20:14.441Z" }, - { url = "https://files.pythonhosted.org/packages/0c/7b/f9b09a7804ec7336effb96c26d37c29d27225783dc1501b7d62dcef6ae25/pillow-12.1.1-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9f51079765661884a486727f0729d29054242f74b46186026582b4e4769918e4", size = 7027140, upload-time = "2026-02-11T04:20:16.387Z" }, - { url = "https://files.pythonhosted.org/packages/98/b2/2fa3c391550bd421b10849d1a2144c44abcd966daadd2f7c12e19ea988c4/pillow-12.1.1-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:99c1506ea77c11531d75e3a412832a13a71c7ebc8192ab9e4b2e355555920e3e", size = 6449855, upload-time = "2026-02-11T04:20:18.554Z" }, - { url = "https://files.pythonhosted.org/packages/96/ff/9caf4b5b950c669263c39e96c78c0d74a342c71c4f43fd031bb5cb7ceac9/pillow-12.1.1-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:36341d06738a9f66c8287cf8b876d24b18db9bd8740fa0672c74e259ad408cff", size = 7151329, upload-time = "2026-02-11T04:20:20.646Z" }, - { url = "https://files.pythonhosted.org/packages/7b/f8/4b24841f582704da675ca535935bccb32b00a6da1226820845fac4a71136/pillow-12.1.1-cp310-cp310-win32.whl", hash = "sha256:6c52f062424c523d6c4db85518774cc3d50f5539dd6eed32b8f6229b26f24d40", size = 6325574, upload-time = "2026-02-11T04:20:22.43Z" }, - { url = "https://files.pythonhosted.org/packages/f8/f9/9f6b01c0881d7036063aa6612ef04c0e2cad96be21325a1e92d0203f8e91/pillow-12.1.1-cp310-cp310-win_amd64.whl", hash = "sha256:c6008de247150668a705a6338156efb92334113421ceecf7438a12c9a12dab23", size = 7032347, upload-time = "2026-02-11T04:20:23.932Z" }, - { url = "https://files.pythonhosted.org/packages/79/13/c7922edded3dcdaf10c59297540b72785620abc0538872c819915746757d/pillow-12.1.1-cp310-cp310-win_arm64.whl", hash = "sha256:1a9b0ee305220b392e1124a764ee4265bd063e54a751a6b62eff69992f457fa9", size = 2453457, upload-time = "2026-02-11T04:20:25.392Z" }, - { url = "https://files.pythonhosted.org/packages/2b/46/5da1ec4a5171ee7bf1a0efa064aba70ba3d6e0788ce3f5acd1375d23c8c0/pillow-12.1.1-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:e879bb6cd5c73848ef3b2b48b8af9ff08c5b71ecda8048b7dd22d8a33f60be32", size = 5304084, upload-time = "2026-02-11T04:20:27.501Z" }, - { url = "https://files.pythonhosted.org/packages/78/93/a29e9bc02d1cf557a834da780ceccd54e02421627200696fcf805ebdc3fb/pillow-12.1.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:365b10bb9417dd4498c0e3b128018c4a624dc11c7b97d8cc54effe3b096f4c38", size = 4657866, upload-time = "2026-02-11T04:20:29.827Z" }, - { url = "https://files.pythonhosted.org/packages/13/84/583a4558d492a179d31e4aae32eadce94b9acf49c0337c4ce0b70e0a01f2/pillow-12.1.1-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:d4ce8e329c93845720cd2014659ca67eac35f6433fd3050393d85f3ecef0dad5", size = 6232148, upload-time = "2026-02-11T04:20:31.329Z" }, - { url = "https://files.pythonhosted.org/packages/d5/e2/53c43334bbbb2d3b938978532fbda8e62bb6e0b23a26ce8592f36bcc4987/pillow-12.1.1-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:fc354a04072b765eccf2204f588a7a532c9511e8b9c7f900e1b64e3e33487090", size = 8038007, upload-time = "2026-02-11T04:20:34.225Z" }, - { url = "https://files.pythonhosted.org/packages/b8/a6/3d0e79c8a9d58150dd98e199d7c1c56861027f3829a3a60b3c2784190180/pillow-12.1.1-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:7e7976bf1910a8116b523b9f9f58bf410f3e8aa330cd9a2bb2953f9266ab49af", size = 6345418, upload-time = "2026-02-11T04:20:35.858Z" }, - { url = "https://files.pythonhosted.org/packages/a2/c8/46dfeac5825e600579157eea177be43e2f7ff4a99da9d0d0a49533509ac5/pillow-12.1.1-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:597bd9c8419bc7c6af5604e55847789b69123bbe25d65cc6ad3012b4f3c98d8b", size = 7034590, upload-time = "2026-02-11T04:20:37.91Z" }, - { url = "https://files.pythonhosted.org/packages/af/bf/e6f65d3db8a8bbfeaf9e13cc0417813f6319863a73de934f14b2229ada18/pillow-12.1.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:2c1fc0f2ca5f96a3c8407e41cca26a16e46b21060fe6d5b099d2cb01412222f5", size = 6458655, upload-time = "2026-02-11T04:20:39.496Z" }, - { url = "https://files.pythonhosted.org/packages/f9/c2/66091f3f34a25894ca129362e510b956ef26f8fb67a0e6417bc5744e56f1/pillow-12.1.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:578510d88c6229d735855e1f278aa305270438d36a05031dfaae5067cc8eb04d", size = 7159286, upload-time = "2026-02-11T04:20:41.139Z" }, - { url = "https://files.pythonhosted.org/packages/7b/5a/24bc8eb526a22f957d0cec6243146744966d40857e3d8deb68f7902ca6c1/pillow-12.1.1-cp311-cp311-win32.whl", hash = "sha256:7311c0a0dcadb89b36b7025dfd8326ecfa36964e29913074d47382706e516a7c", size = 6328663, upload-time = "2026-02-11T04:20:43.184Z" }, - { url = "https://files.pythonhosted.org/packages/31/03/bef822e4f2d8f9d7448c133d0a18185d3cce3e70472774fffefe8b0ed562/pillow-12.1.1-cp311-cp311-win_amd64.whl", hash = "sha256:fbfa2a7c10cc2623f412753cddf391c7f971c52ca40a3f65dc5039b2939e8563", size = 7031448, upload-time = "2026-02-11T04:20:44.696Z" }, - { url = "https://files.pythonhosted.org/packages/49/70/f76296f53610bd17b2e7d31728b8b7825e3ac3b5b3688b51f52eab7c0818/pillow-12.1.1-cp311-cp311-win_arm64.whl", hash = "sha256:b81b5e3511211631b3f672a595e3221252c90af017e399056d0faabb9538aa80", size = 2453651, upload-time = "2026-02-11T04:20:46.243Z" }, - { url = "https://files.pythonhosted.org/packages/07/d3/8df65da0d4df36b094351dce696f2989bec731d4f10e743b1c5f4da4d3bf/pillow-12.1.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:ab323b787d6e18b3d91a72fc99b1a2c28651e4358749842b8f8dfacd28ef2052", size = 5262803, upload-time = "2026-02-11T04:20:47.653Z" }, - { url = "https://files.pythonhosted.org/packages/d6/71/5026395b290ff404b836e636f51d7297e6c83beceaa87c592718747e670f/pillow-12.1.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:adebb5bee0f0af4909c30db0d890c773d1a92ffe83da908e2e9e720f8edf3984", size = 4657601, upload-time = "2026-02-11T04:20:49.328Z" }, - { url = "https://files.pythonhosted.org/packages/b1/2e/1001613d941c67442f745aff0f7cc66dd8df9a9c084eb497e6a543ee6f7e/pillow-12.1.1-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:bb66b7cc26f50977108790e2456b7921e773f23db5630261102233eb355a3b79", size = 6234995, upload-time = "2026-02-11T04:20:51.032Z" }, - { url = "https://files.pythonhosted.org/packages/07/26/246ab11455b2549b9233dbd44d358d033a2f780fa9007b61a913c5b2d24e/pillow-12.1.1-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:aee2810642b2898bb187ced9b349e95d2a7272930796e022efaf12e99dccd293", size = 8045012, upload-time = "2026-02-11T04:20:52.882Z" }, - { url = "https://files.pythonhosted.org/packages/b2/8b/07587069c27be7535ac1fe33874e32de118fbd34e2a73b7f83436a88368c/pillow-12.1.1-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:a0b1cd6232e2b618adcc54d9882e4e662a089d5768cd188f7c245b4c8c44a397", size = 6349638, upload-time = "2026-02-11T04:20:54.444Z" }, - { url = "https://files.pythonhosted.org/packages/ff/79/6df7b2ee763d619cda2fb4fea498e5f79d984dae304d45a8999b80d6cf5c/pillow-12.1.1-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:7aac39bcf8d4770d089588a2e1dd111cbaa42df5a94be3114222057d68336bd0", size = 7041540, upload-time = "2026-02-11T04:20:55.97Z" }, - { url = "https://files.pythonhosted.org/packages/2c/5e/2ba19e7e7236d7529f4d873bdaf317a318896bac289abebd4bb00ef247f0/pillow-12.1.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:ab174cd7d29a62dd139c44bf74b698039328f45cb03b4596c43473a46656b2f3", size = 6462613, upload-time = "2026-02-11T04:20:57.542Z" }, - { url = "https://files.pythonhosted.org/packages/03/03/31216ec124bb5c3dacd74ce8efff4cc7f52643653bad4825f8f08c697743/pillow-12.1.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:339ffdcb7cbeaa08221cd401d517d4b1fe7a9ed5d400e4a8039719238620ca35", size = 7166745, upload-time = "2026-02-11T04:20:59.196Z" }, - { url = "https://files.pythonhosted.org/packages/1f/e7/7c4552d80052337eb28653b617eafdef39adfb137c49dd7e831b8dc13bc5/pillow-12.1.1-cp312-cp312-win32.whl", hash = "sha256:5d1f9575a12bed9e9eedd9a4972834b08c97a352bd17955ccdebfeca5913fa0a", size = 6328823, upload-time = "2026-02-11T04:21:01.385Z" }, - { url = "https://files.pythonhosted.org/packages/3d/17/688626d192d7261bbbf98846fc98995726bddc2c945344b65bec3a29d731/pillow-12.1.1-cp312-cp312-win_amd64.whl", hash = "sha256:21329ec8c96c6e979cd0dfd29406c40c1d52521a90544463057d2aaa937d66a6", size = 7033367, upload-time = "2026-02-11T04:21:03.536Z" }, - { url = "https://files.pythonhosted.org/packages/ed/fe/a0ef1f73f939b0eca03ee2c108d0043a87468664770612602c63266a43c4/pillow-12.1.1-cp312-cp312-win_arm64.whl", hash = "sha256:af9a332e572978f0218686636610555ae3defd1633597be015ed50289a03c523", size = 2453811, upload-time = "2026-02-11T04:21:05.116Z" }, - { url = "https://files.pythonhosted.org/packages/d5/11/6db24d4bd7685583caeae54b7009584e38da3c3d4488ed4cd25b439de486/pillow-12.1.1-cp313-cp313-ios_13_0_arm64_iphoneos.whl", hash = "sha256:d242e8ac078781f1de88bf823d70c1a9b3c7950a44cdf4b7c012e22ccbcd8e4e", size = 4062689, upload-time = "2026-02-11T04:21:06.804Z" }, - { url = "https://files.pythonhosted.org/packages/33/c0/ce6d3b1fe190f0021203e0d9b5b99e57843e345f15f9ef22fcd43842fd21/pillow-12.1.1-cp313-cp313-ios_13_0_arm64_iphonesimulator.whl", hash = "sha256:02f84dfad02693676692746df05b89cf25597560db2857363a208e393429f5e9", size = 4138535, upload-time = "2026-02-11T04:21:08.452Z" }, - { url = "https://files.pythonhosted.org/packages/a0/c6/d5eb6a4fb32a3f9c21a8c7613ec706534ea1cf9f4b3663e99f0d83f6fca8/pillow-12.1.1-cp313-cp313-ios_13_0_x86_64_iphonesimulator.whl", hash = "sha256:e65498daf4b583091ccbb2556c7000abf0f3349fcd57ef7adc9a84a394ed29f6", size = 3601364, upload-time = "2026-02-11T04:21:10.194Z" }, - { url = "https://files.pythonhosted.org/packages/14/a1/16c4b823838ba4c9c52c0e6bbda903a3fe5a1bdbf1b8eb4fff7156f3e318/pillow-12.1.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:6c6db3b84c87d48d0088943bf33440e0c42370b99b1c2a7989216f7b42eede60", size = 5262561, upload-time = "2026-02-11T04:21:11.742Z" }, - { url = "https://files.pythonhosted.org/packages/bb/ad/ad9dc98ff24f485008aa5cdedaf1a219876f6f6c42a4626c08bc4e80b120/pillow-12.1.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:8b7e5304e34942bf62e15184219a7b5ad4ff7f3bb5cca4d984f37df1a0e1aee2", size = 4657460, upload-time = "2026-02-11T04:21:13.786Z" }, - { url = "https://files.pythonhosted.org/packages/9e/1b/f1a4ea9a895b5732152789326202a82464d5254759fbacae4deea3069334/pillow-12.1.1-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:18e5bddd742a44b7e6b1e773ab5db102bd7a94c32555ba656e76d319d19c3850", size = 6232698, upload-time = "2026-02-11T04:21:15.949Z" }, - { url = "https://files.pythonhosted.org/packages/95/f4/86f51b8745070daf21fd2e5b1fe0eb35d4db9ca26e6d58366562fb56a743/pillow-12.1.1-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:fc44ef1f3de4f45b50ccf9136999d71abb99dca7706bc75d222ed350b9fd2289", size = 8041706, upload-time = "2026-02-11T04:21:17.723Z" }, - { url = "https://files.pythonhosted.org/packages/29/9b/d6ecd956bb1266dd1045e995cce9b8d77759e740953a1c9aad9502a0461e/pillow-12.1.1-cp313-cp313-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:5a8eb7ed8d4198bccbd07058416eeec51686b498e784eda166395a23eb99138e", size = 6346621, upload-time = "2026-02-11T04:21:19.547Z" }, - { url = "https://files.pythonhosted.org/packages/71/24/538bff45bde96535d7d998c6fed1a751c75ac7c53c37c90dc2601b243893/pillow-12.1.1-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:47b94983da0c642de92ced1702c5b6c292a84bd3a8e1d1702ff923f183594717", size = 7038069, upload-time = "2026-02-11T04:21:21.378Z" }, - { url = "https://files.pythonhosted.org/packages/94/0e/58cb1a6bc48f746bc4cb3adb8cabff73e2742c92b3bf7a220b7cf69b9177/pillow-12.1.1-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:518a48c2aab7ce596d3bf79d0e275661b846e86e4d0e7dec34712c30fe07f02a", size = 6460040, upload-time = "2026-02-11T04:21:23.148Z" }, - { url = "https://files.pythonhosted.org/packages/6c/57/9045cb3ff11eeb6c1adce3b2d60d7d299d7b273a2e6c8381a524abfdc474/pillow-12.1.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:a550ae29b95c6dc13cf69e2c9dc5747f814c54eeb2e32d683e5e93af56caa029", size = 7164523, upload-time = "2026-02-11T04:21:25.01Z" }, - { url = "https://files.pythonhosted.org/packages/73/f2/9be9cb99f2175f0d4dbadd6616ce1bf068ee54a28277ea1bf1fbf729c250/pillow-12.1.1-cp313-cp313-win32.whl", hash = "sha256:a003d7422449f6d1e3a34e3dd4110c22148336918ddbfc6a32581cd54b2e0b2b", size = 6332552, upload-time = "2026-02-11T04:21:27.238Z" }, - { url = "https://files.pythonhosted.org/packages/3f/eb/b0834ad8b583d7d9d42b80becff092082a1c3c156bb582590fcc973f1c7c/pillow-12.1.1-cp313-cp313-win_amd64.whl", hash = "sha256:344cf1e3dab3be4b1fa08e449323d98a2a3f819ad20f4b22e77a0ede31f0faa1", size = 7040108, upload-time = "2026-02-11T04:21:29.462Z" }, - { url = "https://files.pythonhosted.org/packages/d5/7d/fc09634e2aabdd0feabaff4a32f4a7d97789223e7c2042fd805ea4b4d2c2/pillow-12.1.1-cp313-cp313-win_arm64.whl", hash = "sha256:5c0dd1636633e7e6a0afe7bf6a51a14992b7f8e60de5789018ebbdfae55b040a", size = 2453712, upload-time = "2026-02-11T04:21:31.072Z" }, - { url = "https://files.pythonhosted.org/packages/19/2a/b9d62794fc8a0dd14c1943df68347badbd5511103e0d04c035ffe5cf2255/pillow-12.1.1-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:0330d233c1a0ead844fc097a7d16c0abff4c12e856c0b325f231820fee1f39da", size = 5264880, upload-time = "2026-02-11T04:21:32.865Z" }, - { url = "https://files.pythonhosted.org/packages/26/9d/e03d857d1347fa5ed9247e123fcd2a97b6220e15e9cb73ca0a8d91702c6e/pillow-12.1.1-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:5dae5f21afb91322f2ff791895ddd8889e5e947ff59f71b46041c8ce6db790bc", size = 4660616, upload-time = "2026-02-11T04:21:34.97Z" }, - { url = "https://files.pythonhosted.org/packages/f7/ec/8a6d22afd02570d30954e043f09c32772bfe143ba9285e2fdb11284952cd/pillow-12.1.1-cp313-cp313t-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:2e0c664be47252947d870ac0d327fea7e63985a08794758aa8af5b6cb6ec0c9c", size = 6269008, upload-time = "2026-02-11T04:21:36.623Z" }, - { url = "https://files.pythonhosted.org/packages/3d/1d/6d875422c9f28a4a361f495a5f68d9de4a66941dc2c619103ca335fa6446/pillow-12.1.1-cp313-cp313t-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:691ab2ac363b8217f7d31b3497108fb1f50faab2f75dfb03284ec2f217e87bf8", size = 8073226, upload-time = "2026-02-11T04:21:38.585Z" }, - { url = "https://files.pythonhosted.org/packages/a1/cd/134b0b6ee5eda6dc09e25e24b40fdafe11a520bc725c1d0bbaa5e00bf95b/pillow-12.1.1-cp313-cp313t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:e9e8064fb1cc019296958595f6db671fba95209e3ceb0c4734c9baf97de04b20", size = 6380136, upload-time = "2026-02-11T04:21:40.562Z" }, - { url = "https://files.pythonhosted.org/packages/7a/a9/7628f013f18f001c1b98d8fffe3452f306a70dc6aba7d931019e0492f45e/pillow-12.1.1-cp313-cp313t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:472a8d7ded663e6162dafdf20015c486a7009483ca671cece7a9279b512fcb13", size = 7067129, upload-time = "2026-02-11T04:21:42.521Z" }, - { url = "https://files.pythonhosted.org/packages/1e/f8/66ab30a2193b277785601e82ee2d49f68ea575d9637e5e234faaa98efa4c/pillow-12.1.1-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:89b54027a766529136a06cfebeecb3a04900397a3590fd252160b888479517bf", size = 6491807, upload-time = "2026-02-11T04:21:44.22Z" }, - { url = "https://files.pythonhosted.org/packages/da/0b/a877a6627dc8318fdb84e357c5e1a758c0941ab1ddffdafd231983788579/pillow-12.1.1-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:86172b0831b82ce4f7877f280055892b31179e1576aa00d0df3bb1bbf8c3e524", size = 7190954, upload-time = "2026-02-11T04:21:46.114Z" }, - { url = "https://files.pythonhosted.org/packages/83/43/6f732ff85743cf746b1361b91665d9f5155e1483817f693f8d57ea93147f/pillow-12.1.1-cp313-cp313t-win32.whl", hash = "sha256:44ce27545b6efcf0fdbdceb31c9a5bdea9333e664cda58a7e674bb74608b3986", size = 6336441, upload-time = "2026-02-11T04:21:48.22Z" }, - { url = "https://files.pythonhosted.org/packages/3b/44/e865ef3986611bb75bfabdf94a590016ea327833f434558801122979cd0e/pillow-12.1.1-cp313-cp313t-win_amd64.whl", hash = "sha256:a285e3eb7a5a45a2ff504e31f4a8d1b12ef62e84e5411c6804a42197c1cf586c", size = 7045383, upload-time = "2026-02-11T04:21:50.015Z" }, - { url = "https://files.pythonhosted.org/packages/a8/c6/f4fb24268d0c6908b9f04143697ea18b0379490cb74ba9e8d41b898bd005/pillow-12.1.1-cp313-cp313t-win_arm64.whl", hash = "sha256:cc7d296b5ea4d29e6570dabeaed58d31c3fea35a633a69679fb03d7664f43fb3", size = 2456104, upload-time = "2026-02-11T04:21:51.633Z" }, - { url = "https://files.pythonhosted.org/packages/03/d0/bebb3ffbf31c5a8e97241476c4cf8b9828954693ce6744b4a2326af3e16b/pillow-12.1.1-cp314-cp314-ios_13_0_arm64_iphoneos.whl", hash = "sha256:417423db963cb4be8bac3fc1204fe61610f6abeed1580a7a2cbb2fbda20f12af", size = 4062652, upload-time = "2026-02-11T04:21:53.19Z" }, - { url = "https://files.pythonhosted.org/packages/2d/c0/0e16fb0addda4851445c28f8350d8c512f09de27bbb0d6d0bbf8b6709605/pillow-12.1.1-cp314-cp314-ios_13_0_arm64_iphonesimulator.whl", hash = "sha256:b957b71c6b2387610f556a7eb0828afbe40b4a98036fc0d2acfa5a44a0c2036f", size = 4138823, upload-time = "2026-02-11T04:22:03.088Z" }, - { url = "https://files.pythonhosted.org/packages/6b/fb/6170ec655d6f6bb6630a013dd7cf7bc218423d7b5fa9071bf63dc32175ae/pillow-12.1.1-cp314-cp314-ios_13_0_x86_64_iphonesimulator.whl", hash = "sha256:097690ba1f2efdeb165a20469d59d8bb03c55fb6621eb2041a060ae8ea3e9642", size = 3601143, upload-time = "2026-02-11T04:22:04.909Z" }, - { url = "https://files.pythonhosted.org/packages/59/04/dc5c3f297510ba9a6837cbb318b87dd2b8f73eb41a43cc63767f65cb599c/pillow-12.1.1-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:2815a87ab27848db0321fb78c7f0b2c8649dee134b7f2b80c6a45c6831d75ccd", size = 5266254, upload-time = "2026-02-11T04:22:07.656Z" }, - { url = "https://files.pythonhosted.org/packages/05/30/5db1236b0d6313f03ebf97f5e17cda9ca060f524b2fcc875149a8360b21c/pillow-12.1.1-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:f7ed2c6543bad5a7d5530eb9e78c53132f93dfa44a28492db88b41cdab885202", size = 4657499, upload-time = "2026-02-11T04:22:09.613Z" }, - { url = "https://files.pythonhosted.org/packages/6f/18/008d2ca0eb612e81968e8be0bbae5051efba24d52debf930126d7eaacbba/pillow-12.1.1-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:652a2c9ccfb556235b2b501a3a7cf3742148cd22e04b5625c5fe057ea3e3191f", size = 6232137, upload-time = "2026-02-11T04:22:11.434Z" }, - { url = "https://files.pythonhosted.org/packages/70/f1/f14d5b8eeb4b2cd62b9f9f847eb6605f103df89ef619ac68f92f748614ea/pillow-12.1.1-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:d6e4571eedf43af33d0fc233a382a76e849badbccdf1ac438841308652a08e1f", size = 8042721, upload-time = "2026-02-11T04:22:13.321Z" }, - { url = "https://files.pythonhosted.org/packages/5a/d6/17824509146e4babbdabf04d8171491fa9d776f7061ff6e727522df9bd03/pillow-12.1.1-cp314-cp314-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:b574c51cf7d5d62e9be37ba446224b59a2da26dc4c1bb2ecbe936a4fb1a7cb7f", size = 6347798, upload-time = "2026-02-11T04:22:15.449Z" }, - { url = "https://files.pythonhosted.org/packages/d1/ee/c85a38a9ab92037a75615aba572c85ea51e605265036e00c5b67dfafbfe2/pillow-12.1.1-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a37691702ed687799de29a518d63d4682d9016932db66d4e90c345831b02fb4e", size = 7039315, upload-time = "2026-02-11T04:22:17.24Z" }, - { url = "https://files.pythonhosted.org/packages/ec/f3/bc8ccc6e08a148290d7523bde4d9a0d6c981db34631390dc6e6ec34cacf6/pillow-12.1.1-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:f95c00d5d6700b2b890479664a06e754974848afaae5e21beb4d83c106923fd0", size = 6462360, upload-time = "2026-02-11T04:22:19.111Z" }, - { url = "https://files.pythonhosted.org/packages/f6/ab/69a42656adb1d0665ab051eec58a41f169ad295cf81ad45406963105408f/pillow-12.1.1-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:559b38da23606e68681337ad74622c4dbba02254fc9cb4488a305dd5975c7eeb", size = 7165438, upload-time = "2026-02-11T04:22:21.041Z" }, - { url = "https://files.pythonhosted.org/packages/02/46/81f7aa8941873f0f01d4b55cc543b0a3d03ec2ee30d617a0448bf6bd6dec/pillow-12.1.1-cp314-cp314-win32.whl", hash = "sha256:03edcc34d688572014ff223c125a3f77fb08091e4607e7745002fc214070b35f", size = 6431503, upload-time = "2026-02-11T04:22:22.833Z" }, - { url = "https://files.pythonhosted.org/packages/40/72/4c245f7d1044b67affc7f134a09ea619d4895333d35322b775b928180044/pillow-12.1.1-cp314-cp314-win_amd64.whl", hash = "sha256:50480dcd74fa63b8e78235957d302d98d98d82ccbfac4c7e12108ba9ecbdba15", size = 7176748, upload-time = "2026-02-11T04:22:24.64Z" }, - { url = "https://files.pythonhosted.org/packages/e4/ad/8a87bdbe038c5c698736e3348af5c2194ffb872ea52f11894c95f9305435/pillow-12.1.1-cp314-cp314-win_arm64.whl", hash = "sha256:5cb1785d97b0c3d1d1a16bc1d710c4a0049daefc4935f3a8f31f827f4d3d2e7f", size = 2544314, upload-time = "2026-02-11T04:22:26.685Z" }, - { url = "https://files.pythonhosted.org/packages/6c/9d/efd18493f9de13b87ede7c47e69184b9e859e4427225ea962e32e56a49bc/pillow-12.1.1-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:1f90cff8aa76835cba5769f0b3121a22bd4eb9e6884cfe338216e557a9a548b8", size = 5268612, upload-time = "2026-02-11T04:22:29.884Z" }, - { url = "https://files.pythonhosted.org/packages/f8/f1/4f42eb2b388eb2ffc660dcb7f7b556c1015c53ebd5f7f754965ef997585b/pillow-12.1.1-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:1f1be78ce9466a7ee64bfda57bdba0f7cc499d9794d518b854816c41bf0aa4e9", size = 4660567, upload-time = "2026-02-11T04:22:31.799Z" }, - { url = "https://files.pythonhosted.org/packages/01/54/df6ef130fa43e4b82e32624a7b821a2be1c5653a5fdad8469687a7db4e00/pillow-12.1.1-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:42fc1f4677106188ad9a55562bbade416f8b55456f522430fadab3cef7cd4e60", size = 6269951, upload-time = "2026-02-11T04:22:33.921Z" }, - { url = "https://files.pythonhosted.org/packages/a9/48/618752d06cc44bb4aae8ce0cd4e6426871929ed7b46215638088270d9b34/pillow-12.1.1-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:98edb152429ab62a1818039744d8fbb3ccab98a7c29fc3d5fcef158f3f1f68b7", size = 8074769, upload-time = "2026-02-11T04:22:35.877Z" }, - { url = "https://files.pythonhosted.org/packages/c3/bd/f1d71eb39a72fa088d938655afba3e00b38018d052752f435838961127d8/pillow-12.1.1-cp314-cp314t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:d470ab1178551dd17fdba0fef463359c41aaa613cdcd7ff8373f54be629f9f8f", size = 6381358, upload-time = "2026-02-11T04:22:37.698Z" }, - { url = "https://files.pythonhosted.org/packages/64/ef/c784e20b96674ed36a5af839305f55616f8b4f8aa8eeccf8531a6e312243/pillow-12.1.1-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:6408a7b064595afcab0a49393a413732a35788f2a5092fdc6266952ed67de586", size = 7068558, upload-time = "2026-02-11T04:22:39.597Z" }, - { url = "https://files.pythonhosted.org/packages/73/cb/8059688b74422ae61278202c4e1ad992e8a2e7375227be0a21c6b87ca8d5/pillow-12.1.1-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:5d8c41325b382c07799a3682c1c258469ea2ff97103c53717b7893862d0c98ce", size = 6493028, upload-time = "2026-02-11T04:22:42.73Z" }, - { url = "https://files.pythonhosted.org/packages/c6/da/e3c008ed7d2dd1f905b15949325934510b9d1931e5df999bb15972756818/pillow-12.1.1-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:c7697918b5be27424e9ce568193efd13d925c4481dd364e43f5dff72d33e10f8", size = 7191940, upload-time = "2026-02-11T04:22:44.543Z" }, - { url = "https://files.pythonhosted.org/packages/01/4a/9202e8d11714c1fc5951f2e1ef362f2d7fbc595e1f6717971d5dd750e969/pillow-12.1.1-cp314-cp314t-win32.whl", hash = "sha256:d2912fd8114fc5545aa3a4b5576512f64c55a03f3ebcca4c10194d593d43ea36", size = 6438736, upload-time = "2026-02-11T04:22:46.347Z" }, - { url = "https://files.pythonhosted.org/packages/f3/ca/cbce2327eb9885476b3957b2e82eb12c866a8b16ad77392864ad601022ce/pillow-12.1.1-cp314-cp314t-win_amd64.whl", hash = "sha256:4ceb838d4bd9dab43e06c363cab2eebf63846d6a4aeaea283bbdfd8f1a8ed58b", size = 7182894, upload-time = "2026-02-11T04:22:48.114Z" }, - { url = "https://files.pythonhosted.org/packages/ec/d2/de599c95ba0a973b94410477f8bf0b6f0b5e67360eb89bcb1ad365258beb/pillow-12.1.1-cp314-cp314t-win_arm64.whl", hash = "sha256:7b03048319bfc6170e93bd60728a1af51d3dd7704935feb228c4d4faab35d334", size = 2546446, upload-time = "2026-02-11T04:22:50.342Z" }, - { url = "https://files.pythonhosted.org/packages/56/11/5d43209aa4cb58e0cc80127956ff1796a68b928e6324bbf06ef4db34367b/pillow-12.1.1-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:600fd103672b925fe62ed08e0d874ea34d692474df6f4bf7ebe148b30f89f39f", size = 5228606, upload-time = "2026-02-11T04:22:52.106Z" }, - { url = "https://files.pythonhosted.org/packages/5f/d5/3b005b4e4fda6698b371fa6c21b097d4707585d7db99e98d9b0b87ac612a/pillow-12.1.1-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:665e1b916b043cef294bc54d47bf02d87e13f769bc4bc5fa225a24b3a6c5aca9", size = 4622321, upload-time = "2026-02-11T04:22:53.827Z" }, - { url = "https://files.pythonhosted.org/packages/df/36/ed3ea2d594356fd8037e5a01f6156c74bc8d92dbb0fa60746cc96cabb6e8/pillow-12.1.1-pp311-pypy311_pp73-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:495c302af3aad1ca67420ddd5c7bd480c8867ad173528767d906428057a11f0e", size = 5247579, upload-time = "2026-02-11T04:22:56.094Z" }, - { url = "https://files.pythonhosted.org/packages/54/9a/9cc3e029683cf6d20ae5085da0dafc63148e3252c2f13328e553aaa13cfb/pillow-12.1.1-pp311-pypy311_pp73-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:8fd420ef0c52c88b5a035a0886f367748c72147b2b8f384c9d12656678dfdfa9", size = 6989094, upload-time = "2026-02-11T04:22:58.288Z" }, - { url = "https://files.pythonhosted.org/packages/00/98/fc53ab36da80b88df0967896b6c4b4cd948a0dc5aa40a754266aa3ae48b3/pillow-12.1.1-pp311-pypy311_pp73-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:f975aa7ef9684ce7e2c18a3aa8f8e2106ce1e46b94ab713d156b2898811651d3", size = 5313850, upload-time = "2026-02-11T04:23:00.554Z" }, - { url = "https://files.pythonhosted.org/packages/30/02/00fa585abfd9fe9d73e5f6e554dc36cc2b842898cbfc46d70353dae227f8/pillow-12.1.1-pp311-pypy311_pp73-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:8089c852a56c2966cf18835db62d9b34fef7ba74c726ad943928d494fa7f4735", size = 5963343, upload-time = "2026-02-11T04:23:02.934Z" }, - { url = "https://files.pythonhosted.org/packages/f2/26/c56ce33ca856e358d27fda9676c055395abddb82c35ac0f593877ed4562e/pillow-12.1.1-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:cb9bb857b2d057c6dfc72ac5f3b44836924ba15721882ef103cecb40d002d80e", size = 7029880, upload-time = "2026-02-11T04:23:04.783Z" }, +version = "12.2.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/8c/21/c2bcdd5906101a30244eaffc1b6e6ce71a31bd0742a01eb89e660ebfac2d/pillow-12.2.0.tar.gz", hash = "sha256:a830b1a40919539d07806aa58e1b114df53ddd43213d9c8b75847eee6c0182b5", size = 46987819, upload-time = "2026-04-01T14:46:17.687Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/3a/aa/d0b28e1c811cd4d5f5c2bfe2e022292bd255ae5744a3b9ac7d6c8f72dd75/pillow-12.2.0-cp310-cp310-macosx_10_10_x86_64.whl", hash = "sha256:a4e8f36e677d3336f35089648c8955c51c6d386a13cf6ee9c189c5f5bd713a9f", size = 5354355, upload-time = "2026-04-01T14:42:15.402Z" }, + { url = "https://files.pythonhosted.org/packages/27/8e/1d5b39b8ae2bd7650d0c7b6abb9602d16043ead9ebbfef4bc4047454da2a/pillow-12.2.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:2e589959f10d9824d39b350472b92f0ce3b443c0a3442ebf41c40cb8361c5b97", size = 4695871, upload-time = "2026-04-01T14:42:18.234Z" }, + { url = "https://files.pythonhosted.org/packages/f0/c5/dcb7a6ca6b7d3be41a76958e90018d56c8462166b3ef223150360850c8da/pillow-12.2.0-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:a52edc8bfff4429aaabdf4d9ee0daadbbf8562364f940937b941f87a4290f5ff", size = 6269734, upload-time = "2026-04-01T14:42:20.608Z" }, + { url = "https://files.pythonhosted.org/packages/ea/f1/aa1bb13b2f4eba914e9637893c73f2af8e48d7d4023b9d3750d4c5eb2d0c/pillow-12.2.0-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:975385f4776fafde056abb318f612ef6285b10a1f12b8570f3647ad0d74b48ec", size = 8076080, upload-time = "2026-04-01T14:42:23.095Z" }, + { url = "https://files.pythonhosted.org/packages/a1/2a/8c79d6a53169937784604a8ae8d77e45888c41537f7f6f65ed1f407fe66d/pillow-12.2.0-cp310-cp310-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:bd9c0c7a0c681a347b3194c500cb1e6ca9cab053ea4d82a5cf45b6b754560136", size = 6382236, upload-time = "2026-04-01T14:42:25.82Z" }, + { url = "https://files.pythonhosted.org/packages/b5/42/bbcb6051030e1e421d103ce7a8ecadf837aa2f39b8f82ef1a8d37c3d4ebc/pillow-12.2.0-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:88d387ff40b3ff7c274947ed3125dedf5262ec6919d83946753b5f3d7c67ea4c", size = 7070220, upload-time = "2026-04-01T14:42:28.68Z" }, + { url = "https://files.pythonhosted.org/packages/3f/e1/c2a7d6dd8cfa6b231227da096fd2d58754bab3603b9d73bf609d3c18b64f/pillow-12.2.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:51c4167c34b0d8ba05b547a3bb23578d0ba17b80a5593f93bd8ecb123dd336a3", size = 6493124, upload-time = "2026-04-01T14:42:31.579Z" }, + { url = "https://files.pythonhosted.org/packages/5f/41/7c8617da5d32e1d2f026e509484fdb6f3ad7efaef1749a0c1928adbb099e/pillow-12.2.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:34c0d99ecccea270c04882cb3b86e7b57296079c9a4aff88cb3b33563d95afaa", size = 7194324, upload-time = "2026-04-01T14:42:34.615Z" }, + { url = "https://files.pythonhosted.org/packages/2d/de/a777627e19fd6d62f84070ee1521adde5eeda4855b5cf60fe0b149118bca/pillow-12.2.0-cp310-cp310-win32.whl", hash = "sha256:b85f66ae9eb53e860a873b858b789217ba505e5e405a24b85c0464822fe88032", size = 6376363, upload-time = "2026-04-01T14:42:37.19Z" }, + { url = "https://files.pythonhosted.org/packages/e7/34/fc4cb5204896465842767b96d250c08410f01f2f28afc43b257de842eed5/pillow-12.2.0-cp310-cp310-win_amd64.whl", hash = "sha256:673aa32138f3e7531ccdbca7b3901dba9b70940a19ccecc6a37c77d5fdeb05b5", size = 7083523, upload-time = "2026-04-01T14:42:39.62Z" }, + { url = "https://files.pythonhosted.org/packages/2d/a0/32852d36bc7709f14dc3f64f929a275e958ad8c19a6deba9610d458e28b3/pillow-12.2.0-cp310-cp310-win_arm64.whl", hash = "sha256:3e080565d8d7c671db5802eedfb438e5565ffa40115216eabb8cd52d0ecce024", size = 2463318, upload-time = "2026-04-01T14:42:42.063Z" }, + { url = "https://files.pythonhosted.org/packages/68/e1/748f5663efe6edcfc4e74b2b93edfb9b8b99b67f21a854c3ae416500a2d9/pillow-12.2.0-cp311-cp311-macosx_10_10_x86_64.whl", hash = "sha256:8be29e59487a79f173507c30ddf57e733a357f67881430449bb32614075a40ab", size = 5354347, upload-time = "2026-04-01T14:42:44.255Z" }, + { url = "https://files.pythonhosted.org/packages/47/a1/d5ff69e747374c33a3b53b9f98cca7889fce1fd03d79cdc4e1bccc6c5a87/pillow-12.2.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:71cde9a1e1551df7d34a25462fc60325e8a11a82cc2e2f54578e5e9a1e153d65", size = 4695873, upload-time = "2026-04-01T14:42:46.452Z" }, + { url = "https://files.pythonhosted.org/packages/df/21/e3fbdf54408a973c7f7f89a23b2cb97a7ef30c61ab4142af31eee6aebc88/pillow-12.2.0-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:f490f9368b6fc026f021db16d7ec2fbf7d89e2edb42e8ec09d2c60505f5729c7", size = 6280168, upload-time = "2026-04-01T14:42:49.228Z" }, + { url = "https://files.pythonhosted.org/packages/d3/f1/00b7278c7dd52b17ad4329153748f87b6756ec195ff786c2bdf12518337d/pillow-12.2.0-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:8bd7903a5f2a4545f6fd5935c90058b89d30045568985a71c79f5fd6edf9b91e", size = 8088188, upload-time = "2026-04-01T14:42:51.735Z" }, + { url = "https://files.pythonhosted.org/packages/ad/cf/220a5994ef1b10e70e85748b75649d77d506499352be135a4989c957b701/pillow-12.2.0-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:3997232e10d2920a68d25191392e3a4487d8183039e1c74c2297f00ed1c50705", size = 6394401, upload-time = "2026-04-01T14:42:54.343Z" }, + { url = "https://files.pythonhosted.org/packages/e9/bd/e51a61b1054f09437acfbc2ff9106c30d1eb76bc1453d428399946781253/pillow-12.2.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:e74473c875d78b8e9d5da2a70f7099549f9eb37ded4e2f6a463e60125bccd176", size = 7079655, upload-time = "2026-04-01T14:42:56.954Z" }, + { url = "https://files.pythonhosted.org/packages/6b/3d/45132c57d5fb4b5744567c3817026480ac7fc3ce5d4c47902bc0e7f6f853/pillow-12.2.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:56a3f9c60a13133a98ecff6197af34d7824de9b7b38c3654861a725c970c197b", size = 6503105, upload-time = "2026-04-01T14:42:59.847Z" }, + { url = "https://files.pythonhosted.org/packages/7d/2e/9df2fc1e82097b1df3dce58dc43286aa01068e918c07574711fcc53e6fb4/pillow-12.2.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:90e6f81de50ad6b534cab6e5aef77ff6e37722b2f5d908686f4a5c9eba17a909", size = 7203402, upload-time = "2026-04-01T14:43:02.664Z" }, + { url = "https://files.pythonhosted.org/packages/bd/2e/2941e42858ebb67e50ae741473de81c2984e6eff7b397017623c676e2e8d/pillow-12.2.0-cp311-cp311-win32.whl", hash = "sha256:8c984051042858021a54926eb597d6ee3012393ce9c181814115df4c60b9a808", size = 6378149, upload-time = "2026-04-01T14:43:05.274Z" }, + { url = "https://files.pythonhosted.org/packages/69/42/836b6f3cd7f3e5fa10a1f1a5420447c17966044c8fbf589cc0452d5502db/pillow-12.2.0-cp311-cp311-win_amd64.whl", hash = "sha256:6e6b2a0c538fc200b38ff9eb6628228b77908c319a005815f2dde585a0664b60", size = 7082626, upload-time = "2026-04-01T14:43:08.557Z" }, + { url = "https://files.pythonhosted.org/packages/c2/88/549194b5d6f1f494b485e493edc6693c0a16f4ada488e5bd974ed1f42fad/pillow-12.2.0-cp311-cp311-win_arm64.whl", hash = "sha256:9a8a34cc89c67a65ea7437ce257cea81a9dad65b29805f3ecee8c8fe8ff25ffe", size = 2463531, upload-time = "2026-04-01T14:43:10.743Z" }, + { url = "https://files.pythonhosted.org/packages/58/be/7482c8a5ebebbc6470b3eb791812fff7d5e0216c2be3827b30b8bb6603ed/pillow-12.2.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:2d192a155bbcec180f8564f693e6fd9bccff5a7af9b32e2e4bf8c9c69dbad6b5", size = 5308279, upload-time = "2026-04-01T14:43:13.246Z" }, + { url = "https://files.pythonhosted.org/packages/d8/95/0a351b9289c2b5cbde0bacd4a83ebc44023e835490a727b2a3bd60ddc0f4/pillow-12.2.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:f3f40b3c5a968281fd507d519e444c35f0ff171237f4fdde090dd60699458421", size = 4695490, upload-time = "2026-04-01T14:43:15.584Z" }, + { url = "https://files.pythonhosted.org/packages/de/af/4e8e6869cbed569d43c416fad3dc4ecb944cb5d9492defaed89ddd6fe871/pillow-12.2.0-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:03e7e372d5240cc23e9f07deca4d775c0817bffc641b01e9c3af208dbd300987", size = 6284462, upload-time = "2026-04-01T14:43:18.268Z" }, + { url = "https://files.pythonhosted.org/packages/e9/9e/c05e19657fd57841e476be1ab46c4d501bffbadbafdc31a6d665f8b737b6/pillow-12.2.0-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:b86024e52a1b269467a802258c25521e6d742349d760728092e1bc2d135b4d76", size = 8094744, upload-time = "2026-04-01T14:43:20.716Z" }, + { url = "https://files.pythonhosted.org/packages/2b/54/1789c455ed10176066b6e7e6da1b01e50e36f94ba584dc68d9eebfe9156d/pillow-12.2.0-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:7371b48c4fa448d20d2714c9a1f775a81155050d383333e0a6c15b1123dda005", size = 6398371, upload-time = "2026-04-01T14:43:23.443Z" }, + { url = "https://files.pythonhosted.org/packages/43/e3/fdc657359e919462369869f1c9f0e973f353f9a9ee295a39b1fea8ee1a77/pillow-12.2.0-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:62f5409336adb0663b7caa0da5c7d9e7bdbaae9ce761d34669420c2a801b2780", size = 7087215, upload-time = "2026-04-01T14:43:26.758Z" }, + { url = "https://files.pythonhosted.org/packages/8b/f8/2f6825e441d5b1959d2ca5adec984210f1ec086435b0ed5f52c19b3b8a6e/pillow-12.2.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:01afa7cf67f74f09523699b4e88c73fb55c13346d212a59a2db1f86b0a63e8c5", size = 6509783, upload-time = "2026-04-01T14:43:29.56Z" }, + { url = "https://files.pythonhosted.org/packages/67/f9/029a27095ad20f854f9dba026b3ea6428548316e057e6fc3545409e86651/pillow-12.2.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:fc3d34d4a8fbec3e88a79b92e5465e0f9b842b628675850d860b8bd300b159f5", size = 7212112, upload-time = "2026-04-01T14:43:32.091Z" }, + { url = "https://files.pythonhosted.org/packages/be/42/025cfe05d1be22dbfdb4f264fe9de1ccda83f66e4fc3aac94748e784af04/pillow-12.2.0-cp312-cp312-win32.whl", hash = "sha256:58f62cc0f00fd29e64b29f4fd923ffdb3859c9f9e6105bfc37ba1d08994e8940", size = 6378489, upload-time = "2026-04-01T14:43:34.601Z" }, + { url = "https://files.pythonhosted.org/packages/5d/7b/25a221d2c761c6a8ae21bfa3874988ff2583e19cf8a27bf2fee358df7942/pillow-12.2.0-cp312-cp312-win_amd64.whl", hash = "sha256:7f84204dee22a783350679a0333981df803dac21a0190d706a50475e361c93f5", size = 7084129, upload-time = "2026-04-01T14:43:37.213Z" }, + { url = "https://files.pythonhosted.org/packages/10/e1/542a474affab20fd4a0f1836cb234e8493519da6b76899e30bcc5d990b8b/pillow-12.2.0-cp312-cp312-win_arm64.whl", hash = "sha256:af73337013e0b3b46f175e79492d96845b16126ddf79c438d7ea7ff27783a414", size = 2463612, upload-time = "2026-04-01T14:43:39.421Z" }, + { url = "https://files.pythonhosted.org/packages/4a/01/53d10cf0dbad820a8db274d259a37ba50b88b24768ddccec07355382d5ad/pillow-12.2.0-cp313-cp313-ios_13_0_arm64_iphoneos.whl", hash = "sha256:8297651f5b5679c19968abefd6bb84d95fe30ef712eb1b2d9b2d31ca61267f4c", size = 4100837, upload-time = "2026-04-01T14:43:41.506Z" }, + { url = "https://files.pythonhosted.org/packages/0f/98/f3a6657ecb698c937f6c76ee564882945f29b79bad496abcba0e84659ec5/pillow-12.2.0-cp313-cp313-ios_13_0_arm64_iphonesimulator.whl", hash = "sha256:50d8520da2a6ce0af445fa6d648c4273c3eeefbc32d7ce049f22e8b5c3daecc2", size = 4176528, upload-time = "2026-04-01T14:43:43.773Z" }, + { url = "https://files.pythonhosted.org/packages/69/bc/8986948f05e3ea490b8442ea1c1d4d990b24a7e43d8a51b2c7d8b1dced36/pillow-12.2.0-cp313-cp313-ios_13_0_x86_64_iphonesimulator.whl", hash = "sha256:766cef22385fa1091258ad7e6216792b156dc16d8d3fa607e7545b2b72061f1c", size = 3640401, upload-time = "2026-04-01T14:43:45.87Z" }, + { url = "https://files.pythonhosted.org/packages/34/46/6c717baadcd62bc8ed51d238d521ab651eaa74838291bda1f86fe1f864c9/pillow-12.2.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:5d2fd0fa6b5d9d1de415060363433f28da8b1526c1c129020435e186794b3795", size = 5308094, upload-time = "2026-04-01T14:43:48.438Z" }, + { url = "https://files.pythonhosted.org/packages/71/43/905a14a8b17fdb1ccb58d282454490662d2cb89a6bfec26af6d3520da5ec/pillow-12.2.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:56b25336f502b6ed02e889f4ece894a72612fe885889a6e8c4c80239ff6e5f5f", size = 4695402, upload-time = "2026-04-01T14:43:51.292Z" }, + { url = "https://files.pythonhosted.org/packages/73/dd/42107efcb777b16fa0393317eac58f5b5cf30e8392e266e76e51cff28c3d/pillow-12.2.0-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:f1c943e96e85df3d3478f7b691f229887e143f81fedab9b20205349ab04d73ed", size = 6280005, upload-time = "2026-04-01T14:43:54.242Z" }, + { url = "https://files.pythonhosted.org/packages/a8/68/b93e09e5e8549019e61acf49f65b1a8530765a7f812c77a7461bca7e4494/pillow-12.2.0-cp313-cp313-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:03f6fab9219220f041c74aeaa2939ff0062bd5c364ba9ce037197f4c6d498cd9", size = 8090669, upload-time = "2026-04-01T14:43:57.335Z" }, + { url = "https://files.pythonhosted.org/packages/4b/6e/3ccb54ce8ec4ddd1accd2d89004308b7b0b21c4ac3d20fa70af4760a4330/pillow-12.2.0-cp313-cp313-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:5cdfebd752ec52bf5bb4e35d9c64b40826bc5b40a13df7c3cda20a2c03a0f5ed", size = 6395194, upload-time = "2026-04-01T14:43:59.864Z" }, + { url = "https://files.pythonhosted.org/packages/67/ee/21d4e8536afd1a328f01b359b4d3997b291ffd35a237c877b331c1c3b71c/pillow-12.2.0-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:eedf4b74eda2b5a4b2b2fb4c006d6295df3bf29e459e198c90ea48e130dc75c3", size = 7082423, upload-time = "2026-04-01T14:44:02.74Z" }, + { url = "https://files.pythonhosted.org/packages/78/5f/e9f86ab0146464e8c133fe85df987ed9e77e08b29d8d35f9f9f4d6f917ba/pillow-12.2.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:00a2865911330191c0b818c59103b58a5e697cae67042366970a6b6f1b20b7f9", size = 6505667, upload-time = "2026-04-01T14:44:05.381Z" }, + { url = "https://files.pythonhosted.org/packages/ed/1e/409007f56a2fdce61584fd3acbc2bbc259857d555196cedcadc68c015c82/pillow-12.2.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:1e1757442ed87f4912397c6d35a0db6a7b52592156014706f17658ff58bbf795", size = 7208580, upload-time = "2026-04-01T14:44:08.39Z" }, + { url = "https://files.pythonhosted.org/packages/23/c4/7349421080b12fb35414607b8871e9534546c128a11965fd4a7002ccfbee/pillow-12.2.0-cp313-cp313-win32.whl", hash = "sha256:144748b3af2d1b358d41286056d0003f47cb339b8c43a9ea42f5fea4d8c66b6e", size = 6375896, upload-time = "2026-04-01T14:44:11.197Z" }, + { url = "https://files.pythonhosted.org/packages/3f/82/8a3739a5e470b3c6cbb1d21d315800d8e16bff503d1f16b03a4ec3212786/pillow-12.2.0-cp313-cp313-win_amd64.whl", hash = "sha256:390ede346628ccc626e5730107cde16c42d3836b89662a115a921f28440e6a3b", size = 7081266, upload-time = "2026-04-01T14:44:13.947Z" }, + { url = "https://files.pythonhosted.org/packages/c3/25/f968f618a062574294592f668218f8af564830ccebdd1fa6200f598e65c5/pillow-12.2.0-cp313-cp313-win_arm64.whl", hash = "sha256:8023abc91fba39036dbce14a7d6535632f99c0b857807cbbbf21ecc9f4717f06", size = 2463508, upload-time = "2026-04-01T14:44:16.312Z" }, + { url = "https://files.pythonhosted.org/packages/4d/a4/b342930964e3cb4dce5038ae34b0eab4653334995336cd486c5a8c25a00c/pillow-12.2.0-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:042db20a421b9bafecc4b84a8b6e444686bd9d836c7fd24542db3e7df7baad9b", size = 5309927, upload-time = "2026-04-01T14:44:18.89Z" }, + { url = "https://files.pythonhosted.org/packages/9f/de/23198e0a65a9cf06123f5435a5d95cea62a635697f8f03d134d3f3a96151/pillow-12.2.0-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:dd025009355c926a84a612fecf58bb315a3f6814b17ead51a8e48d3823d9087f", size = 4698624, upload-time = "2026-04-01T14:44:21.115Z" }, + { url = "https://files.pythonhosted.org/packages/01/a6/1265e977f17d93ea37aa28aa81bad4fa597933879fac2520d24e021c8da3/pillow-12.2.0-cp313-cp313t-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:88ddbc66737e277852913bd1e07c150cc7bb124539f94c4e2df5344494e0a612", size = 6321252, upload-time = "2026-04-01T14:44:23.663Z" }, + { url = "https://files.pythonhosted.org/packages/3c/83/5982eb4a285967baa70340320be9f88e57665a387e3a53a7f0db8231a0cd/pillow-12.2.0-cp313-cp313t-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:d362d1878f00c142b7e1a16e6e5e780f02be8195123f164edf7eddd911eefe7c", size = 8126550, upload-time = "2026-04-01T14:44:26.772Z" }, + { url = "https://files.pythonhosted.org/packages/4e/48/6ffc514adce69f6050d0753b1a18fd920fce8cac87620d5a31231b04bfc5/pillow-12.2.0-cp313-cp313t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:2c727a6d53cb0018aadd8018c2b938376af27914a68a492f59dfcaca650d5eea", size = 6433114, upload-time = "2026-04-01T14:44:29.615Z" }, + { url = "https://files.pythonhosted.org/packages/36/a3/f9a77144231fb8d40ee27107b4463e205fa4677e2ca2548e14da5cf18dce/pillow-12.2.0-cp313-cp313t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:efd8c21c98c5cc60653bcb311bef2ce0401642b7ce9d09e03a7da87c878289d4", size = 7115667, upload-time = "2026-04-01T14:44:32.773Z" }, + { url = "https://files.pythonhosted.org/packages/c1/fc/ac4ee3041e7d5a565e1c4fd72a113f03b6394cc72ab7089d27608f8aaccb/pillow-12.2.0-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:9f08483a632889536b8139663db60f6724bfcb443c96f1b18855860d7d5c0fd4", size = 6538966, upload-time = "2026-04-01T14:44:35.252Z" }, + { url = "https://files.pythonhosted.org/packages/c0/a8/27fb307055087f3668f6d0a8ccb636e7431d56ed0750e07a60547b1e083e/pillow-12.2.0-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:dac8d77255a37e81a2efcbd1fc05f1c15ee82200e6c240d7e127e25e365c39ea", size = 7238241, upload-time = "2026-04-01T14:44:37.875Z" }, + { url = "https://files.pythonhosted.org/packages/ad/4b/926ab182c07fccae9fcb120043464e1ff1564775ec8864f21a0ebce6ac25/pillow-12.2.0-cp313-cp313t-win32.whl", hash = "sha256:ee3120ae9dff32f121610bb08e4313be87e03efeadfc6c0d18f89127e24d0c24", size = 6379592, upload-time = "2026-04-01T14:44:40.336Z" }, + { url = "https://files.pythonhosted.org/packages/c2/c4/f9e476451a098181b30050cc4c9a3556b64c02cf6497ea421ac047e89e4b/pillow-12.2.0-cp313-cp313t-win_amd64.whl", hash = "sha256:325ca0528c6788d2a6c3d40e3568639398137346c3d6e66bb61db96b96511c98", size = 7085542, upload-time = "2026-04-01T14:44:43.251Z" }, + { url = "https://files.pythonhosted.org/packages/00/a4/285f12aeacbe2d6dc36c407dfbbe9e96d4a80b0fb710a337f6d2ad978c75/pillow-12.2.0-cp313-cp313t-win_arm64.whl", hash = "sha256:2e5a76d03a6c6dcef67edabda7a52494afa4035021a79c8558e14af25313d453", size = 2465765, upload-time = "2026-04-01T14:44:45.996Z" }, + { url = "https://files.pythonhosted.org/packages/bf/98/4595daa2365416a86cb0d495248a393dfc84e96d62ad080c8546256cb9c0/pillow-12.2.0-cp314-cp314-ios_13_0_arm64_iphoneos.whl", hash = "sha256:3adc9215e8be0448ed6e814966ecf3d9952f0ea40eb14e89a102b87f450660d8", size = 4100848, upload-time = "2026-04-01T14:44:48.48Z" }, + { url = "https://files.pythonhosted.org/packages/0b/79/40184d464cf89f6663e18dfcf7ca21aae2491fff1a16127681bf1fa9b8cf/pillow-12.2.0-cp314-cp314-ios_13_0_arm64_iphonesimulator.whl", hash = "sha256:6a9adfc6d24b10f89588096364cc726174118c62130c817c2837c60cf08a392b", size = 4176515, upload-time = "2026-04-01T14:44:51.353Z" }, + { url = "https://files.pythonhosted.org/packages/b0/63/703f86fd4c422a9cf722833670f4f71418fb116b2853ff7da722ea43f184/pillow-12.2.0-cp314-cp314-ios_13_0_x86_64_iphonesimulator.whl", hash = "sha256:6a6e67ea2e6feda684ed370f9a1c52e7a243631c025ba42149a2cc5934dec295", size = 3640159, upload-time = "2026-04-01T14:44:53.588Z" }, + { url = "https://files.pythonhosted.org/packages/71/e0/fb22f797187d0be2270f83500aab851536101b254bfa1eae10795709d283/pillow-12.2.0-cp314-cp314-macosx_10_15_x86_64.whl", hash = "sha256:2bb4a8d594eacdfc59d9e5ad972aa8afdd48d584ffd5f13a937a664c3e7db0ed", size = 5312185, upload-time = "2026-04-01T14:44:56.039Z" }, + { url = "https://files.pythonhosted.org/packages/ba/8c/1a9e46228571de18f8e28f16fabdfc20212a5d019f3e3303452b3f0a580d/pillow-12.2.0-cp314-cp314-macosx_11_0_arm64.whl", hash = "sha256:80b2da48193b2f33ed0c32c38140f9d3186583ce7d516526d462645fd98660ae", size = 4695386, upload-time = "2026-04-01T14:44:58.663Z" }, + { url = "https://files.pythonhosted.org/packages/70/62/98f6b7f0c88b9addd0e87c217ded307b36be024d4ff8869a812b241d1345/pillow-12.2.0-cp314-cp314-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:22db17c68434de69d8ecfc2fe821569195c0c373b25cccb9cbdacf2c6e53c601", size = 6280384, upload-time = "2026-04-01T14:45:01.5Z" }, + { url = "https://files.pythonhosted.org/packages/5e/03/688747d2e91cfbe0e64f316cd2e8005698f76ada3130d0194664174fa5de/pillow-12.2.0-cp314-cp314-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:7b14cc0106cd9aecda615dd6903840a058b4700fcb817687d0ee4fc8b6e389be", size = 8091599, upload-time = "2026-04-01T14:45:04.5Z" }, + { url = "https://files.pythonhosted.org/packages/f6/35/577e22b936fcdd66537329b33af0b4ccfefaeabd8aec04b266528cddb33c/pillow-12.2.0-cp314-cp314-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:8cbeb542b2ebc6fcdacabf8aca8c1a97c9b3ad3927d46b8723f9d4f033288a0f", size = 6396021, upload-time = "2026-04-01T14:45:07.117Z" }, + { url = "https://files.pythonhosted.org/packages/11/8d/d2532ad2a603ca2b93ad9f5135732124e57811d0168155852f37fbce2458/pillow-12.2.0-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:4bfd07bc812fbd20395212969e41931001fd59eb55a60658b0e5710872e95286", size = 7083360, upload-time = "2026-04-01T14:45:09.763Z" }, + { url = "https://files.pythonhosted.org/packages/5e/26/d325f9f56c7e039034897e7380e9cc202b1e368bfd04d4cbe6a441f02885/pillow-12.2.0-cp314-cp314-musllinux_1_2_aarch64.whl", hash = "sha256:9aba9a17b623ef750a4d11b742cbafffeb48a869821252b30ee21b5e91392c50", size = 6507628, upload-time = "2026-04-01T14:45:12.378Z" }, + { url = "https://files.pythonhosted.org/packages/5f/f7/769d5632ffb0988f1c5e7660b3e731e30f7f8ec4318e94d0a5d674eb65a4/pillow-12.2.0-cp314-cp314-musllinux_1_2_x86_64.whl", hash = "sha256:deede7c263feb25dba4e82ea23058a235dcc2fe1f6021025dc71f2b618e26104", size = 7209321, upload-time = "2026-04-01T14:45:15.122Z" }, + { url = "https://files.pythonhosted.org/packages/6a/7a/c253e3c645cd47f1aceea6a8bacdba9991bf45bb7dfe927f7c893e89c93c/pillow-12.2.0-cp314-cp314-win32.whl", hash = "sha256:632ff19b2778e43162304d50da0181ce24ac5bb8180122cbe1bf4673428328c7", size = 6479723, upload-time = "2026-04-01T14:45:17.797Z" }, + { url = "https://files.pythonhosted.org/packages/cd/8b/601e6566b957ca50e28725cb6c355c59c2c8609751efbecd980db44e0349/pillow-12.2.0-cp314-cp314-win_amd64.whl", hash = "sha256:4e6c62e9d237e9b65fac06857d511e90d8461a32adcc1b9065ea0c0fa3a28150", size = 7217400, upload-time = "2026-04-01T14:45:20.529Z" }, + { url = "https://files.pythonhosted.org/packages/d6/94/220e46c73065c3e2951bb91c11a1fb636c8c9ad427ac3ce7d7f3359b9b2f/pillow-12.2.0-cp314-cp314-win_arm64.whl", hash = "sha256:b1c1fbd8a5a1af3412a0810d060a78b5136ec0836c8a4ef9aa11807f2a22f4e1", size = 2554835, upload-time = "2026-04-01T14:45:23.162Z" }, + { url = "https://files.pythonhosted.org/packages/b6/ab/1b426a3974cb0e7da5c29ccff4807871d48110933a57207b5a676cccc155/pillow-12.2.0-cp314-cp314t-macosx_10_15_x86_64.whl", hash = "sha256:57850958fe9c751670e49b2cecf6294acc99e562531f4bd317fa5ddee2068463", size = 5314225, upload-time = "2026-04-01T14:45:25.637Z" }, + { url = "https://files.pythonhosted.org/packages/19/1e/dce46f371be2438eecfee2a1960ee2a243bbe5e961890146d2dee1ff0f12/pillow-12.2.0-cp314-cp314t-macosx_11_0_arm64.whl", hash = "sha256:d5d38f1411c0ed9f97bcb49b7bd59b6b7c314e0e27420e34d99d844b9ce3b6f3", size = 4698541, upload-time = "2026-04-01T14:45:28.355Z" }, + { url = "https://files.pythonhosted.org/packages/55/c3/7fbecf70adb3a0c33b77a300dc52e424dc22ad8cdc06557a2e49523b703d/pillow-12.2.0-cp314-cp314t-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:5c0a9f29ca8e79f09de89293f82fc9b0270bb4af1d58bc98f540cc4aedf03166", size = 6322251, upload-time = "2026-04-01T14:45:30.924Z" }, + { url = "https://files.pythonhosted.org/packages/1c/3c/7fbc17cfb7e4fe0ef1642e0abc17fc6c94c9f7a16be41498e12e2ba60408/pillow-12.2.0-cp314-cp314t-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:1610dd6c61621ae1cf811bef44d77e149ce3f7b95afe66a4512f8c59f25d9ebe", size = 8127807, upload-time = "2026-04-01T14:45:33.908Z" }, + { url = "https://files.pythonhosted.org/packages/ff/c3/a8ae14d6defd2e448493ff512fae903b1e9bd40b72efb6ec55ce0048c8ce/pillow-12.2.0-cp314-cp314t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0a34329707af4f73cf1782a36cd2289c0368880654a2c11f027bcee9052d35dd", size = 6433935, upload-time = "2026-04-01T14:45:36.623Z" }, + { url = "https://files.pythonhosted.org/packages/6e/32/2880fb3a074847ac159d8f902cb43278a61e85f681661e7419e6596803ed/pillow-12.2.0-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:8e9c4f5b3c546fa3458a29ab22646c1c6c787ea8f5ef51300e5a60300736905e", size = 7116720, upload-time = "2026-04-01T14:45:39.258Z" }, + { url = "https://files.pythonhosted.org/packages/46/87/495cc9c30e0129501643f24d320076f4cc54f718341df18cc70ec94c44e1/pillow-12.2.0-cp314-cp314t-musllinux_1_2_aarch64.whl", hash = "sha256:fb043ee2f06b41473269765c2feae53fc2e2fbf96e5e22ca94fb5ad677856f06", size = 6540498, upload-time = "2026-04-01T14:45:41.879Z" }, + { url = "https://files.pythonhosted.org/packages/18/53/773f5edca692009d883a72211b60fdaf8871cbef075eaa9d577f0a2f989e/pillow-12.2.0-cp314-cp314t-musllinux_1_2_x86_64.whl", hash = "sha256:f278f034eb75b4e8a13a54a876cc4a5ab39173d2cdd93a638e1b467fc545ac43", size = 7239413, upload-time = "2026-04-01T14:45:44.705Z" }, + { url = "https://files.pythonhosted.org/packages/c9/e4/4b64a97d71b2a83158134abbb2f5bd3f8a2ea691361282f010998f339ec7/pillow-12.2.0-cp314-cp314t-win32.whl", hash = "sha256:6bb77b2dcb06b20f9f4b4a8454caa581cd4dd0643a08bacf821216a16d9c8354", size = 6482084, upload-time = "2026-04-01T14:45:47.568Z" }, + { url = "https://files.pythonhosted.org/packages/ba/13/306d275efd3a3453f72114b7431c877d10b1154014c1ebbedd067770d629/pillow-12.2.0-cp314-cp314t-win_amd64.whl", hash = "sha256:6562ace0d3fb5f20ed7290f1f929cae41b25ae29528f2af1722966a0a02e2aa1", size = 7225152, upload-time = "2026-04-01T14:45:50.032Z" }, + { url = "https://files.pythonhosted.org/packages/ff/6e/cf826fae916b8658848d7b9f38d88da6396895c676e8086fc0988073aaf8/pillow-12.2.0-cp314-cp314t-win_arm64.whl", hash = "sha256:aa88ccfe4e32d362816319ed727a004423aab09c5cea43c01a4b435643fa34eb", size = 2556579, upload-time = "2026-04-01T14:45:52.529Z" }, + { url = "https://files.pythonhosted.org/packages/4e/b7/2437044fb910f499610356d1352e3423753c98e34f915252aafecc64889f/pillow-12.2.0-pp311-pypy311_pp73-macosx_10_15_x86_64.whl", hash = "sha256:0538bd5e05efec03ae613fd89c4ce0368ecd2ba239cc25b9f9be7ed426b0af1f", size = 5273969, upload-time = "2026-04-01T14:45:55.538Z" }, + { url = "https://files.pythonhosted.org/packages/f6/f4/8316e31de11b780f4ac08ef3654a75555e624a98db1056ecb2122d008d5a/pillow-12.2.0-pp311-pypy311_pp73-macosx_11_0_arm64.whl", hash = "sha256:394167b21da716608eac917c60aa9b969421b5dcbbe02ae7f013e7b85811c69d", size = 4659674, upload-time = "2026-04-01T14:45:58.093Z" }, + { url = "https://files.pythonhosted.org/packages/d4/37/664fca7201f8bb2aa1d20e2c3d5564a62e6ae5111741966c8319ca802361/pillow-12.2.0-pp311-pypy311_pp73-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:5d04bfa02cc2d23b497d1e90a0f927070043f6cbf303e738300532379a4b4e0f", size = 5288479, upload-time = "2026-04-01T14:46:01.141Z" }, + { url = "https://files.pythonhosted.org/packages/49/62/5b0ed78fce87346be7a5cfcfaaad91f6a1f98c26f86bdbafa2066c647ef6/pillow-12.2.0-pp311-pypy311_pp73-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:0c838a5125cee37e68edec915651521191cef1e6aa336b855f495766e77a366e", size = 7032230, upload-time = "2026-04-01T14:46:03.874Z" }, + { url = "https://files.pythonhosted.org/packages/c3/28/ec0fc38107fc32536908034e990c47914c57cd7c5a3ece4d8d8f7ffd7e27/pillow-12.2.0-pp311-pypy311_pp73-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:4a6c9fa44005fa37a91ebfc95d081e8079757d2e904b27103f4f5fa6f0bf78c0", size = 5355404, upload-time = "2026-04-01T14:46:06.33Z" }, + { url = "https://files.pythonhosted.org/packages/5e/8b/51b0eddcfa2180d60e41f06bd6d0a62202b20b59c68f5a132e615b75aecf/pillow-12.2.0-pp311-pypy311_pp73-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:25373b66e0dd5905ed63fa3cae13c82fbddf3079f2c8bf15c6fb6a35586324c1", size = 6002215, upload-time = "2026-04-01T14:46:08.83Z" }, + { url = "https://files.pythonhosted.org/packages/bc/60/5382c03e1970de634027cee8e1b7d39776b778b81812aaf45b694dfe9e28/pillow-12.2.0-pp311-pypy311_pp73-win_amd64.whl", hash = "sha256:bfa9c230d2fe991bed5318a5f119bd6780cda2915cca595393649fc118ab895e", size = 7080946, upload-time = "2026-04-01T14:46:11.734Z" }, ] [[package]] From 69d349139df077613eed9ddaa0f99a0386a4686c Mon Sep 17 00:00:00 2001 From: twidmer Date: Thu, 16 Apr 2026 09:50:13 +0200 Subject: [PATCH 09/10] Ran ruff --- newton/_src/geometry/narrow_phase.py | 8 ++--- newton/tests/test_speculative_contacts.py | 42 +++++++++++++++++++---- 2 files changed, 38 insertions(+), 12 deletions(-) diff --git a/newton/_src/geometry/narrow_phase.py b/newton/_src/geometry/narrow_phase.py index 1575bb29e2..13ea0daa93 100644 --- a/newton/_src/geometry/narrow_phase.py +++ b/newton/_src/geometry/narrow_phase.py @@ -1231,9 +1231,7 @@ def narrow_phase_process_mesh_plane_contacts_kernel( if wp.static(speculative): vel_rel = shape_lin_vel[plane_shape] - shape_lin_vel[mesh_shape] - rel_speed = ( - wp.length(vel_rel) + shape_ang_speed_bound[mesh_shape] + shape_ang_speed_bound[plane_shape] - ) + rel_speed = wp.length(vel_rel) + shape_ang_speed_bound[mesh_shape] + shape_ang_speed_bound[plane_shape] gap_sum = gap_sum + wp.min(rel_speed * speculative_dt, max_speculative_extension) # Strided loop over vertices across all threads in the launch @@ -1374,9 +1372,7 @@ def narrow_phase_process_mesh_plane_contacts_reduce_kernel( if wp.static(speculative): vel_rel = shape_lin_vel[plane_shape] - shape_lin_vel[mesh_shape] - rel_speed = ( - wp.length(vel_rel) + shape_ang_speed_bound[mesh_shape] + shape_ang_speed_bound[plane_shape] - ) + rel_speed = wp.length(vel_rel) + shape_ang_speed_bound[mesh_shape] + shape_ang_speed_bound[plane_shape] gap_sum = gap_sum + wp.min(rel_speed * speculative_dt, max_speculative_extension) # Process this block's chunk of vertices — write contacts directly diff --git a/newton/tests/test_speculative_contacts.py b/newton/tests/test_speculative_contacts.py index d8a36b60a0..80bbb98cd0 100644 --- a/newton/tests/test_speculative_contacts.py +++ b/newton/tests/test_speculative_contacts.py @@ -265,17 +265,47 @@ def _make_thin_wall_mesh(hx=0.02, hy=1.0, hz=1.0): tris = np.array( [ # -X face - 0, 3, 7, 0, 7, 4, + 0, + 3, + 7, + 0, + 7, + 4, # +X face - 1, 5, 6, 1, 6, 2, + 1, + 5, + 6, + 1, + 6, + 2, # -Y face - 0, 4, 5, 0, 5, 1, + 0, + 4, + 5, + 0, + 5, + 1, # +Y face - 3, 2, 6, 3, 6, 7, + 3, + 2, + 6, + 3, + 6, + 7, # -Z face - 0, 1, 2, 0, 2, 3, + 0, + 1, + 2, + 0, + 2, + 3, # +Z face - 4, 7, 6, 4, 6, 5, + 4, + 7, + 6, + 4, + 6, + 5, ], dtype=np.int32, ) From b739859178625a4c81e8d162c76f9ae410b7c8e5 Mon Sep 17 00:00:00 2001 From: twidmer Date: Thu, 16 Apr 2026 10:17:38 +0200 Subject: [PATCH 10/10] Implement CodeRabbit comments --- CHANGELOG.md | 1 - newton/_src/geometry/narrow_phase.py | 8 ++++---- newton/_src/geometry/sdf_contact.py | 7 ++----- 3 files changed, 6 insertions(+), 10 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index 45e243e230..a8fe5ae11e 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -78,7 +78,6 @@ - Add RJ45 plug-socket insertion example with SDF contacts, latch joint, and interactive gizmo - Add `SpeculativeContactConfig` and speculative contact support in `CollisionPipeline` to detect contacts for fast-moving objects before they tunnel through thin geometry - Add `TRIANGLE_PRISM` support-function type for heightfield triangles, extruding 1 m along the heightfield's local -Z so GJK/MPR naturally resolves shapes on the back side -- Add `ViewerGL.log_scalar()` for live scalar time-series plots in the viewer ### Changed diff --git a/newton/_src/geometry/narrow_phase.py b/newton/_src/geometry/narrow_phase.py index 467ba9bb1f..4a655532c1 100644 --- a/newton/_src/geometry/narrow_phase.py +++ b/newton/_src/geometry/narrow_phase.py @@ -150,7 +150,7 @@ def create_narrow_phase_primitive_kernel(writer_func: Any, speculative: bool = F Returns: A warp kernel for primitive collision detection """ - _module = f"narrow_phase_primitive_{writer_func.__name__}" + _module = f"narrow_phase_primitive_{writer_func.__name__}_{speculative}" @wp.kernel(enable_backward=False, module=_module) def narrow_phase_primitive_kernel( @@ -658,7 +658,7 @@ def create_narrow_phase_kernel_gjk_mpr( """ _sf = support_func.__name__ if support_func is not None else "default" _ppc = post_process_contact.__name__ if post_process_contact is not None else "default" - _module = f"narrow_phase_gjk_mpr_{external_aabb}_{writer_func.__name__}_{_sf}_{_ppc}" + _module = f"narrow_phase_gjk_mpr_{external_aabb}_{writer_func.__name__}_{_sf}_{_ppc}_{speculative}" @wp.kernel(enable_backward=False, module=_module) def narrow_phase_kernel_gjk_mpr( @@ -957,7 +957,7 @@ def narrow_phase_find_mesh_triangle_overlaps_kernel( def create_narrow_phase_process_mesh_triangle_contacts_kernel(writer_func: Any, speculative: bool = False): - _module = f"narrow_phase_mesh_tri_{writer_func.__name__}" + _module = f"narrow_phase_mesh_tri_{writer_func.__name__}_{speculative}" @wp.kernel(enable_backward=False, module=_module) def narrow_phase_process_mesh_triangle_contacts_kernel( @@ -1163,7 +1163,7 @@ def create_narrow_phase_process_mesh_plane_contacts_kernel( Returns: A warp kernel that processes mesh-plane collisions """ - _module = f"narrow_phase_mesh_plane_{writer_func.__name__}_{reduce_contacts}" + _module = f"narrow_phase_mesh_plane_{writer_func.__name__}_{reduce_contacts}_{speculative}" @wp.kernel(enable_backward=False, module=_module) def narrow_phase_process_mesh_plane_contacts_kernel( diff --git a/newton/_src/geometry/sdf_contact.py b/newton/_src/geometry/sdf_contact.py index 825206e836..43d618e49e 100644 --- a/newton/_src/geometry/sdf_contact.py +++ b/newton/_src/geometry/sdf_contact.py @@ -39,10 +39,7 @@ def _query_mesh_face_normal( sign = float(0.0) res = wp.mesh_query_point_sign_normal(mesh_id, point_local, max_dist, sign, face_index, face_u, face_v) if res: - n = wp.mesh_eval_face_normal(mesh_id, face_index) - if sign < 0.0: - n = -n - return n + return wp.mesh_eval_face_normal(mesh_id, face_index) return wp.vec3(0.0, 1.0, 0.0) @@ -1034,7 +1031,7 @@ def create_narrow_phase_process_mesh_mesh_contacts_kernel( # compiled code, otherwise FMA-fusion or register-allocation # differences between independent JIT compilations can produce subtly # different floating-point results, breaking bit-exact reproducibility. - _module = f"sdf_contact_{writer_func.__name__}_{enable_heightfields}_{reduce_contacts}" + _module = f"sdf_contact_{writer_func.__name__}_{enable_heightfields}_{reduce_contacts}_{speculative}" @wp.kernel(enable_backward=False, module=_module) def mesh_sdf_collision_kernel(