From 50fe86a2f46029fbcfce168274b87338ccdd1e5f Mon Sep 17 00:00:00 2001 From: Sam Haves Date: Mon, 30 Mar 2026 15:10:40 -0400 Subject: [PATCH 01/20] Modify mjPLUGIN_LIB_INIT to use C runtime initializer. --- include/mujoco/mjplugin.h | 42 ++++++++++----------------------------- 1 file changed, 10 insertions(+), 32 deletions(-) diff --git a/include/mujoco/mjplugin.h b/include/mujoco/mjplugin.h index 7c6300b9b9..5146e20380 100644 --- a/include/mujoco/mjplugin.h +++ b/include/mujoco/mjplugin.h @@ -182,39 +182,17 @@ struct mjSDF_ { }; typedef struct mjSDF_ mjSDF; -#if defined(__has_attribute) - - #if __has_attribute(constructor) - #define mjPLUGIN_LIB_INIT __attribute__((constructor)) static void _mjplugin_init(void) - #endif // __has_attribute(constructor) - +#if defined(__has_attribute) && __has_attribute(constructor) + #define mjPLUGIN_LIB_INIT \ + static void _mjplugin_init(void) __attribute__((constructor)); \ + static void _mjplugin_init(void) #elif defined(_MSC_VER) - - #ifndef mjDLLMAIN - #define mjDLLMAIN DllMain - #endif - - #if !defined(mjEXTERNC) - #if defined(__cplusplus) - #define mjEXTERNC extern "C" - #else - #define mjEXTERNC - #endif // defined(__cplusplus) - #endif // !defined(mjEXTERNC) - - // NOLINTBEGIN(runtime/int) - #define mjPLUGIN_LIB_INIT \ - static void _mjplugin_dllmain(void); \ - mjEXTERNC int __stdcall mjDLLMAIN(void* hinst, unsigned long reason, void* reserved) { \ - if (reason == 1) { \ - _mjplugin_dllmain(); \ - } \ - return 1; \ - } \ - static void _mjplugin_dllmain(void) - // NOLINTEND(runtime/int) - -#endif // defined(_MSC_VER) + #pragma section(".CRT$XCU", read) + #define mjPLUGIN_LIB_INIT \ + static void _mjplugin_init(void); \ + __pragma(warning(suppress: 4189)) __declspec(allocate(".CRT$XCU")) static void (*_mjplugin_init_ptr)(void) = _mjplugin_init; \ + static void _mjplugin_init(void) +#endif // function pointer type for mj_loadAllPluginLibraries callback typedef void (*mjfPluginLibraryLoadCallback)(const char* filename, int first, int count); From 4e209995797b88c9024357a96c0155e37ffc241f Mon Sep 17 00:00:00 2001 From: havess Date: Mon, 30 Mar 2026 15:21:58 -0400 Subject: [PATCH 02/20] Revert "Modify mjPLUGIN_LIB_INIT to use C runtime initializer." This reverts commit 50fe86a2f46029fbcfce168274b87338ccdd1e5f. --- include/mujoco/mjplugin.h | 42 +++++++++++++++++++++++++++++---------- 1 file changed, 32 insertions(+), 10 deletions(-) diff --git a/include/mujoco/mjplugin.h b/include/mujoco/mjplugin.h index 5146e20380..7c6300b9b9 100644 --- a/include/mujoco/mjplugin.h +++ b/include/mujoco/mjplugin.h @@ -182,17 +182,39 @@ struct mjSDF_ { }; typedef struct mjSDF_ mjSDF; -#if defined(__has_attribute) && __has_attribute(constructor) - #define mjPLUGIN_LIB_INIT \ - static void _mjplugin_init(void) __attribute__((constructor)); \ - static void _mjplugin_init(void) +#if defined(__has_attribute) + + #if __has_attribute(constructor) + #define mjPLUGIN_LIB_INIT __attribute__((constructor)) static void _mjplugin_init(void) + #endif // __has_attribute(constructor) + #elif defined(_MSC_VER) - #pragma section(".CRT$XCU", read) - #define mjPLUGIN_LIB_INIT \ - static void _mjplugin_init(void); \ - __pragma(warning(suppress: 4189)) __declspec(allocate(".CRT$XCU")) static void (*_mjplugin_init_ptr)(void) = _mjplugin_init; \ - static void _mjplugin_init(void) -#endif + + #ifndef mjDLLMAIN + #define mjDLLMAIN DllMain + #endif + + #if !defined(mjEXTERNC) + #if defined(__cplusplus) + #define mjEXTERNC extern "C" + #else + #define mjEXTERNC + #endif // defined(__cplusplus) + #endif // !defined(mjEXTERNC) + + // NOLINTBEGIN(runtime/int) + #define mjPLUGIN_LIB_INIT \ + static void _mjplugin_dllmain(void); \ + mjEXTERNC int __stdcall mjDLLMAIN(void* hinst, unsigned long reason, void* reserved) { \ + if (reason == 1) { \ + _mjplugin_dllmain(); \ + } \ + return 1; \ + } \ + static void _mjplugin_dllmain(void) + // NOLINTEND(runtime/int) + +#endif // defined(_MSC_VER) // function pointer type for mj_loadAllPluginLibraries callback typedef void (*mjfPluginLibraryLoadCallback)(const char* filename, int first, int count); From bd4cdecb8027f564d255ec37e0a931b7ae6de341 Mon Sep 17 00:00:00 2001 From: havess Date: Mon, 30 Mar 2026 15:57:00 -0400 Subject: [PATCH 03/20] Reapply "Modify mjPLUGIN_LIB_INIT to use C runtime initializer." This reverts commit 4e209995797b88c9024357a96c0155e37ffc241f. --- include/mujoco/mjplugin.h | 42 ++++++++++----------------------------- 1 file changed, 10 insertions(+), 32 deletions(-) diff --git a/include/mujoco/mjplugin.h b/include/mujoco/mjplugin.h index 7c6300b9b9..5146e20380 100644 --- a/include/mujoco/mjplugin.h +++ b/include/mujoco/mjplugin.h @@ -182,39 +182,17 @@ struct mjSDF_ { }; typedef struct mjSDF_ mjSDF; -#if defined(__has_attribute) - - #if __has_attribute(constructor) - #define mjPLUGIN_LIB_INIT __attribute__((constructor)) static void _mjplugin_init(void) - #endif // __has_attribute(constructor) - +#if defined(__has_attribute) && __has_attribute(constructor) + #define mjPLUGIN_LIB_INIT \ + static void _mjplugin_init(void) __attribute__((constructor)); \ + static void _mjplugin_init(void) #elif defined(_MSC_VER) - - #ifndef mjDLLMAIN - #define mjDLLMAIN DllMain - #endif - - #if !defined(mjEXTERNC) - #if defined(__cplusplus) - #define mjEXTERNC extern "C" - #else - #define mjEXTERNC - #endif // defined(__cplusplus) - #endif // !defined(mjEXTERNC) - - // NOLINTBEGIN(runtime/int) - #define mjPLUGIN_LIB_INIT \ - static void _mjplugin_dllmain(void); \ - mjEXTERNC int __stdcall mjDLLMAIN(void* hinst, unsigned long reason, void* reserved) { \ - if (reason == 1) { \ - _mjplugin_dllmain(); \ - } \ - return 1; \ - } \ - static void _mjplugin_dllmain(void) - // NOLINTEND(runtime/int) - -#endif // defined(_MSC_VER) + #pragma section(".CRT$XCU", read) + #define mjPLUGIN_LIB_INIT \ + static void _mjplugin_init(void); \ + __pragma(warning(suppress: 4189)) __declspec(allocate(".CRT$XCU")) static void (*_mjplugin_init_ptr)(void) = _mjplugin_init; \ + static void _mjplugin_init(void) +#endif // function pointer type for mj_loadAllPluginLibraries callback typedef void (*mjfPluginLibraryLoadCallback)(const char* filename, int first, int count); From 3f9cde5f5866a41bb8b1bb40d262fcfa0ec4e07c Mon Sep 17 00:00:00 2001 From: havess Date: Mon, 30 Mar 2026 16:09:36 -0400 Subject: [PATCH 04/20] Try and avoid linker optimizing out the plugin registration. --- include/mujoco/mjplugin.h | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/include/mujoco/mjplugin.h b/include/mujoco/mjplugin.h index 5146e20380..8542af12c4 100644 --- a/include/mujoco/mjplugin.h +++ b/include/mujoco/mjplugin.h @@ -188,10 +188,15 @@ typedef struct mjSDF_ mjSDF; static void _mjplugin_init(void) #elif defined(_MSC_VER) #pragma section(".CRT$XCU", read) - #define mjPLUGIN_LIB_INIT \ - static void _mjplugin_init(void); \ - __pragma(warning(suppress: 4189)) __declspec(allocate(".CRT$XCU")) static void (*_mjplugin_init_ptr)(void) = _mjplugin_init; \ - static void _mjplugin_init(void) + + #define mjPLUGIN_LIB_INIT \ + static void __cdecl _mj_init_##__COUNTER__(void); \ + /* The 'used' attribute for the linker */ \ + __declspec(allocate(".CRT$XCU")) \ + static void (__cdecl * _mj_ptr_##__COUNTER__)(void) = _mj_init_##__COUNTER__; \ + /* This pragma prevents the linker from optimizing this specific pointer away */ \ + __pragma(comment(linker, "/include:" "_mj_ptr_" #__COUNTER__)) \ + static void __cdecl _mj_init_##__COUNTER__(void) #endif // function pointer type for mj_loadAllPluginLibraries callback From 47284b202c1722e7ea6f2796f6dcc0c98ec1561c Mon Sep 17 00:00:00 2001 From: havess Date: Mon, 30 Mar 2026 16:31:57 -0400 Subject: [PATCH 05/20] Fix missing # --- .github/workflows/build.yml | 6 ++--- include/mujoco/mjplugin.h | 39 ++++++++++++++++++++--------- plugin/actuator/register.cc | 2 +- plugin/elasticity/register.cc | 2 +- plugin/obj_decoder/obj_decoder.cc | 2 +- plugin/sdf/register.cc | 2 +- plugin/sensor/register.cc | 2 +- plugin/stl_decoder/stl_decoder.cc | 2 +- plugin/usd_decoder/usd_decoder.cc | 2 +- src/experimental/mjz/mjz_decoder.cc | 2 +- 10 files changed, 38 insertions(+), 23 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index f2c0680571..6389087ef9 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -347,7 +347,7 @@ jobs: CHATMSG_AUTHOR_EMAIL: ${{ github.event.head_commit.author.email }} CHATMSG_COMMIT_MESSAGE: ${{ github.event.head_commit.message }} CHATMSG_JOB_ID: ${{ matrix.label }} - if: ${{ failure() && github.event_name == 'push' && env.GCHAT_API_URL != '' }} + if: failure() && github.event_name == 'push' && env.GCHAT_API_URL != '' && github.ref_name == 'main' run: bash ./.github/workflows/build_steps.sh notify_team_chat # This job quickly determines if MuJoCo Studio is broken. @@ -406,7 +406,7 @@ jobs: CHATMSG_AUTHOR_EMAIL: ${{ github.event.head_commit.author.email }} CHATMSG_COMMIT_MESSAGE: ${{ github.event.head_commit.message }} CHATMSG_JOB_ID: ${{ matrix.label }} - if: ${{ failure() && github.event_name == 'push' && env.GCHAT_API_URL != '' }} + if: failure() && github.event_name == 'push' && env.GCHAT_API_URL != '' && github.ref_name == 'main' run: bash ./.github/workflows/build_steps.sh notify_team_chat @@ -451,5 +451,5 @@ jobs: CHATMSG_AUTHOR_EMAIL: ${{ github.event.head_commit.author.email }} CHATMSG_COMMIT_MESSAGE: ${{ github.event.head_commit.message }} CHATMSG_JOB_ID: ${{ env.label }} - if: ${{ failure() && github.event_name == 'push' && env.GCHAT_API_URL != '' }} + if: failure() && github.event_name == 'push' && env.GCHAT_API_URL != '' && github.ref_name == 'main' run: bash ./.github/workflows/build_steps.sh notify_team_chat diff --git a/include/mujoco/mjplugin.h b/include/mujoco/mjplugin.h index 8542af12c4..ccd7369a54 100644 --- a/include/mujoco/mjplugin.h +++ b/include/mujoco/mjplugin.h @@ -182,21 +182,36 @@ struct mjSDF_ { }; typedef struct mjSDF_ mjSDF; -#if defined(__has_attribute) && __has_attribute(constructor) - #define mjPLUGIN_LIB_INIT \ - static void _mjplugin_init(void) __attribute__((constructor)); \ - static void _mjplugin_init(void) +#if defined(__GNUC__) || defined(__clang__) + // GCC and Clang (including clang-cl) + #define mjPLUGIN_LIB_INIT(n) \ + static void _mj_init_##n(void) __attribute__((constructor)); \ + static void _mj_init_##n(void) #elif defined(_MSC_VER) + #define m_STR(x) #x + #define m_XSTR(x) m_STR(x) + + // On x86, symbols are decorated with a leading underscore. + // On x64, they are not. + #ifdef _M_IX86 + #define LINKER_NAME "__mj_ptr_" + #else + #define LINKER_NAME "_mj_ptr_" + #endif + #pragma section(".CRT$XCU", read) - #define mjPLUGIN_LIB_INIT \ - static void __cdecl _mj_init_##__COUNTER__(void); \ - /* The 'used' attribute for the linker */ \ - __declspec(allocate(".CRT$XCU")) \ - static void (__cdecl * _mj_ptr_##__COUNTER__)(void) = _mj_init_##__COUNTER__; \ - /* This pragma prevents the linker from optimizing this specific pointer away */ \ - __pragma(comment(linker, "/include:" "_mj_ptr_" #__COUNTER__)) \ - static void __cdecl _mj_init_##__COUNTER__(void) + #define mjPLUGIN_LIB_INIT(n) \ + static void __cdecl _mj_init_##n(void); \ + /* We use extern "C" to prevent C++ name mangling */ \ + extern "C" __declspec(allocate(".CRT$XCU")) \ + void (__cdecl * _mj_ptr_##n)(void) = _mj_init_##n; \ + /* Force the linker to include the pointer symbol */ \ + __pragma(comment(linker, "/include:" LINKER_NAME #n)) \ + static void __cdecl _mj_init_##n(void) + +#else + #error "Unknown compiler: Plugin registration not supported." #endif // function pointer type for mj_loadAllPluginLibraries callback diff --git a/plugin/actuator/register.cc b/plugin/actuator/register.cc index 66f24b9364..e3c3e2f54c 100644 --- a/plugin/actuator/register.cc +++ b/plugin/actuator/register.cc @@ -17,6 +17,6 @@ namespace mujoco::plugin::actuator { -mjPLUGIN_LIB_INIT { Pid::RegisterPlugin(); } +mjPLUGIN_LIB_INIT(actuator) { Pid::RegisterPlugin(); } } // namespace mujoco::plugin::actuator diff --git a/plugin/elasticity/register.cc b/plugin/elasticity/register.cc index ab8d283a60..b4a68754a6 100644 --- a/plugin/elasticity/register.cc +++ b/plugin/elasticity/register.cc @@ -17,7 +17,7 @@ namespace mujoco::plugin::elasticity { -mjPLUGIN_LIB_INIT { +mjPLUGIN_LIB_INIT(elasticity) { Cable::RegisterPlugin(); } diff --git a/plugin/obj_decoder/obj_decoder.cc b/plugin/obj_decoder/obj_decoder.cc index 18cfdf5ff7..929e959ac0 100644 --- a/plugin/obj_decoder/obj_decoder.cc +++ b/plugin/obj_decoder/obj_decoder.cc @@ -114,7 +114,7 @@ int CanDecode(const mjResource* resource) { } // namespace -mjPLUGIN_LIB_INIT { +mjPLUGIN_LIB_INIT(obj_decoder) { mjpDecoder decoder; mjp_defaultDecoder(&decoder); decoder.content_type = "model/obj"; diff --git a/plugin/sdf/register.cc b/plugin/sdf/register.cc index 4e727e38e8..591467237d 100644 --- a/plugin/sdf/register.cc +++ b/plugin/sdf/register.cc @@ -20,7 +20,7 @@ namespace mujoco::plugin::sdf { -mjPLUGIN_LIB_INIT { +mjPLUGIN_LIB_INIT(sdf) { Bolt::RegisterPlugin(); Bowl::RegisterPlugin(); Gear::RegisterPlugin(); diff --git a/plugin/sensor/register.cc b/plugin/sensor/register.cc index dd8a70d8d1..b3a587afff 100644 --- a/plugin/sensor/register.cc +++ b/plugin/sensor/register.cc @@ -17,7 +17,7 @@ namespace mujoco::plugin::sensor { -mjPLUGIN_LIB_INIT { +mjPLUGIN_LIB_INIT(sensor) { TouchGrid::RegisterPlugin(); } diff --git a/plugin/stl_decoder/stl_decoder.cc b/plugin/stl_decoder/stl_decoder.cc index c6932d9ab5..7e1d1a5a69 100644 --- a/plugin/stl_decoder/stl_decoder.cc +++ b/plugin/stl_decoder/stl_decoder.cc @@ -132,7 +132,7 @@ int CanDecode(const mjResource* resource) { } // namespace -mjPLUGIN_LIB_INIT { +mjPLUGIN_LIB_INIT(stl_decoder) { mjpDecoder decoder; mjp_defaultDecoder(&decoder); decoder.content_type = "model/stl"; diff --git a/plugin/usd_decoder/usd_decoder.cc b/plugin/usd_decoder/usd_decoder.cc index 58a24590e4..f1ab1c0517 100644 --- a/plugin/usd_decoder/usd_decoder.cc +++ b/plugin/usd_decoder/usd_decoder.cc @@ -2459,7 +2459,7 @@ int CanDecode(const mjResource* resource) { } // namespace // clang-format off -mjPLUGIN_LIB_INIT { +mjPLUGIN_LIB_INIT(usd_decoder) { mjpDecoder decoder; mjp_defaultDecoder(&decoder); decoder.content_type = "model/usd"; diff --git a/src/experimental/mjz/mjz_decoder.cc b/src/experimental/mjz/mjz_decoder.cc index 8defa31d96..ee29a80f6c 100644 --- a/src/experimental/mjz/mjz_decoder.cc +++ b/src/experimental/mjz/mjz_decoder.cc @@ -192,7 +192,7 @@ static mjSpec* ParseZipBuffer(const void* buffer, int nbuffer, const char* name, return mj_parseXML(root.c_str(), vfs, error, error_sz); } -mjPLUGIN_LIB_INIT { +mjPLUGIN_LIB_INIT(mjz_decoder) { mjpDecoder decoder; decoder.content_type = "application/zip"; decoder.extension = ".mjz|.zip"; From 315c2b5e2b24674dde251f600d4f60c57c23cb48 Mon Sep 17 00:00:00 2001 From: Sam Haves Date: Thu, 2 Apr 2026 12:37:21 -0400 Subject: [PATCH 06/20] Test building obj and stl decoders as part of mujoco lib. --- .github/workflows/build_steps.sh | 4 --- cmake/ShellTests.cmake | 1 - plugin/obj_decoder/CMakeLists.txt | 47 +++---------------------------- plugin/stl_decoder/CMakeLists.txt | 41 ++------------------------- sample/testspeed.cc | 6 ---- test/user/CMakeLists.txt | 9 ------ test/xml/CMakeLists.txt | 3 -- wasm/CMakeLists.txt | 7 ++++- wasm/tests/CMakeLists.txt | 7 ++++- 9 files changed, 18 insertions(+), 107 deletions(-) diff --git a/.github/workflows/build_steps.sh b/.github/workflows/build_steps.sh index 7286aca673..08423311d8 100755 --- a/.github/workflows/build_steps.sh +++ b/.github/workflows/build_steps.sh @@ -101,8 +101,6 @@ copy_plugins_posix() { mkdir -p ${TMPDIR}/mujoco_install/mujoco_plugin && cp lib/libactuator.* ${TMPDIR}/mujoco_install/mujoco_plugin && cp lib/libelasticity.* ${TMPDIR}/mujoco_install/mujoco_plugin && - cp lib/libobj_decoder.* ${TMPDIR}/mujoco_install/mujoco_plugin && - cp lib/libstl_decoder.* ${TMPDIR}/mujoco_install/mujoco_plugin && cp lib/libsensor.* ${TMPDIR}/mujoco_install/mujoco_plugin && cp lib/libsdf_plugin.* ${TMPDIR}/mujoco_install/mujoco_plugin } @@ -113,8 +111,6 @@ copy_plugins_window() { mkdir -p ${TMPDIR}/mujoco_install/mujoco_plugin && cp bin/Release/actuator.dll ${TMPDIR}/mujoco_install/mujoco_plugin && cp bin/Release/elasticity.dll ${TMPDIR}/mujoco_install/mujoco_plugin && - cp bin/Release/obj_decoder.dll ${TMPDIR}/mujoco_install/mujoco_plugin && - cp bin/Release/stl_decoder.dll ${TMPDIR}/mujoco_install/mujoco_plugin && cp bin/Release/sensor.dll ${TMPDIR}/mujoco_install/mujoco_plugin } diff --git a/cmake/ShellTests.cmake b/cmake/ShellTests.cmake index d2480a25d1..b26b165850 100644 --- a/cmake/ShellTests.cmake +++ b/cmake/ShellTests.cmake @@ -38,7 +38,6 @@ function(add_mujoco_shell_test TEST_NAME TARGET_BINARY) "CMAKE_SOURCE_DIR=${CMAKE_SOURCE_DIR}" "TARGET_BINARY=$" "TEST_TMPDIR=${TEST_TMPDIR}" - "MUJOCO_PLUGIN_DIR=$" ) if(WIN32) # Define the directory containing the mujoco DLL library so that it can be added to the PATH. diff --git a/plugin/obj_decoder/CMakeLists.txt b/plugin/obj_decoder/CMakeLists.txt index 17b671997c..689dfc51eb 100644 --- a/plugin/obj_decoder/CMakeLists.txt +++ b/plugin/obj_decoder/CMakeLists.txt @@ -12,48 +12,9 @@ # See the License for the specific language governing permissions and # limitations under the License. -if(EMSCRIPTEN) - add_library(obj_decoder OBJECT obj_decoder.cc) -else() - set(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) - set(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_LIBDIR}") - - add_library(obj_decoder SHARED obj_decoder.cc) -endif() - -target_include_directories(obj_decoder PRIVATE - ${CMAKE_CURRENT_SOURCE_DIR}/../.. - ${CMAKE_CURRENT_SOURCE_DIR}/../../include +target_compile_definitions(mujoco PRIVATE TINYOBJLOADER_IMPLEMENTATION) +target_sources(mujoco PRIVATE + obj_decoder.cc ) -if(EMSCRIPTEN) - target_link_libraries(obj_decoder PRIVATE - tinyobjloader - ) -else() - target_link_libraries(obj_decoder PRIVATE - mujoco - tinyobjloader - ) -endif() - -target_compile_definitions(obj_decoder PRIVATE TINYOBJLOADER_IMPLEMENTATION) - -target_compile_options(obj_decoder PRIVATE - ${AVX_COMPILE_OPTIONS} - ${MUJOCO_MACOS_COMPILE_OPTIONS} - ${EXTRA_COMPILE_OPTIONS} - ${MUJOCO_CXX_FLAGS} -) - -if(NOT EMSCRIPTEN) - target_link_options(obj_decoder PRIVATE - ${MUJOCO_MACOS_LINK_OPTIONS} - ${EXTRA_LINK_OPTIONS} - ) - - install( - TARGETS obj_decoder - LIBRARY DESTINATION "${CMAKE_INSTALL_BINDIR}/mujoco_plugin" - ) -endif() +target_link_libraries(mujoco PRIVATE tinyobjloader) diff --git a/plugin/stl_decoder/CMakeLists.txt b/plugin/stl_decoder/CMakeLists.txt index 1d383632b0..50eef18d98 100644 --- a/plugin/stl_decoder/CMakeLists.txt +++ b/plugin/stl_decoder/CMakeLists.txt @@ -12,43 +12,6 @@ # See the License for the specific language governing permissions and # limitations under the License. -if(EMSCRIPTEN) - add_library(stl_decoder OBJECT stl_decoder.cc) -else() - set(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE) - set(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_LIBDIR}") - - add_library(stl_decoder SHARED stl_decoder.cc) -endif() - -target_include_directories(stl_decoder PRIVATE - ${CMAKE_CURRENT_SOURCE_DIR}/../.. - ${CMAKE_CURRENT_SOURCE_DIR}/../../include +target_sources(mujoco PRIVATE + stl_decoder.cc ) - -if(EMSCRIPTEN) - target_link_libraries(stl_decoder PRIVATE) -else() - target_link_libraries(stl_decoder PRIVATE - mujoco - ) -endif() - -target_compile_options(stl_decoder PRIVATE - ${AVX_COMPILE_OPTIONS} - ${MUJOCO_MACOS_COMPILE_OPTIONS} - ${EXTRA_COMPILE_OPTIONS} - ${MUJOCO_CXX_FLAGS} -) - -if(NOT EMSCRIPTEN) - target_link_options(stl_decoder PRIVATE - ${MUJOCO_MACOS_LINK_OPTIONS} - ${EXTRA_LINK_OPTIONS} - ) - - install( - TARGETS stl_decoder - LIBRARY DESTINATION "${CMAKE_INSTALL_BINDIR}/mujoco_plugin" - ) -endif() diff --git a/sample/testspeed.cc b/sample/testspeed.cc index 544edfc613..f14e657212 100644 --- a/sample/testspeed.cc +++ b/sample/testspeed.cc @@ -187,12 +187,6 @@ int main(int argc, char** argv) { nthread = mjMAX(1, mjMIN(maxthread, nthread)); npoolthread = mjMAX(1, mjMIN(maxthread, npoolthread)); - // load plugins from MUJOCO_PLUGIN_DIR if set - const char* plugin_dir = std::getenv("MUJOCO_PLUGIN_DIR"); - if (plugin_dir) { - mj_loadAllPluginLibraries(plugin_dir, nullptr); - } - // get filename, determine file type std::string filename(argv[1]); bool binary = (filename.find(".mjb") != std::string::npos); // NOLINT diff --git a/test/user/CMakeLists.txt b/test/user/CMakeLists.txt index 7cbc667f2c..912a26c0d4 100644 --- a/test/user/CMakeLists.txt +++ b/test/user/CMakeLists.txt @@ -14,9 +14,6 @@ mujoco_test( user_model_test - PROPERTIES - ENVIRONMENT - "MUJOCO_PLUGIN_DIR=$" ADDITIONAL_LINK_LIBRARIES absl::str_format ) @@ -31,16 +28,10 @@ mujoco_test( mujoco_test( user_flex_test - PROPERTIES - ENVIRONMENT - "MUJOCO_PLUGIN_DIR=$" ) mujoco_test( user_mesh_test - PROPERTIES - ENVIRONMENT - "MUJOCO_PLUGIN_DIR=$" ADDITIONAL_LINK_LIBRARIES absl::str_format ) diff --git a/test/xml/CMakeLists.txt b/test/xml/CMakeLists.txt index 63348c625b..d4cefdb1b3 100644 --- a/test/xml/CMakeLists.txt +++ b/test/xml/CMakeLists.txt @@ -16,9 +16,6 @@ mujoco_test(xml_api_test) mujoco_test( xml_native_reader_test - PROPERTIES - ENVIRONMENT - "MUJOCO_PLUGIN_DIR=$" ) mujoco_test(xml_utils_test) diff --git a/wasm/CMakeLists.txt b/wasm/CMakeLists.txt index 909401d1e8..0800483955 100644 --- a/wasm/CMakeLists.txt +++ b/wasm/CMakeLists.txt @@ -67,6 +67,11 @@ set_target_properties(mujoco_wasm PROPERTIES OUTPUT_NAME "mujoco" ) -target_link_libraries(mujoco_wasm ccd lodepng mujoco tinyxml2 qhullstatic_r obj_decoder stl_decoder) +# Link the mujoco library as a whole archive to avoid losing plugin +# registration such as obj_decoder and stl_decoder. +target_link_libraries(mujoco_wasm PRIVATE + -Wl,--whole-archive mujoco -Wl,--no-whole-archive + ccd lodepng tinyxml2 qhullstatic_r +) install(TARGETS mujoco_wasm DESTINATION ${DIVISIBLE_INSTALL_BIN_DIR}) diff --git a/wasm/tests/CMakeLists.txt b/wasm/tests/CMakeLists.txt index 0a21ec31c8..f6d7428986 100644 --- a/wasm/tests/CMakeLists.txt +++ b/wasm/tests/CMakeLists.txt @@ -53,6 +53,11 @@ add_executable(mujoco_wasm_benchmark ${MUJOCO_WASM_FILES}) set_target_properties(mujoco_wasm_benchmark PROPERTIES LINK_FLAGS "${EMCC_LINKER_FLAGS_STR}") -target_link_libraries(mujoco_wasm_benchmark ccd lodepng mujoco tinyxml2 qhullstatic_r obj_decoder stl_decoder) +# Link the mujoco library as a whole archive to avoid losing plugin +# registration such as obj_decoder and stl_decoder. +target_link_libraries(mujoco_wasm_benchmark PRIVATE + -Wl,--whole-archive mujoco -Wl,--no-whole-archive + ccd lodepng tinyxml2 qhullstatic_r +) install(TARGETS mujoco_wasm_benchmark DESTINATION ${DIVISIBLE_INSTALL_BIN_DIR}) From e971baaab60562c16d9d5e641eb1aca2d30d813f Mon Sep 17 00:00:00 2001 From: Haroon Qureshi Date: Tue, 31 Mar 2026 03:36:23 -0700 Subject: [PATCH 07/20] Use mjrf functions from within other mjrf functions. PiperOrigin-RevId: 892234323 Change-Id: I70ff01121764b552da84bdcc9b01527ae138dfea --- src/experimental/filament/render_context_filament.cc | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/experimental/filament/render_context_filament.cc b/src/experimental/filament/render_context_filament.cc index 2e00bc7966..d49069f534 100644 --- a/src/experimental/filament/render_context_filament.cc +++ b/src/experimental/filament/render_context_filament.cc @@ -58,7 +58,7 @@ void mjrf_defaultContext(mjrContext* con) { } void mjrf_makeContext(const mjModel* m, mjrContext* con, int fontscale) { - mjr_freeContext(con); + mjrf_freeContext(con); mjrFilamentConfig cfg; mjrf_defaultFilamentConfig(&cfg); cfg.width = m->vis.global.offwidth; @@ -72,7 +72,7 @@ void mjrf_freeContext(mjrContext* con) { delete g_filament_context; g_filament_context = nullptr; } - mjr_defaultContext(con); + mjrf_defaultContext(con); } void mjrf_render(mjrRect viewport, mjvScene* scn, const mjrContext* con) { From e1753ca58534a434eae34cbdb5a9e7d8a1baef23 Mon Sep 17 00:00:00 2001 From: Michael Moss Date: Tue, 31 Mar 2026 03:54:25 -0700 Subject: [PATCH 08/20] Workaround for TypeScript `'outFile' is deprecated` errors. PiperOrigin-RevId: 892241799 Change-Id: Ibe028d453f35f5e03bdf66418bc4b45c20e807d3 --- .github/workflows/build_steps.sh | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/.github/workflows/build_steps.sh b/.github/workflows/build_steps.sh index 08423311d8..4c55e5d431 100755 --- a/.github/workflows/build_steps.sh +++ b/.github/workflows/build_steps.sh @@ -62,6 +62,12 @@ setup_emsdk() { git clone https://github.com/emscripten-core/emsdk.git ./emsdk/emsdk install 4.0.10 ./emsdk/emsdk activate 4.0.10 + # Force installing emscripten's typescript dependencies. This is a + # workaround for the github update to a newer typescript, which gives an + # error on the deprecated `--outFile` flag. + pushd emsdk/upstream/emscripten + npm i + popd } From 93d7f7ffe5bffe0ff4a97beae754e8faa67ee35b Mon Sep 17 00:00:00 2001 From: Haroon Qureshi Date: Tue, 31 Mar 2026 04:16:08 -0700 Subject: [PATCH 09/20] Factor out mjModel-specific objects from ObjectManager. All objects that are specific to the mjModel (meshes, textures, etc.) are now managed by a ModelObjects class which is owned by the SceneView and not the FilamentContext. PiperOrigin-RevId: 892250776 Change-Id: Iddad66fd3ab1a60c4becdcb5d0c935ed9ea8ad90 --- src/experimental/filament/CMakeLists.txt | 2 + .../filament/filament/drawable.cc | 92 +++--- src/experimental/filament/filament/drawable.h | 7 +- .../filament/filament/filament_context.cc | 24 +- .../filament/filament/filament_context.h | 2 +- .../filament/filament/material.cc | 2 +- src/experimental/filament/filament/material.h | 4 - .../filament/filament/model_objects.cc | 258 ++++++++++++++++ .../filament/filament/model_objects.h | 100 +++++++ .../filament/filament/object_manager.cc | 276 ++---------------- .../filament/filament/object_manager.h | 81 +---- .../filament/filament/scene_view.cc | 141 +++++---- .../filament/filament/scene_view.h | 10 +- 13 files changed, 560 insertions(+), 439 deletions(-) create mode 100644 src/experimental/filament/filament/model_objects.cc create mode 100644 src/experimental/filament/filament/model_objects.h diff --git a/src/experimental/filament/CMakeLists.txt b/src/experimental/filament/CMakeLists.txt index 5c9242aa43..2a0c5c8fa7 100644 --- a/src/experimental/filament/CMakeLists.txt +++ b/src/experimental/filament/CMakeLists.txt @@ -47,6 +47,8 @@ target_sources(${MUJOCO_FILAMENT_TARGET_NAME} filament/material.h filament/math_util.cc filament/math_util.h + filament/model_objects.cc + filament/model_objects.h filament/model_util.cc filament/model_util.h filament/object_manager.cc diff --git a/src/experimental/filament/filament/drawable.cc b/src/experimental/filament/filament/drawable.cc index 8dd575bba6..30f1b9f00c 100644 --- a/src/experimental/filament/filament/drawable.cc +++ b/src/experimental/filament/filament/drawable.cc @@ -35,6 +35,7 @@ #include "experimental/filament/filament/geom_util.h" #include "experimental/filament/filament/material.h" #include "experimental/filament/filament/math_util.h" +#include "experimental/filament/filament/model_objects.h" #include "experimental/filament/filament/object_manager.h" namespace mujoco { @@ -85,8 +86,11 @@ static bool IsBehind(const mjtNum* headpos, const float* pos, const float* mat) (headpos[2] - pos[2]) * mat[8] < 0.0f); } -Drawable::Drawable(ObjectManager* object_mgr, const mjvGeom& geom) - : material_(object_mgr), renderables_(object_mgr->GetEngine()) { +Drawable::Drawable(ObjectManager* object_mgr, ModelObjects* model_objects, + const mjvGeom& geom) + : material_(object_mgr), + model_objs_(model_objects), + renderables_(object_mgr->GetEngine()) { if (geom.category == mjCAT_DECOR) { renderables_.SetCastShadows(false); renderables_.SetReceiveShadows(false); @@ -100,53 +104,53 @@ Drawable::Drawable(ObjectManager* object_mgr, const mjvGeom& geom) AddHeightField(geom.dataid); break; case mjGEOM_PLANE: - AddShape(ObjectManager::kPlane); + AddShape(ModelObjects::kPlane); break; case mjGEOM_SPHERE: - AddShape(ObjectManager::kSphere); + AddShape(ModelObjects::kSphere); break; case mjGEOM_ELLIPSOID: - AddShape(ObjectManager::kSphere); + AddShape(ModelObjects::kSphere); break; case mjGEOM_BOX: - AddShape(ObjectManager::kBox); + AddShape(ModelObjects::kBox); break; case mjGEOM_CAPSULE: - AddShape(ObjectManager::kTube); - AddShape(ObjectManager::kDome); - AddShape(ObjectManager::kDome); + AddShape(ModelObjects::kTube); + AddShape(ModelObjects::kDome); + AddShape(ModelObjects::kDome); break; case mjGEOM_CYLINDER: - AddShape(ObjectManager::kTube); - AddShape(ObjectManager::kDisk); - AddShape(ObjectManager::kDisk); + AddShape(ModelObjects::kTube); + AddShape(ModelObjects::kDisk); + AddShape(ModelObjects::kDisk); break; case mjGEOM_ARROW: - AddShape(ObjectManager::kTube); - AddShape(ObjectManager::kCone); - AddShape(ObjectManager::kDisk); + AddShape(ModelObjects::kTube); + AddShape(ModelObjects::kCone); + AddShape(ModelObjects::kDisk); break; case mjGEOM_ARROW1: - AddShape(ObjectManager::kTube); - AddShape(ObjectManager::kCone); - AddShape(ObjectManager::kDisk); - AddShape(ObjectManager::kDisk); + AddShape(ModelObjects::kTube); + AddShape(ModelObjects::kCone); + AddShape(ModelObjects::kDisk); + AddShape(ModelObjects::kDisk); break; case mjGEOM_ARROW2: - AddShape(ObjectManager::kTube); - AddShape(ObjectManager::kCone); - AddShape(ObjectManager::kCone); - AddShape(ObjectManager::kDisk); - AddShape(ObjectManager::kDisk); + AddShape(ModelObjects::kTube); + AddShape(ModelObjects::kCone); + AddShape(ModelObjects::kCone); + AddShape(ModelObjects::kDisk); + AddShape(ModelObjects::kDisk); break; case mjGEOM_LINE: - AddShape(ObjectManager::kLine); + AddShape(ModelObjects::kLine); break; case mjGEOM_LINEBOX: - AddShape(ObjectManager::kLineBox); + AddShape(ModelObjects::kLineBox); break; case mjGEOM_TRIANGLE: - AddShape(ObjectManager::kTriangle); + AddShape(ModelObjects::kTriangle); break; case mjGEOM_FLEX: case mjGEOM_SKIN: @@ -187,8 +191,7 @@ void Drawable::Update(const mjModel* model, const mjvScene* scene, } void Drawable::AddMesh(int data_id) { - ObjectManager* object_mgr = material_.GetObjectManager(); - const FilamentBuffers* buffers = object_mgr->GetMeshBuffer(data_id); + const FilamentBuffers* buffers = model_objs_->GetMeshBuffer(data_id); if (buffers == nullptr) { mju_error("Unknown mesh %d", data_id); } @@ -196,17 +199,15 @@ void Drawable::AddMesh(int data_id) { } void Drawable::AddHeightField(int hfield_id) { - ObjectManager* object_mgr = material_.GetObjectManager(); - const FilamentBuffers* buffers = object_mgr->GetHeightFieldBuffer(hfield_id); + const FilamentBuffers* buffers = model_objs_->GetHeightFieldBuffer(hfield_id); if (buffers == nullptr) { mju_error("Unknown height field %d", hfield_id); } renderables_.Append(*buffers); } -void Drawable::AddShape(ObjectManager::ShapeType shape_type) { - ObjectManager* object_mgr = material_.GetObjectManager(); - const FilamentBuffers* buffers = object_mgr->GetShapeBuffer(shape_type); +void Drawable::AddShape(ModelObjects::ShapeType shape_type) { + const FilamentBuffers* buffers = model_objs_->GetShapeBuffer(shape_type); if (buffers == nullptr) { mju_error("Unknown shape %d", shape_type); } @@ -352,8 +353,7 @@ void Drawable::SetTransform(const mjvGeom& geom) { void Drawable::UpdateMaterial(const mjvGeom& geom, bool use_segid_color, bool enable_reflection, const mjtNum* headpos) { - ObjectManager* object_mgr = material_.GetObjectManager(); - const mjModel* model = object_mgr->GetModel(); + const mjModel* model = model_objs_->GetModel(); float4 color = ReadFloat4(geom.rgba); if (geom.type == mjGEOM_PLANE) { @@ -370,15 +370,15 @@ void Drawable::UpdateMaterial(const mjvGeom& geom, bool use_segid_color, Material::Textures textures; if (geom.matid >= 0) { - textures.color = object_mgr->GetTexture(geom.matid, mjTEXROLE_RGB); - textures.normal = object_mgr->GetTexture(geom.matid, mjTEXROLE_NORMAL); - textures.emissive = object_mgr->GetTexture(geom.matid, mjTEXROLE_EMISSIVE); - textures.orm = object_mgr->GetTexture(geom.matid, mjTEXROLE_ORM); - textures.metallic = object_mgr->GetTexture(geom.matid, mjTEXROLE_METALLIC); + textures.color = model_objs_->GetTexture(geom.matid, mjTEXROLE_RGB); + textures.normal = model_objs_->GetTexture(geom.matid, mjTEXROLE_NORMAL); + textures.emissive = model_objs_->GetTexture(geom.matid, mjTEXROLE_EMISSIVE); + textures.orm = model_objs_->GetTexture(geom.matid, mjTEXROLE_ORM); + textures.metallic = model_objs_->GetTexture(geom.matid, mjTEXROLE_METALLIC); textures.roughness = - object_mgr->GetTexture(geom.matid, mjTEXROLE_ROUGHNESS); + model_objs_->GetTexture(geom.matid, mjTEXROLE_ROUGHNESS); textures.occlusion = - object_mgr->GetTexture(geom.matid, mjTEXROLE_OCCLUSION); + model_objs_->GetTexture(geom.matid, mjTEXROLE_OCCLUSION); material_.UpdateTextures(textures); } @@ -548,9 +548,9 @@ void Drawable::UpdateMaterial(const mjvGeom& geom, bool use_segid_color, } // Apply material multipliers from the model. - params.emissive *= object_mgr->GetEmissiveMultiplier(); - params.specular *= object_mgr->GetSpecularMultiplier(); - params.glossiness *= object_mgr->GetShininessMultiplier(); + params.emissive *= model_objs_->GetEmissiveMultiplier(); + params.specular *= model_objs_->GetSpecularMultiplier(); + params.glossiness *= model_objs_->GetShininessMultiplier(); material_.UpdateParams(params); } diff --git a/src/experimental/filament/filament/drawable.h b/src/experimental/filament/filament/drawable.h index dc1f95d040..19002de6c6 100644 --- a/src/experimental/filament/filament/drawable.h +++ b/src/experimental/filament/filament/drawable.h @@ -23,6 +23,7 @@ #include #include #include "experimental/filament/filament/material.h" +#include "experimental/filament/filament/model_objects.h" #include "experimental/filament/filament/object_manager.h" #include "experimental/filament/filament/renderables.h" @@ -31,7 +32,8 @@ namespace mujoco { // Manages the filament Entities and MaterialInstances for a single mjvGeom. class Drawable { public: - Drawable(ObjectManager* object_mgr, const mjvGeom& geom); + Drawable(ObjectManager* object_mgr, ModelObjects* model_objects, + const mjvGeom& geom); ~Drawable() noexcept = default; Drawable(const Drawable&) = delete; @@ -71,7 +73,7 @@ class Drawable { private: void AddMesh(int data_id); void AddHeightField(int hfield_id); - void AddShape(ObjectManager::ShapeType shape_type); + void AddShape(ModelObjects::ShapeType shape_type); // Updates the transform of the drawable for rendering. void SetTransform(const mjvGeom& geom); @@ -81,6 +83,7 @@ class Drawable { bool enable_reflection, const mjtNum* headpos); Material material_; + ModelObjects* model_objs_ = nullptr; Renderables renderables_; bool reflective_ = false; filament::math::mat4 transform_; diff --git a/src/experimental/filament/filament/filament_context.cc b/src/experimental/filament/filament/filament_context.cc index 0fa4b14d5d..d783cefaa8 100644 --- a/src/experimental/filament/filament/filament_context.cc +++ b/src/experimental/filament/filament/filament_context.cc @@ -41,10 +41,10 @@ #include "experimental/filament/filament/filament_platform_factory.h" #include "experimental/filament/filament/gui_view.h" #include "experimental/filament/filament/imgui_editor.h" -#include "experimental/filament/filament/object_manager.h" #include "experimental/filament/filament/model_util.h" -#include "experimental/filament/filament/scene_view.h" +#include "experimental/filament/filament/object_manager.h" #include "experimental/filament/filament/render_target_util.h" +#include "experimental/filament/filament/scene_view.h" #include "experimental/filament/render_context_filament.h" namespace mujoco { @@ -72,6 +72,8 @@ FilamentContext::FilamentContext(const mjrFilamentConfig* config) } #endif offscreen_swap_chain_ = engine_->createSwapChain(config_.width, config_.height); + + object_manager_ = std::make_unique(engine_); } FilamentContext::~FilamentContext() { @@ -86,8 +88,7 @@ FilamentContext::~FilamentContext() { } void FilamentContext::Init(const mjModel* model) { - object_manager_ = std::make_unique(model, engine_); - scene_view_ = std::make_unique(engine_, object_manager_.get()); + scene_view_ = std::make_unique(object_manager_.get(), model); gui_view_ = std::make_unique( engine_, object_manager_->GetMaterial(ObjectManager::kUnlitUi)); @@ -270,15 +271,24 @@ void FilamentContext::ReadPixels(mjrRect viewport, unsigned char* rgb, } void FilamentContext::UploadMesh(const mjModel* model, int id) { - object_manager_->UploadMesh(model, id); + if (!scene_view_) { + mju_error("SceneView is not initialized."); + } + scene_view_->UploadMesh(model, id); } void FilamentContext::UploadTexture(const mjModel* model, int id) { - object_manager_->UploadTexture(model, id); + if (!scene_view_) { + mju_error("SceneView is not initialized."); + } + scene_view_->UploadTexture(model, id); } void FilamentContext::UploadHeightField(const mjModel* model, int id) { - object_manager_->UploadHeightField(model, id); + if (!scene_view_) { + mju_error("SceneView is not initialized."); + } + scene_view_->UploadHeightField(model, id); } uintptr_t FilamentContext::UploadGuiImage(uintptr_t tex_id, diff --git a/src/experimental/filament/filament/filament_context.h b/src/experimental/filament/filament/filament_context.h index ec0a724347..7e2e2a9aba 100644 --- a/src/experimental/filament/filament/filament_context.h +++ b/src/experimental/filament/filament/filament_context.h @@ -26,8 +26,8 @@ #include #include "experimental/filament/filament/gui_view.h" #include "experimental/filament/filament/object_manager.h" -#include "experimental/filament/filament/scene_view.h" #include "experimental/filament/filament/render_target_util.h" +#include "experimental/filament/filament/scene_view.h" #include "experimental/filament/render_context_filament.h" namespace mujoco { diff --git a/src/experimental/filament/filament/material.cc b/src/experimental/filament/filament/material.cc index 1557e9e55c..08c167a251 100644 --- a/src/experimental/filament/filament/material.cc +++ b/src/experimental/filament/filament/material.cc @@ -26,7 +26,7 @@ namespace mujoco { Material::Material(ObjectManager* object_mgr) : object_mgr_(object_mgr) { instances_[kDepth] = - object_mgr->GetMaterial(ObjectManager::kUnlitDepth)->createInstance(); + object_mgr_->GetMaterial(ObjectManager::kUnlitDepth)->createInstance(); instances_[kSegmentation] = object_mgr_->GetMaterial(ObjectManager::kUnlitSegmentation) ->createInstance(); diff --git a/src/experimental/filament/filament/material.h b/src/experimental/filament/filament/material.h index 22452fb611..51ccac7126 100644 --- a/src/experimental/filament/filament/material.h +++ b/src/experimental/filament/filament/material.h @@ -89,10 +89,6 @@ class Material { return instances_[mode]; } - // Returns the ObjectManager owning the Materials which are used to create - // the MaterialInstances. - ObjectManager* GetObjectManager() { return object_mgr_; } - private: // Updates the material instances based on the currently set parameters and // textures. diff --git a/src/experimental/filament/filament/model_objects.cc b/src/experimental/filament/filament/model_objects.cc new file mode 100644 index 0000000000..ac3f4ca213 --- /dev/null +++ b/src/experimental/filament/filament/model_objects.cc @@ -0,0 +1,258 @@ +// Copyright 2026 DeepMind Technologies Limited +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "experimental/filament/filament/model_objects.h" + +#include +#include +#include + +#include +#include +#include +#include +#include +#include "experimental/filament/filament/buffer_util.h" +#include "experimental/filament/filament/builtins.h" +#include "experimental/filament/filament/model_util.h" +#include "experimental/filament/filament/texture_util.h" + + +namespace mujoco { + +ModelObjects::ModelObjects(const mjModel* model, filament::Engine* engine) + : model_(model), engine_(engine) { + const int nstack = model->vis.quality.numstacks; + const int nslice = model->vis.quality.numslices; + const int nquad = model->vis.quality.numquads; + shapes_[kLine] = CreateLine(engine_); + shapes_[kBox] = CreateBox(engine_, nquad); + shapes_[kLineBox] = CreateLineBox(engine_); + shapes_[kCone] = CreateCone(engine_, nstack, nslice); + shapes_[kDisk] = CreateDisk(engine_, nslice); + shapes_[kDome] = CreateDome(engine_, nstack / 2, nslice); + shapes_[kTube] = CreateTube(engine_, nstack, nslice); + shapes_[kPlane] = CreatePlane(engine_, nquad); + shapes_[kSphere] = CreateSphere(engine_, nstack, nslice); + shapes_[kTriangle] = CreateTriangle(engine_); + + for (int i = 0; i < model_->ntex; ++i) { + UploadTexture(model_, i); + } + for (int i = 0; i < model_->nmesh; ++i) { + UploadMesh(model_, i); + } + for (int i = 0; i < model_->nhfield; ++i) { + UploadHeightField(model_, i); + } + + specular_multiplier_ = ReadElement( + model_, "filament.phong.specular_multiplier", specular_multiplier_); + shininess_multiplier_ = ReadElement( + model_, "filament.phong.shininess_multiplier", shininess_multiplier_); + emissive_multiplier_ = ReadElement( + model_, "filament.phong.emissive_multiplier", emissive_multiplier_); +} + +ModelObjects::~ModelObjects() { + for (auto& iter : skyboxes_) { + engine_->destroy(iter); + } + for (auto& iter : indirect_lights_) { + engine_->destroy(iter); + } + for (auto& iter : meshes_) { + engine_->destroy(iter.second.vertex_buffer); + engine_->destroy(iter.second.index_buffer); + } + for (auto& iter : shapes_) { + engine_->destroy(iter.vertex_buffer); + engine_->destroy(iter.index_buffer); + } + for (auto& iter : textures_) { + engine_->destroy(iter.second); + } +} + +void ModelObjects::UploadMesh(const mjModel* model, int id) { + if (model != model_) { + mju_error("Model mismatch."); + } + if (id < 0 || id >= model->nmesh) { + mju_error("Invalid mesh index %d", id); + } + + if (auto iter = meshes_.find(id); iter != meshes_.end()) { + engine_->destroy(iter->second.vertex_buffer); + engine_->destroy(iter->second.index_buffer); + } + if (auto iter = convex_hulls_.find(id); iter != convex_hulls_.end()) { + engine_->destroy(iter->second.vertex_buffer); + engine_->destroy(iter->second.index_buffer); + } + + FilamentBuffers& buffers = meshes_[id]; + buffers.vertex_buffer = + CreateVertexBuffer(engine_, model, id, MeshType::kNormal); + buffers.index_buffer = + CreateIndexBuffer(engine_, model, id, MeshType::kNormal); + + if (model->mesh_graphadr[id] >= 0) { + FilamentBuffers& hull_buffers = convex_hulls_[id]; + hull_buffers.vertex_buffer = + CreateVertexBuffer(engine_, model, id, MeshType::kConvexHull); + hull_buffers.index_buffer = + CreateIndexBuffer(engine_, model, id, MeshType::kConvexHull); + } +} + +void ModelObjects::UploadTexture(const mjModel* model, int id) { + if (model != model_) { + mju_error("Model mismatch."); + } + if (id < 0 || id >= model->ntex) { + mju_error("Invalid texture index: %d", id); + } + + if (auto iter = textures_.find(id); iter != textures_.end()) { + engine_->destroy(iter->second); + } + + const int texture_type = model->tex_type[id]; + if (model->tex_height[id] == 1) { + const mjtByte* bytes = model->tex_data + model->tex_adr[id]; + const int num_bytes = model->tex_width[id]; + textures_[id] = + CreateKtxTexture(engine_, bytes, num_bytes, spherical_harmonics_[id]); + } else if (texture_type == mjTEXTURE_2D) { + textures_[id] = CreateTexture(engine_, model, id, TextureType::kNormal2d); + } else if (texture_type == mjTEXTURE_CUBE) { + textures_[id] = CreateTexture(engine_, model, id, TextureType::kCube); + } else if (texture_type == mjTEXTURE_SKYBOX) { + textures_[id] = CreateTexture(engine_, model, id, TextureType::kCube); + } else { + mju_error("Unsupported: Texture type: %d", texture_type); + } +} + +void ModelObjects::UploadHeightField(const mjModel* model, int id) { + if (model != model_) { + mju_error("Model mismatch."); + } + if (id < 0 || id >= model->nhfield) { + mju_error("Invalid height field index %d", id); + } + + if (auto iter = height_fields_.find(id); iter != height_fields_.end()) { + engine_->destroy(iter->second.vertex_buffer); + engine_->destroy(iter->second.index_buffer); + } + + FilamentBuffers& buffers = height_fields_[id]; + buffers.vertex_buffer = + CreateVertexBuffer(engine_, model, id, MeshType::kHeightField); + buffers.index_buffer = + CreateIndexBuffer(engine_, model, id, MeshType::kHeightField); +} + +const FilamentBuffers* ModelObjects::GetMeshBuffer(int data_id) const { + // As defined by mjv_updateScene: + // original mesh: mesh_id * 2 + // convex hull: (mesh_id * 2) + 1 + const int mesh_id = data_id / 2; + if (data_id % 2 == 0) { + auto it = meshes_.find(mesh_id); + return it != meshes_.end() ? &it->second : nullptr; + } else { + auto it = convex_hulls_.find(mesh_id); + return it != convex_hulls_.end() ? &it->second : nullptr; + } +} + +const FilamentBuffers* ModelObjects::GetHeightFieldBuffer( + int hfield_id) const { + auto it = height_fields_.find(hfield_id); + return it != height_fields_.end() ? &it->second : nullptr; +} + +const FilamentBuffers* ModelObjects::GetShapeBuffer(ShapeType shape) const { + if (shape < 0 || shape >= kNumShapes) { + mju_error("Invalid shape type: %d", shape); + } + return &shapes_[shape]; +} + +const filament::Texture* ModelObjects::GetTexture(int tex_id) const { + auto it = textures_.find(tex_id); + return it != textures_.end() ? it->second : nullptr; +} + +const filament::Texture* ModelObjects::GetTexture(int mat_id, int role) const { + if (mat_id < 0 || mat_id >= model_->nmat || role < 0 || role >= mjNTEXROLE) { + return nullptr; + } + const int tex_id = model_->mat_texid[mat_id * mjNTEXROLE + role]; + return GetTexture(tex_id); +} + +filament::IndirectLight* ModelObjects::CreateIndirectLight(int tex_id, + float intensity) { + filament::Texture* texture = nullptr; + auto texture_iter = textures_.find(tex_id); + if (texture_iter != textures_.end()) { + texture = texture_iter->second; + } + + SphericalHarmonics* spherical_harmonics = nullptr; + auto sh_iter = spherical_harmonics_.find(tex_id); + if (sh_iter != spherical_harmonics_.end()) { + spherical_harmonics = &sh_iter->second; + } + + filament::IndirectLight::Builder builder; + builder.reflections(texture); + if (spherical_harmonics != nullptr) { + builder.irradiance(3, *spherical_harmonics); + } + builder.intensity(intensity); + // Rotate the light to match mujoco's Z-up convention. + builder.rotation(filament::math::mat3f::rotation( + filament::math::f::PI / 2, filament::math::float3{1, 0, 0})); + filament::IndirectLight* indirect_light = builder.build(*engine_); + indirect_lights_.push_back(indirect_light); + return indirect_light; +} + +filament::Skybox* ModelObjects::CreateSkybox() { + filament::Texture* skybox_texture = nullptr; + for (auto& iter : textures_) { + const int texture_type = model_->tex_type[iter.first]; + if (texture_type == mjTEXTURE_SKYBOX) { + skybox_texture = iter.second; + break; + } + } + + if (skybox_texture == nullptr) { + return nullptr; + } + + filament::Skybox::Builder builder; + builder.environment(skybox_texture); + filament::Skybox* skybox = builder.build(*engine_); + skyboxes_.push_back(skybox); + return skybox; +} + +} // namespace mujoco diff --git a/src/experimental/filament/filament/model_objects.h b/src/experimental/filament/filament/model_objects.h new file mode 100644 index 0000000000..5de28f8ab3 --- /dev/null +++ b/src/experimental/filament/filament/model_objects.h @@ -0,0 +1,100 @@ +// Copyright 2026 DeepMind Technologies Limited +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_MODEL_OBJECTS_H_ +#define MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_MODEL_OBJECTS_H_ + +#include +#include +#include + +#include +#include +#include +#include +#include +#include "experimental/filament/filament/buffer_util.h" + +namespace mujoco { + +// Creates and owns various filament objects based on the data in a mjrContext. +class ModelObjects { + public: + ModelObjects(const mjModel* model, filament::Engine* engine); + ~ModelObjects(); + + enum ShapeType { + kLine, + kLineBox, + kPlane, + kTriangle, + kBox, + kSphere, + kCone, + kDisk, + kDome, + kTube, + kNumShapes, + }; + + void UploadMesh(const mjModel* model, int id); + + void UploadTexture(const mjModel* model, int id); + + void UploadHeightField(const mjModel* model, int id); + + // Returns the filament engine used by the ModelObjects to create filament + // objects. + filament::Engine* GetEngine() const { return engine_; } + + // Returns the cached instance of a filament object created from the mjModel. + const FilamentBuffers* GetShapeBuffer(ShapeType shape) const; + const FilamentBuffers* GetMeshBuffer(int data_id) const; + const FilamentBuffers* GetHeightFieldBuffer(int hfield_id) const; + const filament::Texture* GetTexture(int tex_id) const; + const filament::Texture* GetTexture(int mat_id, int role) const; + + filament::Skybox* CreateSkybox(); + filament::IndirectLight* CreateIndirectLight(int tex_id, float intensity); + + float GetSpecularMultiplier() const { return specular_multiplier_; } + float GetShininessMultiplier() const { return shininess_multiplier_; } + float GetEmissiveMultiplier() const { return emissive_multiplier_; } + + const mjModel* GetModel() const { return model_; } + + ModelObjects(const ModelObjects&) = delete; + ModelObjects& operator=(const ModelObjects&) = delete; + + private: + using SphericalHarmonics = filament::math::float3[9]; + + const mjModel* model_ = nullptr; + filament::Engine* engine_ = nullptr; + std::vector skyboxes_; + std::vector indirect_lights_; + std::array shapes_; + std::unordered_map meshes_; + std::unordered_map convex_hulls_; + std::unordered_map height_fields_; + std::unordered_map textures_; + std::unordered_map spherical_harmonics_; + float specular_multiplier_ = 0.2f; + float shininess_multiplier_ = 0.1f; + float emissive_multiplier_ = 0.3f; +}; + +} // namespace mujoco + +#endif // MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_MODEL_OBJECTS_H_ diff --git a/src/experimental/filament/filament/object_manager.cc b/src/experimental/filament/filament/object_manager.cc index 4aedb12034..4bf5a0cd02 100644 --- a/src/experimental/filament/filament/object_manager.cc +++ b/src/experimental/filament/filament/object_manager.cc @@ -14,12 +14,9 @@ #include "experimental/filament/filament/object_manager.h" -#include #include #include #include -#include -#include #include #include @@ -29,11 +26,7 @@ #include #include #include -#include "experimental/filament/filament/buffer_util.h" -#include "experimental/filament/filament/builtins.h" -#include "experimental/filament/filament/model_util.h" #include "experimental/filament/filament/texture_util.h" -#include "experimental/filament/render_context_filament.h" #include "user/user_resource.h" namespace mujoco { @@ -64,23 +57,8 @@ struct Asset { } // namespace -ObjectManager::ObjectManager(const mjModel* model, filament::Engine* engine) - : model_(model), engine_(engine) { - const int nquad = model->vis.quality.numquads; - const int nstack = model->vis.quality.numstacks; - const int nslice = model->vis.quality.numslices; - - shapes_[kLine] = CreateLine(engine_); - shapes_[kBox] = CreateBox(engine_, nquad); - shapes_[kLineBox] = CreateLineBox(engine_); - shapes_[kCone] = CreateCone(engine_, nstack, nslice); - shapes_[kDisk] = CreateDisk(engine_, nslice); - shapes_[kDome] = CreateDome(engine_, nstack / 2, nslice); - shapes_[kTube] = CreateTube(engine_, nstack, nslice); - shapes_[kPlane] = CreatePlane(engine_, nquad); - shapes_[kSphere] = CreateSphere(engine_, nstack, nslice); - shapes_[kTriangle] = CreateTriangle(engine_); - +ObjectManager::ObjectManager(filament::Engine* engine) + : engine_(engine) { auto LoadMaterial = [this](std::string_view filename) { Asset asset(filename); filament::Material::Builder material_builder; @@ -107,16 +85,6 @@ ObjectManager::ObjectManager(const mjModel* model, filament::Engine* engine) materials_[kUnlitDepth] = LoadMaterial("unlit_depth.filamat"); materials_[kUnlitUi] = LoadMaterial("unlit_ui.filamat"); - for (int i = 0; i < model_->ntex; ++i) { - UploadTexture(model_, i); - } - for (int i = 0; i < model_->nmesh; ++i) { - UploadMesh(model_, i); - } - for (int i = 0; i < model_->nhfield; ++i) { - UploadHeightField(model_, i); - } - static uint8_t black_rgb[3] = {0, 0, 0}; fallback_black_ = Create2dTexture(engine_, 1, 1, 3, black_rgb, false); static uint8_t white_rgb[3] = {255, 255, 255}; @@ -135,37 +103,19 @@ ObjectManager::ObjectManager(const mjModel* model, filament::Engine* engine) fallback_textures_[mjTEXROLE_EMISSIVE] = fallback_black_; fallback_textures_[mjTEXROLE_ORM] = fallback_orm_; - fallback_indirect_light_ = LoadFallbackIndirectLight("ibl.ktx", 1.0f); - - specular_multiplier_ = ReadElement( - model_, "filament.phong.specular_multiplier", specular_multiplier_); - shininess_multiplier_ = ReadElement( - model_, "filament.phong.shininess_multiplier", shininess_multiplier_); - emissive_multiplier_ = ReadElement( - model_, "filament.phong.emissive_multiplier", emissive_multiplier_); + LoadFallbackIndirectLight("ibl.ktx", 1.0f); } ObjectManager::~ObjectManager() { - for (auto& iter : skyboxes_) { - engine_->destroy(iter); + if (fallback_indirect_light_) { + engine_->destroy(fallback_indirect_light_); } - for (auto& iter : indirect_lights_) { - engine_->destroy(iter); + if (fallback_indirect_light_texture_) { + engine_->destroy(fallback_indirect_light_texture_); } for (auto& iter : materials_) { engine_->destroy(iter); } - for (auto& iter : meshes_) { - engine_->destroy(iter.second.vertex_buffer); - engine_->destroy(iter.second.index_buffer); - } - for (auto& iter : shapes_) { - engine_->destroy(iter.vertex_buffer); - engine_->destroy(iter.index_buffer); - } - for (auto& iter : textures_) { - engine_->destroy(iter.second); - } // fallback_textures_ maps to these textures. engine_->destroy(fallback_white_); engine_->destroy(fallback_black_); @@ -173,87 +123,6 @@ ObjectManager::~ObjectManager() { engine_->destroy(fallback_orm_); } -void ObjectManager::UploadMesh(const mjModel* model, int id) { - if (model != model_) { - mju_error("Model mismatch."); - } - if (id < 0 || id >= model->nmesh) { - mju_error("Invalid mesh index %d", id); - } - - if (auto iter = meshes_.find(id); iter != meshes_.end()) { - engine_->destroy(iter->second.vertex_buffer); - engine_->destroy(iter->second.index_buffer); - } - if (auto iter = convex_hulls_.find(id); iter != convex_hulls_.end()) { - engine_->destroy(iter->second.vertex_buffer); - engine_->destroy(iter->second.index_buffer); - } - - FilamentBuffers& buffers = meshes_[id]; - buffers.vertex_buffer = - CreateVertexBuffer(engine_, model, id, MeshType::kNormal); - buffers.index_buffer = - CreateIndexBuffer(engine_, model, id, MeshType::kNormal); - - if (model->mesh_graphadr[id] >= 0) { - FilamentBuffers& hull_buffers = convex_hulls_[id]; - hull_buffers.vertex_buffer = - CreateVertexBuffer(engine_, model, id, MeshType::kConvexHull); - hull_buffers.index_buffer = - CreateIndexBuffer(engine_, model, id, MeshType::kConvexHull); - } -} - -void ObjectManager::UploadTexture(const mjModel* model, int id) { - if (model != model_) { - mju_error("Model mismatch."); - } - if (id < 0 || id >= model->ntex) { - mju_error("Invalid texture index: %d", id); - } - - if (auto iter = textures_.find(id); iter != textures_.end()) { - engine_->destroy(iter->second); - } - - const int texture_type = model->tex_type[id]; - if (model->tex_height[id] == 1) { - const mjtByte* bytes = model->tex_data + model->tex_adr[id]; - const int num_bytes = model->tex_width[id]; - textures_[id] = - CreateKtxTexture(engine_, bytes, num_bytes, spherical_harmonics_[id]); - } else if (texture_type == mjTEXTURE_2D) { - textures_[id] = CreateTexture(engine_, model, id, TextureType::kNormal2d); - } else if (texture_type == mjTEXTURE_CUBE) { - textures_[id] = CreateTexture(engine_, model, id, TextureType::kCube); - } else if (texture_type == mjTEXTURE_SKYBOX) { - textures_[id] = CreateTexture(engine_, model, id, TextureType::kCube); - } else { - mju_error("Unsupported: Texture type: %d", texture_type); - } -} - -void ObjectManager::UploadHeightField(const mjModel* model, int id) { - if (model != model_) { - mju_error("Model mismatch."); - } - if (id < 0 || id >= model->nhfield) { - mju_error("Invalid height field index %d", id); - } - - if (auto iter = height_fields_.find(id); iter != height_fields_.end()) { - engine_->destroy(iter->second.vertex_buffer); - engine_->destroy(iter->second.index_buffer); - } - - FilamentBuffers& buffers = height_fields_[id]; - buffers.vertex_buffer = - CreateVertexBuffer(engine_, model, id, MeshType::kHeightField); - buffers.index_buffer = - CreateIndexBuffer(engine_, model, id, MeshType::kHeightField); -} - filament::Material* ObjectManager::GetMaterial(MaterialType type) const { if (type < 0 || type >= kNumMaterials) { mju_error("Invalid material type: %d", type); @@ -261,137 +130,50 @@ filament::Material* ObjectManager::GetMaterial(MaterialType type) const { return materials_[type]; } -const FilamentBuffers* ObjectManager::GetMeshBuffer(int data_id) const { - // As defined by mjv_updateScene: - // original mesh: mesh_id * 2 - // convex hull: (mesh_id * 2) + 1 - const int mesh_id = data_id / 2; - if (data_id % 2 == 0) { - auto it = meshes_.find(mesh_id); - return it != meshes_.end() ? &it->second : nullptr; - } else { - auto it = convex_hulls_.find(mesh_id); - return it != convex_hulls_.end() ? &it->second : nullptr; - } -} - -const FilamentBuffers* ObjectManager::GetHeightFieldBuffer( - int hfield_id) const { - auto it = height_fields_.find(hfield_id); - return it != height_fields_.end() ? &it->second : nullptr; -} - -const FilamentBuffers* ObjectManager::GetShapeBuffer(ShapeType shape) const { - if (shape < 0 || shape >= kNumShapes) { - mju_error("Invalid shape type: %d", shape); - } - return &shapes_[shape]; -} - -const filament::Texture* ObjectManager::GetTexture(int tex_id) const { - auto it = textures_.find(tex_id); - return it != textures_.end() ? it->second : nullptr; -} - -const filament::Texture* ObjectManager::GetTexture(int mat_id, int role) const { - if (mat_id < 0 || mat_id >= model_->nmat || role < 0 || role >= mjNTEXROLE) { - return nullptr; - } - const int tex_id = model_->mat_texid[mat_id * mjNTEXROLE + role]; - return GetTexture(tex_id); -} - -const filament::Texture* ObjectManager::GetTextureWithFallback(int mat_id, - int role) const { - if (auto texture = GetTexture(mat_id, role)) { - return texture; +const filament::Texture* ObjectManager::GetFallbackTexture( + mjtTextureRole role) const { + if (role < 0 || role >= mjNTEXROLE) { + mju_error("Invalid texture role: %d", role); } - return GetFallbackTexture(role); -} - -const filament::Texture* ObjectManager::GetFallbackTexture(int role) const { - auto iter = fallback_textures_.find(role); - if (iter != fallback_textures_.end()) { - return iter->second; - } - return nullptr; + return fallback_textures_[role]; } filament::IndirectLight* ObjectManager::GetFallbackIndirectLight() { return fallback_indirect_light_; } -filament::IndirectLight* ObjectManager::CreateIndirectLight(int tex_id, - float intensity) { - filament::Texture* texture = nullptr; - auto texture_iter = textures_.find(tex_id); - if (texture_iter != textures_.end()) { - texture = texture_iter->second; - } - - if (texture == nullptr) { - return nullptr; +void ObjectManager::LoadFallbackIndirectLight( + std::string_view filename, float intensity) { + if (fallback_indirect_light_texture_ != nullptr) { + engine_->destroy(fallback_indirect_light_texture_); + fallback_indirect_light_texture_ = nullptr; } - - SphericalHarmonics* spherical_harmonics = nullptr; - auto sh_iter = spherical_harmonics_.find(tex_id); - if (sh_iter != spherical_harmonics_.end()) { - spherical_harmonics = &sh_iter->second; + if (fallback_indirect_light_ != nullptr) { + engine_->destroy(fallback_indirect_light_); + fallback_indirect_light_ = nullptr; } - return CreateIndirectLight(texture, spherical_harmonics, intensity); -} - -filament::IndirectLight* ObjectManager::LoadFallbackIndirectLight( - std::string_view filename, float intensity) { Asset asset(filename); if (asset.size == 0) { - return nullptr; + return; } filament::math::float3 spherical_harmonics[9]; - filament::Texture* tex = + fallback_indirect_light_texture_ = CreateKtxTexture(engine_, reinterpret_cast(asset.payload), asset.size, spherical_harmonics); - return CreateIndirectLight(tex, &spherical_harmonics, intensity); -} + if (fallback_indirect_light_texture_ == nullptr) { + return; + } -filament::IndirectLight* ObjectManager::CreateIndirectLight( - filament::Texture* texture, SphericalHarmonics* spherical_harmonics, - float intensity) { + // Build the indirect light. filament::IndirectLight::Builder builder; - builder.reflections(texture); - if (spherical_harmonics != nullptr) { - builder.irradiance(3, *spherical_harmonics); - } + builder.reflections(fallback_indirect_light_texture_); + builder.irradiance(3, spherical_harmonics); builder.intensity(intensity); // Rotate the light to match mujoco's Z-up convention. builder.rotation(filament::math::mat3f::rotation( filament::math::f::PI / 2, filament::math::float3{1, 0, 0})); - filament::IndirectLight* indirect_light = builder.build(*engine_); - indirect_lights_.push_back(indirect_light); - return indirect_light; + fallback_indirect_light_ = builder.build(*engine_); } - -filament::Skybox* ObjectManager::CreateSkybox() { - filament::Texture* skybox_texture = nullptr; - for (auto& iter : textures_) { - const int texture_type = model_->tex_type[iter.first]; - if (texture_type == mjTEXTURE_SKYBOX) { - skybox_texture = iter.second; - break; - } - } - - if (skybox_texture == nullptr) { - return nullptr; - } - - filament::Skybox::Builder builder; - builder.environment(skybox_texture); - filament::Skybox* skybox = builder.build(*engine_); - skyboxes_.push_back(skybox); - return skybox; -} - } // namespace mujoco diff --git a/src/experimental/filament/filament/object_manager.h b/src/experimental/filament/filament/object_manager.h index 6fe51dccbe..37459b4d41 100644 --- a/src/experimental/filament/filament/object_manager.h +++ b/src/experimental/filament/filament/object_manager.h @@ -16,25 +16,19 @@ #define MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_OBJECT_MANAGER_H_ #include -#include #include -#include -#include #include #include #include -#include -#include -#include "experimental/filament/filament/buffer_util.h" -#include "experimental/filament/render_context_filament.h" +#include namespace mujoco { // Creates and owns various filament objects based on the data in a mjrContext. class ObjectManager { public: - ObjectManager(const mjModel* model, filament::Engine* engine); + ObjectManager(filament::Engine* engine); ~ObjectManager(); enum MaterialType { @@ -59,85 +53,34 @@ class ObjectManager { kNumMaterials, }; - enum ShapeType { - kLine, - kLineBox, - kPlane, - kTriangle, - kBox, - kSphere, - kCone, - kDisk, - kDome, - kTube, - kNumShapes, - }; - - using SphericalHarmonics = filament::math::float3[9]; - - void UploadMesh(const mjModel* model, int id); - - void UploadTexture(const mjModel* model, int id); - - void UploadHeightField(const mjModel* model, int id); - - // Returns the filament engine used by the ObjectManager to create filament - // objects. + // Returns the filament Engine that owns the assets. filament::Engine* GetEngine() const { return engine_; } + // Returns the Material of the given type. filament::Material* GetMaterial(MaterialType type) const; - // Returns the cached instance of a filament object created from the mjModel. - const FilamentBuffers* GetMeshBuffer(int data_id) const; - const FilamentBuffers* GetShapeBuffer(ShapeType shape) const; - const FilamentBuffers* GetHeightFieldBuffer(int hfield_id) const; - const filament::Texture* GetTexture(int tex_id) const; - const filament::Texture* GetTexture(int mat_id, int role) const; - const filament::Texture* GetTextureWithFallback(int mat_id, int role) const; - const filament::Texture* GetFallbackTexture(int role) const; - filament::IndirectLight* GetFallbackIndirectLight(); - - // Creates and returns a new instance of a filament object. The objects are - // owned by the ObjectManager and will be deleted in the destructor. - filament::Skybox* CreateSkybox(); - filament::IndirectLight* CreateIndirectLight( - filament::Texture* texture, SphericalHarmonics* spherical_harmonics, - float intensity); - filament::IndirectLight* CreateIndirectLight(int tex_id, float intensity); - filament::IndirectLight* LoadFallbackIndirectLight(std::string_view filename, - float intensity); + // Returns the fallback Texture with the given role. + const filament::Texture* GetFallbackTexture(mjtTextureRole role) const; - float GetSpecularMultiplier() const { return specular_multiplier_; } - float GetShininessMultiplier() const { return shininess_multiplier_; } - float GetEmissiveMultiplier() const { return emissive_multiplier_; } + // Returns the fallback IndirectLight. + filament::IndirectLight* GetFallbackIndirectLight(); - const mjModel* GetModel() const { return model_; } + // Loads an indirect light from a file, setting it to the fallback. + void LoadFallbackIndirectLight(std::string_view filename, float intensity); ObjectManager(const ObjectManager&) = delete; ObjectManager& operator=(const ObjectManager&) = delete; private: - const mjModel* model_ = nullptr; filament::Engine* engine_ = nullptr; - - std::array shapes_; std::array materials_; - std::vector skyboxes_; - std::vector indirect_lights_; - std::unordered_map meshes_; - std::unordered_map convex_hulls_; - std::unordered_map height_fields_; - std::unordered_map textures_; - std::unordered_map spherical_harmonics_; - std::unordered_map fallback_textures_; + std::array fallback_textures_; filament::Texture* fallback_white_ = nullptr; filament::Texture* fallback_black_ = nullptr; filament::Texture* fallback_normal_ = nullptr; filament::Texture* fallback_orm_ = nullptr; + filament::Texture* fallback_indirect_light_texture_ = nullptr; filament::IndirectLight* fallback_indirect_light_ = nullptr; - float specular_multiplier_ = 0.2f; - float shininess_multiplier_ = 0.1f; - float emissive_multiplier_ = 0.3f; }; } // namespace mujoco diff --git a/src/experimental/filament/filament/scene_view.cc b/src/experimental/filament/filament/scene_view.cc index cba553955c..aba4e0b8de 100644 --- a/src/experimental/filament/filament/scene_view.cc +++ b/src/experimental/filament/filament/scene_view.cc @@ -46,6 +46,7 @@ #include "experimental/filament/filament/gui_view.h" #include "experimental/filament/filament/light.h" #include "experimental/filament/filament/math_util.h" +#include "experimental/filament/filament/model_objects.h" #include "experimental/filament/filament/model_util.h" #include "experimental/filament/filament/object_manager.h" #include "experimental/filament/filament/render_target_util.h" @@ -113,37 +114,38 @@ static void SetupReflectionCamera(const mat4& surface_xform, reflection_camera->setCustomProjection(oblique, near, far); } -SceneView::SceneView(filament::Engine* engine, ObjectManager* object_mgr) - : object_mgr_(object_mgr), engine_(engine) { - scene_ = engine_->createScene(); - camera_ = engine_->createCamera(utils::EntityManager::get().create()); - reflect_camera_ = engine_->createCamera(utils::EntityManager::get().create()); +SceneView::SceneView(ObjectManager* object_mgr, const mjModel* model) + : object_mgr_(object_mgr) { + filament::Engine* engine = object_mgr_->GetEngine(); + model_objects_ = std::make_unique(model, engine); + + scene_ = engine->createScene(); + camera_ = engine->createCamera(utils::EntityManager::get().create()); + reflect_camera_ = engine->createCamera(utils::EntityManager::get().create()); for (auto& view : views_) { - view = engine_->createView(); + view = engine->createView(); view->setScene(scene_); view->setCamera(camera_); } - reflect_view_ = engine_->createView(); + reflect_view_ = engine->createView(); reflect_view_->setScene(scene_); reflect_view_->setCamera(reflect_camera_); reflect_view_->setShadowingEnabled(false); reflect_view_->setPostProcessingEnabled(false); - const mjModel* m = object_mgr_->GetModel(); - // Configure options for the normal view. auto& cg = color_grading_options_; - cg.exposure = ReadElement(m, "filament.out.exposure", cg.exposure); - cg.contrast = ReadElement(m, "filament.out.contrast", cg.contrast); - cg.vibrance = ReadElement(m, "filament.out.vibrance", cg.vibrance); - cg.saturation = ReadElement(m, "filament.out.saturation", cg.saturation); - cg.temperature = ReadElement(m, "filament.out.temperature", cg.temperature); - cg.tint = ReadElement(m, "filament.out.tint", cg.tint); + cg.exposure = ReadElement(model, "filament.out.exposure", cg.exposure); + cg.contrast = ReadElement(model, "filament.out.contrast", cg.contrast); + cg.vibrance = ReadElement(model, "filament.out.vibrance", cg.vibrance); + cg.saturation = ReadElement(model, "filament.out.saturation", cg.saturation); + cg.temperature = ReadElement(model, "filament.out.temperature", cg.temperature); + cg.tint = ReadElement(model, "filament.out.tint", cg.tint); auto tone_mapping = - ReadElement(m, "filament.out.tone_mapping"); + ReadElement(model, "filament.out.tone_mapping"); if (tone_mapping == "aces") { cg.tone_mapper = ToneMapperType::kACES; } else if (tone_mapping == "aces_legacy") { @@ -158,9 +160,9 @@ SceneView::SceneView(filament::Engine* engine, ObjectManager* object_mgr) SetColorGradingOptions(cg); auto ao = views_[kNormalIndex]->getAmbientOcclusionOptions(); - ao.enabled = ReadElement(m, "filament.ao.enabled", true); - ao.bentNormals = ReadElement(m, "filament.ao.bent_normals", false); - ao.ssct.enabled = ReadElement(m, "filament.ao.ssct", ao.ssct.enabled); + ao.enabled = ReadElement(model, "filament.ao.enabled", true); + ao.bentNormals = ReadElement(model, "filament.ao.bent_normals", false); + ao.ssct.enabled = ReadElement(model, "filament.ao.ssct", ao.ssct.enabled); ao.quality = filament::QualityLevel::ULTRA; ao.lowPassFilter = filament::QualityLevel::ULTRA; ao.upsampling = filament::QualityLevel::ULTRA; @@ -168,16 +170,16 @@ SceneView::SceneView(filament::Engine* engine, ObjectManager* object_mgr) views_[kNormalIndex]->setAmbientOcclusionOptions(ao); auto msaa = views_[kNormalIndex]->getMultiSampleAntiAliasingOptions(); - msaa.enabled = ReadElement(m, "filament.msaa.enabled", true); + msaa.enabled = ReadElement(model, "filament.msaa.enabled", true); views_[kNormalIndex]->setMultiSampleAntiAliasingOptions(msaa); default_shadow_map_size_ = ReadElement( - m, "filament.shadows.map_size", default_shadow_map_size_); + model, "filament.shadows.map_size", default_shadow_map_size_); default_vsm_blur_width_ = ReadElement( - m, "filament.shadows.vsm_blur_width", default_vsm_blur_width_); + model, "filament.shadows.vsm_blur_width", default_vsm_blur_width_); auto shadow_type = views_[kNormalIndex]->getShadowType(); - shadow_type = ReadElement(m, "filament.shadows.type", shadow_type); + shadow_type = ReadElement(model, "filament.shadows.type", shadow_type); views_[kNormalIndex]->setShadowType(shadow_type); // Disable post processing for the depth and segmentation views to preserve @@ -190,44 +192,44 @@ SceneView::SceneView(filament::Engine* engine, ObjectManager* object_mgr) auto& tm = engine->getTransformManager(); tm.create(fog); auto rotation_axis = ReadElement( - m, "filament.fog.rotation_axis", float3{-1, 0, 0}); + model, "filament.fog.rotation_axis", float3{-1, 0, 0}); tm.setTransform(tm.getInstance(fog), mat4::rotation(filament::math::f::PI / 2, rotation_axis)); auto fog_opts = views_[kNormalIndex]->getFogOptions(); - fog_opts.enabled = ReadElement(m, "filament.fog.enabled", fog_opts.enabled); - fog_opts.color = ReadElement(m, "filament.fog.color", fog_opts.color); + fog_opts.enabled = + ReadElement(model, "filament.fog.enabled", fog_opts.enabled); + fog_opts.color = ReadElement(model, "filament.fog.color", fog_opts.color); fog_opts.distance = ReadElement( - m, "filament.fog.distance", fog_opts.distance); + model, "filament.fog.distance", fog_opts.distance); fog_opts.density = ReadElement( - m, "filament.fog.density", fog_opts.density); + model, "filament.fog.density", fog_opts.density); fog_opts.cutOffDistance = ReadElement( - m, "filament.fog.cutOffDistance", fog_opts.cutOffDistance); + model, "filament.fog.cutOffDistance", fog_opts.cutOffDistance); fog_opts.maximumOpacity = ReadElement( - m, "filament.fog.maximumOpacity", fog_opts.maximumOpacity); - fog_opts.height = ReadElement(m, "filament.fog.height", fog_opts.height); + model, "filament.fog.maximumOpacity", fog_opts.maximumOpacity); + fog_opts.height = ReadElement(model, "filament.fog.height", fog_opts.height); fog_opts.heightFalloff = ReadElement( - m, "filament.fog.heightFalloff", fog_opts.heightFalloff); + model, "filament.fog.heightFalloff", fog_opts.heightFalloff); fog_opts.inScatteringStart = ReadElement( - m, "filament.fog.inScatteringStart", fog_opts.inScatteringStart); + model, "filament.fog.inScatteringStart", fog_opts.inScatteringStart); fog_opts.inScatteringSize = ReadElement( - m, "filament.fog.inScatteringSize", fog_opts.inScatteringSize); + model, "filament.fog.inScatteringSize", fog_opts.inScatteringSize); views_[kNormalIndex]->setFogOptions(fog_opts); fallback_head_light_intensity_ = - ReadElement(m, "filament.fallback.head_light_intensity", + ReadElement(model, "filament.fallback.head_light_intensity", fallback_head_light_intensity_); fallback_scene_light_intensity_ = - ReadElement(m, "filament.fallback.scene_light_intensity", + ReadElement(model, "filament.fallback.scene_light_intensity", fallback_scene_light_intensity_); fallback_environment_light_intensity_ = - ReadElement(m, "filament.fallback.environment_light_intensity", + ReadElement(model, "filament.fallback.environment_light_intensity", fallback_environment_light_intensity_); // Create an empty/black indirect light to ensure that the skybox is oriented // to respect mujoco's Z-up convention. - scene_->setIndirectLight( - object_mgr_->CreateIndirectLight(nullptr, nullptr, 100000)); + scene_->setIndirectLight(model_objects_->CreateIndirectLight(-1, 100000)); PrepareLights(); } @@ -237,15 +239,16 @@ SceneView::~SceneView() { drawables_.clear(); reflect_targets_.clear(); - engine_->destroyCameraComponent(reflect_camera_->getEntity()); - engine_->destroy(reflect_view_); + filament::Engine* engine = object_mgr_->GetEngine(); + engine->destroyCameraComponent(reflect_camera_->getEntity()); + engine->destroy(reflect_view_); - engine_->destroyCameraComponent(camera_->getEntity()); - engine_->destroy(views_[kNormalIndex]->getColorGrading()); + engine->destroyCameraComponent(camera_->getEntity()); + engine->destroy(views_[kNormalIndex]->getColorGrading()); for (auto& view : views_) { - engine_->destroy(view); + engine->destroy(view); } - engine_->destroy(scene_); + engine->destroy(scene_); } void SceneView::Render(filament::Renderer* renderer, DrawMode draw_mode, @@ -304,22 +307,23 @@ void SceneView::SetViewport(mjrRect viewport) { } void SceneView::SetColorGradingOptions(const ColorGradingOptions& opts) { + filament::Engine* engine = object_mgr_->GetEngine(); + auto tone_mapper = CreateToneMapper(opts.tone_mapper); auto color_grading = ToBuilder(color_grading_options_) .toneMapper(tone_mapper.get()) - .build(*engine_); + .build(*engine); views_[kNormalIndex]->setColorGrading(color_grading); - engine_->destroy(color_grading_); + engine->destroy(color_grading_); color_grading_ = color_grading; color_grading_options_ = opts; } void SceneView::SetEnvironmentLight(std::string_view filename, float intensity) { - auto* ibl = object_mgr_->LoadFallbackIndirectLight(filename, intensity); - if (ibl) { - scene_->setIndirectLight(ibl); - } + scene_->setIndirectLight(nullptr); + object_mgr_->LoadFallbackIndirectLight(filename, intensity); + scene_->setIndirectLight(object_mgr_->GetFallbackIndirectLight()); } void SceneView::SetFallbackEnvironmentLight(float intensity) { @@ -357,8 +361,9 @@ std::optional SceneView::ClipFromWorld(const float3& pos) const{ } void SceneView::PrepareLights() { - const mjModel* model = object_mgr_->GetModel(); - filament::Skybox* skybox = object_mgr_->CreateSkybox(); + filament::Engine* engine = object_mgr_->GetEngine(); + const mjModel* model = model_objects_->GetModel(); + filament::Skybox* skybox = model_objects_->CreateSkybox(); if (skybox) { scene_->setSkybox(skybox); } @@ -369,7 +374,7 @@ void SceneView::PrepareLights() { total_light_intensity += model->light_intensity[i]; if (model->light_type[i] == mjLIGHT_IMAGE) { - auto* indirect_light = object_mgr_->CreateIndirectLight( + auto* indirect_light = model_objects_->CreateIndirectLight( model->light_texid[i], model->light_intensity[i]); if (indirect_light) { scene_->setIndirectLight(indirect_light); @@ -390,7 +395,7 @@ void SceneView::PrepareLights() { params.spot_cone_angle = model->light_cutoff[i]; } - auto light_obj = std::make_unique(engine_, params); + auto light_obj = std::make_unique(engine, params); #ifndef __EMSCRIPTEN__ // TODO(b/458045799): Re-enable when lights work on glinux and chromebook. light_obj->AddToScene(scene_); @@ -408,7 +413,7 @@ void SceneView::PrepareLights() { params.type = mjLIGHT_DIRECTIONAL; params.castshadow = 0; params.intensity = 0; - auto light_obj = std::make_unique(engine_, params); + auto light_obj = std::make_unique(engine, params); #ifndef __EMSCRIPTEN__ // TODO(b/458045799): Re-enable when lights work on glinux and chromebook. light_obj->AddToScene(scene_); @@ -456,9 +461,10 @@ void SceneView::UpdateScene(const mjvScene* scene) { } } - auto drawable = std::make_unique(object_mgr_, *geom); + auto drawable = + std::make_unique(object_mgr_, model_objects_.get(), *geom); drawable->AddToScene(scene_); - drawable->Update(object_mgr_->GetModel(), scene, *geom); + drawable->Update(model_objects_->GetModel(), scene, *geom); if (drawable->IsReflective()) { AddReflectiveDrawable(drawable.get()); } @@ -507,9 +513,10 @@ void SceneView::AddReflectiveDrawable(Drawable* drawable) { // Ensure we have the same number of render targets as we do reflective // drawables. + filament::Engine* engine = object_mgr_->GetEngine(); while (reflect_targets_.size() < reflectives_.size()) { reflect_targets_.push_back(std::make_unique( - engine_, kRenderTargetReflectionColor, kRenderTargetDepth)); + engine, kRenderTargetReflectionColor, kRenderTargetDepth)); } // Prepare a render target for the reflective drawable. @@ -519,7 +526,21 @@ void SceneView::AddReflectiveDrawable(Drawable* drawable) { drawable->UpdateReflectionTexture(target->GetColorTexture()); } -filament::Engine* SceneView::GetEngine() const { return engine_; } +void SceneView::UploadMesh(const mjModel* model, int id) { + model_objects_->UploadMesh(model, id); +} + +void SceneView::UploadTexture(const mjModel* model, int id) { + model_objects_->UploadTexture(model, id); +} + +void SceneView::UploadHeightField(const mjModel* model, int id) { + model_objects_->UploadHeightField(model, id); +} + +filament::Engine* SceneView::GetEngine() const { + return object_mgr_->GetEngine(); +} filament::View* SceneView::GetDefaultRenderView() { return views_[kNormalIndex]; diff --git a/src/experimental/filament/filament/scene_view.h b/src/experimental/filament/filament/scene_view.h index a46a54d29d..8ced8be13e 100644 --- a/src/experimental/filament/filament/scene_view.h +++ b/src/experimental/filament/filament/scene_view.h @@ -31,10 +31,12 @@ #include #include #include +#include #include "experimental/filament/filament/color_grading_options.h" #include "experimental/filament/filament/drawable.h" #include "experimental/filament/filament/light.h" #include "experimental/filament/filament/material.h" +#include "experimental/filament/filament/model_objects.h" #include "experimental/filament/filament/object_manager.h" #include "experimental/filament/filament/render_target_util.h" @@ -47,7 +49,7 @@ namespace mujoco { // different rendering modes (e.g. normal, depth, segmentation, etc.) class SceneView { public: - SceneView(filament::Engine* engine, ObjectManager* object_mgr); + SceneView(ObjectManager* object_mgr, const mjModel* model); ~SceneView(); // Updates all views to render into the given viewport. @@ -71,6 +73,10 @@ class SceneView { void Render(filament::Renderer* renderer, DrawMode draw_mode, filament::RenderTarget* target = nullptr); + void UploadMesh(const mjModel* model, int id); + void UploadTexture(const mjModel* model, int id); + void UploadHeightField(const mjModel* model, int id); + // Accessors. filament::Engine* GetEngine() const; filament::View* GetDefaultRenderView(); @@ -96,12 +102,12 @@ class SceneView { const filament::math::float3& pos) const; ObjectManager* object_mgr_ = nullptr; - filament::Engine* engine_ = nullptr; filament::Scene* scene_ = nullptr; filament::Camera* camera_ = nullptr; filament::ColorGrading* color_grading_ = nullptr; std::vector> lights_; std::vector> drawables_; + std::unique_ptr model_objects_; std::array views_; filament::math::mat4 clip_from_world_; ColorGradingOptions color_grading_options_; From e9559e7901d61c7cb0dab65d270e3b7a211cf8b3 Mon Sep 17 00:00:00 2001 From: Haroon Qureshi Date: Tue, 31 Mar 2026 05:57:39 -0700 Subject: [PATCH 10/20] Correctly compute bounding boxes for meshes. Enable culling when bounding box is available. PiperOrigin-RevId: 892289875 Change-Id: I124426b6e7e72f4d9a1486320d72d6eb032e0828 --- .../filament/filament/buffer_util.h | 3 +- .../filament/filament/builtins.cc | 38 ++++++--- .../filament/filament/geom_util.cc | 27 +++++-- .../filament/filament/model_objects.cc | 11 +-- .../filament/filament/model_util.cc | 81 +++++++++++++------ .../filament/filament/model_util.h | 4 +- .../filament/filament/renderables.cc | 17 ++-- 7 files changed, 128 insertions(+), 53 deletions(-) diff --git a/src/experimental/filament/filament/buffer_util.h b/src/experimental/filament/filament/buffer_util.h index 4a2a11046d..b6167ff837 100644 --- a/src/experimental/filament/filament/buffer_util.h +++ b/src/experimental/filament/filament/buffer_util.h @@ -18,6 +18,7 @@ #include #include #include +#include #include #include #include @@ -33,7 +34,7 @@ namespace mujoco { struct FilamentBuffers { filament::IndexBuffer* index_buffer = nullptr; filament::VertexBuffer* vertex_buffer = nullptr; - filament::Box bounds = {{-1, -1, -1}, {1, 1, 1}}; + std::optional bounds = std::nullopt; filament::RenderableManager::PrimitiveType type = filament::RenderableManager::PrimitiveType::TRIANGLES; }; diff --git a/src/experimental/filament/filament/builtins.cc b/src/experimental/filament/filament/builtins.cc index ba2525a8cc..825aa95371 100644 --- a/src/experimental/filament/filament/builtins.cc +++ b/src/experimental/filament/filament/builtins.cc @@ -87,7 +87,7 @@ class LineBuilder { } filament::Box GetBounds() const { - return {{-0.001, -0.001, 0}, {0.001, 0.001, 1}}; + return filament::Box().set({-0.001, -0.001, 0}, {0.001, 0.001, 1}); } }; @@ -137,7 +137,9 @@ class PlaneBuilder { } } - filament::Box GetBounds() const { return {{-1, -1, -0.001}, {1, 1, 0.001}}; } + filament::Box GetBounds() const { + return filament::Box().set({-1, -1, -0.001}, {1, 1, 0.001}); + } private: int num_quads_per_axis_; @@ -174,7 +176,9 @@ class TriangleBuilder { ptr[2] = 2; } - filament::Box GetBounds() const { return {{-1, -1, -0.001}, {1, 1, 0.001}}; } + filament::Box GetBounds() const { + return filament::Box().set({-1, -1, -0.001}, {1, 1, 0.001}); + } private: float4 orientation_; @@ -239,7 +243,9 @@ class LineBoxBuilder { ptr[23] = 5; } - filament::Box GetBounds() const { return {{-1, -1, -1}, {1, 1, 1}}; } + filament::Box GetBounds() const { + return filament::Box().set({-1, -1, -1}, {1, 1, 1}); + } }; class BoxBuilder { @@ -305,7 +311,9 @@ class BoxBuilder { } } - filament::Box GetBounds() const { return {{-1, -1, -1}, {1, 1, 1}}; } + filament::Box GetBounds() const { + return filament::Box().set({-1, -1, -1}, {1, 1, 1}); + } private: template @@ -378,7 +386,9 @@ class TubeBuilder { } } - filament::Box GetBounds() const { return {{-1, -1, -1}, {1, 1, 1}}; } + filament::Box GetBounds() const { + return filament::Box().set({-1, -1, -1}, {1, 1, 1}); + } private: int num_stacks_; @@ -461,7 +471,9 @@ class ConeBuilder { } } - filament::Box GetBounds() const { return {{-1, -1, 0}, {1, 1, 1}}; } + filament::Box GetBounds() const { + return filament::Box().set({-1, -1, 0}, {1, 1, 1}); + } private: static VertexType MakeVert(float theta, float radius) { @@ -520,7 +532,9 @@ class DiskBuilder { } } - filament::Box GetBounds() const { return {{-1, -1, -0.001}, {1, 1, 0.001}}; } + filament::Box GetBounds() const { + return filament::Box().set({-1, -1, -0.001}, {1, 1, 0.001}); + } private: int num_slices_; @@ -625,7 +639,9 @@ class SphereBuilder { } } - filament::Box GetBounds() const { return {{-1, -1, -1}, {1, 1, 1}}; } + filament::Box GetBounds() const { + return filament::Box().set({-1, -1, -1}, {1, 1, 1}); + } private: static VertexType MakeVert(float x, float y, float z) { @@ -726,7 +742,9 @@ class DomeBuilder { } } - filament::Box GetBounds() const { return {{-1, -1, 0}, {1, 1, 1}}; } + filament::Box GetBounds() const { + return filament::Box().set({-1, -1, 0}, {1, 1, 1}); + } private: static VertexType MakeVert(float x, float y, float z) { diff --git a/src/experimental/filament/filament/geom_util.cc b/src/experimental/filament/filament/geom_util.cc index fed02258f8..a26fd07317 100644 --- a/src/experimental/filament/filament/geom_util.cc +++ b/src/experimental/filament/filament/geom_util.cc @@ -14,12 +14,16 @@ #include "experimental/filament/filament/geom_util.h" +#include #include #include #include #include #include +#include +#include +#include #include #include "experimental/filament/filament/buffer_util.h" #include "experimental/filament/filament/math_util.h" @@ -27,6 +31,8 @@ namespace mujoco { +using filament::math::float3; + static std::span GetPositions(const mjModel* model, const mjvScene* scene, const mjvGeom& geom) { @@ -102,11 +108,15 @@ template static void FillVertices(std::byte* buffer, std::size_t len, std::span positions, std::span normals, - std::span uvs) { + std::span uvs, + float3* vmin, + float3* vmax) { const int num_vertices = len / sizeof(T); T* ptr = reinterpret_cast(buffer); for (int i = 0; i < num_vertices; ++i) { ptr->position = ReadFloat3(positions.data(), i); + *vmin = min(*vmin, ptr->position); + *vmax = max(*vmax, ptr->position); ptr->orientation = CalculateOrientation(ReadFloat3(normals.data(), i)); if constexpr (T::kHasUv) { ptr->uv.x = uvs[i * 2]; @@ -118,18 +128,21 @@ static void FillVertices(std::byte* buffer, std::size_t len, static filament::VertexBuffer* BuildVertexBuffer( filament::Engine* engine, std::span positions, - std::span normals, std::span uvs) { + std::span normals, std::span uvs, float3* vmin, + float3* vmax) { const int num_vertices = positions.size() / 3; if (uvs.data() != nullptr) { using VertexType = VertexWithUv; auto fill = [&](std::byte* buffer, std::size_t len) { - FillVertices(buffer, len, positions, normals, uvs); + FillVertices(buffer, len, positions, normals, uvs, vmin, + vmax); }; return CreateVertexBuffer(engine, num_vertices, fill); } else { using VertexType = VertexNoUv; auto fill = [&](std::byte* buffer, std::size_t len) { - FillVertices(buffer, len, positions, normals, uvs); + FillVertices(buffer, len, positions, normals, uvs, vmin, + vmax); }; return CreateVertexBuffer(engine, num_vertices, fill); } @@ -163,8 +176,12 @@ FilamentBuffers CreateGeomBuffers(filament::Engine* engine, } FilamentBuffers buffers; - buffers.vertex_buffer = BuildVertexBuffer(engine, positions, normals, uvs); + float3 vmin = {FLT_MAX, FLT_MAX, FLT_MAX}; + float3 vmax = {-FLT_MAX, -FLT_MAX, -FLT_MAX}; + buffers.vertex_buffer = + BuildVertexBuffer(engine, positions, normals, uvs, &vmin, &vmax); buffers.index_buffer = BuildIndexBuffer(engine, indices, num_indices); + buffers.bounds.emplace().set(vmin, vmax); return buffers; } diff --git a/src/experimental/filament/filament/model_objects.cc b/src/experimental/filament/filament/model_objects.cc index ac3f4ca213..217648ae07 100644 --- a/src/experimental/filament/filament/model_objects.cc +++ b/src/experimental/filament/filament/model_objects.cc @@ -103,15 +103,16 @@ void ModelObjects::UploadMesh(const mjModel* model, int id) { } FilamentBuffers& buffers = meshes_[id]; - buffers.vertex_buffer = - CreateVertexBuffer(engine_, model, id, MeshType::kNormal); + buffers.vertex_buffer = CreateVertexBuffer( + engine_, model, id, MeshType::kNormal, &buffers.bounds.emplace()); buffers.index_buffer = CreateIndexBuffer(engine_, model, id, MeshType::kNormal); if (model->mesh_graphadr[id] >= 0) { FilamentBuffers& hull_buffers = convex_hulls_[id]; hull_buffers.vertex_buffer = - CreateVertexBuffer(engine_, model, id, MeshType::kConvexHull); + CreateVertexBuffer(engine_, model, id, MeshType::kConvexHull, + &hull_buffers.bounds.emplace()); hull_buffers.index_buffer = CreateIndexBuffer(engine_, model, id, MeshType::kConvexHull); } @@ -160,8 +161,8 @@ void ModelObjects::UploadHeightField(const mjModel* model, int id) { } FilamentBuffers& buffers = height_fields_[id]; - buffers.vertex_buffer = - CreateVertexBuffer(engine_, model, id, MeshType::kHeightField); + buffers.vertex_buffer = CreateVertexBuffer( + engine_, model, id, MeshType::kHeightField, &buffers.bounds.emplace()); buffers.index_buffer = CreateIndexBuffer(engine_, model, id, MeshType::kHeightField); } diff --git a/src/experimental/filament/filament/model_util.cc b/src/experimental/filament/filament/model_util.cc index 77fc83a847..78fca85c19 100644 --- a/src/experimental/filament/filament/model_util.cc +++ b/src/experimental/filament/filament/model_util.cc @@ -15,10 +15,12 @@ #include "experimental/filament/filament/model_util.h" #include +#include #include #include #include +#include #include #include #include @@ -48,11 +50,20 @@ static bool UseFaceNormal(const float3& face_normal, // clang-format on } +static void UpdateBounds(const float3& v, float3* vmin, float3* vmax) { + vmin->x = std::min(vmin->x, v.x); + vmin->y = std::min(vmin->y, v.y); + vmin->z = std::min(vmin->z, v.z); + vmax->x = std::max(vmax->x, v.x); + vmax->y = std::max(vmax->y, v.y); + vmax->z = std::max(vmax->z, v.z); +} + template static void FillConvexHullBuffer(T* ptr, std::size_t num, const mjModel* model, - int meshid) { + int meshid, float3* vmin, float3* vmax) { const int numvert = model->mesh_graph[model->mesh_graphadr[meshid]]; - const int numface = model->mesh_graph[model->mesh_graphadr[meshid]+1]; + const int numface = model->mesh_graph[model->mesh_graphadr[meshid] + 1]; const int vertadr = model->mesh_vertadr[meshid]; const float* vertices = model->mesh_vert + (3 * vertadr); @@ -65,13 +76,18 @@ static void FillConvexHullBuffer(T* ptr, std::size_t num, const mjModel* model, } for (int face = 0; face < numface; ++face) { - int j = model->mesh_graphadr[meshid] + 2 + 3*numvert + 3*numface + 3*face; + int j = + model->mesh_graphadr[meshid] + 2 + 3 * numvert + 3 * numface + 3 * face; const float3 p1 = ReadFloat3(vertices, model->mesh_graph[j + 0]); const float3 p2 = ReadFloat3(vertices, model->mesh_graph[j + 1]); const float3 p3 = ReadFloat3(vertices, model->mesh_graph[j + 2]); const float4 orientation = CalculateOrientation(p1, p2, p3); + UpdateBounds(p1, vmin, vmax); + UpdateBounds(p2, vmin, vmax); + UpdateBounds(p3, vmin, vmax); + ptr->position = p1; ptr->orientation = orientation; if constexpr (T::kHasUv) { @@ -97,7 +113,7 @@ static void FillConvexHullBuffer(T* ptr, std::size_t num, const mjModel* model, template static void FillMeshBuffer(T* ptr, std::size_t num, const mjModel* model, - int meshid) { + int meshid, float3* vmin, float3* vmax) { const int faceadr = model->mesh_faceadr[meshid]; const int facenum = model->mesh_facenum[meshid]; if (num != facenum * 3) { @@ -118,8 +134,12 @@ static void FillMeshBuffer(T* ptr, std::size_t num, const mjModel* model, const float3 p1 = ReadFloat3(vertices, model->mesh_face[face + 0]); const float3 p2 = ReadFloat3(vertices, model->mesh_face[face + 1]); const float3 p3 = ReadFloat3(vertices, model->mesh_face[face + 2]); - const float3 face_normal = CalculateNormal(p1, p2, p3); + UpdateBounds(p1, vmin, vmax); + UpdateBounds(p2, vmin, vmax); + UpdateBounds(p3, vmin, vmax); + + const float3 face_normal = CalculateNormal(p1, p2, p3); const float3 n1 = ReadFloat3(normals, model->mesh_facenormal[face + 0]); const float3 n2 = ReadFloat3(normals, model->mesh_facenormal[face + 1]); const float3 n3 = ReadFloat3(normals, model->mesh_facenormal[face + 2]); @@ -160,7 +180,8 @@ static void FillMeshBuffer(T* ptr, std::size_t num, const mjModel* model, } static void FillHeightFieldBuffer(VertexNoUv* ptr, std::size_t num, - const mjModel* model, int hfieldid) { + const mjModel* model, int hfieldid, + float3* vmin, float3* vmax) { int count = 0; auto append_tri = [&](float3 a, float3 b, float3 c) { float4 orientation = CalculateOrientation(a, b, c); @@ -173,6 +194,10 @@ static void FillHeightFieldBuffer(VertexNoUv* ptr, std::size_t num, ptr[count].position = c; ptr[count].orientation = orientation; ++count; + + UpdateBounds(a, vmin, vmax); + UpdateBounds(b, vmin, vmax); + UpdateBounds(c, vmin, vmax); }; auto append_quad = [&](float3 a, float3 b, float3 c, float3 d) { append_tri(a, b, d); @@ -186,7 +211,7 @@ static void FillHeightFieldBuffer(VertexNoUv* ptr, std::size_t num, const float width = 0.5f * (ncol - 1); float sz[4]; for (int i = 0; i < 4; ++i) { - sz[i] = static_cast(model->hfield_size[4 * hfieldid + i]); + sz[i] = static_cast(model->hfield_size[4 * hfieldid + i]); } auto get_pos = [=](int r, int c) { @@ -254,8 +279,8 @@ static void FillHeightFieldBuffer(VertexNoUv* ptr, std::size_t num, } // Build the right edge. for (int row = 0; row < nrow - 1; ++row) { - const float3 a = get_pos(row + 1, ncol-1); - const float3 b = get_pos(row, ncol-1); + const float3 a = get_pos(row + 1, ncol - 1); + const float3 b = get_pos(row, ncol - 1); const float3 c = {b.x, b.y, -sz[3]}; const float3 d = {a.x, a.y, -sz[3]}; append_quad(a, b, c, d); @@ -270,8 +295,8 @@ static void FillHeightFieldBuffer(VertexNoUv* ptr, std::size_t num, } // Build the back edge. for (int col = 0; col < ncol - 1; ++col) { - const float3 a = get_pos(nrow-1, col + 1); - const float3 b = get_pos(nrow-1, col); + const float3 a = get_pos(nrow - 1, col + 1); + const float3 b = get_pos(nrow - 1, col); const float3 c = {b.x, b.y, -sz[3]}; const float3 d = {a.x, a.y, -sz[3]}; append_quad(a, b, c, d); @@ -286,9 +311,7 @@ static void FillHeightFieldBuffer(VertexNoUv* ptr, std::size_t num, const float x1 = sz[0] * ((col + 1) / base_width - 1.0f); const float y0 = sz[1] * ((row + 0) / base_height - 1.0f); const float y1 = sz[1] * ((row + 1) / base_height - 1.0f); - append_quad({x0, y0, -sz[3]}, - {x0, y1, -sz[3]}, - {x1, y1, -sz[3]}, + append_quad({x0, y0, -sz[3]}, {x0, y1, -sz[3]}, {x1, y1, -sz[3]}, {x1, y0, -sz[3]}); } } @@ -305,7 +328,7 @@ static int CalculateHeightFieldVertexCount(const mjModel* model, int hfieldid) { // we need. But, in general... // We use 4 triangles (i.e. 12 vertices) per quad. - const int surface_count = 12 * (nrow-1) * (ncol-1); + const int surface_count = 12 * (nrow - 1) * (ncol - 1); // We use 1 quad (i.e. 6 vertices) per edge element. We double this because // we have two edges per dimension (e.g. left/right and front/back). const int edge_count = (12 * (nrow - 1)) + (12 * (ncol - 1)); @@ -322,17 +345,23 @@ template static filament::VertexBuffer* CreateVertexBuffer(filament::Engine* engine, const mjModel* model, int id, int vertex_count, - FillFn fill_fn) { - return CreateVertexBuffer( + FillFn fill_fn, + filament::Box* bounds) { + float3 vmin = {FLT_MAX, FLT_MAX, FLT_MAX}; + float3 vmax = {-FLT_MAX, -FLT_MAX, -FLT_MAX}; + filament::VertexBuffer* buffer = CreateVertexBuffer( engine, vertex_count, [&](std::byte* buffer, std::size_t num_bytes) { auto* ptr = reinterpret_cast(buffer); - fill_fn(ptr, num_bytes / sizeof(T), model, id); + fill_fn(ptr, num_bytes / sizeof(T), model, id, &vmin, &vmax); }); + bounds->set(vmin, vmax); + return buffer; } filament::VertexBuffer* CreateVertexBuffer(filament::Engine* engine, const mjModel* model, int id, - MeshType mesh_type) { + MeshType mesh_type, + filament::Box* bounds) { if (id < 0) { mju_error("Invalid mesh index %d", id); return nullptr; @@ -376,11 +405,13 @@ filament::VertexBuffer* CreateVertexBuffer(filament::Engine* engine, switch (mesh_type) { case MeshType::kNormal: return CreateVertexBuffer(engine, model, id, vertex_count, - FillMeshBuffer); + FillMeshBuffer, + bounds); break; case MeshType::kConvexHull: return CreateVertexBuffer(engine, model, id, vertex_count, - FillConvexHullBuffer); + FillConvexHullBuffer, + bounds); break; case MeshType::kHeightField: mju_error("Height fields do not support UV coordinates."); @@ -391,15 +422,17 @@ filament::VertexBuffer* CreateVertexBuffer(filament::Engine* engine, switch (mesh_type) { case MeshType::kNormal: return CreateVertexBuffer(engine, model, id, vertex_count, - FillMeshBuffer); + FillMeshBuffer, + bounds); break; case MeshType::kConvexHull: return CreateVertexBuffer(engine, model, id, vertex_count, - FillConvexHullBuffer); + FillConvexHullBuffer, + bounds); break; case MeshType::kHeightField: return CreateVertexBuffer(engine, model, id, vertex_count, - FillHeightFieldBuffer); + FillHeightFieldBuffer, bounds); break; } } diff --git a/src/experimental/filament/filament/model_util.h b/src/experimental/filament/filament/model_util.h index 46f9beec10..571716741f 100644 --- a/src/experimental/filament/filament/model_util.h +++ b/src/experimental/filament/filament/model_util.h @@ -17,6 +17,7 @@ #include +#include #include #include #include @@ -45,7 +46,8 @@ enum class TextureType { // Generates a filament VertexBuffer for a given mesh in the mjModel. filament::VertexBuffer* CreateVertexBuffer(filament::Engine* engine, const mjModel* model, int id, - MeshType mesh_type); + MeshType mesh_type, + filament::Box* bounds); // Generates a filament IndexBuffer for a given mesh in the mjModel. filament::IndexBuffer* CreateIndexBuffer(filament::Engine* engine, diff --git a/src/experimental/filament/filament/renderables.cc b/src/experimental/filament/filament/renderables.cc index 0eeb0c87dc..fcce336ff7 100644 --- a/src/experimental/filament/filament/renderables.cc +++ b/src/experimental/filament/filament/renderables.cc @@ -105,13 +105,16 @@ utils::Entity Renderables::CreateEntity(const FilamentBuffers& buffers) { if (material_instance_) { builder.material(0, material_instance_); } - builder.boundingBox(buffers.bounds) - .culling(false) - .castShadows(cast_shadows_) - .receiveShadows(receive_shadows_) - .layerMask(0xff, layer_mask_) - .priority(priority_) - .screenSpaceContactShadows(true); + if (buffers.bounds.has_value()) { + builder.boundingBox(buffers.bounds.value()); + } else { + builder.culling(false); + } + builder.castShadows(cast_shadows_); + builder.receiveShadows(receive_shadows_); + builder.layerMask(0xff, layer_mask_); + builder.priority(priority_); + builder.screenSpaceContactShadows(true);; builder.build(*engine_, entity); if (assigned_scene_) { From f391336347ea2ad0742a8f9bdc10716903aac2ad Mon Sep 17 00:00:00 2001 From: "dependabot[bot]" <49699333+dependabot[bot]@users.noreply.github.com> Date: Tue, 31 Mar 2026 07:27:16 -0700 Subject: [PATCH 11/20] Copybara import of the project: -- 9a748c86e78009393be8ef2f586c5637ac6225d9 by dependabot[bot] <49699333+dependabot[bot]@users.noreply.github.com>: Bump pip from 24.3.1 to 26.0 in /python Bumps [pip](https://github.com/pypa/pip) from 24.3.1 to 26.0. - [Changelog](https://github.com/pypa/pip/blob/main/NEWS.rst) - [Commits](https://github.com/pypa/pip/compare/24.3.1...26.0) --- updated-dependencies: - dependency-name: pip dependency-version: '26.0' dependency-type: direct:production ... Signed-off-by: dependabot[bot] COPYBARA_INTEGRATE_REVIEW=https://github.com/google-deepmind/mujoco/pull/3064 from google-deepmind:dependabot/pip/python/pip-26.0 9a748c86e78009393be8ef2f586c5637ac6225d9 PiperOrigin-RevId: 892327253 Change-Id: I0cf41d08a1ffeb3238cddd5a3fcf39388810d9b7 --- python/build_requirements.txt | 5 +++-- python/make_sdist_requirements.txt | 5 +++-- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/python/build_requirements.txt b/python/build_requirements.txt index 49b3750f82..9be02aabac 100644 --- a/python/build_requirements.txt +++ b/python/build_requirements.txt @@ -44,8 +44,9 @@ numpy==2.1.3; python_version >= '3.10' \ --hash=sha256:825656d0743699c529c5943554d223c021ff0494ff1442152ce887ef4f7561a1 \ --hash=sha256:b47fbb433d3260adcd51eb54f92a2ffbc90a4595f8970ee00e064c644ac788f5 \ --hash=sha256:c894b4305373b9c5576d7a12b473702afdf48ce5369c074ba304cc5ad8730dff -pip==24.3.1 \ - --hash=sha256:3790624780082365f47549d032f3770eeb2b1e8bd1f7b2e02dace1afa361b4ed +pip==26.0 \ + --hash=sha256:3ce220a0a17915972fbf1ab451baae1521c4539e778b28127efa79b974aff0fa \ + --hash=sha256:98436feffb9e31bc9339cf369fd55d3331b1580b6a6f1173bacacddcf9c34754 PyOpenGL==3.1.7 \ --hash=sha256:a6ab19cf290df6101aaf7470843a9c46207789855746399d0af92521a0a92b7a pytest==8.3.3 \ diff --git a/python/make_sdist_requirements.txt b/python/make_sdist_requirements.txt index da33bbb9ca..cd3c177453 100644 --- a/python/make_sdist_requirements.txt +++ b/python/make_sdist_requirements.txt @@ -2,8 +2,9 @@ absl-py==2.1.0 \ --hash=sha256:526a04eadab8b4ee719ce68f204172ead1027549089702d99b9059f129ff1308 build==1.2.2.post1 \ --hash=sha256:1d61c0887fa860c01971625baae8bdd338e517b836a2f70dd1f7aa3a6b2fc5b5 -pip==24.3.1 \ - --hash=sha256:3790624780082365f47549d032f3770eeb2b1e8bd1f7b2e02dace1afa361b4ed +pip==26.0 \ + --hash=sha256:3ce220a0a17915972fbf1ab451baae1521c4539e778b28127efa79b974aff0fa \ + --hash=sha256:98436feffb9e31bc9339cf369fd55d3331b1580b6a6f1173bacacddcf9c34754 setuptools==78.1.1 \ --hash=sha256:c3a9c4211ff4c309edb8b8c4f1cbfa7ae324c4ba9f91ff254e3d305b9fd54561 \ --hash=sha256:fcc17fd9cd898242f6b4adfaca46137a9edef687f43e6f78469692a5e70d851d From cd70990ee2d311d6dab0dc64e4bd540829f6884d Mon Sep 17 00:00:00 2001 From: Taylor Howell Date: Wed, 1 Apr 2026 01:53:33 -0700 Subject: [PATCH 12/20] Import NVIDIA/warp from GitHub. PiperOrigin-RevId: 892794388 Change-Id: Ic681071dc68bfaecaaab4e131c1c464dca99f9b5 --- mjx/cuda_requirements.txt | 10 +- .../warp/_src/jax_experimental/custom_call.py | 6 +- .../warp/_src/jax_experimental/ffi.py | 178 ++++++++++++++---- mjx/pyproject.toml | 2 +- 4 files changed, 152 insertions(+), 44 deletions(-) diff --git a/mjx/cuda_requirements.txt b/mjx/cuda_requirements.txt index 0f9ae0d572..2ced5d1285 100644 --- a/mjx/cuda_requirements.txt +++ b/mjx/cuda_requirements.txt @@ -16,8 +16,8 @@ jax-cuda12-pjrt==0.5.3; python_version >= '3.10' \ jax-cuda12-pjrt==0.4.30; python_version == '3.9' \ --hash=sha256:895d0198ad99638fcaf976c47592e2a543eef79ea15fabd24a402d055390c328 \ --hash=sha256:c36fb1e0c236563bf3a87e70f4d1ab28a31d7cf5d722c9ede30c4172116e8bcb -warp-lang==1.11.1 \ - --hash=sha256:1ad11f1fa775269e991a3d55039152c8a504baf86701c849b485cb8e66c49d15 \ - --hash=sha256:8b098f41e71d421d80ee7562e38aa8380ff6b0d3b4c6ee866cfbdef733ac5bdc \ - --hash=sha256:5d0904b0eefcc81f39ba65375427a3de99006088aa43e24a9011263f07d0cd07 \ - --hash=sha256:15dc10aa51fb0fdbe1ca16d52e5fadca35a47ffd9d0c636826506f96bb2e7c41 +warp-lang==1.12.0 \ + --hash=sha256:c78c3701d5cad86c30ef5017410d294ec46a396bb0d502ee1c98743494f3a62f \ + --hash=sha256:a1436f60a1881cd94f787e751a83fc0987626be2d3e2b4e74c64a6947c6d1266 \ + --hash=sha256:a2d6decba693aba5b828573c4414fd6a3f4c4a934db9c322736ef2b3fa99fe76 \ + --hash=sha256:697248edd2f1e2952f50e3db33b214af76173641a8894aacc467bed6dc247f8a diff --git a/mjx/mujoco/mjx/third_party/warp/_src/jax_experimental/custom_call.py b/mjx/mujoco/mjx/third_party/warp/_src/jax_experimental/custom_call.py index b46a107135..0adf643594 100644 --- a/mjx/mujoco/mjx/third_party/warp/_src/jax_experimental/custom_call.py +++ b/mjx/mujoco/mjx/third_party/warp/_src/jax_experimental/custom_call.py @@ -19,7 +19,7 @@ import warp as wp from warp._src.context import type_str from warp._src.jax import get_jax_device -from warp._src.types import array_t, launch_bounds_t, strides_from_shape +from warp._src.types import array_t, launch_bounds_t, matches_array_class, strides_from_shape from warp._src.utils import warn _wp_module_name_ = "warp.jax_experimental.custom_call" @@ -340,7 +340,7 @@ def warp_call_lowering(ctx, *args, kernel=None, launch_dims=None): wtype = warg.type rtt = ir.RankedTensorType(actual.type) - if not isinstance(wtype, wp.array): + if not matches_array_class(wtype, wp.array): raise Exception("Only contiguous arrays are supported for Jax kernel arguments") if not base_type_is_compatible(wtype.dtype, rtt.element_type): @@ -364,7 +364,7 @@ def warp_call_lowering(ctx, *args, kernel=None, launch_dims=None): for warg in wp_kernel.adj.args[len(args) :]: wtype = warg.type - if not isinstance(wtype, wp.array): + if not matches_array_class(wtype, wp.array): raise Exception("Only contiguous arrays are supported for Jax kernel arguments") # Infer dimensions from the first input. diff --git a/mjx/mujoco/mjx/third_party/warp/_src/jax_experimental/ffi.py b/mjx/mujoco/mjx/third_party/warp/_src/jax_experimental/ffi.py index f5c925dd44..e9fe408f47 100644 --- a/mjx/mujoco/mjx/third_party/warp/_src/jax_experimental/ffi.py +++ b/mjx/mujoco/mjx/third_party/warp/_src/jax_experimental/ffi.py @@ -29,19 +29,23 @@ from warp._src.codegen import get_full_arg_spec, make_full_qualified_name from warp._src.context import CudaMemcpyKind from warp._src.jax import get_jax_device -from warp._src.types import array_t, launch_bounds_t, strides_from_shape, type_size_in_bytes, type_to_warp +from warp._src.types import ( + array_t, + launch_bounds_t, + matches_array_class, + strides_from_shape, + type_size_in_bytes, + type_to_warp, +) from .xla_ffi import * _wp_module_name_ = "warp.jax_experimental.ffi" -# Type alias for differentiable kernel cache key -DiffKernelCacheKey = tuple[Callable, tuple, int, str, tuple[str, ...]] - # Holders for the custom callbacks to keep them alive. -_FFI_KERNEL_REGISTRY: dict[str, FfiKernel] = {} -_FFI_DIFF_KERNEL_REGISTRY: dict[DiffKernelCacheKey, Callable] = {} -_FFI_CALLABLE_REGISTRY: dict[str, FfiCallable] = {} +_FFI_KERNEL_REGISTRY: dict[tuple, FfiKernel] = {} +_FFI_DIFF_KERNEL_REGISTRY: dict[tuple, Callable] = {} +_FFI_CALLABLE_REGISTRY: dict[tuple, FfiCallable] = {} _FFI_CALLBACK_REGISTRY: dict[str, ctypes.CFUNCTYPE] = {} _FFI_REGISTRY_LOCK = threading.Lock() @@ -61,6 +65,21 @@ def check_jax_version(): raise RuntimeError(msg) +def collapse_batch_dims(shape, desired_ndim): + # roll leading batch dims into one + while len(shape) > desired_ndim: + shape = (shape[0] * shape[1], *shape[2:]) + return shape + + +def compute_batch_size(shape, batch_ndim): + # compute product of batch dims at front + batch_size = 1 + for i in range(batch_ndim): + batch_size *= shape[i] + return batch_size + + class GraphMode(IntEnum): """CUDA graph capture modes for :func:`warp.jax_experimental.jax_callable`. @@ -91,7 +110,7 @@ def __init__(self, name, type, in_out=False): self.name = name self.type = type self.in_out = in_out - self.is_array = isinstance(type, wp.array) + self.is_array = matches_array_class(type, wp.array) if self.is_array: if hasattr(type.dtype, "_wp_scalar_type_"): @@ -125,7 +144,15 @@ def __init__(self, static_inputs, launch_dims): class FfiKernel: def __init__( - self, kernel, num_outputs, vmap_method, launch_dims, output_dims, in_out_argnames, module_preload_mode + self, + kernel, + num_outputs, + vmap_method, + launch_dims, + output_dims, + in_out_argnames, + module_preload_mode, + has_side_effect=False, ): self.kernel = kernel self.name = generate_unique_name(kernel.func) @@ -134,6 +161,7 @@ def __init__( self.launch_dims = launch_dims self.output_dims = output_dims self.module_preload_mode = module_preload_mode + self.has_side_effect = has_side_effect self.first_array_arg = None self.launch_id = 0 self.launch_descriptors = {} @@ -250,7 +278,8 @@ def __call__(self, *args, output_dims=None, launch_dims=None, vmap_method=None): out_types.append(get_jax_output_type(input_arg, input_value.shape)) # launch dimensions - if launch_dims is None: + infer_launch_dims = launch_dims is None + if infer_launch_dims: # use the shape of the first input array if self.first_array_arg is not None: launch_dims = get_warp_shape(self.input_args[self.first_array_arg], args[self.first_array_arg].shape) @@ -284,6 +313,7 @@ def __call__(self, *args, output_dims=None, launch_dims=None, vmap_method=None): out_types, vmap_method=vmap_method, input_output_aliases=self.input_output_aliases, + has_side_effect=self.has_side_effect, ) # preload on the specified devices @@ -303,7 +333,9 @@ def __call__(self, *args, output_dims=None, launch_dims=None, vmap_method=None): # save launch data to be retrieved by callback launch_id = self.launch_id - self.launch_descriptors[launch_id] = FfiLaunchDesc(static_inputs, launch_dims) + self.launch_descriptors[launch_id] = FfiLaunchDesc( + static_inputs, launch_dims if not infer_launch_dims else None + ) self.launch_id += 1 return call(*args, launch_id=launch_id) @@ -343,19 +375,23 @@ def ffi_callback(self, call_frame): assert num_inputs == self.num_inputs assert num_outputs == self.num_outputs - launch_bounds = launch_bounds_t(launch_desc.launch_dims) - # first kernel param is the launch bounds kernel_params = (ctypes.c_void_p * (1 + self.num_kernel_args))() - kernel_params[0] = ctypes.addressof(launch_bounds) - arg_refs = [] + batch_size = None # input and in-out args for i, input_arg in enumerate(self.input_args): if input_arg.is_array: buffer = inputs[i].contents - shape = buffer.dims[: input_arg.type.ndim] + shape = buffer.dims[: buffer.rank - input_arg.dtype_ndim] + if buffer.rank > input_arg.jax_ndim: + # handle batching + shape = collapse_batch_dims(shape, input_arg.type.ndim) + if batch_size is None: + batch_size = compute_batch_size( + buffer.dims[: buffer.rank], buffer.rank - input_arg.jax_ndim + ) strides = strides_from_shape(shape, input_arg.type.dtype) arg = array_t(buffer.data, 0, input_arg.type.ndim, shape, strides) kernel_params[i + 1] = ctypes.addressof(arg) @@ -370,12 +406,34 @@ def ffi_callback(self, call_frame): # pure output args (skip in-out FFI buffers) for i, output_arg in enumerate(self.output_args): buffer = outputs[i + self.num_in_out].contents - shape = buffer.dims[: output_arg.type.ndim] + shape = buffer.dims[: buffer.rank - output_arg.dtype_ndim] + if buffer.rank > output_arg.jax_ndim: + # handle batching + shape = collapse_batch_dims(shape, output_arg.type.ndim) + if batch_size is None: + batch_size = compute_batch_size( + buffer.dims[: buffer.rank], buffer.rank - output_arg.jax_ndim + ) strides = strides_from_shape(shape, output_arg.type.dtype) arg = array_t(buffer.data, 0, output_arg.type.ndim, shape, strides) kernel_params[num_inputs + i + 1] = ctypes.addressof(arg) arg_refs.append(arg) # keep a reference + # determine launch bounds + if launch_desc.launch_dims is None: + # infer launch dims from argument shape, works with vmap + arr = arg_refs[self.first_array_arg] + launch_dims = arr.shape[: arr.ndim] + else: + # use specified launch dims + launch_dims = launch_desc.launch_dims + if batch_size is not None: + # roll batch size into the first launch dimension + launch_dims = (batch_size * launch_dims[0], *launch_dims[1:]) + + launch_bounds = launch_bounds_t(launch_dims) + kernel_params[0] = ctypes.addressof(launch_bounds) + # get device and stream device = wp.get_cuda_device(get_device_ordinal_from_callframe(call_frame.contents)) stream = get_stream_from_callframe(call_frame.contents) @@ -808,7 +866,7 @@ def ffi_callback(self, call_frame): for i, arg in enumerate(self.input_args): if arg.is_array: buffer = inputs[i].contents - shape = buffer.dims[: buffer.rank - arg.dtype_ndim] + shape = collapse_batch_dims(buffer.dims[: buffer.rank - arg.dtype_ndim], arg.type.ndim) arr = wp.array(ptr=buffer.data, dtype=arg.type.dtype, shape=shape, device=device) arg_list.append(arr) else: @@ -819,7 +877,7 @@ def ffi_callback(self, call_frame): # pure output args (skip in-out FFI buffers) for i, arg in enumerate(self.output_args): buffer = outputs[i + self.num_in_out].contents - shape = buffer.dims[: buffer.rank - arg.dtype_ndim] + shape = collapse_batch_dims(buffer.dims[: buffer.rank - arg.dtype_ndim], arg.type.ndim) arr = wp.array(ptr=buffer.data, dtype=arg.type.dtype, shape=shape, device=device) arg_list.append(arr) @@ -1095,6 +1153,7 @@ def jax_kernel( in_out_argnames=None, module_preload_mode=ModulePreloadMode.CURRENT_DEVICE, enable_backward: bool = False, + has_side_effect: bool = False, ): """Create a JAX callback from a Warp kernel. @@ -1103,21 +1162,23 @@ def jax_kernel( Args: kernel: The Warp kernel to launch. num_outputs: Specify the number of output arguments if greater than 1. - This must include the number of ``in_out_arguments``. + This must include the number of ``in_out_arguments``. vmap_method: String specifying how the callback transforms under ``vmap()``. - This argument can also be specified for individual calls. + This argument can also be specified for individual calls. launch_dims: Specify the default kernel launch dimensions. If None, launch - dimensions are inferred from the shape of the first array argument. - This argument can also be specified for individual calls. + dimensions are inferred from the shape of the first array argument. + This argument can also be specified for individual calls. output_dims: Specify the default dimensions of output arrays. If None, output - dimensions are inferred from the launch dimensions. - This argument can also be specified for individual calls. + dimensions are inferred from the launch dimensions. + This argument can also be specified for individual calls. in_out_argnames: Names of arguments that are both inputs and outputs (aliased buffers). These must be array arguments that appear before any pure output arguments in the kernel signature. The number of in-out arguments is included in ``num_outputs``. Not supported when ``enable_backward=True``. module_preload_mode: Specify the devices where the module should be preloaded. enable_backward: Enable automatic differentiation for this kernel. + has_side_effect: Whether the custom call has side effects. When True, + the FFI call will be executed even when the outputs are not used. Limitations: - All kernel arguments must be contiguous arrays or scalars. @@ -1129,21 +1190,41 @@ def jax_kernel( check_jax_version() + if isinstance(output_dims, dict): + hashable_output_dims = tuple(sorted(output_dims.items())) + elif hasattr(output_dims, "__len__"): + hashable_output_dims = tuple(output_dims) + else: + hashable_output_dims = output_dims + + if hasattr(launch_dims, "__len__"): + hashable_launch_dims = tuple(launch_dims) + else: + hashable_launch_dims = launch_dims + if not enable_backward: key = ( kernel.func, kernel.sig, num_outputs, vmap_method, - tuple(launch_dims) if launch_dims else launch_dims, - tuple(sorted(output_dims.items())) if output_dims else output_dims, + hashable_launch_dims, + hashable_output_dims, module_preload_mode, + has_side_effect, ) with _FFI_REGISTRY_LOCK: if key not in _FFI_KERNEL_REGISTRY: new_kernel = FfiKernel( - kernel, num_outputs, vmap_method, launch_dims, output_dims, in_out_argnames, module_preload_mode + kernel, + num_outputs, + vmap_method, + launch_dims, + output_dims, + in_out_argnames, + module_preload_mode, + has_side_effect=has_side_effect, ) _FFI_KERNEL_REGISTRY[key] = new_kernel @@ -1173,7 +1254,7 @@ def jax_kernel( static_args = [] for i, p in enumerate(parameters[:num_inputs]): param_type = p.annotation - if not isinstance(param_type, wp.array): + if not matches_array_class(param_type, wp.array): if param_type in wp._src.types.value_types: static_args.append(i) else: @@ -1183,7 +1264,7 @@ def _resolve_launch_dims(call_args): # determine launch dimensions from the shape of the first input array for i, p in enumerate(parameters[:num_inputs]): param_type = p.annotation - if isinstance(param_type, wp.array): + if matches_array_class(param_type, wp.array): arg = call_args[i] arg_shape = tuple(arg.shape) if hasattr(param_type.dtype, "_wp_scalar_type_"): @@ -1203,7 +1284,13 @@ def fwd_kernel_wrapper(*args): fwd_kernel_wrapper.__annotations__ = {p.name: p.annotation for p in parameters} fwd_kernel_wrapper.__annotations__["return"] = None - jax_fwd_kernel = jax_callable(fwd_kernel_wrapper, num_outputs=num_outputs, vmap_method=vmap_method) + jax_fwd_kernel = jax_callable( + fwd_kernel_wrapper, + num_outputs=num_outputs, + vmap_method=vmap_method, + module_preload_mode=module_preload_mode, + has_side_effect=has_side_effect, + ) # backward arguments only include static args once bwd_arg_count = 2 * parameter_count - len(static_args) @@ -1285,6 +1372,8 @@ def bwd_kernel_wrapper(*args): bwd_kernel_wrapper, num_outputs=len(bwd_input_params) - len(static_args), vmap_method=vmap_method, + module_preload_mode=module_preload_mode, + has_side_effect=has_side_effect, ) differentiable_input_indices = [i for i in range(num_inputs) if i not in static_args] @@ -1331,7 +1420,7 @@ def bwd_function(*bwd_args): if ann is None: continue # Check if annotation is a warp array type (annotation is an instance of wp.array) - is_array_ann = isinstance(ann, wp.array) + is_array_ann = matches_array_class(ann, wp.array) if not is_array_ann: continue dtype_ndim = 0 @@ -1355,6 +1444,15 @@ def bwd_function(*bwd_args): jax_func = jax.custom_vjp(jax_fwd_kernel, nondiff_argnums=tuple(static_args)) jax_func.defvjp(fwd_function, bwd_function) + key = ( + kernel.func, + kernel.sig, + num_outputs, + vmap_method, + module_preload_mode, + has_side_effect, + ) + if static_args: static_names = [parameters[i].name for i in static_args] @@ -1364,7 +1462,7 @@ def _user_callable(*args): _user_callable.__signature__ = signature # Cache differentiable wrapper - key = (kernel.func, kernel.sig, num_outputs, vmap_method, tuple(sorted(static_names))) + key = (*key, tuple(sorted(static_names))) with _FFI_REGISTRY_LOCK: cached = _FFI_DIFF_KERNEL_REGISTRY.get(key) if cached is None: @@ -1373,7 +1471,7 @@ def _user_callable(*args): return _FFI_DIFF_KERNEL_REGISTRY[key] # Cache differentiable wrapper (no static args) - key = (kernel.func, kernel.sig, num_outputs, vmap_method, ()) + key = (*key, ()) with _FFI_REGISTRY_LOCK: cached = _FFI_DIFF_KERNEL_REGISTRY.get(key) if cached is None: @@ -1426,6 +1524,8 @@ def jax_callable( graph_cache_max: Maximum number of cached graphs captured using ``GraphMode.WARP``. If ``None``, use ``warp.jax_experimental.get_jax_callable_default_graph_cache_max()``. module_preload_mode: Specify the devices where the module should be preloaded. + has_side_effect: Whether the custom call has side effects. When True, + the FFI call will be executed even when the outputs are not used. Limitations: - All kernel arguments must be contiguous arrays or scalars. @@ -1440,14 +1540,22 @@ def jax_callable( if graph_cache_max is None: graph_cache_max = FfiCallable.default_graph_cache_max + if isinstance(output_dims, dict): + hashable_output_dims = tuple(sorted(output_dims.items())) + elif hasattr(output_dims, "__len__"): + hashable_output_dims = tuple(output_dims) + else: + hashable_output_dims = output_dims + # Note: we don't include graph_cache_max in the key, it is applied below. key = ( func, num_outputs, graph_mode, vmap_method, - tuple(sorted(output_dims.items())) if output_dims else output_dims, + hashable_output_dims, module_preload_mode, + has_side_effect, ) with _FFI_REGISTRY_LOCK: diff --git a/mjx/pyproject.toml b/mjx/pyproject.toml index ff7133cdd6..60063b70f9 100644 --- a/mjx/pyproject.toml +++ b/mjx/pyproject.toml @@ -36,7 +36,7 @@ dependencies = [ [project.optional-dependencies] warp = [ - "warp-lang==1.11.1", + "warp-lang==1.12.0", ] [project.scripts] From fab67707fe2f733b729ad07ad62cbc3b8eb3c590 Mon Sep 17 00:00:00 2001 From: Haroon Qureshi Date: Wed, 1 Apr 2026 03:47:08 -0700 Subject: [PATCH 13/20] Move all texture creation functions into texture_util. PiperOrigin-RevId: 892838123 Change-Id: I84a536b111c3d6b5391513d6623c2e9a4d02f3df --- .../filament/filament/filament_context.cc | 25 +++++---- .../filament/filament/model_util.cc | 19 ------- .../filament/filament/model_util.h | 10 ---- .../filament/filament/render_target_util.cc | 34 +----------- .../filament/filament/render_target_util.h | 15 ++---- .../filament/filament/scene_view.cc | 4 +- .../filament/filament/texture_util.cc | 54 ++++++++++++++++++- .../filament/filament/texture_util.h | 25 +++++++++ 8 files changed, 99 insertions(+), 87 deletions(-) diff --git a/src/experimental/filament/filament/filament_context.cc b/src/experimental/filament/filament/filament_context.cc index d783cefaa8..973425d192 100644 --- a/src/experimental/filament/filament/filament_context.cc +++ b/src/experimental/filament/filament/filament_context.cc @@ -45,6 +45,7 @@ #include "experimental/filament/filament/object_manager.h" #include "experimental/filament/filament/render_target_util.h" #include "experimental/filament/filament/scene_view.h" +#include "experimental/filament/filament/texture_util.h" #include "experimental/filament/render_context_filament.h" namespace mujoco { @@ -62,16 +63,18 @@ FilamentContext::FilamentContext(const mjrFilamentConfig* config) engine_ = engine_builder.build(); renderer_ = engine_->createRenderer(); - #ifdef __EMSCRIPTEN__ - window_swap_chain_ = engine_->createSwapChain(nullptr); - #else +#ifdef __EMSCRIPTEN__ + window_swap_chain_ = engine_->createSwapChain(nullptr); +#else if (config_.native_window) { window_swap_chain_ = engine_->createSwapChain(config_.native_window); } else { - window_swap_chain_ = engine_->createSwapChain(config_.width, config_.height); + window_swap_chain_ = + engine_->createSwapChain(config_.width, config_.height); } - #endif - offscreen_swap_chain_ = engine_->createSwapChain(config_.width, config_.height); +#endif + offscreen_swap_chain_ = + engine_->createSwapChain(config_.width, config_.height); object_manager_ = std::make_unique(engine_); } @@ -183,11 +186,13 @@ void FilamentContext::SetFrameBuffer(int framebuffer) { void FilamentContext::PrepareRenderTargets(int width, int height) { color_target_ = std::make_unique( - engine_, kRenderTargetColor, kRenderTargetDepth); + engine_, RenderTargetTextureType::kColor, + RenderTargetTextureType::kDepth); color_target_->Prepare(width, height); depth_target_ = std::make_unique( - engine_, kRenderTargetDepthColor, kRenderTargetDepth); + engine_, RenderTargetTextureType::kDepthColor, + RenderTargetTextureType::kDepth); depth_target_->Prepare(width, height); } @@ -310,8 +315,6 @@ double FilamentContext::GetFrameRate() const { return 1.0e9 / static_cast(ns); } -void FilamentContext::UpdateGui() { - DrawGui(scene_view_.get()); -} +void FilamentContext::UpdateGui() { DrawGui(scene_view_.get()); } } // namespace mujoco diff --git a/src/experimental/filament/filament/model_util.cc b/src/experimental/filament/filament/model_util.cc index 78fca85c19..62e72d732b 100644 --- a/src/experimental/filament/filament/model_util.cc +++ b/src/experimental/filament/filament/model_util.cc @@ -486,23 +486,4 @@ filament::IndexBuffer* CreateIndexBuffer(filament::Engine* engine, FillSequence); } } - -filament::Texture* CreateTexture(filament::Engine* engine, const mjModel* model, - int id, TextureType texture_type) { - if (id < 0 || id >= model->ntex) { - mju_error("Invalid texture index %d", id); - } - - const int width = model->tex_width[id]; - const int height = model->tex_height[id]; - const bool is_srgb = model->tex_colorspace[id] == mjCOLORSPACE_SRGB; - const int num_channels = model->tex_nchannel[id]; - const mjtByte* data = model->tex_data + model->tex_adr[id]; - filament::Texture* texture = - texture_type == TextureType::kNormal2d - ? Create2dTexture(engine, width, height, num_channels, data, is_srgb) - : CreateCubeTexture(engine, width, height, num_channels, data, - is_srgb); - return texture; -} } // namespace mujoco diff --git a/src/experimental/filament/filament/model_util.h b/src/experimental/filament/filament/model_util.h index 571716741f..edf14fedd0 100644 --- a/src/experimental/filament/filament/model_util.h +++ b/src/experimental/filament/filament/model_util.h @@ -37,12 +37,6 @@ enum class MeshType { kHeightField, }; -// The types of textures stored in the mjModel. -enum class TextureType { - kNormal2d, - kCube, -}; - // Generates a filament VertexBuffer for a given mesh in the mjModel. filament::VertexBuffer* CreateVertexBuffer(filament::Engine* engine, const mjModel* model, int id, @@ -54,10 +48,6 @@ filament::IndexBuffer* CreateIndexBuffer(filament::Engine* engine, const mjModel* model, int id, MeshType mesh_type); -// Generates a filament Texture for a given 2D texture in the mjModel. -filament::Texture* CreateTexture(filament::Engine* engine, const mjModel* model, - int id, TextureType texture_type); - // Reads a value with the given name from the mjModel's data sections. The // default_value is returned if the named element is not found. template diff --git a/src/experimental/filament/filament/render_target_util.cc b/src/experimental/filament/filament/render_target_util.cc index 52cbc25cbc..306bb258cd 100644 --- a/src/experimental/filament/filament/render_target_util.cc +++ b/src/experimental/filament/filament/render_target_util.cc @@ -21,39 +21,7 @@ namespace mujoco { -static filament::Texture* CreateRenderTargetTexture( - filament::Engine* engine, int width, int height, - RenderTargetTextureType type) { - filament::Texture::Builder builder; - builder.width(width); - builder.height(height); - switch (type) { - case kRenderTargetColor: - builder.usage(filament::Texture::Usage::COLOR_ATTACHMENT | - filament::Texture::Usage::BLIT_SRC); - builder.format(filament::Texture::InternalFormat::RGB8); - break; - case kRenderTargetDepth: - builder.usage(filament::Texture::Usage::DEPTH_ATTACHMENT | - filament::Texture::Usage::SAMPLEABLE); - builder.format(filament::Texture::InternalFormat::DEPTH32F); - break; - case kRenderTargetDepthColor: - builder.usage(filament::Texture::Usage::COLOR_ATTACHMENT | - filament::Texture::Usage::BLIT_SRC); - builder.format(filament::Texture::InternalFormat::R32F); - break; - case kRenderTargetReflectionColor: - builder.usage(filament::Texture::Usage::COLOR_ATTACHMENT | - filament::Texture::Usage::BLIT_SRC | - filament::Texture::Usage::SAMPLEABLE); - builder.format(filament::Texture::InternalFormat::RGBA8); - break; - default: - mju_error("Unknown type: %d", static_cast(type)); - } - return builder.build(*engine); -} + RenderTargetAndTextures::RenderTargetAndTextures(filament::Engine* engine, RenderTargetTextureType color, diff --git a/src/experimental/filament/filament/render_target_util.h b/src/experimental/filament/filament/render_target_util.h index e8dfb9392e..c7651741e5 100644 --- a/src/experimental/filament/filament/render_target_util.h +++ b/src/experimental/filament/filament/render_target_util.h @@ -17,19 +17,10 @@ #include #include +#include "experimental/filament/filament/texture_util.h" namespace mujoco { -// The different types of textures we can create for a render target. -enum RenderTargetTextureType { - kRenderTargetNone, - kRenderTargetColor, - kRenderTargetDepth, - kRenderTargetDepthColor, - kRenderTargetReflectionColor, - kNumRenderTargetTextureTypes, -}; - // Manages a filament RenderTarget and the textures which are bound to it. class RenderTargetAndTextures { public: @@ -63,8 +54,8 @@ class RenderTargetAndTextures { filament::Texture* color_texture_ = nullptr; filament::Texture* depth_texture_ = nullptr; filament::RenderTarget* render_target_ = nullptr; - RenderTargetTextureType color_type_ = kRenderTargetNone; - RenderTargetTextureType depth_type_ = kRenderTargetNone; + RenderTargetTextureType color_type_; + RenderTargetTextureType depth_type_; int width_ = 0; int height_ = 0; }; diff --git a/src/experimental/filament/filament/scene_view.cc b/src/experimental/filament/filament/scene_view.cc index aba4e0b8de..9b64243e17 100644 --- a/src/experimental/filament/filament/scene_view.cc +++ b/src/experimental/filament/filament/scene_view.cc @@ -50,6 +50,7 @@ #include "experimental/filament/filament/model_util.h" #include "experimental/filament/filament/object_manager.h" #include "experimental/filament/filament/render_target_util.h" +#include "experimental/filament/filament/texture_util.h" namespace mujoco { @@ -516,7 +517,8 @@ void SceneView::AddReflectiveDrawable(Drawable* drawable) { filament::Engine* engine = object_mgr_->GetEngine(); while (reflect_targets_.size() < reflectives_.size()) { reflect_targets_.push_back(std::make_unique( - engine, kRenderTargetReflectionColor, kRenderTargetDepth)); + engine, RenderTargetTextureType::kReflectionColor, + RenderTargetTextureType::kDepth)); } // Prepare a render target for the reflective drawable. diff --git a/src/experimental/filament/filament/texture_util.cc b/src/experimental/filament/filament/texture_util.cc index 1cf5567c1c..c003f4032f 100644 --- a/src/experimental/filament/filament/texture_util.cc +++ b/src/experimental/filament/filament/texture_util.cc @@ -26,7 +26,6 @@ #include #include - namespace mujoco { static filament::Texture::Format GetTextureFormat(int num_channels) { @@ -168,6 +167,40 @@ filament::Texture* CreateCubeTexture(filament::Engine* engine, int width, return texture; } +filament::Texture* CreateRenderTargetTexture( + filament::Engine* engine, int width, int height, + RenderTargetTextureType type) { + filament::Texture::Builder builder; + builder.width(width); + builder.height(height); + switch (type) { + case RenderTargetTextureType::kColor: + builder.usage(filament::Texture::Usage::COLOR_ATTACHMENT | + filament::Texture::Usage::BLIT_SRC); + builder.format(filament::Texture::InternalFormat::RGB8); + break; + case RenderTargetTextureType::kDepth: + builder.usage(filament::Texture::Usage::DEPTH_ATTACHMENT | + filament::Texture::Usage::SAMPLEABLE); + builder.format(filament::Texture::InternalFormat::DEPTH32F); + break; + case RenderTargetTextureType::kDepthColor: + builder.usage(filament::Texture::Usage::COLOR_ATTACHMENT | + filament::Texture::Usage::BLIT_SRC); + builder.format(filament::Texture::InternalFormat::R32F); + break; + case RenderTargetTextureType::kReflectionColor: + builder.usage(filament::Texture::Usage::COLOR_ATTACHMENT | + filament::Texture::Usage::BLIT_SRC | + filament::Texture::Usage::SAMPLEABLE); + builder.format(filament::Texture::InternalFormat::RGBA8); + break; + default: + mju_error("Unknown type: %d", static_cast(type)); + } + return builder.build(*engine); +} + filament::Texture* CreateKtxTexture( filament::Engine* engine, const uint8_t* data, int size, filament::math::float3* spherical_harmonics_out) { @@ -178,4 +211,23 @@ filament::Texture* CreateKtxTexture( const bool is_srgb = false; return ktxreader::Ktx1Reader::createTexture(engine, bundle, is_srgb); } + +filament::Texture* CreateTexture(filament::Engine* engine, const mjModel* model, + int id, TextureType texture_type) { + if (id < 0 || id >= model->ntex) { + mju_error("Invalid texture index %d", id); + } + + const int width = model->tex_width[id]; + const int height = model->tex_height[id]; + const bool is_srgb = model->tex_colorspace[id] == mjCOLORSPACE_SRGB; + const int num_channels = model->tex_nchannel[id]; + const mjtByte* data = model->tex_data + model->tex_adr[id]; + filament::Texture* texture = + texture_type == TextureType::kNormal2d + ? Create2dTexture(engine, width, height, num_channels, data, is_srgb) + : CreateCubeTexture(engine, width, height, num_channels, data, + is_srgb); + return texture; +} } // namespace mujoco diff --git a/src/experimental/filament/filament/texture_util.h b/src/experimental/filament/filament/texture_util.h index 3136b81ce3..dd267af8a6 100644 --- a/src/experimental/filament/filament/texture_util.h +++ b/src/experimental/filament/filament/texture_util.h @@ -20,10 +20,26 @@ #include #include #include +#include // Functions for creating filament textures. namespace mujoco { +// The types of textures we can create. +enum class TextureType { + kNormal2d, + kCube, + kKtx, +}; + +// The different types of textures we can create for a render target. +enum class RenderTargetTextureType { + kColor, + kDepth, + kDepthColor, + kReflectionColor, +}; + // Creates a filament Texture for the given 2D texture. filament::Texture* Create2dTexture(filament::Engine* engine, int width, int height, int num_channels, @@ -39,6 +55,15 @@ filament::Texture* CreateKtxTexture( filament::Engine* engine, const uint8_t* data, int size, filament::math::float3* spherical_harmonics_out); +// Creates a filament Texture for the given texture in the mjModel. +filament::Texture* CreateTexture(filament::Engine* engine, const mjModel* model, + int id, TextureType texture_type); + +// Creates a filament Texture for the given render target. +filament::Texture* CreateRenderTargetTexture(filament::Engine* engine, + int width, int height, + RenderTargetTextureType type); + } // namespace mujoco #endif // MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_TEXTURE_UTIL_H_ From 0cebefcc81a214822043bc1e872218af48ece8c2 Mon Sep 17 00:00:00 2001 From: Haroon Qureshi Date: Wed, 1 Apr 2026 03:51:23 -0700 Subject: [PATCH 14/20] Introduce a Texture class that wraps filament::Texture. PiperOrigin-RevId: 892839636 Change-Id: I3c08fba0a514cfb758ec2842d8510c6d88300874 --- .../filament/filament/drawable.cc | 8 +- src/experimental/filament/filament/drawable.h | 3 +- .../filament/filament/material.cc | 85 +++------- src/experimental/filament/filament/material.h | 20 +-- .../filament/filament/model_objects.cc | 64 ++++---- .../filament/filament/model_objects.h | 11 +- .../filament/filament/object_manager.cc | 64 ++++---- .../filament/filament/object_manager.h | 16 +- .../filament/filament/render_target_util.cc | 36 +++-- .../filament/filament/render_target_util.h | 12 +- .../filament/filament/texture_util.cc | 151 +++++++++--------- .../filament/filament/texture_util.h | 59 ++++--- 12 files changed, 253 insertions(+), 276 deletions(-) diff --git a/src/experimental/filament/filament/drawable.cc b/src/experimental/filament/filament/drawable.cc index 30f1b9f00c..5525060016 100644 --- a/src/experimental/filament/filament/drawable.cc +++ b/src/experimental/filament/filament/drawable.cc @@ -37,6 +37,7 @@ #include "experimental/filament/filament/math_util.h" #include "experimental/filament/filament/model_objects.h" #include "experimental/filament/filament/object_manager.h" +#include "experimental/filament/filament/texture_util.h" namespace mujoco { @@ -226,7 +227,7 @@ void Drawable::SetDrawMode(Material::DrawMode mode) { renderables_.SetMaterialInstance(material_.GetMaterialInstance(mode)); } -void Drawable::UpdateReflectionTexture(const filament::Texture* tex) { +void Drawable::UpdateReflectionTexture(const Texture* tex) { material_.UpdateReflectionTexture(tex); } @@ -422,7 +423,7 @@ void Drawable::UpdateMaterial(const mjvGeom& geom, bool use_segid_color, } else { material_.SetNormalMaterialType(ObjectManager::kPhongColor); } - } else if (textures.color->getTarget() == + } else if (textures.color->GetFilamentTexture()->getTarget() == filament::Texture::Sampler::SAMPLER_CUBEMAP) { if (color.a < 1.0f) { material_.SetNormalMaterialType(ObjectManager::kPhongCubeFade); @@ -490,7 +491,8 @@ void Drawable::UpdateMaterial(const mjvGeom& geom, bool use_segid_color, // the programmatic UVs. if (textures.color) { - if (textures.color->getTarget() == filament::Texture::Sampler::SAMPLER_2D) { + if (textures.color->GetFilamentTexture()->getTarget() == + filament::Texture::Sampler::SAMPLER_2D) { // For 2D textures, `tex_repeat` specifies how many times the texture // image is repeated. The `tex_uniform` flag determines if the repetition // is applied at in object space (false) or in world space (true). diff --git a/src/experimental/filament/filament/drawable.h b/src/experimental/filament/filament/drawable.h index 19002de6c6..06796aed95 100644 --- a/src/experimental/filament/filament/drawable.h +++ b/src/experimental/filament/filament/drawable.h @@ -26,6 +26,7 @@ #include "experimental/filament/filament/model_objects.h" #include "experimental/filament/filament/object_manager.h" #include "experimental/filament/filament/renderables.h" +#include "experimental/filament/filament/texture_util.h" namespace mujoco { @@ -68,7 +69,7 @@ class Drawable { // Sets the reflection texture for the drawable. We have a separate setter // because we need to render the reflection texture before it can be applied // to the material. - void UpdateReflectionTexture(const filament::Texture* tex); + void UpdateReflectionTexture(const Texture* tex); private: void AddMesh(int data_id); diff --git a/src/experimental/filament/filament/material.cc b/src/experimental/filament/filament/material.cc index 08c167a251..e04e3f8149 100644 --- a/src/experimental/filament/filament/material.cc +++ b/src/experimental/filament/filament/material.cc @@ -21,6 +21,7 @@ #include #include #include "experimental/filament/filament/object_manager.h" +#include "experimental/filament/filament/texture_util.h" namespace mujoco { @@ -71,7 +72,7 @@ void Material::UpdateTextures(const Textures& textures) { UpdateMaterialInstances(); } -void Material::UpdateReflectionTexture(const filament::Texture* tex) { +void Material::UpdateReflectionTexture(const Texture* tex) { textures_.reflection = tex; UpdateMaterialInstances(); } @@ -128,70 +129,26 @@ void Material::UpdateMaterialInstances() { sampler.setMinFilter( filament::TextureSampler::MinFilter::LINEAR_MIPMAP_LINEAR); - if (material->hasParameter("BaseColor")) { - if (textures_.color) { - instance->setParameter("BaseColor", textures_.color, sampler); - } else { - auto* fallback = object_mgr_->GetFallbackTexture(mjTEXROLE_RGB); - instance->setParameter("BaseColor", fallback, sampler); + auto TrySetTexture = [&](const char* name, const Texture* texture, + mjtTextureRole role) { + if (material->hasParameter(name)) { + if (texture) { + instance->setParameter(name, texture->GetFilamentTexture(), sampler); + } else { + auto* fallback = object_mgr_->GetFallbackTexture(role); + instance->setParameter(name, fallback->GetFilamentTexture(), sampler); + } } - } - if (material->hasParameter("Normal")) { - if (textures_.normal) { - instance->setParameter("Normal", textures_.normal, sampler); - } else { - auto* fallback = object_mgr_->GetFallbackTexture(mjTEXROLE_NORMAL); - instance->setParameter("Normal", fallback, sampler); - } - } - if (material->hasParameter("Metallic")) { - if (textures_.metallic) { - instance->setParameter("Metallic", textures_.metallic, sampler); - } else { - auto* fallback = object_mgr_->GetFallbackTexture(mjTEXROLE_METALLIC); - instance->setParameter("Metallic", fallback, sampler); - } - } - if (material->hasParameter("Roughness")) { - if (textures_.roughness) { - instance->setParameter("Roughness", textures_.roughness, sampler); - } else { - auto* fallback = object_mgr_->GetFallbackTexture(mjTEXROLE_ROUGHNESS); - instance->setParameter("Roughness", fallback, sampler); - } - } - if (material->hasParameter("Occlusion")) { - if (textures_.occlusion) { - instance->setParameter("Occlusion", textures_.occlusion, sampler); - } else { - auto* fallback = object_mgr_->GetFallbackTexture(mjTEXROLE_OCCLUSION); - instance->setParameter("Occlusion", fallback, sampler); - } - } - if (material->hasParameter("ORM")) { - if (textures_.orm) { - instance->setParameter("ORM", textures_.orm, sampler); - } else { - auto* fallback = object_mgr_->GetFallbackTexture(mjTEXROLE_ORM); - instance->setParameter("ORM", fallback, sampler); - } - } - if (material->hasParameter("Emissive")) { - if (textures_.emissive) { - instance->setParameter("Emissive", textures_.emissive, sampler); - } else { - auto* fallback = object_mgr_->GetFallbackTexture(mjTEXROLE_EMISSIVE); - instance->setParameter("Emissive", fallback, sampler); - } - } - if (material->hasParameter("Reflection")) { - if (textures_.reflection) { - instance->setParameter("Reflection", textures_.reflection, sampler); - } else { - auto* fallback = object_mgr_->GetFallbackTexture(mjTEXROLE_USER); - instance->setParameter("Reflection", fallback, sampler); - } - } + }; + + TrySetTexture("BaseColor", textures_.color, mjTEXROLE_RGB); + TrySetTexture("Normal", textures_.normal, mjTEXROLE_NORMAL); + TrySetTexture("Metallic", textures_.metallic, mjTEXROLE_METALLIC); + TrySetTexture("Roughness", textures_.roughness, mjTEXROLE_ROUGHNESS); + TrySetTexture("Occlusion", textures_.occlusion, mjTEXROLE_OCCLUSION); + TrySetTexture("ORM", textures_.orm, mjTEXROLE_ORM); + TrySetTexture("Emissive", textures_.emissive, mjTEXROLE_EMISSIVE); + TrySetTexture("Reflection", textures_.reflection, mjTEXROLE_USER); } } // namespace mujoco diff --git a/src/experimental/filament/filament/material.h b/src/experimental/filament/filament/material.h index 51ccac7126..849cb89e8f 100644 --- a/src/experimental/filament/filament/material.h +++ b/src/experimental/filament/filament/material.h @@ -17,11 +17,11 @@ #include #include -#include #include #include #include #include "experimental/filament/filament/object_manager.h" +#include "experimental/filament/filament/texture_util.h" namespace mujoco { @@ -39,14 +39,14 @@ class Material { // The textures that can be assigned to the drawable's material. struct Textures { - const filament::Texture* color = nullptr; - const filament::Texture* normal = nullptr; - const filament::Texture* metallic = nullptr; - const filament::Texture* roughness = nullptr; - const filament::Texture* occlusion = nullptr; - const filament::Texture* orm = nullptr; - const filament::Texture* emissive = nullptr; - const filament::Texture* reflection = nullptr; + const Texture* color = nullptr; + const Texture* normal = nullptr; + const Texture* metallic = nullptr; + const Texture* roughness = nullptr; + const Texture* occlusion = nullptr; + const Texture* orm = nullptr; + const Texture* emissive = nullptr; + const Texture* reflection = nullptr; }; // The parameters that can be applied to the drawable's material. @@ -82,7 +82,7 @@ class Material { // Update the reflection texture. We do this separately since the reflection // texture needs to be rendered before it can be applied to the material. - void UpdateReflectionTexture(const filament::Texture* tex); + void UpdateReflectionTexture(const Texture* tex); // Returns the material instance assigned to the draw mode. filament::MaterialInstance* GetMaterialInstance(DrawMode mode) { diff --git a/src/experimental/filament/filament/model_objects.cc b/src/experimental/filament/filament/model_objects.cc index 217648ae07..0529d90e60 100644 --- a/src/experimental/filament/filament/model_objects.cc +++ b/src/experimental/filament/filament/model_objects.cc @@ -15,6 +15,7 @@ #include "experimental/filament/filament/model_objects.h" #include +#include #include #include @@ -80,9 +81,7 @@ ModelObjects::~ModelObjects() { engine_->destroy(iter.vertex_buffer); engine_->destroy(iter.index_buffer); } - for (auto& iter : textures_) { - engine_->destroy(iter.second); - } + textures_.clear(); } void ModelObjects::UploadMesh(const mjModel* model, int id) { @@ -126,25 +125,30 @@ void ModelObjects::UploadTexture(const mjModel* model, int id) { mju_error("Invalid texture index: %d", id); } - if (auto iter = textures_.find(id); iter != textures_.end()) { - engine_->destroy(iter->second); - } + const int width = model->tex_width[id]; + const int height = model->tex_height[id]; + const int num_channels = model->tex_nchannel[id]; + const int tex_type = model->tex_type[id]; + const mjtByte* data = model->tex_data + model->tex_adr[id]; + const mjtColorSpace color_space = (mjtColorSpace)model->tex_colorspace[id]; - const int texture_type = model->tex_type[id]; - if (model->tex_height[id] == 1) { - const mjtByte* bytes = model->tex_data + model->tex_adr[id]; - const int num_bytes = model->tex_width[id]; - textures_[id] = - CreateKtxTexture(engine_, bytes, num_bytes, spherical_harmonics_[id]); - } else if (texture_type == mjTEXTURE_2D) { - textures_[id] = CreateTexture(engine_, model, id, TextureType::kNormal2d); - } else if (texture_type == mjTEXTURE_CUBE) { - textures_[id] = CreateTexture(engine_, model, id, TextureType::kCube); - } else if (texture_type == mjTEXTURE_SKYBOX) { - textures_[id] = CreateTexture(engine_, model, id, TextureType::kCube); - } else { - mju_error("Unsupported: Texture type: %d", texture_type); - } + const TextureType type = [&] { + if (height == 1) { + return TextureType::kKtx; + } else if (tex_type == mjTEXTURE_2D) { + return TextureType::kNormal2d; + } else if (tex_type == mjTEXTURE_CUBE) { + return TextureType::kCube; + } else if (tex_type == mjTEXTURE_SKYBOX) { + return TextureType::kCube; + } else { + mju_error("Unsupported texture type: %d", tex_type); + return TextureType::kNormal2d; + } + }(); + + textures_[id] = std::make_unique(engine_, type, color_space, width, + height, num_channels, data); } void ModelObjects::UploadHeightField(const mjModel* model, int id) { @@ -194,12 +198,12 @@ const FilamentBuffers* ModelObjects::GetShapeBuffer(ShapeType shape) const { return &shapes_[shape]; } -const filament::Texture* ModelObjects::GetTexture(int tex_id) const { +const Texture* ModelObjects::GetTexture(int tex_id) const { auto it = textures_.find(tex_id); - return it != textures_.end() ? it->second : nullptr; + return it != textures_.end() ? it->second.get() : nullptr; } -const filament::Texture* ModelObjects::GetTexture(int mat_id, int role) const { +const Texture* ModelObjects::GetTexture(int mat_id, int role) const { if (mat_id < 0 || mat_id >= model_->nmat || role < 0 || role >= mjNTEXROLE) { return nullptr; } @@ -210,15 +214,11 @@ const filament::Texture* ModelObjects::GetTexture(int mat_id, int role) const { filament::IndirectLight* ModelObjects::CreateIndirectLight(int tex_id, float intensity) { filament::Texture* texture = nullptr; + const Texture::SphericalHarmonics* spherical_harmonics = nullptr; auto texture_iter = textures_.find(tex_id); if (texture_iter != textures_.end()) { - texture = texture_iter->second; - } - - SphericalHarmonics* spherical_harmonics = nullptr; - auto sh_iter = spherical_harmonics_.find(tex_id); - if (sh_iter != spherical_harmonics_.end()) { - spherical_harmonics = &sh_iter->second; + texture = texture_iter->second->GetFilamentTexture(); + spherical_harmonics = texture_iter->second->GetSphericalHarmonics(); } filament::IndirectLight::Builder builder; @@ -240,7 +240,7 @@ filament::Skybox* ModelObjects::CreateSkybox() { for (auto& iter : textures_) { const int texture_type = model_->tex_type[iter.first]; if (texture_type == mjTEXTURE_SKYBOX) { - skybox_texture = iter.second; + skybox_texture = iter.second->GetFilamentTexture(); break; } } diff --git a/src/experimental/filament/filament/model_objects.h b/src/experimental/filament/filament/model_objects.h index 5de28f8ab3..94fc298780 100644 --- a/src/experimental/filament/filament/model_objects.h +++ b/src/experimental/filament/filament/model_objects.h @@ -16,6 +16,7 @@ #define MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_MODEL_OBJECTS_H_ #include +#include #include #include @@ -25,6 +26,7 @@ #include #include #include "experimental/filament/filament/buffer_util.h" +#include "experimental/filament/filament/texture_util.h" namespace mujoco { @@ -62,8 +64,8 @@ class ModelObjects { const FilamentBuffers* GetShapeBuffer(ShapeType shape) const; const FilamentBuffers* GetMeshBuffer(int data_id) const; const FilamentBuffers* GetHeightFieldBuffer(int hfield_id) const; - const filament::Texture* GetTexture(int tex_id) const; - const filament::Texture* GetTexture(int mat_id, int role) const; + const Texture* GetTexture(int tex_id) const; + const Texture* GetTexture(int mat_id, int role) const; filament::Skybox* CreateSkybox(); filament::IndirectLight* CreateIndirectLight(int tex_id, float intensity); @@ -78,8 +80,6 @@ class ModelObjects { ModelObjects& operator=(const ModelObjects&) = delete; private: - using SphericalHarmonics = filament::math::float3[9]; - const mjModel* model_ = nullptr; filament::Engine* engine_ = nullptr; std::vector skyboxes_; @@ -88,8 +88,7 @@ class ModelObjects { std::unordered_map meshes_; std::unordered_map convex_hulls_; std::unordered_map height_fields_; - std::unordered_map textures_; - std::unordered_map spherical_harmonics_; + std::unordered_map> textures_; float specular_multiplier_ = 0.2f; float shininess_multiplier_ = 0.1f; float emissive_multiplier_ = 0.3f; diff --git a/src/experimental/filament/filament/object_manager.cc b/src/experimental/filament/filament/object_manager.cc index 4bf5a0cd02..7699e65547 100644 --- a/src/experimental/filament/filament/object_manager.cc +++ b/src/experimental/filament/filament/object_manager.cc @@ -15,6 +15,7 @@ #include "experimental/filament/filament/object_manager.h" #include +#include #include #include @@ -86,22 +87,27 @@ ObjectManager::ObjectManager(filament::Engine* engine) materials_[kUnlitUi] = LoadMaterial("unlit_ui.filamat"); static uint8_t black_rgb[3] = {0, 0, 0}; - fallback_black_ = Create2dTexture(engine_, 1, 1, 3, black_rgb, false); + fallback_black_ = std::make_unique( + engine_, TextureType::kNormal2d, mjCOLORSPACE_LINEAR, 1, 1, 3, black_rgb); static uint8_t white_rgb[3] = {255, 255, 255}; - fallback_white_ = Create2dTexture(engine_, 1, 1, 3, white_rgb, false); + fallback_white_ = std::make_unique( + engine_, TextureType::kNormal2d, mjCOLORSPACE_LINEAR, 1, 1, 3, white_rgb); static uint8_t normal_data[3] = {128, 128, 255}; - fallback_normal_ = Create2dTexture(engine_, 1, 1, 3, normal_data, false); + fallback_normal_ = + std::make_unique(engine_, TextureType::kNormal2d, + mjCOLORSPACE_LINEAR, 1, 1, 3, normal_data); static uint8_t orm_data[3] = {0, 255, 0}; - fallback_orm_ = Create2dTexture(engine_, 1, 1, 3, orm_data, false); - - fallback_textures_[mjTEXROLE_USER] = fallback_black_; - fallback_textures_[mjTEXROLE_RGB] = fallback_white_; - fallback_textures_[mjTEXROLE_OCCLUSION] = fallback_white_; - fallback_textures_[mjTEXROLE_ROUGHNESS] = fallback_white_; - fallback_textures_[mjTEXROLE_METALLIC] = fallback_black_; - fallback_textures_[mjTEXROLE_NORMAL] = fallback_normal_; - fallback_textures_[mjTEXROLE_EMISSIVE] = fallback_black_; - fallback_textures_[mjTEXROLE_ORM] = fallback_orm_; + fallback_orm_ = std::make_unique( + engine_, TextureType::kNormal2d, mjCOLORSPACE_LINEAR, 1, 1, 3, orm_data); + + fallback_textures_[mjTEXROLE_USER] = fallback_black_.get(); + fallback_textures_[mjTEXROLE_RGB] = fallback_white_.get(); + fallback_textures_[mjTEXROLE_OCCLUSION] = fallback_white_.get(); + fallback_textures_[mjTEXROLE_ROUGHNESS] = fallback_white_.get(); + fallback_textures_[mjTEXROLE_METALLIC] = fallback_black_.get(); + fallback_textures_[mjTEXROLE_NORMAL] = fallback_normal_.get(); + fallback_textures_[mjTEXROLE_EMISSIVE] = fallback_black_.get(); + fallback_textures_[mjTEXROLE_ORM] = fallback_orm_.get(); LoadFallbackIndirectLight("ibl.ktx", 1.0f); } @@ -110,17 +116,10 @@ ObjectManager::~ObjectManager() { if (fallback_indirect_light_) { engine_->destroy(fallback_indirect_light_); } - if (fallback_indirect_light_texture_) { - engine_->destroy(fallback_indirect_light_texture_); - } + fallback_indirect_light_texture_.reset(); for (auto& iter : materials_) { engine_->destroy(iter); } - // fallback_textures_ maps to these textures. - engine_->destroy(fallback_white_); - engine_->destroy(fallback_black_); - engine_->destroy(fallback_normal_); - engine_->destroy(fallback_orm_); } filament::Material* ObjectManager::GetMaterial(MaterialType type) const { @@ -130,7 +129,7 @@ filament::Material* ObjectManager::GetMaterial(MaterialType type) const { return materials_[type]; } -const filament::Texture* ObjectManager::GetFallbackTexture( +const Texture* ObjectManager::GetFallbackTexture( mjtTextureRole role) const { if (role < 0 || role >= mjNTEXROLE) { mju_error("Invalid texture role: %d", role); @@ -144,10 +143,7 @@ filament::IndirectLight* ObjectManager::GetFallbackIndirectLight() { void ObjectManager::LoadFallbackIndirectLight( std::string_view filename, float intensity) { - if (fallback_indirect_light_texture_ != nullptr) { - engine_->destroy(fallback_indirect_light_texture_); - fallback_indirect_light_texture_ = nullptr; - } + fallback_indirect_light_texture_.reset(); if (fallback_indirect_light_ != nullptr) { engine_->destroy(fallback_indirect_light_); fallback_indirect_light_ = nullptr; @@ -158,18 +154,22 @@ void ObjectManager::LoadFallbackIndirectLight( return; } - filament::math::float3 spherical_harmonics[9]; - fallback_indirect_light_texture_ = - CreateKtxTexture(engine_, reinterpret_cast(asset.payload), - asset.size, spherical_harmonics); + fallback_indirect_light_texture_ = std::make_unique( + engine_, TextureType::kKtx, mjCOLORSPACE_AUTO, asset.size, 1, 1, + reinterpret_cast(asset.payload)); if (fallback_indirect_light_texture_ == nullptr) { return; } + const Texture::SphericalHarmonics* spherical_harmonics = + fallback_indirect_light_texture_->GetSphericalHarmonics(); + // Build the indirect light. filament::IndirectLight::Builder builder; - builder.reflections(fallback_indirect_light_texture_); - builder.irradiance(3, spherical_harmonics); + builder.reflections(fallback_indirect_light_texture_->GetFilamentTexture()); + if (spherical_harmonics) { + builder.irradiance(3, *spherical_harmonics); + } builder.intensity(intensity); // Rotate the light to match mujoco's Z-up convention. builder.rotation(filament::math::mat3f::rotation( diff --git a/src/experimental/filament/filament/object_manager.h b/src/experimental/filament/filament/object_manager.h index 37459b4d41..64d9eadf73 100644 --- a/src/experimental/filament/filament/object_manager.h +++ b/src/experimental/filament/filament/object_manager.h @@ -16,12 +16,14 @@ #define MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_OBJECT_MANAGER_H_ #include +#include #include #include #include #include #include +#include "experimental/filament/filament/texture_util.h" namespace mujoco { @@ -60,7 +62,7 @@ class ObjectManager { filament::Material* GetMaterial(MaterialType type) const; // Returns the fallback Texture with the given role. - const filament::Texture* GetFallbackTexture(mjtTextureRole role) const; + const Texture* GetFallbackTexture(mjtTextureRole role) const; // Returns the fallback IndirectLight. filament::IndirectLight* GetFallbackIndirectLight(); @@ -74,12 +76,12 @@ class ObjectManager { private: filament::Engine* engine_ = nullptr; std::array materials_; - std::array fallback_textures_; - filament::Texture* fallback_white_ = nullptr; - filament::Texture* fallback_black_ = nullptr; - filament::Texture* fallback_normal_ = nullptr; - filament::Texture* fallback_orm_ = nullptr; - filament::Texture* fallback_indirect_light_texture_ = nullptr; + std::array fallback_textures_; + std::unique_ptr fallback_white_ = nullptr; + std::unique_ptr fallback_black_ = nullptr; + std::unique_ptr fallback_normal_ = nullptr; + std::unique_ptr fallback_orm_ = nullptr; + std::unique_ptr fallback_indirect_light_texture_ = nullptr; filament::IndirectLight* fallback_indirect_light_ = nullptr; }; diff --git a/src/experimental/filament/filament/render_target_util.cc b/src/experimental/filament/filament/render_target_util.cc index 306bb258cd..ef221e4ef9 100644 --- a/src/experimental/filament/filament/render_target_util.cc +++ b/src/experimental/filament/filament/render_target_util.cc @@ -14,15 +14,15 @@ #include "experimental/filament/filament/render_target_util.h" +#include + #include #include #include -#include +#include "experimental/filament/filament/texture_util.h" namespace mujoco { - - RenderTargetAndTextures::RenderTargetAndTextures(filament::Engine* engine, RenderTargetTextureType color, RenderTargetTextureType depth) @@ -41,15 +41,15 @@ void RenderTargetAndTextures::Prepare(int width, int height) { height_ = height; color_texture_ = - CreateRenderTargetTexture(engine_, width, height, color_type_); + std::make_unique(engine_, color_type_, width, height); depth_texture_ = - CreateRenderTargetTexture(engine_, width, height, depth_type_); + std::make_unique(engine_, depth_type_, width, height); filament::RenderTarget::Builder builder; builder.texture(filament::RenderTarget::AttachmentPoint::COLOR, - color_texture_); + color_texture_->GetFilamentTexture()); builder.texture(filament::RenderTarget::AttachmentPoint::DEPTH, - depth_texture_); + depth_texture_->GetFilamentTexture()); render_target_ = builder.build(*engine_); } @@ -58,14 +58,20 @@ void RenderTargetAndTextures::Destroy() { engine_->destroy(render_target_); render_target_ = nullptr; } - if (color_texture_) { - engine_->destroy(color_texture_); - color_texture_ = nullptr; - } - if (depth_texture_) { - engine_->destroy(depth_texture_); - depth_texture_ = nullptr; - } + color_texture_.reset(); + depth_texture_.reset(); +} + +Texture* RenderTargetAndTextures::GetColorTexture() const { + return color_texture_.get(); +} + +Texture* RenderTargetAndTextures::GetDepthTexture() const { + return depth_texture_.get(); +} + +filament::RenderTarget* RenderTargetAndTextures::GetRenderTarget() const { + return render_target_; } } // namespace mujoco diff --git a/src/experimental/filament/filament/render_target_util.h b/src/experimental/filament/filament/render_target_util.h index c7651741e5..d2d581a96e 100644 --- a/src/experimental/filament/filament/render_target_util.h +++ b/src/experimental/filament/filament/render_target_util.h @@ -15,6 +15,8 @@ #ifndef MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_RENDER_TARGET_UTIL_H_ #define MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_RENDER_TARGET_UTIL_H_ +#include + #include #include #include "experimental/filament/filament/texture_util.h" @@ -39,21 +41,21 @@ class RenderTargetAndTextures { void Prepare(int width, int height); // Returns the color texture. - filament::Texture* GetColorTexture() const { return color_texture_; } + Texture* GetColorTexture() const; // Returns the depth texture. - filament::Texture* GetDepthTexture() const { return depth_texture_; } + Texture* GetDepthTexture() const; // Returns the render target. - filament::RenderTarget* GetRenderTarget() const { return render_target_; } + filament::RenderTarget* GetRenderTarget() const; private: void Destroy(); filament::Engine* engine_ = nullptr; - filament::Texture* color_texture_ = nullptr; - filament::Texture* depth_texture_ = nullptr; filament::RenderTarget* render_target_ = nullptr; + std::unique_ptr color_texture_ = nullptr; + std::unique_ptr depth_texture_ = nullptr; RenderTargetTextureType color_type_; RenderTargetTextureType depth_type_; int width_ = 0; diff --git a/src/experimental/filament/filament/texture_util.cc b/src/experimental/filament/filament/texture_util.cc index c003f4032f..20b633934a 100644 --- a/src/experimental/filament/filament/texture_util.cc +++ b/src/experimental/filament/filament/texture_util.cc @@ -23,7 +23,6 @@ #include #include #include -#include #include namespace mujoco { @@ -69,12 +68,60 @@ static filament::Texture::InternalFormat GetTextureInternalFormat( } } -filament::Texture* Create2dTexture(filament::Engine* engine, int width, - int height, int num_channels, - const uint8_t* data, bool is_srgb) { +Texture::Texture(filament::Engine* engine, TextureType texture_type, + mjtColorSpace color_space, int width, int height, + int num_channels, const uint8_t* data) + : engine_(engine) { + const bool is_srgb = color_space == mjCOLORSPACE_SRGB; + if (texture_type == TextureType::kCube) { + CreateCubeTexture(width, height, num_channels, data, is_srgb); + } else if (texture_type == TextureType::kNormal2d) { + Create2dTexture(width, height, num_channels, data, is_srgb); + } else if (texture_type == TextureType::kKtx) { + CreateKtxTexture(data, width * height * num_channels); + } else { + mju_error("Unsupported texture type: %d", static_cast(texture_type)); + } +} + +Texture::Texture(filament::Engine* engine, RenderTargetTextureType type, + int width, int height) : engine_(engine) { + filament::Texture::Builder builder; + builder.width(width); + builder.height(height); + switch (type) { + case RenderTargetTextureType::kColor: + builder.usage(filament::Texture::Usage::COLOR_ATTACHMENT | + filament::Texture::Usage::BLIT_SRC); + builder.format(filament::Texture::InternalFormat::RGB8); + break; + case RenderTargetTextureType::kDepth: + builder.usage(filament::Texture::Usage::DEPTH_ATTACHMENT | + filament::Texture::Usage::SAMPLEABLE); + builder.format(filament::Texture::InternalFormat::DEPTH32F); + break; + case RenderTargetTextureType::kDepthColor: + builder.usage(filament::Texture::Usage::COLOR_ATTACHMENT | + filament::Texture::Usage::BLIT_SRC); + builder.format(filament::Texture::InternalFormat::R32F); + break; + case RenderTargetTextureType::kReflectionColor: + builder.usage(filament::Texture::Usage::COLOR_ATTACHMENT | + filament::Texture::Usage::BLIT_SRC | + filament::Texture::Usage::SAMPLEABLE); + builder.format(filament::Texture::InternalFormat::RGBA8); + break; + default: + mju_error("Unknown type: %d", static_cast(type)); + } + texture_ = builder.build(*engine); +} + +void Texture::Create2dTexture(int width, int height, int num_channels, + const uint8_t* data, bool is_srgb) { if (num_channels != 1 && num_channels != 3 && num_channels != 4) { mju_error("Unsupported number of channels: %d", num_channels); - return nullptr; + return; } filament::Texture::Builder builder; @@ -87,28 +134,26 @@ filament::Texture* Create2dTexture(filament::Engine* engine, int width, filament::Texture::Usage::SAMPLEABLE | filament::Texture::Usage::UPLOADABLE); } - filament::Texture* texture = builder.build(*engine); + texture_ = builder.build(*engine_); if (data) { const size_t num_bytes = width * height * sizeof(uint8_t) * num_channels; const filament::Texture::Format format = GetTextureFormat(num_channels); - texture->setImage( - *engine, 0, + texture_->setImage( + *engine_, 0, filament::Texture::PixelBufferDescriptor( data, num_bytes, format, filament::Texture::Type::UBYTE)); if (!is_srgb) { - texture->generateMipmaps(*engine); + texture_->generateMipmaps(*engine_); } } - return texture; } -filament::Texture* CreateCubeTexture(filament::Engine* engine, int width, - int height, int num_channels, - const uint8_t* data, bool is_srgb) { +void Texture::CreateCubeTexture(int width, int height, int num_channels, + const uint8_t* data, bool is_srgb) { if (num_channels != 3) { mju_error("Only support RGB cubemaps."); - return nullptr; + return; } const int kNumFacesPerCube = 6; @@ -116,7 +161,7 @@ filament::Texture* CreateCubeTexture(filament::Engine* engine, int width, int face_height = height; if (width != height) { if (width * kNumFacesPerCube != height) { - mju_error("Cube maps must contain 6 square images."); + mju_error("Cube maps must contain 6 square images."); } face_height = height / kNumFacesPerCube; } @@ -134,7 +179,7 @@ filament::Texture* CreateCubeTexture(filament::Engine* engine, int width, filament::Texture::Usage::SAMPLEABLE | filament::Texture::Usage::UPLOADABLE); } - filament::Texture* texture = builder.build(*engine); + texture_ = builder.build(*engine_); const int face_size = width * face_height * num_channels; const int num_bytes = face_size * kNumFacesPerCube; @@ -157,77 +202,27 @@ filament::Texture* CreateCubeTexture(filament::Engine* engine, int width, if (data) { filament::Texture::PixelBufferDescriptor desc( - buffer, num_bytes, filament::Texture::Format::RGB, - filament::Texture::Type::UBYTE, callback); - texture->setImage(*engine, 0, std::move(desc), offsets); + buffer, num_bytes, filament::Texture::Format::RGB, + filament::Texture::Type::UBYTE, callback); + texture_->setImage(*engine_, 0, std::move(desc), offsets); if (!is_srgb) { - texture->generateMipmaps(*engine); + texture_->generateMipmaps(*engine_); } } - return texture; } -filament::Texture* CreateRenderTargetTexture( - filament::Engine* engine, int width, int height, - RenderTargetTextureType type) { - filament::Texture::Builder builder; - builder.width(width); - builder.height(height); - switch (type) { - case RenderTargetTextureType::kColor: - builder.usage(filament::Texture::Usage::COLOR_ATTACHMENT | - filament::Texture::Usage::BLIT_SRC); - builder.format(filament::Texture::InternalFormat::RGB8); - break; - case RenderTargetTextureType::kDepth: - builder.usage(filament::Texture::Usage::DEPTH_ATTACHMENT | - filament::Texture::Usage::SAMPLEABLE); - builder.format(filament::Texture::InternalFormat::DEPTH32F); - break; - case RenderTargetTextureType::kDepthColor: - builder.usage(filament::Texture::Usage::COLOR_ATTACHMENT | - filament::Texture::Usage::BLIT_SRC); - builder.format(filament::Texture::InternalFormat::R32F); - break; - case RenderTargetTextureType::kReflectionColor: - builder.usage(filament::Texture::Usage::COLOR_ATTACHMENT | - filament::Texture::Usage::BLIT_SRC | - filament::Texture::Usage::SAMPLEABLE); - builder.format(filament::Texture::InternalFormat::RGBA8); - break; - default: - mju_error("Unknown type: %d", static_cast(type)); - } - return builder.build(*engine); -} - -filament::Texture* CreateKtxTexture( - filament::Engine* engine, const uint8_t* data, int size, - filament::math::float3* spherical_harmonics_out) { +void Texture::CreateKtxTexture(const uint8_t* data, int size) { image::Ktx1Bundle* bundle = new image::Ktx1Bundle(data, size); - if (spherical_harmonics_out) { - bundle->getSphericalHarmonics(spherical_harmonics_out); - } + has_spherical_harmonics_ = true; + bundle->getSphericalHarmonics(spherical_harmonics_); const bool is_srgb = false; - return ktxreader::Ktx1Reader::createTexture(engine, bundle, is_srgb); + texture_ = ktxreader::Ktx1Reader::createTexture(engine_, bundle, is_srgb); } -filament::Texture* CreateTexture(filament::Engine* engine, const mjModel* model, - int id, TextureType texture_type) { - if (id < 0 || id >= model->ntex) { - mju_error("Invalid texture index %d", id); +Texture::~Texture() { + if (texture_) { + engine_->destroy(texture_); } - - const int width = model->tex_width[id]; - const int height = model->tex_height[id]; - const bool is_srgb = model->tex_colorspace[id] == mjCOLORSPACE_SRGB; - const int num_channels = model->tex_nchannel[id]; - const mjtByte* data = model->tex_data + model->tex_adr[id]; - filament::Texture* texture = - texture_type == TextureType::kNormal2d - ? Create2dTexture(engine, width, height, num_channels, data, is_srgb) - : CreateCubeTexture(engine, width, height, num_channels, data, - is_srgb); - return texture; } + } // namespace mujoco diff --git a/src/experimental/filament/filament/texture_util.h b/src/experimental/filament/filament/texture_util.h index dd267af8a6..42925325e0 100644 --- a/src/experimental/filament/filament/texture_util.h +++ b/src/experimental/filament/filament/texture_util.h @@ -40,30 +40,43 @@ enum class RenderTargetTextureType { kReflectionColor, }; -// Creates a filament Texture for the given 2D texture. -filament::Texture* Create2dTexture(filament::Engine* engine, int width, - int height, int num_channels, - const uint8_t* data, bool is_srgb); - -// Creates a filament Texture for the given cube texture. -filament::Texture* CreateCubeTexture(filament::Engine* engine, int width, - int height, int num_channels, - const uint8_t* data, bool is_srgb); - -// Creates a filament Texture for the given KTX payload. -filament::Texture* CreateKtxTexture( - filament::Engine* engine, const uint8_t* data, int size, - filament::math::float3* spherical_harmonics_out); - -// Creates a filament Texture for the given texture in the mjModel. -filament::Texture* CreateTexture(filament::Engine* engine, const mjModel* model, - int id, TextureType texture_type); - -// Creates a filament Texture for the given render target. -filament::Texture* CreateRenderTargetTexture(filament::Engine* engine, - int width, int height, - RenderTargetTextureType type); +class Texture { + public: + // Creates a texture with the given data. + Texture(filament::Engine* engine, TextureType texture_type, + mjtColorSpace color_space, int width, int height, int num_channels, + const uint8_t* data); + // Creates a texture for use with a render target. + Texture(filament::Engine* engine, RenderTargetTextureType type, int width, + int height); + + ~Texture(); + + filament::Texture* GetFilamentTexture() const { return texture_; } + + using SphericalHarmonics = filament::math::float3[9]; + + const SphericalHarmonics* GetSphericalHarmonics() const { + return has_spherical_harmonics_ ? &spherical_harmonics_ : nullptr; + } + + Texture(const Texture&) = delete; + Texture& operator=(const Texture&) = delete; + + private: + + void Create2dTexture(int width, int height, int num_channels, + const uint8_t* data, bool is_srgb); + void CreateCubeTexture(int width, int height, int num_channels, + const uint8_t* data, bool is_srgb); + void CreateKtxTexture(const uint8_t* data, int size); + + filament::Engine* engine_ = nullptr; + filament::Texture* texture_ = nullptr; + SphericalHarmonics spherical_harmonics_; + bool has_spherical_harmonics_ = false; +}; } // namespace mujoco #endif // MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_TEXTURE_UTIL_H_ From 8fc5ef3a5dee81dc3bfc5e0f41e86220de6eec6f Mon Sep 17 00:00:00 2001 From: Haroon Qureshi Date: Wed, 1 Apr 2026 04:31:54 -0700 Subject: [PATCH 15/20] Split Texture creation into two structs. TextureConfig describes the properties of the texture (e.g. width, height, pixel format, etc.). TextureData contains the binary payload of the texture. PiperOrigin-RevId: 892854578 Change-Id: I604b926ac38ff1050cac8fdf9ec767b789c0798e --- .../filament/filament/model_objects.cc | 59 ++-- .../filament/filament/object_manager.cc | 65 ++++- .../filament/filament/texture_util.cc | 274 ++++++++++-------- .../filament/filament/texture_util.h | 93 +++++- 4 files changed, 323 insertions(+), 168 deletions(-) diff --git a/src/experimental/filament/filament/model_objects.cc b/src/experimental/filament/filament/model_objects.cc index 0529d90e60..b65bb1bec7 100644 --- a/src/experimental/filament/filament/model_objects.cc +++ b/src/experimental/filament/filament/model_objects.cc @@ -125,30 +125,43 @@ void ModelObjects::UploadTexture(const mjModel* model, int id) { mju_error("Invalid texture index: %d", id); } - const int width = model->tex_width[id]; - const int height = model->tex_height[id]; - const int num_channels = model->tex_nchannel[id]; - const int tex_type = model->tex_type[id]; - const mjtByte* data = model->tex_data + model->tex_adr[id]; - const mjtColorSpace color_space = (mjtColorSpace)model->tex_colorspace[id]; - - const TextureType type = [&] { - if (height == 1) { - return TextureType::kKtx; - } else if (tex_type == mjTEXTURE_2D) { - return TextureType::kNormal2d; - } else if (tex_type == mjTEXTURE_CUBE) { - return TextureType::kCube; - } else if (tex_type == mjTEXTURE_SKYBOX) { - return TextureType::kCube; - } else { - mju_error("Unsupported texture type: %d", tex_type); - return TextureType::kNormal2d; - } - }(); + TextureConfig config; + DefaultTextureConfig(&config); + config.width = model->tex_width[id]; + config.height = model->tex_height[id]; + config.target = (mjtTexture)model->tex_type[id]; + config.color_space = (mjtColorSpace)model->tex_colorspace[id]; + switch (model->tex_nchannel[id]) { + case 1: + config.format = mjPIXEL_FORMAT_R8; + break; + case 3: + config.format = mjPIXEL_FORMAT_RGB8; + break; + case 4: + config.format = mjPIXEL_FORMAT_RGBA8; + break; + default: + mju_error("Unsupported texture format: %d", model->tex_nchannel[id]); + break; + } + if (config.height == 1 && model->tex_nchannel[id] == 1) { + config.format = mjPIXEL_FORMAT_KTX; + } + + + TextureData payload; + DefaultTextureData(&payload); + payload.bytes = model->tex_data + model->tex_adr[id]; + payload.nbytes = + model->tex_width[id] * model->tex_height[id] * model->tex_nchannel[id]; + // We assume that the model has the same lifetime as the engine. + payload.user_data = nullptr; + payload.release_callback = nullptr; - textures_[id] = std::make_unique(engine_, type, color_space, width, - height, num_channels, data); + auto texture = std::make_unique(engine_, config); + texture->Upload(payload); + textures_[id] = std::move(texture); } void ModelObjects::UploadHeightField(const mjModel* model, int id) { diff --git a/src/experimental/filament/filament/object_manager.cc b/src/experimental/filament/filament/object_manager.cc index 7699e65547..018951616f 100644 --- a/src/experimental/filament/filament/object_manager.cc +++ b/src/experimental/filament/filament/object_manager.cc @@ -14,6 +14,7 @@ #include "experimental/filament/filament/object_manager.h" +#include #include #include #include @@ -87,18 +88,35 @@ ObjectManager::ObjectManager(filament::Engine* engine) materials_[kUnlitUi] = LoadMaterial("unlit_ui.filamat"); static uint8_t black_rgb[3] = {0, 0, 0}; - fallback_black_ = std::make_unique( - engine_, TextureType::kNormal2d, mjCOLORSPACE_LINEAR, 1, 1, 3, black_rgb); static uint8_t white_rgb[3] = {255, 255, 255}; - fallback_white_ = std::make_unique( - engine_, TextureType::kNormal2d, mjCOLORSPACE_LINEAR, 1, 1, 3, white_rgb); static uint8_t normal_data[3] = {128, 128, 255}; - fallback_normal_ = - std::make_unique(engine_, TextureType::kNormal2d, - mjCOLORSPACE_LINEAR, 1, 1, 3, normal_data); static uint8_t orm_data[3] = {0, 255, 0}; - fallback_orm_ = std::make_unique( - engine_, TextureType::kNormal2d, mjCOLORSPACE_LINEAR, 1, 1, 3, orm_data); + + TextureConfig config; + DefaultTextureConfig(&config); + config.width = 1; + config.height = 1; + config.target = mjTEXTURE_2D; + config.format = mjPIXEL_FORMAT_RGB8; + config.color_space = mjCOLORSPACE_LINEAR; + + auto CreateFallbackTexture = [this, &config](uint8_t color[3]) { + auto texture = std::make_unique(engine_, config); + + TextureData payload; + DefaultTextureData(&payload); + payload.bytes = color; + payload.nbytes = 3; + payload.release_callback = nullptr; + payload.user_data = nullptr; + texture->Upload(payload); + return texture; + }; + + fallback_black_ = CreateFallbackTexture(black_rgb); + fallback_white_ = CreateFallbackTexture(white_rgb); + fallback_normal_ = CreateFallbackTexture(normal_data); + fallback_orm_ = CreateFallbackTexture(orm_data); fallback_textures_[mjTEXROLE_USER] = fallback_black_.get(); fallback_textures_[mjTEXROLE_RGB] = fallback_white_.get(); @@ -149,14 +167,33 @@ void ObjectManager::LoadFallbackIndirectLight( fallback_indirect_light_ = nullptr; } - Asset asset(filename); - if (asset.size == 0) { + Asset* asset = new Asset(filename); + auto release_asset = +[](void* user_data) { + delete static_cast(user_data); + }; + if (asset->size == 0) { + release_asset(asset); return; } - fallback_indirect_light_texture_ = std::make_unique( - engine_, TextureType::kKtx, mjCOLORSPACE_AUTO, asset.size, 1, 1, - reinterpret_cast(asset.payload)); + TextureConfig config; + DefaultTextureConfig(&config); + config.width = 1; + config.height = 1; + config.target = mjTEXTURE_CUBE; + config.format = mjPIXEL_FORMAT_KTX; + config.color_space = mjCOLORSPACE_AUTO; + + fallback_indirect_light_texture_ = std::make_unique(engine_, config); + + TextureData payload; + DefaultTextureData(&payload); + payload.bytes = asset->payload; + payload.nbytes = static_cast(asset->size); + payload.release_callback = release_asset; + payload.user_data = asset; + + fallback_indirect_light_texture_->Upload(payload); if (fallback_indirect_light_texture_ == nullptr) { return; } diff --git a/src/experimental/filament/filament/texture_util.cc b/src/experimental/filament/filament/texture_util.cc index 20b633934a..b711d24838 100644 --- a/src/experimental/filament/filament/texture_util.cc +++ b/src/experimental/filament/filament/texture_util.cc @@ -27,61 +27,124 @@ namespace mujoco { -static filament::Texture::Format GetTextureFormat(int num_channels) { - switch (num_channels) { - case 1: +static constexpr int kNumFacesPerCube = 6; + +static bool IsCompressed(const TextureConfig& config) { + return config.format == mjPIXEL_FORMAT_KTX; +} + +static bool IsCubeMap(const TextureConfig& config) { + return config.target == mjTEXTURE_CUBE || config.target == mjTEXTURE_SKYBOX; +} + +static int GetFaceHeight(const TextureConfig& config) { + int face_height = config.height; + if (config.width != config.height) { + if (config.width * kNumFacesPerCube != config.height) { + mju_error("Cube maps must contain 6 square images."); + } + face_height = config.height / kNumFacesPerCube; + } + if (config.width != face_height) { + mju_error("Cube map faces must be square."); + } + return face_height; +} + +static int GetNumChannels(const TextureConfig& config) { + switch (config.format) { + case mjPIXEL_FORMAT_R8: + return 1; + case mjPIXEL_FORMAT_RGB8: + return 3; + case mjPIXEL_FORMAT_RGBA8: + return 4; + default: + mju_error("Unsupported format: %d", (int)config.format); + return 0; + } +} + +static filament::Texture::Format GetTextureFormat(const TextureConfig& config) { + switch (config.format) { + case mjPIXEL_FORMAT_R8: return filament::Texture::Format::R; - case 3: + case mjPIXEL_FORMAT_RGB8: return filament::Texture::Format::RGB; - case 4: + case mjPIXEL_FORMAT_RGBA8: return filament::Texture::Format::RGBA; default: - mju_error("Unsupported number of channels: %d", num_channels); + mju_error("Unsupported format: %d", (int)config.format); return filament::Texture::Format::UNUSED; } } static filament::Texture::InternalFormat GetTextureInternalFormat( - int num_channels, bool is_srgb) { - if (is_srgb) { - switch (num_channels) { - case 3: + const TextureConfig& config) { + if (config.color_space == mjCOLORSPACE_SRGB) { + switch (config.format) { + case mjPIXEL_FORMAT_RGB8: return filament::Texture::InternalFormat::SRGB8; - case 4: + case mjPIXEL_FORMAT_RGBA8: return filament::Texture::InternalFormat::SRGB8_A8; default: - mju_error("Unsupported number of channels: %d", num_channels); + mju_error("Unsupported format: %d", (int)config.format); return filament::Texture::InternalFormat::UNUSED; } } else { - switch (num_channels) { - case 1: + switch (config.format) { + case mjPIXEL_FORMAT_R8: return filament::Texture::InternalFormat::R8; - case 3: + case mjPIXEL_FORMAT_RGB8: return filament::Texture::InternalFormat::RGB8; - case 4: + case mjPIXEL_FORMAT_RGBA8: return filament::Texture::InternalFormat::RGBA8; default: - mju_error("Unsupported number of channels: %d", num_channels); + mju_error("Unsupported format: %d", (int)config.format); return filament::Texture::InternalFormat::UNUSED; } } } -Texture::Texture(filament::Engine* engine, TextureType texture_type, - mjtColorSpace color_space, int width, int height, - int num_channels, const uint8_t* data) - : engine_(engine) { - const bool is_srgb = color_space == mjCOLORSPACE_SRGB; - if (texture_type == TextureType::kCube) { - CreateCubeTexture(width, height, num_channels, data, is_srgb); - } else if (texture_type == TextureType::kNormal2d) { - Create2dTexture(width, height, num_channels, data, is_srgb); - } else if (texture_type == TextureType::kKtx) { - CreateKtxTexture(data, width * height * num_channels); +void DefaultTextureData(TextureData* data) { + std::memset(data, 0, sizeof(TextureData)); +} + +void DefaultTextureConfig(TextureConfig* config) { + std::memset(config, 0, sizeof(TextureConfig)); +} + +Texture::Texture(filament::Engine* engine, const TextureConfig& config) + : engine_(engine), config_(config) { + if (IsCompressed(config_)) { + // We defer creation of compressed textures until Upload() is called. In + // the meantime, we don't really know anything about the texture (e.g. + // width, height, etc.). + return; + } + + filament::Texture::Builder builder; + builder.width(config_.width); + builder.height(config_.height); + builder.format(GetTextureInternalFormat(config_)); + + if (IsCubeMap(config_)) { + if (config_.format != mjPIXEL_FORMAT_RGB8) { + mju_error("Only support RGB cubemaps."); + return; + } + builder.height(GetFaceHeight(config_)); + builder.sampler(filament::Texture::Sampler::SAMPLER_CUBEMAP); } else { - mju_error("Unsupported texture type: %d", static_cast(texture_type)); + builder.sampler(filament::Texture::Sampler::SAMPLER_2D); } + + if (config_.color_space != mjCOLORSPACE_SRGB) { + builder.usage(filament::Texture::Usage::GEN_MIPMAPPABLE | + filament::Texture::Usage::SAMPLEABLE | + filament::Texture::Usage::UPLOADABLE); + } + texture_ = builder.build(*engine_); } Texture::Texture(filament::Engine* engine, RenderTargetTextureType type, @@ -117,111 +180,90 @@ Texture::Texture(filament::Engine* engine, RenderTargetTextureType type, texture_ = builder.build(*engine); } -void Texture::Create2dTexture(int width, int height, int num_channels, - const uint8_t* data, bool is_srgb) { - if (num_channels != 1 && num_channels != 3 && num_channels != 4) { - mju_error("Unsupported number of channels: %d", num_channels); - return; +Texture::~Texture() { + ReleaseData(); + if (texture_) { + engine_->destroy(texture_); } +} - filament::Texture::Builder builder; - builder.width(width); - builder.height(height); - builder.format(GetTextureInternalFormat(num_channels, is_srgb)); - builder.sampler(filament::Texture::Sampler::SAMPLER_2D); - if (!is_srgb) { - builder.usage(filament::Texture::Usage::GEN_MIPMAPPABLE | - filament::Texture::Usage::SAMPLEABLE | - filament::Texture::Usage::UPLOADABLE); - } - texture_ = builder.build(*engine_); +void Texture::Upload(const TextureData& data) { + user_data_ = data.user_data; + release_callback_ = data.release_callback; - if (data) { - const size_t num_bytes = width * height * sizeof(uint8_t) * num_channels; - const filament::Texture::Format format = GetTextureFormat(num_channels); - texture_->setImage( - *engine_, 0, - filament::Texture::PixelBufferDescriptor( - data, num_bytes, format, filament::Texture::Type::UBYTE)); - if (!is_srgb) { - texture_->generateMipmaps(*engine_); - } + if (data.bytes == nullptr || data.nbytes == 0) { + ReleaseData(); + return; } -} -void Texture::CreateCubeTexture(int width, int height, int num_channels, - const uint8_t* data, bool is_srgb) { - if (num_channels != 3) { - mju_error("Only support RGB cubemaps."); + if (config_.format == mjPIXEL_FORMAT_KTX) { + image::Ktx1Bundle* bundle = new image::Ktx1Bundle( + reinterpret_cast(data.bytes), data.nbytes); + has_spherical_harmonics_ = true; + bundle->getSphericalHarmonics(spherical_harmonics_); + const bool is_srgb = false; + texture_ = ktxreader::Ktx1Reader::createTexture(engine_, bundle, is_srgb); + config_.width = texture_->getWidth(); + config_.height = texture_->getHeight(); + ReleaseData(); return; } - const int kNumFacesPerCube = 6; + const int num_channels = GetNumChannels(config_); + const filament::Texture::Type type = filament::Texture::Type::UBYTE; + const filament::Texture::Format format = GetTextureFormat(config_); - int face_height = height; - if (width != height) { - if (width * kNumFacesPerCube != height) { - mju_error("Cube maps must contain 6 square images."); + if (!IsCubeMap(config_)) { + if (config_.width * config_.height * num_channels != data.nbytes) { + mju_error("Texture size does not match data size."); } - face_height = height / kNumFacesPerCube; - } - if (width != face_height) { - mju_error("Cube map faces must be square."); - } - filament::Texture::Builder builder; - builder.width(width); - builder.height(face_height); - builder.format(GetTextureInternalFormat(num_channels, is_srgb)); - builder.sampler(filament::Texture::Sampler::SAMPLER_CUBEMAP); - if (!is_srgb) { - builder.usage(filament::Texture::Usage::GEN_MIPMAPPABLE | - filament::Texture::Usage::SAMPLEABLE | - filament::Texture::Usage::UPLOADABLE); - } - texture_ = builder.build(*engine_); - - const int face_size = width * face_height * num_channels; - const int num_bytes = face_size * kNumFacesPerCube; - - uint8_t* buffer = new uint8_t[num_bytes]; - auto callback = +[](void* buffer, size_t size, void* user) { - delete [] reinterpret_cast(buffer); - }; - - filament::Texture::FaceOffsets offsets(face_size); - if (width == height) { - // Copy the image to all the faces. - for (int i = 0; i < kNumFacesPerCube; ++i) { - std::memcpy(buffer + (i * face_size), data, face_size); - } + auto callback = +[](void* buffer, size_t size, void* user) { + reinterpret_cast(user)->ReleaseData(); + }; + filament::Texture::PixelBufferDescriptor desc(data.bytes, data.nbytes, + format, type, callback, this); + texture_->setImage(*engine_, 0, std::move(desc)); } else { - // Use the cubemap as is. - std::memcpy(buffer, data, num_bytes); - } + const int face_size = config_.width * GetFaceHeight(config_) * num_channels; + const int num_bytes = face_size * kNumFacesPerCube; + filament::Texture::FaceOffsets offsets(face_size); - if (data) { - filament::Texture::PixelBufferDescriptor desc( - buffer, num_bytes, filament::Texture::Format::RGB, - filament::Texture::Type::UBYTE, callback); - texture_->setImage(*engine_, 0, std::move(desc), offsets); - if (!is_srgb) { - texture_->generateMipmaps(*engine_); + if (config_.width == config_.height) { + uint8_t* copy = new uint8_t[num_bytes]; + auto release_callback = +[](void* buffer, size_t size, void* user) { + delete [] reinterpret_cast(buffer); + }; + for (int i = 0; i < kNumFacesPerCube; ++i) { + std::memcpy(copy + (i * face_size), data.bytes, face_size); + } + filament::Texture::PixelBufferDescriptor desc(copy, num_bytes, format, + type, release_callback); + texture_->setImage(*engine_, 0, std::move(desc), offsets); + ReleaseData(); + } else { + if (num_bytes != data.nbytes) { + mju_error("Texture size does not match data size."); + } + auto callback = +[](void* buffer, size_t size, void* user) { + reinterpret_cast(user)->ReleaseData(); + }; + filament::Texture::PixelBufferDescriptor desc( + data.bytes, data.nbytes, format, type, callback, this); + texture_->setImage(*engine_, 0, std::move(desc), offsets); } } -} -void Texture::CreateKtxTexture(const uint8_t* data, int size) { - image::Ktx1Bundle* bundle = new image::Ktx1Bundle(data, size); - has_spherical_harmonics_ = true; - bundle->getSphericalHarmonics(spherical_harmonics_); - const bool is_srgb = false; - texture_ = ktxreader::Ktx1Reader::createTexture(engine_, bundle, is_srgb); + if (config_.color_space != mjCOLORSPACE_SRGB) { + texture_->generateMipmaps(*engine_); + } } -Texture::~Texture() { - if (texture_) { - engine_->destroy(texture_); +void Texture::ReleaseData() { + if (release_callback_) { + release_callback_(user_data_); + release_callback_ = nullptr; + user_data_ = nullptr; } } diff --git a/src/experimental/filament/filament/texture_util.h b/src/experimental/filament/filament/texture_util.h index 42925325e0..bba7b16e4b 100644 --- a/src/experimental/filament/filament/texture_util.h +++ b/src/experimental/filament/filament/texture_util.h @@ -15,7 +15,7 @@ #ifndef MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_TEXTURE_UTIL_H_ #define MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_TEXTURE_UTIL_H_ -#include +#include #include #include @@ -25,14 +25,16 @@ // Functions for creating filament textures. namespace mujoco { -// The types of textures we can create. -enum class TextureType { +// The types of textures we can create. For internal use only. +enum class TextureTarget { + // A standard 2D image with a width and a height. kNormal2d, + // A 2D texture split up into the 6 faces of a cube. kCube, - kKtx, }; // The different types of textures we can create for a render target. +// For internal use only. enum class RenderTargetTextureType { kColor, kDepth, @@ -40,23 +42,85 @@ enum class RenderTargetTextureType { kReflectionColor, }; +// Pixel formats for textures. +typedef enum mjtPixelFormat_ { + mjPIXEL_FORMAT_UNKNOWN = 0, + mjPIXEL_FORMAT_R8, + mjPIXEL_FORMAT_RGB8, + mjPIXEL_FORMAT_RGBA8, + mjPIXEL_FORMAT_DEPTH32F, + mjPIXEL_FORMAT_KTX, +} mjtPixelFormat; + +// The binary contents of a texture. +struct TextureData { + // Pointer to the image data. If null, an empty texture will be created. + void* bytes; + + // The number of bytes in the image data. + size_t nbytes; + + // Because rendering may be multithreaded, we cannot make assumptions about + // when the image data will finish uploading to the GPU. As such, we will use + // this callback to notify callers when it is safe to free the image data. + void (*release_callback)(void* user_data); + + // User data to pass to the release callback. + void* user_data; +}; + +// Initializes the TextureData to default values. +void DefaultTextureData(TextureData* data); + +// Defines the basic properties of a texture. +struct TextureConfig { + // The width of the texture. For compressed textures (e.g. KTX), this is the + // number of bytes in the compressed data. + int width; + + // The height of the texture. For compressed textures (e.g. KTX), this should + // be 0. + int height; + + // The target of the texture (e.g. 2D, cube, etc.) + mjtTexture target; + + // The format of the pixels in the texture (e.g. RGB8, RGBA8, KTX, etc.) + mjtPixelFormat format; + + // The color space of the texture (e.g. LINEAR, sRGB, etc.) + mjtColorSpace color_space; +}; + +// Initializes the TextureConfig to default values. +void DefaultTextureConfig(TextureConfig* config); + +// Wrapper around a filament::Texture. class Texture { public: // Creates a texture with the given data. - Texture(filament::Engine* engine, TextureType texture_type, - mjtColorSpace color_space, int width, int height, int num_channels, - const uint8_t* data); + Texture(filament::Engine* engine, const TextureConfig& config); - // Creates a texture for use with a render target. + // Creates a texture for use with a render target, for internal use. Texture(filament::Engine* engine, RenderTargetTextureType type, int width, int height); ~Texture(); + // Uploads the given data to the texture. + void Upload(const TextureData& data); + + // Returns the width of the texture. + int GetWidth() const { return config_.width; } + + // Returns the height of the texture. + int GetHeight() const { return config_.height; } + + // Returns the underlying filament texture. filament::Texture* GetFilamentTexture() const { return texture_; } + // Returns any spherical harmonics data associated with the texture. using SphericalHarmonics = filament::math::float3[9]; - const SphericalHarmonics* GetSphericalHarmonics() const { return has_spherical_harmonics_ ? &spherical_harmonics_ : nullptr; } @@ -65,17 +129,16 @@ class Texture { Texture& operator=(const Texture&) = delete; private: - - void Create2dTexture(int width, int height, int num_channels, - const uint8_t* data, bool is_srgb); - void CreateCubeTexture(int width, int height, int num_channels, - const uint8_t* data, bool is_srgb); - void CreateKtxTexture(const uint8_t* data, int size); + void ReleaseData(); filament::Engine* engine_ = nullptr; filament::Texture* texture_ = nullptr; + TextureConfig config_; SphericalHarmonics spherical_harmonics_; bool has_spherical_harmonics_ = false; + + void* user_data_ = nullptr; + void (*release_callback_)(void* user_data) = nullptr; }; } // namespace mujoco From e1f6d12ef0c641ccb889ea381dde1302e3bced86 Mon Sep 17 00:00:00 2001 From: Haroon Qureshi Date: Wed, 1 Apr 2026 05:05:34 -0700 Subject: [PATCH 16/20] Update GuiView to use Texture class. PiperOrigin-RevId: 892866156 Change-Id: I2a2e9ef51df51472b675d69edcf2d5ba291721ea --- .../filament/filament/gui_view.cc | 122 ++++++++---------- src/experimental/filament/filament/gui_view.h | 4 +- 2 files changed, 59 insertions(+), 67 deletions(-) diff --git a/src/experimental/filament/filament/gui_view.cc b/src/experimental/filament/filament/gui_view.cc index 8fa83cae55..70b21cf157 100644 --- a/src/experimental/filament/filament/gui_view.cc +++ b/src/experimental/filament/filament/gui_view.cc @@ -17,6 +17,7 @@ #include #include #include +#include #include #include @@ -31,6 +32,7 @@ #include #include #include "experimental/filament/filament/buffer_util.h" +#include "experimental/filament/filament/texture_util.h" #include "experimental/filament/filament/vertex_util.h" namespace mujoco { @@ -67,9 +69,7 @@ GuiView::~GuiView() { for (auto& instance : instances_) { engine_->destroy(instance); } - for (auto& texture : textures_) { - engine_->destroy(texture.second); - } + textures_.clear(); engine_->destroyCameraComponent(camera_->getEntity()); engine_->destroy(view_); engine_->destroy(scene_); @@ -98,62 +98,52 @@ uintptr_t GuiView::UploadImage(uintptr_t tex_id, const uint8_t* pixels, mju_error("Unsupported image bpp. Got %d, wanted 3 or 4", bpp); } - const auto internal_format = - bpp == 4 ? filament::Texture::InternalFormat::RGBA8 - : filament::Texture::InternalFormat::RGB8; - const auto texture_format = bpp == 4 ? filament::Texture::Format::RGBA - : filament::Texture::Format::RGB; + if (pixels == nullptr) { + // If the pixels are nullptr, we destroy the texture. + if (tex_id != 0) { + textures_.erase(tex_id); + } + return 0; + } - filament::Texture* texture = nullptr; + // Assign a new texture ID. if (tex_id == 0) { - texture = filament::Texture::Builder() - .width(width) - .height(height) - .levels(1) - .format(internal_format) - .sampler(filament::Texture::Sampler::SAMPLER_2D) - .build(*engine_); tex_id = textures_.size() + 1; - textures_[tex_id] = texture; - } else { - auto iter = textures_.find(tex_id); - if (iter == textures_.end()) { - mju_error("Texture not found: %lu", tex_id); - } - texture = iter->second; + } - if (pixels == nullptr) { - // A nullptr implies that the user wants to destroy the texture. - engine_->destroy(texture); - textures_.erase(tex_id); - return 0; - } else if (texture->getWidth() != width || texture->getHeight() != height) { - // Recreate the texture if the dimensions have changed. - engine_->destroy(texture); - texture = filament::Texture::Builder() - .width(width) - .height(height) - .levels(1) - .format(internal_format) - .sampler(filament::Texture::Sampler::SAMPLER_2D) - .build(*engine_); - textures_[tex_id] = texture; - } + std::unique_ptr& texture = textures_[tex_id]; + + // If the texture does not exist or the dimensions have changed, we create a + // new texture. + if (texture == nullptr || texture->GetWidth() != width || + texture->GetHeight() != height) { + TextureConfig config; + DefaultTextureConfig(&config); + config.width = width; + config.height = height; + config.target = mjTEXTURE_2D; + config.format = bpp == 4 ? mjPIXEL_FORMAT_RGBA8 : mjPIXEL_FORMAT_RGB8; + config.color_space = mjCOLORSPACE_LINEAR; + texture = std::make_unique(engine_, config); } // Create a copy of the image to pass it to filament as we don't know the // lifetime of the data. - const int num_bytes = width * height * bpp; + const size_t num_bytes = width * height * bpp; std::byte* bytes = new std::byte[num_bytes]; - std::memcpy(bytes, pixels, num_bytes); - const auto callback = [](void* buffer, size_t size, void* user) { - auto* ptr = reinterpret_cast(user); - delete[] ptr; + const auto callback = +[](void* user) { + delete[] reinterpret_cast(user); }; - filament::Texture::PixelBufferDescriptor pb(bytes, num_bytes, texture_format, - filament::Texture::Type::UBYTE, - callback); - texture->setImage(*engine_, 0, std::move(pb)); + + TextureData texture_data; + DefaultTextureData(&texture_data); + texture_data.bytes = bytes; + texture_data.nbytes = num_bytes; + texture_data.user_data = bytes; + texture_data.release_callback = callback; + + std::memcpy(bytes, pixels, num_bytes); + texture->Upload(texture_data); return tex_id; } @@ -162,40 +152,39 @@ void GuiView::CreateTexture(ImTextureData* data) { mju_error("Unsupported texture format."); } - filament::Texture* texture = - filament::Texture::Builder() - .width(data->Width) - .height(data->Height) - .levels(1) - .format(filament::Texture::InternalFormat::RGBA8) - .sampler(filament::Texture::Sampler::SAMPLER_2D) - .build(*engine_); + TextureConfig config; + DefaultTextureConfig(&config); + config.width = data->Width; + config.height = data->Height; + config.target = mjTEXTURE_2D; + config.format = mjPIXEL_FORMAT_RGBA8; + config.color_space = mjCOLORSPACE_LINEAR; const uintptr_t tex_id = textures_.size() + 1; - textures_[tex_id] = texture; + textures_[tex_id] = std::make_unique(engine_, config); data->SetTexID((ImTextureID)tex_id); UpdateTexture(data); } void GuiView::UpdateTexture(ImTextureData* data) { - const int size = data->Width * data->Height * 4; - filament::Texture::PixelBufferDescriptor pb(data->GetPixels(), size, - filament::Texture::Format::RGBA, - filament::Texture::Type::UBYTE); auto iter = textures_.find(data->TexID); if (iter == textures_.end()) { mju_error("Texture not found: %llu", data->TexID); } - filament::Texture* texture = iter->second; - texture->setImage(*engine_, 0, std::move(pb)); + TextureData texture_data; + DefaultTextureData(&texture_data); + texture_data.bytes = data->GetPixels(); + texture_data.nbytes = data->Width * data->Height * 4; + texture_data.user_data = nullptr; + texture_data.release_callback = nullptr; + iter->second->Upload(texture_data); data->SetStatus(ImTextureStatus_OK); } void GuiView::DestroyTexture(ImTextureData* data) { auto iter = textures_.find(data->TexID); if (iter != textures_.end()) { - engine_->destroy(iter->second); textures_.erase(data->TexID); data->SetTexID(ImTextureID_Invalid); data->SetStatus(ImTextureStatus_Destroyed); @@ -361,7 +350,8 @@ filament::MaterialInstance* GuiView::GetMaterialInstance(int index, } filament::MaterialInstance* instance = instances_[index]; - instance->setParameter("glyph", iter->second, filament::TextureSampler()); + instance->setParameter("glyph", iter->second->GetFilamentTexture(), + filament::TextureSampler()); instance->setScissor(rect.left, rect.bottom, rect.width, rect.height); return instance; } diff --git a/src/experimental/filament/filament/gui_view.h b/src/experimental/filament/filament/gui_view.h index 2adb6d07af..b18ccb79cd 100644 --- a/src/experimental/filament/filament/gui_view.h +++ b/src/experimental/filament/filament/gui_view.h @@ -16,6 +16,7 @@ #define MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_GUI_VIEW_H_ #include +#include #include #include @@ -29,6 +30,7 @@ #include #include #include "experimental/filament/filament/buffer_util.h" +#include "experimental/filament/filament/texture_util.h" namespace mujoco { @@ -71,7 +73,7 @@ class GuiView { utils::Entity renderable_; std::vector buffers_; std::vector instances_; - std::unordered_map textures_; + std::unordered_map> textures_; int num_elements_ = 0; }; From 0715115074a75910dc2fcd31ee696ce3cab72069 Mon Sep 17 00:00:00 2001 From: Haroon Qureshi Date: Wed, 1 Apr 2026 05:13:19 -0700 Subject: [PATCH 17/20] Rename texture_util to texture. PiperOrigin-RevId: 892868713 Change-Id: I113132dc9e4535e94d48c4e71520acb159e2e216 --- src/experimental/filament/CMakeLists.txt | 4 ++-- src/experimental/filament/filament/drawable.cc | 2 +- src/experimental/filament/filament/drawable.h | 2 +- src/experimental/filament/filament/filament_context.cc | 2 +- src/experimental/filament/filament/gui_view.cc | 2 +- src/experimental/filament/filament/gui_view.h | 2 +- src/experimental/filament/filament/material.cc | 2 +- src/experimental/filament/filament/material.h | 2 +- src/experimental/filament/filament/model_objects.cc | 2 +- src/experimental/filament/filament/model_objects.h | 2 +- src/experimental/filament/filament/model_util.cc | 1 - src/experimental/filament/filament/object_manager.cc | 2 +- src/experimental/filament/filament/object_manager.h | 2 +- src/experimental/filament/filament/render_target_util.cc | 2 +- src/experimental/filament/filament/render_target_util.h | 2 +- src/experimental/filament/filament/scene_view.cc | 2 +- .../filament/filament/{texture_util.cc => texture.cc} | 2 +- .../filament/filament/{texture_util.h => texture.h} | 6 +++--- 18 files changed, 20 insertions(+), 21 deletions(-) rename src/experimental/filament/filament/{texture_util.cc => texture.cc} (99%) rename src/experimental/filament/filament/{texture_util.h => texture.h} (95%) diff --git a/src/experimental/filament/CMakeLists.txt b/src/experimental/filament/CMakeLists.txt index 2a0c5c8fa7..457a5db9d6 100644 --- a/src/experimental/filament/CMakeLists.txt +++ b/src/experimental/filament/CMakeLists.txt @@ -59,8 +59,8 @@ target_sources(${MUJOCO_FILAMENT_TARGET_NAME} filament/renderables.h filament/scene_view.cc filament/scene_view.h - filament/texture_util.cc - filament/texture_util.h + filament/texture.cc + filament/texture.h filament/vertex_util.cc filament/vertex_util.h ) diff --git a/src/experimental/filament/filament/drawable.cc b/src/experimental/filament/filament/drawable.cc index 5525060016..f32afe1ae4 100644 --- a/src/experimental/filament/filament/drawable.cc +++ b/src/experimental/filament/filament/drawable.cc @@ -37,7 +37,7 @@ #include "experimental/filament/filament/math_util.h" #include "experimental/filament/filament/model_objects.h" #include "experimental/filament/filament/object_manager.h" -#include "experimental/filament/filament/texture_util.h" +#include "experimental/filament/filament/texture.h" namespace mujoco { diff --git a/src/experimental/filament/filament/drawable.h b/src/experimental/filament/filament/drawable.h index 06796aed95..2f2dc81e38 100644 --- a/src/experimental/filament/filament/drawable.h +++ b/src/experimental/filament/filament/drawable.h @@ -26,7 +26,7 @@ #include "experimental/filament/filament/model_objects.h" #include "experimental/filament/filament/object_manager.h" #include "experimental/filament/filament/renderables.h" -#include "experimental/filament/filament/texture_util.h" +#include "experimental/filament/filament/texture.h" namespace mujoco { diff --git a/src/experimental/filament/filament/filament_context.cc b/src/experimental/filament/filament/filament_context.cc index 973425d192..cbd06da21e 100644 --- a/src/experimental/filament/filament/filament_context.cc +++ b/src/experimental/filament/filament/filament_context.cc @@ -45,7 +45,7 @@ #include "experimental/filament/filament/object_manager.h" #include "experimental/filament/filament/render_target_util.h" #include "experimental/filament/filament/scene_view.h" -#include "experimental/filament/filament/texture_util.h" +#include "experimental/filament/filament/texture.h" #include "experimental/filament/render_context_filament.h" namespace mujoco { diff --git a/src/experimental/filament/filament/gui_view.cc b/src/experimental/filament/filament/gui_view.cc index 70b21cf157..1876936eb1 100644 --- a/src/experimental/filament/filament/gui_view.cc +++ b/src/experimental/filament/filament/gui_view.cc @@ -32,7 +32,7 @@ #include #include #include "experimental/filament/filament/buffer_util.h" -#include "experimental/filament/filament/texture_util.h" +#include "experimental/filament/filament/texture.h" #include "experimental/filament/filament/vertex_util.h" namespace mujoco { diff --git a/src/experimental/filament/filament/gui_view.h b/src/experimental/filament/filament/gui_view.h index b18ccb79cd..2b189324f6 100644 --- a/src/experimental/filament/filament/gui_view.h +++ b/src/experimental/filament/filament/gui_view.h @@ -30,7 +30,7 @@ #include #include #include "experimental/filament/filament/buffer_util.h" -#include "experimental/filament/filament/texture_util.h" +#include "experimental/filament/filament/texture.h" namespace mujoco { diff --git a/src/experimental/filament/filament/material.cc b/src/experimental/filament/filament/material.cc index e04e3f8149..aaf9c6ba42 100644 --- a/src/experimental/filament/filament/material.cc +++ b/src/experimental/filament/filament/material.cc @@ -21,7 +21,7 @@ #include #include #include "experimental/filament/filament/object_manager.h" -#include "experimental/filament/filament/texture_util.h" +#include "experimental/filament/filament/texture.h" namespace mujoco { diff --git a/src/experimental/filament/filament/material.h b/src/experimental/filament/filament/material.h index 849cb89e8f..b717b9c41d 100644 --- a/src/experimental/filament/filament/material.h +++ b/src/experimental/filament/filament/material.h @@ -21,7 +21,7 @@ #include #include #include "experimental/filament/filament/object_manager.h" -#include "experimental/filament/filament/texture_util.h" +#include "experimental/filament/filament/texture.h" namespace mujoco { diff --git a/src/experimental/filament/filament/model_objects.cc b/src/experimental/filament/filament/model_objects.cc index b65bb1bec7..3df4f2e220 100644 --- a/src/experimental/filament/filament/model_objects.cc +++ b/src/experimental/filament/filament/model_objects.cc @@ -27,7 +27,7 @@ #include "experimental/filament/filament/buffer_util.h" #include "experimental/filament/filament/builtins.h" #include "experimental/filament/filament/model_util.h" -#include "experimental/filament/filament/texture_util.h" +#include "experimental/filament/filament/texture.h" namespace mujoco { diff --git a/src/experimental/filament/filament/model_objects.h b/src/experimental/filament/filament/model_objects.h index 94fc298780..7007e81a3e 100644 --- a/src/experimental/filament/filament/model_objects.h +++ b/src/experimental/filament/filament/model_objects.h @@ -26,7 +26,7 @@ #include #include #include "experimental/filament/filament/buffer_util.h" -#include "experimental/filament/filament/texture_util.h" +#include "experimental/filament/filament/texture.h" namespace mujoco { diff --git a/src/experimental/filament/filament/model_util.cc b/src/experimental/filament/filament/model_util.cc index 62e72d732b..2bd581ddff 100644 --- a/src/experimental/filament/filament/model_util.cc +++ b/src/experimental/filament/filament/model_util.cc @@ -32,7 +32,6 @@ #include #include "experimental/filament/filament/buffer_util.h" #include "experimental/filament/filament/math_util.h" -#include "experimental/filament/filament/texture_util.h" #include "experimental/filament/filament/vertex_util.h" namespace mujoco { diff --git a/src/experimental/filament/filament/object_manager.cc b/src/experimental/filament/filament/object_manager.cc index 018951616f..80679284d3 100644 --- a/src/experimental/filament/filament/object_manager.cc +++ b/src/experimental/filament/filament/object_manager.cc @@ -28,7 +28,7 @@ #include #include #include -#include "experimental/filament/filament/texture_util.h" +#include "experimental/filament/filament/texture.h" #include "user/user_resource.h" namespace mujoco { diff --git a/src/experimental/filament/filament/object_manager.h b/src/experimental/filament/filament/object_manager.h index 64d9eadf73..523203479d 100644 --- a/src/experimental/filament/filament/object_manager.h +++ b/src/experimental/filament/filament/object_manager.h @@ -23,7 +23,7 @@ #include #include #include -#include "experimental/filament/filament/texture_util.h" +#include "experimental/filament/filament/texture.h" namespace mujoco { diff --git a/src/experimental/filament/filament/render_target_util.cc b/src/experimental/filament/filament/render_target_util.cc index ef221e4ef9..2e4ce391f2 100644 --- a/src/experimental/filament/filament/render_target_util.cc +++ b/src/experimental/filament/filament/render_target_util.cc @@ -19,7 +19,7 @@ #include #include #include -#include "experimental/filament/filament/texture_util.h" +#include "experimental/filament/filament/texture.h" namespace mujoco { diff --git a/src/experimental/filament/filament/render_target_util.h b/src/experimental/filament/filament/render_target_util.h index d2d581a96e..ce6b96dcc9 100644 --- a/src/experimental/filament/filament/render_target_util.h +++ b/src/experimental/filament/filament/render_target_util.h @@ -19,7 +19,7 @@ #include #include -#include "experimental/filament/filament/texture_util.h" +#include "experimental/filament/filament/texture.h" namespace mujoco { diff --git a/src/experimental/filament/filament/scene_view.cc b/src/experimental/filament/filament/scene_view.cc index 9b64243e17..7009dd176c 100644 --- a/src/experimental/filament/filament/scene_view.cc +++ b/src/experimental/filament/filament/scene_view.cc @@ -50,7 +50,7 @@ #include "experimental/filament/filament/model_util.h" #include "experimental/filament/filament/object_manager.h" #include "experimental/filament/filament/render_target_util.h" -#include "experimental/filament/filament/texture_util.h" +#include "experimental/filament/filament/texture.h" namespace mujoco { diff --git a/src/experimental/filament/filament/texture_util.cc b/src/experimental/filament/filament/texture.cc similarity index 99% rename from src/experimental/filament/filament/texture_util.cc rename to src/experimental/filament/filament/texture.cc index b711d24838..1ce6277492 100644 --- a/src/experimental/filament/filament/texture_util.cc +++ b/src/experimental/filament/filament/texture.cc @@ -12,7 +12,7 @@ // See the License for the specific language governing permissions and // limitations under the License. -#include "experimental/filament/filament/texture_util.h" +#include "experimental/filament/filament/texture.h" #include #include diff --git a/src/experimental/filament/filament/texture_util.h b/src/experimental/filament/filament/texture.h similarity index 95% rename from src/experimental/filament/filament/texture_util.h rename to src/experimental/filament/filament/texture.h index bba7b16e4b..44b0ea3160 100644 --- a/src/experimental/filament/filament/texture_util.h +++ b/src/experimental/filament/filament/texture.h @@ -12,8 +12,8 @@ // See the License for the specific language governing permissions and // limitations under the License. -#ifndef MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_TEXTURE_UTIL_H_ -#define MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_TEXTURE_UTIL_H_ +#ifndef MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_TEXTURE_H_ +#define MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_TEXTURE_H_ #include @@ -142,4 +142,4 @@ class Texture { }; } // namespace mujoco -#endif // MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_TEXTURE_UTIL_H_ +#endif // MUJOCO_SRC_EXPERIMENTAL_FILAMENT_FILAMENT_TEXTURE_H_ From 93f5821c8f5e0f70f206ce986a42281bcc289830 Mon Sep 17 00:00:00 2001 From: Yuval Tassa Date: Wed, 1 Apr 2026 07:49:53 -0700 Subject: [PATCH 18/20] Add `` actuator and related docs and tests. PiperOrigin-RevId: 892927987 Change-Id: I38ed6412801341ba03ddf5fe7b93a6081df24d37 --- doc/APIreference/functions.rst | 9 + doc/XMLreference.rst | 219 +++ doc/XMLschema.rst | 168 +++ doc/_static/dcmotor.pdf | Bin 0 -> 599056 bytes doc/changelog.rst | 3 + doc/dcmotor/buildpdf.sh | 21 + doc/dcmotor/dcmotor.tex | 1416 +++++++++++++++++++ doc/dcmotor/refs.bib | 82 ++ doc/includes/references.h | 9 +- include/mujoco/mjmodel.h | 5 +- include/mujoco/mujoco.h | 6 + python/mujoco/introspect/enums.py | 9 +- python/mujoco/introspect/functions.py | 80 ++ python/mujoco/specs.cc | 25 + python/mujoco/specs_test.py | 7 + src/engine/engine_derivative.c | 33 + src/engine/engine_forward.c | 269 +++- src/engine/engine_support.c | 59 +- src/engine/engine_util_misc.c | 20 + src/engine/engine_util_misc.h | 17 + src/user/user_api.cc | 161 +++ src/user/user_objects.cc | 10 +- src/xml/xml_native_reader.cc | 79 +- src/xml/xml_native_reader.h | 2 +- src/xml/xml_native_writer.cc | 2 +- test/engine/engine_derivative_test.cc | 16 +- test/engine/engine_forward_test.cc | 943 ++++++++++++ test/engine/testdata/derivative/dcmotor.xml | 35 + test/xml/xml_native_reader_test.cc | 319 +++++ unity/Runtime/Bindings/MjBindings.cs | 9 +- wasm/codegen/generated/bindings.cc | 16 + 31 files changed, 3994 insertions(+), 55 deletions(-) create mode 100644 doc/_static/dcmotor.pdf create mode 100755 doc/dcmotor/buildpdf.sh create mode 100644 doc/dcmotor/dcmotor.tex create mode 100644 doc/dcmotor/refs.bib create mode 100644 test/engine/testdata/derivative/dcmotor.xml diff --git a/doc/APIreference/functions.rst b/doc/APIreference/functions.rst index df6381f541..fa61555b04 100644 --- a/doc/APIreference/functions.rst +++ b/doc/APIreference/functions.rst @@ -4658,6 +4658,15 @@ Set actuator to muscle; return error if any.a Set actuator to active adhesion; return error if any. +.. _mjs_setToDCMotor: + +`mjs_setToDCMotor <#mjs_setToDCMotor>`__ +~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ + +.. mujoco-include:: mjs_setToDCMotor + +Set actuator to DC motor; return error if any. + .. _AddAssets: Assets diff --git a/doc/XMLreference.rst b/doc/XMLreference.rst index 7e90fa1488..2552f93219 100644 --- a/doc/XMLreference.rst +++ b/doc/XMLreference.rst @@ -6323,6 +6323,174 @@ This element has a subset of the common attributes and two custom attributes. to the target body. +.. _actuator-dcmotor: + +:el-prefix:`actuator/` |-| **dcmotor** |*| +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +This element creates a DC motor actuator. Note that :el:`dcmotor` is quite different from the :ref:`general actuation +model`. Unlike the general model where the components of force generation are independent affine functions +mapping from control to force, :el:`dcmotor` relies on highly coupled physical dynamics. See the `DC motor technical +note <_static/dcmotor.pdf>`__ for complete mathematical formulations and parameter semantics, but we include a few +important notes here: + +- Note that while :ref:`resistance`, :ref:`motorconst` and + :ref:`nominal` are each optional, some combination of them is required. + See Section 2.1 of the `technical note <_static/dcmotor.pdf>`__. +- The control :ref:`input` semantic is either the voltage applied to the motor terminals, or a + position or velocity target for a PID :ref:`controller`. +- Optional features include electrical dynamics (:ref:`inductance`), + :ref:`cogging torque`, :ref:`thermal resistance variation`, and + :ref:`LuGre` friction. + +The underlying :el:`general` attributes are set to the :el:`dcmotor` type, and their associated parameter arrays are +computed internally: + +========= ======= ========= ======== +Attribute Setting Attribute Setting +========= ======= ========= ======== +dyntype dcmotor dynprm computed +gaintype dcmotor gainprm computed +biastype dcmotor biasprm computed +========= ======= ========= ======== + +This element has the following custom attributes in addition to the common attributes: + +.. _actuator-dcmotor-name: + +.. _actuator-dcmotor-class: + +.. _actuator-dcmotor-group: + +.. _actuator-dcmotor-delay: + +.. _actuator-dcmotor-nsample: + +.. _actuator-dcmotor-interp: + +.. _actuator-dcmotor-ctrllimited: + +.. _actuator-dcmotor-ctrlrange: + +.. _actuator-dcmotor-lengthrange: + +.. _actuator-dcmotor-gear: + +.. _actuator-dcmotor-damping: + +.. _actuator-dcmotor-armature: + +.. _actuator-dcmotor-cranklength: + +.. _actuator-dcmotor-joint: + +.. _actuator-dcmotor-jointinparent: + +.. _actuator-dcmotor-tendon: + +.. _actuator-dcmotor-cranksite: + +.. _actuator-dcmotor-slidersite: + +.. _actuator-dcmotor-site: + +.. _actuator-dcmotor-refsite: + +.. _actuator-dcmotor-user: + +.. |actuator/dcmotor attrib list| replace:: + :at:`name`, :at:`class`, :at:`group`, :at:`nsample`, :at:`interp`, :at:`delay`, :at:`ctrllimited`, :at:`ctrlrange`, + :at:`lengthrange`, :at:`gear`, :at:`damping`, :at:`armature`, :at:`cranklength`, :at:`joint`, :at:`jointinparent`, + :at:`tendon`, :at:`cranksite`, :at:`slidersite`, :at:`site`, :at:`refsite`, :at:`user` + +|actuator/dcmotor attrib list| + Same as in actuator/ :ref:`general `. + +.. _actuator-dcmotor-resistance: + +:at:`resistance`: :at-val:`real, optional` + Terminal resistance :math:`R` in Ohm. (see `tech note <_static/dcmotor.pdf>`__ for details) + +.. _actuator-dcmotor-motorconst: + +:at:`motorconst`: :at-val:`real(2), optional` + Motor constants, defined as :at:`motorconst` = ":at-val:`Kt` :at-val:`Ke`" (N·m/A, equivalently V·s/rad). + :at-val:`Kt` is the torque constant and :at-val:`Ke` the back-EMF constant; they can differ when magnetic saturation + is present. If both are positive, the effective constant is :math:`K = \sqrt{K_t K_e}` (geometric mean). If only one + is positive, :math:`K` equals that value; a single value is interpreted as :math:`K_t = K_e`. If your datasheet gives + the speed constant :math:`K_v` in rad/(V·s), use :math:`K_e = 1/K_v`. (see `tech note <_static/dcmotor.pdf>`__ for + details) + +.. _actuator-dcmotor-nominal: + +:at:`nominal`: :at-val:`real(3), optional` + Nominal operating point, defined as :at:`nominal` = ":at-val:`voltage` :at-val:`stall_torque` + :at-val:`no_load_speed`". The compiler derives :math:`K =` :at-val:`voltage` / :at-val:`no_load_speed` and :math:`R = + K` · :at-val:`voltage` / :at-val:`stall_torque`. (see `tech note <_static/dcmotor.pdf>`__ for details) + +.. _actuator-dcmotor-inductance: + +:at:`inductance`: :at-val:`real(2), "0 0"` + Electrical dynamics, defined as :at:`inductance` = ":at-val:`L` :at-val:`timeconst`" (Henry, seconds). These are + alternative specifications: :at-val:`L` is the winding inductance and :at-val:`timeconst` :math:`= L/R` is the + electrical time constant. Specify one; if both are given, :at-val:`L` takes precedence. If both are 0 (the default), + no electrical dynamics are modeled and the current is computed algebraically. Adds one activation variable for + armature current. (see `tech note <_static/dcmotor.pdf>`__ for details) + +.. _actuator-dcmotor-thermal: + +:at:`thermal`: :at-val:`real(6), "0 0 0 0 0 0"` + Thermal model, defined as :at:`thermal` = ":at-val:`resistance` :at-val:`capacitance` :at-val:`timeconst` + :at-val:`tempcoef` :at-val:`reftemp` :at-val:`ambient`" (K/W, J/K, s, 1/K, °C, °C). The first three sub-values + specify the thermal time constant: :at-val:`timeconst` = :at-val:`resistance` :math:`\times` :at-val:`capacitance`. + Specify either :at-val:`timeconst` directly, or :at-val:`resistance` and :at-val:`capacitance`; if all three are + given, :at-val:`timeconst` takes precedence. If all are 0 (the default), thermal modeling is disabled. Adds one + activation variable for winding temperature. (see `tech note <_static/dcmotor.pdf>`__ for details) + +.. _actuator-dcmotor-saturation: + +:at:`saturation`: :at-val:`real(4), "0 0 0 0"` + Limits on the actuator, defined as :at:`saturation` = ":at-val:`torque` :at-val:`current` :at-val:`voltage` + :at-val:`current_rate`". :at-val:`torque` and :at-val:`current` are alternative specifications of the maximum + continuous torque: if :at-val:`current` is given, :at-val:`torque` :math:`= K \cdot` :at-val:`current`; if both are + given, :at-val:`torque` takes precedence. Sets :at:`forcerange` to [:math:`-\tau_{\max},\, \tau_{\max}`]. + :at-val:`voltage` sets the maximum voltage :math:`V_{\max}`. :at-val:`current_rate` sets the maximum rate of change + of current :math:`(di/dt)_{\max}` (requires :ref:`inductance`). A value of 0 (the + default) for any sub-value disables the respective limit. (see `tech note <_static/dcmotor.pdf>`__ for details) + +.. _actuator-dcmotor-cogging: + +:at:`cogging`: :at-val:`real(3), "0 0 0"` + Cogging torque, defined as :at:`cogging` = ":at-val:`amplitude` :at-val:`poles` :at-val:`phase`" (N·m, integer, rad). + Adds a position-dependent torque :math:`= \textsf{amplitude} \cdot \sin(\textsf{poles} \cdot \theta + + \textsf{phase})`. Disabled when :at-val:`amplitude` = 0 (the default). + (see `tech note <_static/dcmotor.pdf>`__ for details) + +.. _actuator-dcmotor-lugre: + +:at:`lugre`: :at-val:`real(6), "0 0 0 0 0 0"` + LuGre friction, defined as :at:`lugre` = ":at-val:`stiffness` :at-val:`damping` :at-val:`viscous` :at-val:`coulomb` + :at-val:`static` :at-val:`stribeck`" (N·m/rad, N·m·s/rad, N·m·s/rad, N·m, N·m, rad/s). Disabled when + :at-val:`stiffness` = 0 (the default). Adds one activation variable for bristle deflection. Note that the + :at-val:`viscous` coefficient is mapped directly to the actuator :ref:`damping` array + (specifically the linear term, :at-val:`damping[0]`). If both are specified, their values are summed. + (see `tech note <_static/dcmotor.pdf>`__ for details) + +.. _actuator-dcmotor-input: + +:at:`input`: :at-val:`[voltage, position, velocity], "voltage"` + Specifies the input signal semantics. In "voltage" mode, the control directly sets applied motor voltage. In + "position" or "velocity" modes, the PID :ref:`controller` uses the control as a + reference setpoint relative to the joint trajectory. (see `tech note <_static/dcmotor.pdf>`__ for details) + +.. _actuator-dcmotor-controller: + +:at:`controller`: :at-val:`real(5), "0 0 0 0 0"` + PID controller parameters, defined as :at:`controller` = ":at-val:`kp` :at-val:`ki` :at-val:`kd` + :at-val:`slewmax` :at-val:`Imax`". Depending on the :at:`input` mode, the controller stabilizes either position or + velocity. If the :at:`input` mode is voltage, the controller is ignored. A value of 0 (the default) disables the + respective feature: :at-val:`slewmax` = 0 means no slew-rate limiting, :at-val:`Imax` = 0 means no anti-windup + clamping. (see `tech note <_static/dcmotor.pdf>`__ for details) + .. _actuator-plugin: :el-prefix:`actuator/` |-| **plugin** |?| @@ -9887,6 +10055,57 @@ refsite, tendon, slidersite, cranksite. All :ref:`adhesion ` attributes are available here except: name, class, body. +.. _default-dcmotor: + +.. _default-dcmotor-ctrllimited: + +.. _default-dcmotor-ctrlrange: + +.. _default-dcmotor-gear: + +.. _default-dcmotor-damping: + +.. _default-dcmotor-armature: + +.. _default-dcmotor-cranklength: + +.. _default-dcmotor-user: + +.. _default-dcmotor-group: + +.. _default-dcmotor-delay: + +.. _default-dcmotor-nsample: + +.. _default-dcmotor-interp: + +.. _default-dcmotor-motorconst: + +.. _default-dcmotor-resistance: + +.. _default-dcmotor-nominal: + +.. _default-dcmotor-saturation: + +.. _default-dcmotor-inductance: + +.. _default-dcmotor-cogging: + +.. _default-dcmotor-controller: + +.. _default-dcmotor-input: + +.. _default-dcmotor-thermal: + +.. _default-dcmotor-lugre: + +:el-prefix:`default/` |-| **dcmotor** |?| +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +All :ref:`dcmotor ` attributes are available here except: name, class, joint, jointinparent, site, +refsite, tendon, slidersite, cranksite. + + .. _custom: **custom** |*| diff --git a/doc/XMLschema.rst b/doc/XMLschema.rst index 74f725618c..4dbc6c2991 100755 --- a/doc/XMLschema.rst +++ b/doc/XMLschema.rst @@ -2984,6 +2984,105 @@ :ref:`gain` + .. dropdown:: :ref:`dcmotor` |*| + + .. grid:: 2 3 4 4 + :gutter: 0 + + .. grid-item:: + :ref:`name` + + .. grid-item:: + :ref:`class` + + .. grid-item:: + :ref:`group` + + .. grid-item:: + :ref:`nsample` + + .. grid-item:: + :ref:`interp` + + .. grid-item:: + :ref:`delay` + + .. grid-item:: + :ref:`ctrllimited` + + .. grid-item:: + :ref:`ctrlrange` + + .. grid-item:: + :ref:`lengthrange` + + .. grid-item:: + :ref:`gear` + + .. grid-item:: + :ref:`damping` + + .. grid-item:: + :ref:`armature` + + .. grid-item:: + :ref:`cranklength` + + .. grid-item:: + :ref:`user` + + .. grid-item:: + :ref:`joint` + + .. grid-item:: + :ref:`jointinparent` + + .. grid-item:: + :ref:`tendon` + + .. grid-item:: + :ref:`slidersite` + + .. grid-item:: + :ref:`cranksite` + + .. grid-item:: + :ref:`site` + + .. grid-item:: + :ref:`refsite` + + .. grid-item:: + :ref:`motorconst` + + .. grid-item:: + :ref:`resistance` + + .. grid-item:: + :ref:`nominal` + + .. grid-item:: + :ref:`saturation` + + .. grid-item:: + :ref:`inductance` + + .. grid-item:: + :ref:`cogging` + + .. grid-item:: + :ref:`controller` + + .. grid-item:: + :ref:`thermal` + + .. grid-item:: + :ref:`lugre` + + .. grid-item:: + :ref:`input` + + .. dropdown:: :ref:`plugin` |*| .. grid:: 2 3 4 4 @@ -6146,6 +6245,75 @@ :ref:`delay` + .. dropdown:: :ref:`dcmotor` :octicon:`dot` + + .. grid:: 2 3 4 4 + :gutter: 0 + + .. grid-item:: + :ref:`ctrllimited` + + .. grid-item:: + :ref:`ctrlrange` + + .. grid-item:: + :ref:`gear` + + .. grid-item:: + :ref:`damping` + + .. grid-item:: + :ref:`armature` + + .. grid-item:: + :ref:`cranklength` + + .. grid-item:: + :ref:`user` + + .. grid-item:: + :ref:`group` + + .. grid-item:: + :ref:`nsample` + + .. grid-item:: + :ref:`interp` + + .. grid-item:: + :ref:`delay` + + .. grid-item:: + :ref:`motorconst` + + .. grid-item:: + :ref:`resistance` + + .. grid-item:: + :ref:`nominal` + + .. grid-item:: + :ref:`saturation` + + .. grid-item:: + :ref:`inductance` + + .. grid-item:: + :ref:`cogging` + + .. grid-item:: + :ref:`controller` + + .. grid-item:: + :ref:`input` + + .. grid-item:: + :ref:`thermal` + + .. grid-item:: + :ref:`lugre` + + .. dropdown:: :ref:`custom` |*| diff --git a/doc/_static/dcmotor.pdf b/doc/_static/dcmotor.pdf new file mode 100644 index 0000000000000000000000000000000000000000..caf8a36c1ce25a04fb7a8c06d2b45dc5f7cbc829 GIT binary patch literal 599056 zcma%>Q;aVR?54-IZTmN#Ib++lZF|nxI%C_mZQHhO@Au#A-DZ>RRg?Cn>D#ne|-iRgbD45OH(jf<%h5u=!m zp^K@Asj@bo?C-Wo{lN+_WQ`|sk8f2ZDZdbwLU@#FCQ&nBG^F?j+68G0EPW!L7w>jM& z)QX?CR+Bsq307 zm2(3tYJiX^m8A}wy5uX;IR*w9n#~@ zP7F`U$rn;M_f6Tj*1uB>(TtnAub1dX4NvlR4w!f2&o^_s!}9`Abo_K!8V^3W`E4;Mfnhp`XzqbcUv#>0s;Hw@p{4HH9Rf@^nUP4i~;?TY^KuZzIRPYNuH^*RsTG} zfd5NT@pV2yg$Io)gE=5eM#QjEJAb^oM|7u;?^YNnNn!Es4$cb-@A7rWhx1)=_mzJuI z0Ks}gM>+Ed7({`F_*cT}KwW||6-&Sk?YFOjYlf%thZy0@nx6HUEOIn{jW1jTQyK}$ z07{PLPH4BwFS&3z0&b0+Wus+O=~8wa)?Py{5?h@}c#201c7}!l@<(%~)K57BWni?Y z(hH6f!_TDK^#y&KaqIHIcTQcz)*aX3YrgZour4}fRzB$P%I0N&+=DOdcis4$v}kA7 zr7+!+{rY9@)QFf6?M>h>Hq`Wt_QzK7vX>gs*&0hARL|xg3mb-#BTei4pB42pV^EM z+XU|;qFc_PpK^72ViUXTU4V?MouAzHBop+Gb?rUPxd_4N$;+eLipk13BCDrq#nrBw zu`AY*3)vO)Ce{K>M`?w5lxc%Ag-|}Yon^ic;;vXN z+|!2HJfxUX)3D)*NjIp8{OO7X^-k+wa1MiXT*%${qBH)vVE=M628uk4$AIwHz+-(MJts8eI{>DlMC`e05Bws?< zk}k-l%S9848_u2OQ(9)Zao)ex31+6x1~u{60C{8IIZr61#5+<^sfi5ub7FIKjGVV-0Ps0>4rAT-V1w5;RX8K_VQgSo` z!~!goeQ}KhXi8YN|CVQN>p9Kg)1PxLRNcL?7NTT$0)`f|aMM#+q9rC0;t3q*IM&KH z7XFTNBw7f`1c^YD&-nC^TANR*pDiP1nl>T`hE*Q)r_plG6Jc$B>!#Fd)J$9;Xh2kG z%+OJCo@xEH&jMltG|Of~omo_e%Lavqt=FYU%sVvG^JppjTSZY=j=Fuom zm|YrmC9X2nxS}D`l{w`aksI1Y-~L$R^4|X<$Z>}zwh}Ax3bJFSc2!1A%^c*$FixBj zW37Ea<-s;vslOj@t(rL3lZB|{f>LNiro=zwCi|x}o6{-&AvwBj%HY-{FWo{vE?`$_ zU*I5THS;;Eb|A&9Q9-n3r5#1W!jYHQD-kC=s_Bv=vFNmPZ_OS2G`QH|b9 zkq!py`C&0H=&M(fBkZHCekRv5B+}D1QqsI?KnY%OWcC|xz^x+lPD^aSrgSAia_syg z@jyDaUqSKj*v&r_K{aA_%Bheift^fjk4pc*9E`nnRc9r74D8r-1$P|nnA_V%LqX7* z!Zsf(qlIXd-{$o(%WXYC`Pz5qT8=NHn;+8QpB9rQDD_SBz?{O#545g5)mf1shkLTC zhRT6pB`2mUEzEjs2KskNFoH9*E-os}h%xq=1l&&wo7tk2OM@s(7ao%nO6@5H5Z8js zzgVAM-l`3_ZKP+YN1_h4O8COlvsh=@^B>pRDSQo`qj`w(ZH{MqJC@(m9iP+1BAhq! zs_A5LEERA%HPcxwZOVPdtQ6b3R2kHX+?-ll48BLk^DP z&xl;rqPI#Y&+5w1b z_cZWpjwS?kVHG8SCZ9_e?pc25sMGAma<*1X7JOwETSjy4Tl`qc3FI?thGKS%Ea!}M zux*nwyCJ#|tsokKipT-$Yad9p+(%?|Fj7x7Bt2;<#s;APcr|6b+8{Slg!+@K3urlZ zhow?whx$i)VUP1lLMTELhUkC6&6L* z83ro`f&#MS$N(#i?%rGWOytSVzeYtVm69t#r#TBpFMvAflzf;aJDSy#1;g>NNaD6L z-lbq*H@B|nmW0NK&X_QfVCGP?#3J3e3>q$xN8Su;9*Fi!yLxxw220*1L{f$`$T!tZ zy6@!6t%R;DRs)F}3VU_wU$xz<#xR^PT?urrJsPT>KrDDW}9UO9i}4b;$_P`GMg zuQptRl!B_jM0Akj40qPJ6rbED_n;6j0Yo4M{&_<>*HGe{+auz|hEv}kI}4{=QRlc& z^$^RUbgnF9HL@N{AHuZzIPCUc$B-k>=gNw1OIjS0*~9>B6zqMp12hqoH%)0; zpuuIPek&i172Vrp?5`<;6a;WFgf(Jk{T)!1DR|~i%10j)8;TD_{ zHJq!a+c5Z9sAIM6sCfx84G8%#ANTaNmDoaG(hyC*0%_VbIBZXPg(Q(x-nne3(-KMk z{JFJdju1T(`>1<<*SG)sVe9>YBdSlS?A|y z=Fs?c+%C6f(#;->gTQkD7<3zSjfqNbM9p;R3TG-o34#6KQe>X4f}a&sC>Bx?A$zk6 z1c?lu{XtWQTA&j@{i#8rr9z7IB7rA_kENBpSfZO%N4bz7jr1K*63Yuxxlk15w7wCz zICY{1D-i7@dN^cjP!f5mHgaUpo#9ImKe8eD0L&Jc1|)<}dr~O(I;#cSLn?E$183e( z*<^f>)FeL{)?)~@n>-v|i)P9C1mvM=G5o(SJ*6mDoG3US!<`|lnYBg>s*J&aT1So>2>KD zPRu@|2*K116=^blvG?;kHir=XaFk!{euwVqjSy71k2 zvGNnudA@(m?nlh>1an%kPnA-`viR2{Bh1}wM*g1FJ8M8 zZq*)6Me`|y$TJZlVcoK#c!mW4ceTF0BdZ`!KhtD)pt2$42IC}TtZh@{x+nxT^}BU5 z9qH&@p)HVe1)%Dks-Xny5n75E{G%~xax8zCUNZ$tB%P^e9r|k!!+JwCi*5lu@-%ZN z$F7gU*Aj719t;04I%uQ z5K%~SqaRx;K!DEPt5>lUTe`Rs1Jj%56^7p2*%yNwy=PpGf!Gw1g+8h_J_ zJ2HSpU^)~>dJ|?wzN_03o9pNW>a=@RW3gVPb|ZbX{DN`gHvJK`=n9zQhvFq#63F<` zpD-eFU=VAKE01VTCG+Dq`>FefRf|%%Re++0R72=@75y?|mK#W^%77)j zKdftL1>b-bRB80L?pnu)G!SZq7ZF!Z0nxl&O|ooxjzZpe)fktU6dNm=vW7FWWCC&Z zMMZ}PB9$a)JU6;@ge~;hpJSBqxOSSusL##J-?t0$F4M@(p1ap5v$j*VMUO7I`#3=b z@XB^Ax+9~JJ#(PJxiu`Zwyiq;ajQjLZyn%Id6eu!OUC5^Y$?c}4u@aM6VO>$wAb8}bjjyGT)_Xc z0_^ypu;8u#mNV?Dy@{t$?AC;>@c@V#p-+>W1vJ_IrLg3}tw90sGBQh3V7W91g0LHg zmDB36CR~-iUIl>7ZWKzgxW_RRG=&)JOF)5dX}(aviDNt~hJseza-ULnhQDu1&gJQnk1h*4nQPW+~cqeUXAjPj_Zumqg5d;arTdfXMg?$itD3tfHAc*`9J9RKkt9AGk}Bb{|3+i z7A7v%|4#sY?W>(gJKTKor&q|26L7&(x{`+R@}pWc-OBBca^r4y>BVkbkJoK#ud7!|7@ka; z@3Y&*54mT-|nv7 z-yU|&Tg1!h>qRer_l1*ATGZ1`p*FvbYc*UYM0Nk~3lgZziuYLY;A2hz0Yx8{yJ z8wQYQnYW(l8-T{Ai?D*;YsyOumly zXD4Ng&(iOLR<*EW9C|totL}EqZ&A%wO+vK+m^|NBzAf8agyYEz!qv)Uc+SEWOpJjr z$=M0j%*^vap=?;aOHS;{F!3kaY4y(IealvmS~7`MX~NpB^x83|$zJ!=jZ)4T z$*#J-o3_63ECvS&VHLNAzO%gLN7YwLF+{%hN7Iw-RP}|;&S!eHCc3s6D<*2WQ(ynq zZF~&KDsIBViHzRa+4FRn1M^=@(=Ihvg>x5$J$uuSh9KAw>bHF_?GsaaI?@MgAZ?&2x_d^0=<+_Wuba^OcpaB0Wcx?JUV0co8EgQFaZilH<$Y){D? zsvkkNURmZcGAvzul8V+Y>*u^QLs%TlAYtjfF6EE_mXlH4w39CVO+VvYZrKN|PFH(e%# z`(WS{|Ce&|P~RxpvbAsbFeCT(eGv4|bGl4W|G%uJ51-DrK{rq3lZQ$1eWtT1KT0m+ z(f7ZBoP7Kx#N?zG5^RMNpM1H<@Gs+6gKKxgqI2BsH{r5)N>>Q$myO_crKBT3Ps40w zjlZAlpKb~a^5(z2H5hz_;tO>?Tr=Y)E%Tmq6JPF~$I}_ye2X`pm4jcCpSIZ-a&hyC zM?A?U?qVnY9a>EcIV`3_TUviugcnMlR$T1rEv_*(;5!hkw=<2ZsI|(8PaRH#Wgx7U zkbD7_LZ*iY0-O05+z^EM(5{~#Y1Fh-iY-N>82eKS9KE|+FucxW(DYXRN zc6;~D4%T7izOW0vhr^3Z%KDwp@^-#o*z03Co;cBX0$~z>iLMu1GT>}nRs=V|m4ADS zN4GF@wK5hJ)E!J2@wap9cyapqTiI1m`I4D$&at`j5@o6F{l)fOTHM8^%WihRsk-Ba zIP*LIR%#zJl=#=VdEJ*0Saej=OM{-{Dxmps(5{&$NqlofK3*SIV9jj%7Rau#ibFqz zUqd_M*2ek3?UH@~47b zf9D~ecnq)1n)K(q3EXw(V^I>!9j#xh-DQRzRbsk3pFI&8m9pS}E|DGce;NZI9^s;G2J=U5V;|1)0|N?b_R`cd_Hz zJur615kDVZ9mSnTEquh+i%KZp>*!bUH)48^n>RoIoA2ermE%wvqKbDjS6IE|m8A*i z2rhxz*?!)=yV$sfyNWle77t}VzOCfikm-9v-6w>>m}4_l;ZO7YVG|$rR0OUmYiwYu zPFq+42?pM--3j5^RdT5gp|$Wc0EDVJS}OhuVx^Ph;@{MG7)3Pf1FzBX;far=p| z=N`s<8(n`#N@Nq(p!s~T_~(;K1oL9Sb)G+#OQ~$qnxA*_x<68Q_Dps^=bMDf!nb*# zMy+Az#RLShckLD75q8Np&jrtWI#H$p#wz=0KI`g7dp%Xo$QY1^5wNA4;43cv8oWv+ zSQL=1tQx3t1<66{TD!HoS9yf5#n1t8z}$D24e>7uv(p|AGrWBTV^GiUy30*W;h)ce z74E*e&G)2WA&6m>%I(P}2#p(mDh9W0m!td(j%j0$BB-l~&~xkTw0^{@Zlz>ur$}^V z-i#_TmiX2Fzz1}$tG;hv!y10R)NQC3Rw+!n=@&a|{%p~^s{*4D*6Xyk_r-aPd<#NynxvwpNbJuhh8ORA>J7K$i7kHkC&Enqf~l+U7cbkK@TQW^!md#M03OXMBVK zMOnB(K{w?!MOoopqgf$5=&hWlCHO@p({;xiqd`s?WGYYL-^Btm%?MOjl%>;z1Q zU-Ub7-F}*L51g!s`?OcsP>DfTzP&Y}G9}~^s!cB;uUGW$RR-j|9r&d4JuDwV~n&A;Gc^rwSL!W&l#G&P@tY&?_GDn{y|UP z`tZ{<0+kyyEEvvnYwvNNY(3lF58_jz0X#y<$@D3i?$68iE4@@7#P))a z8#<&Ns0ftNay!97-+Pjfj;8e<4(j^lEGrlN`gPtOQ{+V^yQZ3=>^MAz1P!7br$=}} z#f!BK>~=x&$Mdi76E%-SZFo5@biECg7V>tQ;@8GbBlmut8CShupi*ANVv*qT`yPyL zmU<7x8GLdO>WuZi$&fvth3p%4I5P1K9`Ue$l11k5$NA}p4VQb{yQxq+i0t01tlCIi zbGxMC+z%8N$2x>JwAU>u^MxuW>6;q|bC>Qcls}4+W0%?);HfNJIRAb2Q?P_k9JMp8~xW(3=$M^pzU+nSBGVfIm84Os!k4ZG&)A0(=!etrrH5+2K^={w}i8I&C) z-GMsGh#{7fr}J@@A3NgMEn2BChB&mT$Or7QZ-N(~rYIx1vJ`WM?y6@Fg5Od+MH!P& zAWa;(WT=|+*f|)2&>3C{s$zxla?|eY<)Q1ye#&G^aiItbrk?I@S0AC$uX#06qf@-S zxV6#*P;M}N5zB_s4Z5DQ*-rjfyg?H-(!Zbh`H{u`g(-pJpAQocvBQ>sb^O3gFJT8N z?KUudzkG>VB{NDb@YLnWn5)I6kEQE-(+@f0NxttP>ECu0MmSN*mx`&?FWnAI=>gI3 zmnC(0PC+mM?${tBR5JL$%Lyr*Sh)T+Hk_^%xuc=0y7jE{Iecg2^iEdyC9sIeer87A zm$7*Rqm5KcwEi;SSX)%NvM1``exdZ$3J0y1nX1J$9F-4-biN!}nV@)vYl$lG!Ky1h;-9|3L5fJ?Jkoi_f4?Rd#C+GNgP-A}GpR+_%ziDPw_IRVJbWzD+)0OKXDmAVR zKpVZc)gtb=1$Kledc}|JnPlik-HW~5{EK^;58<)1`|-T*MJ3zS11fNbvVdbr9goJ{o;{mN|c+F&72z^-pm|+Pj64TAAypEH`A* zv>anKcBmDz{>kmXn=#Ar`uOns*6?F3&1SBG+>1$)u9h!3RVeAl6&ZD`qhVutq^pl6 za=trLT#}(1O+}gXoSW~C*JvRSgQ|B|fqqm?c4Q>Z3d_qXO1@SscV|0q{f-XIQ((+X zSd4y<-oIRb^jr4T6SP-7(|ZU!kM#=QcwIyu;g=ToC@-<5wfdtQP!peZXmYKe7RCbl zMQVN@Xyk0hNxSp&+P9O3^=N=(-cRm8Z$c#?LN)ND@ujI%IXdc1^V6)6A1~Fx-$W)U zu?(mxPmYh}Gn803c7E+pZ_;n9l*8p*u@=045Q$mGle5A1uL|Jt*SNU=pY4+V(ooUn zunfqrCLfa53pG_@J0|P9;pfAjIE6qX#ISV=Md?)WsA@v#E1u*Z*FPe3%2C&?I^?-* z>Ph`usk-%t@ML(d6(j^l^9#m(Dc|r&>?A=w=5aMy=U0f3F>rD&+z}^H=itr-C+X|! ztRdRmztvAWi)h5fjEPGoC`Sun@1*njTG!bgd15Q!Fjf6ub5VoM zdN1!rI^m$;JRH|4;ohk+j=bv8G^-_$d}s1;Q`ccJO{;#Ff-gl+aK{sp#Ctqd$ zNWOR+h~Rq`j-*S+k_vr6r}tTEDa2@HhYM}Eu1*HYPdUx*N?*`w7BiopU-zaVM4q)Z zd;Ee=wP4T-*I>-*5lfKQzp4vjc6?A9bUp1x81gDu8WAhp<@ANT8p7tj{0dPYiS;{N zLXtlXDSt{Fr>|_pN;PLyz?AuS(y3w**;#^?O)8D`rwuAd=(s>P)ZeM#!c`_+jEz!z zcQpa=I?U_(eqjI-<|;<>+wSFgEW_&s`{y^a%wra47LG>fW{8#Z5Tr6p=4C@AXW>l< zinQ2Dq~>^6^xL${YMuf2wyUhQC&!lyCm{;v*d&L!%!ng@wLwM+p95($_BnlYA&sMIw-%W94j=0iO)+Rm|2*U@mHu?)tYr2 zGFJ>a@eTy1SHn007ewSYJ%bDV<1s7?+86)Q2=5BBF~Xd?#}$P-+w9~ZZ>~I-l~zyF z15X40*03?w*$HQ;iM@CnVC%zOWSQ9r+#Jgg%X=LYHqT5@l^puu#P67FxEU0ffk@Mj zrH`d(y^JGUcQ`JU&BlYPaeaSKG8J|3he3(F^|*Ro zwHTN{8j7DaAl|n^M^(`Vw`oW0#ISBWl_|FvMjst1E;8~=7+L;-#KJuWp(B4 zxLtJJ+hT7X^-4DAh&UYw33 zd?)PTij#;tpcN*gWj=MD%q7;Ih!`Uf@RFR;)F603stYQW2#NV7A;OgojW9KE)Xeh+CA=jq|wHe{S^ z-ut*Hb)`Rbzs^vk(6MHL3ChCA;sgqVT11|TG2uieTat4O%OEL~X04$i#XfrDZ%T$e zLGq8tNMx4NbSn-m0A5No?q_bQ62(6d%i=?G?67HyGe}OvFMu^sm?;^m#i5aEO-vI< zTpkVp6d}0E$L%E}W$%#I@=myeL>@^pr>cVbqsIaW2o5oFbYn0jgJaGEdiFA*vAgQv{vEf{z!n7*=i7O;6ak}?mrz)!W~#JWI2$_V=nm+3{ntxU|f#~ zBtr#aoCC!_MxRCbxOADo<82=%LqD-^==k>N$#j9ERe6ZWbT|!VQ?EWnH2rKuUYD0F zB&bOWz(iVWmk;qGow-L&=#8|-G;%5@l4M?A;58o>(B~WGfq9{$zf#h zK@7s+(`O{XMBs$P-g(rzrmz5_qu~CUK(9G=b)!%M7BZuH9Z=o8hJ1bj7ctBhM7qsq zwHA0L110SUERYidk+Ytq?q#uBB2Z$ z$*>%BIh@8?ZrKLzRQIXDatKJ9CZ9+}FG+C#OhcM?FdljVl@{4BiDygI7gQLv>tSIA zTN{mh3hiV=I*blpD&O?N>0jQs2$ca`P{1~sV;9CEN@8*-4#l8~QOk}5rYeGHWxtW| zIF{gL(v0YU8PAdp z!$6x|q7jTdgq4&~soJ=ub>FN20yihFS;{O3x2zJ}3u**sRwQcSyx@>oz)#Eu#+HXA z7;=kZt$f3<-_R%E06*C$Ic(gIy7fY-F1H%#Dqh}auJPG$;sdKDSZ%G8tw_yIBf{+T z2R#ign>P7RhlvbMa?|Vthm~BG^TlJCb1{nN-b46Fm@Spc8thbQdcVUQaYGEuZN5T& zGA&(A!`U4+T%3H#Olpa~j3`uNazPX++aQdn(moM}bUB-@@z~Q8Ds-IayOr$iT3Vo_ z@r+Ml$G&WQ+?Q~48K?AQ#lI;>2^9aLAw!JV+GJzA73Z0yy ztpR??Ql9D_K%-E|VhK!lwwpa~z_p^gI5k?4o4fx=f;ci`g!?ayJZ*?rh||zEUS*p~ zne92%;&YLG@H5rm@eD(#(H_-6{u@z|*i=(aKeX|jD(CE+=13wwCovPL=>7|z{FJyJ># zz;#}8lOl&zS64rbcC(78MnGV8OO>WlI2g7jn^Lv^yGrF_8V#yor=z+k{}3+J_+Vrp zw^BFn7H%f9zx1^qty_l12#*d-2qfGlTjz!Zd>P+7MF#z%Li=Nu?#noDU)ZriG9*7R z`FOTtIuJc;)RDi!C_GpK6Nk2cItS}#U2M87{?8zu_ClB(1t1|1+G@K17v9Z8(IE7& z7?(|wFMJXDQlZ?Xh$RJBxwf&|$NXFplH!HVCEKzon3w|i)OIOZN8X^B$FS!InqHx#Z$AG7^Je>`Vpq;ez?L9k$Qh|_C14MDAf zLUr}8&{5mWMtFa1Yq7Dc;a`G4$A)I(y*{9rKS47v4HC&XY?r@naq7x{V`rL!%c}3r7PL>u_EMd6GmvtwlnR>91rE3gW@yA&rmcQ)Tu$@c~lu9Y!N_g9=P8sUPUsC z=gI)mUCjdm)PSP=`H^gB#$AlDiT3im#V?5h(*m?Nf&yER<)ttivo#T`CDy#qylE9` z!2&cJxr_@&{NcB-@|wfX60u8`ZmNG9UD=9ZR)Psr={?|V-0JinWtsVCXn~=e%ZE*_ z6P@J~kbsP=(v^ND3qb7qg77$FfksSva%VcovYb%_#9jKg$40D zyCw{`Y&G?+QA|CvI7?UP)Me(p6?=xe)ACc?$(Dpx`$o$AQ;?NvjANV~NPn+I+|q#( z7Oh=)t_L9&5i%!>tBM6=VEH5`H(Q?2rYbmqTOg27%=v_FzT@n|i4dQ5rt5Xt7%!Wt zAZESglifY$7Q(R4?_$GI)VGR`yCcA-6{S8ey(2ml*V@bVL@y(dUyfH1kcGa%#a+F} zN=0v6icoWxTY-q1ZP=r6L#yZDl4V(vuk^e$eu6+*gAt2|??h5WamsSKjil<_OkwWw zBIoPj#f~ntuO}yRZumfb_syMMG^*QxJzssf+AZv_=nS{V6Z6_n~$Klu~jgF zfgTV(&KZ^47GRp31(+)^t3yAr1IBiNda}8v)Y^j3g4G$hi_J-_&Nqz$6%_8$JnX{& z1fD4)EY2;!(CkqFs4T`cjw$9Vj!%-%RR|8XEci{G6+?`{Y%JBHp%XRIy%tn~JfkZF zn_A{Z?zAIawBhcYy0$2E{4N4ko3#E!(m7%Qtwf5%^Y)&V@!%)+jCpfdcN6MNCWrUL-wB&LzWy zqHBXGiPeNcGG2L3q1P8|0@0JoF=5BDpsKzigCxO{(7a5c*$0=!8OefiOvd|{Yob2~ zO%ZZUCVx2ISs!gKbLPRUm1E||N!>vc1`t0QzWcOfkEks^)>%}hzddS)R-}WdJt+;> z4?uk&iwQxefGDMeW~>WatzU})uwj%PKC_06RJ5D`noKh5D(Uwp(vm@qDOD5C>3u2J zOq-jGb83OAz_Bgg1^VM@_gE+pptCy*+D73>t-*^h_F2&-`^DebWwjs>Hf0+#6IP~{ zf0|g!jyxAw^>L;p85+pdG$YU!(o*TEH7NQsa@i=XN!2%35t^$Q9^E^{T%cMUT%sW_>eNHK;y`) z&$Rb~qPTIF6ur=bw2`XL!;+_YnZ-vuQ%9;;PoEn&9l#IZFqbSU4o624A+uy~y0#~nTa=Q6M^fhTl0 zC}XBw5Nq%jRl-KN_BS$2t$-hO%;{ntUG@j)?$sdz-1^5DY}Ua!I~6PtS*`;sdC^*6 zSKR`(8Njv%BfZm{FnwKglu*0`9Kcc27Yfh32+3=$+A5;p==+C za!k)lhd(h>Zo^4)pfAd9xGetJ7E$0ZU7DnSc2dYzQDrP#mi2W_G}(69cx=+<;9Z?Q zbVc>sUNYc_Sd-;&Lru&EGh>`xmkoDQF5M=x=D^>S-Fi{#>eg}Kx7?a!a9^C;4tC{e z-j)q~Z8+X;^5OvAm0fmE{Mdf-ua(PFSD2&cJ;S7SnZ)i0LEJ`(umgzJUKD8O%+nv8 zsrtA`3wyDVZ5t)pX-d`l6|0{uRED3Y&bUO`bR2VT4`ka#$k$?&X|pcTGhQqcyG|r~ zsmg9YlSz> zbJXuexD%Q-=JOD|0Y?n zYq#!YZqXOrtZlo-IDNVF=p^s`zS#34cWgat)6UtdHMvpeb*C-*TwcPYsr^*l*bcn$ zyLNAt>C#u+spY#>uXwH8@P5AC7JB!S_3i!X(XQOBy}a!One)}m`_&Wt#Si}ZgxOZd z^|}>s(N8(+QJeP#F8r(zdo7NgnIz117x7|Dlu3v<@4@2t6X&{s@JN7LuI7xTJBaW0 zMj?G(GZ3|?nyP0hgf~?b@7Dt;O7c_-(&f}B#K-6KXr|lPagZpobz5jV?TTcgx#LGP zh{xBkGX3#8RRdIrg(LCJvV~A)h&yDay9S_QfvhI6KL?X|49)GTazuO0NfrFlK{5)` z>5B|T)u>chWLEKy&>+S)tAs7Y4iyGNxLXbVz+1mU^kWUbBUKSrfBWNZN0@f~h^`la z3&Kw36t5yVJd#`N0$dLW^@`&q z5rm`)FShiF;G1$NKe3L-g%L8xaY{PN#@sPIiG8QYA*|gO1N)>=T?dO{% zmnTDUM;M6;l#I)oV34esv=>ymaMSU%NU;&P2D6ey5lvXl^s7?o$Hu7AA&$ zN!gm$rp1cAxPTNS9eE(SmF+r>Mq)`-B;s{ZU`1Qg1BVQ8{k2egEavXiwXQR+1Ke00 zdA`8Pc-j<2sSBv~cPq&v9C7q1`b4dWd9X7=dBF-z)e3J$pEx!^%Ue<%Mg~H|T^)@M zQZY@ekNjyP4b8xm8enuhBULN7FM~$j_4eGcQmadlPWT3DGjVehe(GRiWM(f9=E@`@ zSu(1fnFiP?H<5LyC_U7quZS|AT0Pz_rP;E9Pf=7ik)SHFG1^NY*gp}6C%+w)J|cX5 zf_*k3I;<^Pq{?Bu0HtZ}-|Cc1sVZy#qk~r+|Gv^2TMY=B!!0cGONko`QU|pFrH}n0 z4Ama}zi`gEl`MHF86xNzXx(xgs|3>Z+;A#1b73kb*bu1MZZ)Vnln8P*5m(`A->D~p zMihbN5STb95y7RPjcLf`9V{3rbP}CD2r&&*7$Rx9|5N{Z8OKRYA(NFBlZSt`p9xp zk{bcwda%SsTxonPhQ=}lyyFZ$6_=K_!u-Pk>hf&?DeXMIY{Cp(^d&(f`%$l?j{it< zA9R|2$%1SUoRplF()m`oT`*=J#ujiQ<=pWZPM5(Moy5lWYJnUH^aPU!q-wJYc=;YO zU9xC&ip z%gR`%G>MIE^r<6~3qc?in_!i9-VLKGqZKXqmyo(s*i)YtTG2po*P;2Xc!i=Dco;S_ z+7!w|H$+OCdW+ulHrc2M)rdxj)GGYAg}CluZ!$BBu5N51Wl{W?;tRA*(XZtBN%KoK zN(C86l2Bq=F72K2W7;ro5n35i7AY+;V>qz}<%?c`S{vxn>G_Bo#PHxX(7&1Q! z`p$cfV91*bM72EaUtnXVgozR7ei)DmDJbX;2FrbEgvFWZrcX5r2b+J9^r7C}s<3o1 zpaZK#tBQ2&<)WX^y?zFnX>Bh>I{rdTyv?;C2`rcRMzXBI5Sb|@>o5@+usn$_1_rem zvptLs1(&%GPB-}ar^v57^N<`~8p9dCgz0 zhhkbKBP!dU67O+doTBcV%{>z zvE@+prE;No857SeM)PGf7{)F(WGA&3TLXvLe+pkmN#)i%5mnwqkdhUo&FfdpJ4BHU zHgH#O7<4tj<&@S8cj#&b**B(scu{79@X#Oe5R}>HUDc}D?lNddW0sx#>|wESMrZ%X zEeH5mnRv^YftTQtybtG|kuJ~oAc{$F$fUcMG1qDrr+btI+%;c83xX!r&4lKnBOr1AYVTHlF?@D*S#i-*H+M&t%>T>p>n*J7loA<9+?K)`v`rM2(So^V= zuGc&y*lg2wQnsH`aKG5QE|;Dz!3@grvt0)M++6Kx9*Xv{80+$Q6zp_sGx>=9!R(L= z#OvvDdz=8~+2s;$uB@K`a=z|Ppg(R1+Z6kHJ2oF}otiA%ESl|JJ*H)vrg`#h+dhs* zX4(XI?5_;A901Kv-7UULJWGzwIqR-~*KM9YNwt>1UpT0g0zPT*2T=#-ro}#8%8j`d z=;g5O`P)HxvRSzt=TF0jEJW&jpg{PlP4FR(=3KrVT~Gfje!;xC;T`>)4%wM<8{UAv znges4w1z%H?>C=O5kyAjbfrsNbPb}alYog^=QP+TNx`pkx}#14?~YxqPW6es?M2hp z&cRiOdO7=(yS<^_9H2&=jTt?WPNexkW7vBufzJ36;3d>Kk9W@8#B*MO;)L{)>!{*( z6PVOq0UMtjHC6rrOhf&$H|R|ZfxIoeBw~h56SOl`_8)Q4-)|iGwD(%N>eT_Jv4=1C z_XvW1|Kyia9D8YsG3|MMoIH8?JL6XxPd$E4B8i;bRuwzd?w6apj6A0fmF?Hd-x7U2 zNhv(5o0fc{c-?h6J#!|adF|NkFfT-6Rsj=C35_S=g-UqgqYmWKefbYFvETZ|*2(1(&aP&G%QYFF4s! zTDwJKFK&jZ^|ESw>mTo`3Unh5^bM7I!jV&dvG*sebD7`buswB2_G@i<7S)zR@?Q#b z{U+yph=RP@eSJojwuPP4Ao)(fIX-KO!*N?ulX>D`17*^EA_Uko`1on>hdzbl)*sf9 zjb;vc0JBG$w#QrXu>#jO$n0#dKiZ5$1{K$iFQTbMXMrz;2?5Xn(3a>6E@6#Lrsi{V zG^Kxspp1c*1kY#g%P2I!Wp?Mzzh4E;2bDTgZy#+Oy6Nm}9?l)0_v15fwbPt0#~vz^ zi;>3oVibL+X?ZzICggQdiIdB3NbQ^!q?g$aVN$~6*J$(((Q;w1N zQ1<6bV}=Bg)bxQG5wVAv|0?Pf8GA>=qoM#dcuJ)$>Obo~vsXsAclh}P&xN>fx{7*x z_J@&{I%pratnXSHS8)SziM)kbCexg)!=>f5)B1O%9GbD2DuT-Tg2 zYw>I5pXWb(cQ=2NDPon#+lhTGrh7dXQt&GfCb)cm@^wBr>JH@3Z#2s&5ZTRmvnR1u z%Asp#zwxrxu|+Tf*1l0oOgs_+@u401X@!b)>Dta(VugYvsQO|6N_#l8C9k0$6N~l? z7(1y`e@NfR2M#&2KSth19D&TmcLEKD*;$Fw_8Kk~w#KJ@JXKwdyy)J`BPMsJ-CfSK7k7MoMg^6YHUO;)1A{FoWF!4yh;3a}xmWjMp!UkIb-rN^ zt0ne5GHnPW%M z_iXkuBAq_Zcoe%y*K!4w#JX0gdVskC%5Un6!KAHf**}>|NcDV za^3aIQ>Yg^erqOHNc&ia2<81`$>%LvZuRQcxvB&!;A!Vjds`0LfFN_^Kzp|P6H&)N z^L4e_p8bRJwF_64RPf5M*u&;lt|A_l|HHM9G0VY79{J}t$dRH-G|twF$auDl5>N=u z1@9CENZl>WJwl{{OY5^|>%Pmq@1*Cl+MoWsR{qUxxqWK03cXXz80_~H>F1y&_SUeV zO&v~_rMK~?U|v3#!uW=`p7C6GK-Qhf-Y0Wy34_>wh~4n~2ksLWD<|83%Y6dsY9$|V zCi!0*6#A{fxvdpN;orw_t&FXqUlGo^D$dM?fMDB(s}|$pnrI$wub-ym63A#Py0&cQ zhIlt9*)pLpqQvy28ghU$lj|OHlM~m>bC~{9nOV>}G)Ly7;e+bdZCe6ww}W(oD*}d>h<`$zMdU{ z)#dkxJLu0Vt~u<1)H{bPcP~vrg4H+RU6_i%Y@Z*|?Q?%ex%`K(QBH0Em7w5d{LEdx zLvO%ic{b8sAw!jAdFUpcfI>$s?x3EUDh}(nPZcYM2ZTS?$ASM|8d(sU&CtBH-6TxV zHpB3G-v`##!7eU7teUSig^RoRYtpB|&P=3c;}Jn_Ua=6K!kDfi?mcaIUA&QL&9b-)&}sQ{^Y!~x#xsP@5eIq-GOKQ6oAO4wQaWxI68-MgGfpmVx=sdGZaMH7_3FN6}Atn z*5sz4-}MN@GoE3-Uh)g!FROFkVcM1M0DuQ3t99?U1}$R6YAQiK;=z6}c?!6=fwj-e zYv)B1gzBojL4d$8bF+*{P^5bgplZy29QPCqbS81gZ)!H1fo^BmG>ZXVeH)oX&e~b# zTW`q~AL&DY*uM(52WbuGo%?L! zAL3dj8Yz`Bh_mGVF7t?=AhtMV2RmWuHgt<;%ouC$4kCv1ab&5gtPt6h3!lO#jw%rl zA0~$huP?~aiXzZAYrdpGoX&mQ6AoksRA-qDAjkCQr*nYCu0Ubsy=F&nnjj^1j|gmK z57588f>?;aX6ga!APIH`5FxtMcKK)N1N51o$9d0iLT>f%AmesQ8g#?9TOc2879+d} zNYWLJ6Rs^5K8VAS_jthYFB5`t?4}mrawhMkf+gDzGY8S4-PP6nn=iFpc8WS!I@Xr$ z={s)^zz^d9%^wk4B|jqUWPcaou=>3se%M&R$&YUer&~h4?ojqTs3DUE1DYx~-<;TS zLh!m_+_cloEUsKb#ryL;hFR^9U66|Y;eMKzt=8e*e{4i#&wxb#$U~DRQG?pH6DqWE zl7Ys%;Tn239uZ0?G0O@w8uC5fde@fF{SQ7qI|O)M{m$apI=7Rjw@K#ym%WH>o^6=#bmU(5$EzvuY zOCADf$8Ll6zjTb0ueA$zM$!&OgU#fEgkA%@42gpIy*mNOb$Ic;il}}Ef67(|cWBoD@p3Apgf325yLJ?smw={1#5O=Km0m>TgP*+<6StDJt zB({&E@NA&McbZ_4r`23)RwqS{BSAVo2>S zfKAf#L%dT!J3mc_?PRSV2{A*Tu98dY)^KBg=lj)b57(W)=6^8E72>a&VrklEDZ=BN zbd%xaisdos-!c4HuUp!%e9i{$h?MM>s1=!Yiflo<6k* zMKKEEv3Rpr^S0k({0VxIE8p=JvqlqG%QyX}s5t`)P7 z+0T9~tq*sZEm=@9JW_s>m~~;mG(C=S;kO;X)#@CqASjl+29Ra3oRZId6Tdo*q#k={ zlitGh^eRb&w2}wY(4y8P4_7bNdWK(2%8vy5c4y79yv3ZNz2L^6;D=pEg^&{BrlFXd zlN|$Tj`+Al{M6fkAPX{wtkIZZj2Vtx#B`&0h!!diUFrJC0e^I1zEr0O`Zn@FmHkSp z47;b}m-`2NC0)mO z+e{4^`bR?}3uU&V1RgYH$xCtGSMFG!d2F1D_=NYvCdE3Wcls5oqLOXwV_KPNBHEHl^TBJUvo<~^a4+6G8C`di%W;%>xVCN=`Ep@qm8 z)MJ|KT?5`9n6nyfvV7k@7EUp@#63kBXV&~T$AM`K&Kddk7nH~s^He2=o(!w)*D8>v z9XkRR<$|qi1Wmo{Q}Os+^zv_=HH-%m3u2K~OMSnFy3_{5R<=>7@>PIs=OHSow|kg9 zqTan@>!N<6O=-VtPe!xDKEq%B-5@ijSL<4~#C1$K_`uAFCW2>>x{)Ujs>C!DTq^tmHT+$w)|C z!WMtI#;N<6s#i>{A+bIMIPrlm4}ha+3+mu+y&q)@>P0QmP5YnvY5m@jr`~ogW*%xK z$Um*!diI*K+h(aZYPO7W6oCXOFP_Z1nNXY^Q>YFy9<`x@Sn>CzyI@Q}#T7KgE7p7m zLYjn&i`x?)HeFuKt4aR-;=jA2c-05>E~?!&>xj?qIB!&W=l2ZiZ`_2KD=P!$L&>3@ zTM%Dq=`4z36T6`)K-6}F%N_YA`iji~C5O(hf@@@d&x5D4Fju~)TUyes@Bk9OpLPpG z`E-5k%6b!V?N>x;2gnJ+bc*A?r}aIt;4=-Xst@JGYos6?&J6*Ht(ngyaf4x#H#2w~@tlGwN11UKu*map3`pU07wP(DW+EXwY@O{H+WXsm(=`!Ro=;dO| zopM@^KmJ6a=HLS{1qWOMP-m^Q=J9x(rMwAWO{u?GL_1nzc@u^FDicNGS_%3Ae z2~%qJ6q%HL1)oxQLFqXHy@h|(G*#B=Zsb|swbr*HeqlgV!hZ&Pm*6WN!)%>xfii5{?q0|-PM*= zudScTx((x#jL+H2U(?)<`qzHmREgVE=^ORN;1B+i>O&8tXd?bG&8TF zP@s)Zyk*ZyG8L`(DG2J?De#_d(~kfXKK5;nj@c2Y`myr3j7+Z?KFefSi}l^?sX-lc z1>tg#nVrO+%jD9+7LULdGU)dDXt$njUg9;tvuDd)ikW#Ew3&i#Gku^qRq-=Y0bs4_@tu7oEP+)@14CA0sy@MW^g=qG88%g-wwNW>~0+j9F3d zOx&lz%_0W=z297E)(ytr4M_86vp=l0VX9Qz|)XUR-&`(NvyRZp*k?)q&b|kEP^D`sbqh_YK%o%EGOua zng=z6VNB0jL~+4gTZS$&oH(&cBR)BFSwNYt(P*^V^8Zqjdqiwx??!O4Bmda4`TauS zMJ6y{61Aqzgmzwgok2)mM;QZgc>hfQqU;FuK|!Ht^OThlXt*$<8e~OrP|-LfO9$U` zOu~8@qx2|^cUjBngjB&pgVAwJr!}XWOZh^Y7b(i-XvgUSQ4TD~(BG4D*s0_yV}2IA zSfXbHmGZtONuxTl$v|tBez$3f6lM`u1s{}|eo~E46w=@peWSy&1rLChx>Qb32P5p5 zWQmNTwt`{s)}lsNCS;_7P$_4~G9qyp6>$Y?Dg8bXc}Oogl954}crLX$%*n>0u5d>} zo)WEsrY;MwDnp0X5bPc`4-Y1S2!HlHU%rw9{PuT?)d?SmB{W7+{LGti8E_FQ7SXK0t}5khRaBUDvVsTwXtp3t$W()fHfMNiLt<6aKY?F0 zLXFmHu1K{kRNzId2P6$jnWd|A2pl4Cn8xc7E^e&_*k1- zDcAb^(~WPvOS%z73#DX>78aG{7JIVJVT?_6?MNaZN_X+K;|e?(^x2QtLyG@Vf{(F2@suRTA;Q#YTa9!LUhAM?Q#Dc{!fw$>xDnK@;cyDZOuIEF zN|(}piKGk zHcTy7XRQz4CxaN|C{s5YAowQ)(RRsUK+M48Uf`U@&=Aycp9(21>Lv=%i4X2FjbO;) z2t9X7rxk3H?BxZiQ^P+{V6myo*^7j_>_e$)v348?SzYSB!_5^2M`nILS-3N*FA3EV zjF>DUBW;nRuS>f98OxdIJG+h`-FM(9Frs*E@rSvp3bFWRLBSyGX9^c~Bwy44m*K=l z)&t=EyYNjtg2P!HSuOX*3Hjefb@silP((v<`N1HV`3=6(d^nsk++bL03k+}pXjy$T(cpG^TMYD@x*7cTY8$trGr~>e@cs!VPklDu75qV{&^k=<8oeG_W zL|MwAaYAx8Lk}Be81eVlAlL$BGG5A_PJwlQrZHIiif3nSGH9eZ9lT(ljfpt6z~m-j zp~W*?Ivnq*6Hbidk*k~g23ovNn_k-miS_sVKVp8gk|a&BzaDfx-&Kx?D*LCudo7-E z5DKcE^VasibL5WmxwqD-;uy?a116)+cn)2aHO)|&CKhU%rsKz-y&iR)@-I5Q(`+`7 z^Jm%5=?=PIp6E|qb%A!!=?%^VpBqW zWx~1}>(Ok~qt%i*dEKj3QD`M$Yt-%@g6972{&ttLM2)ZOjC6n&NiQEFwL3U!+bwD1 zUwh$qIBS)(|C(RcYwKPO9@E=&Wef}EOjQu-kHS?3gB#A`w72B8+X#c_{62diBIA(t z9+Yr&+;Uz;>hD_uW!z=-aF@CPONXvQqbJvX`IT>b)$rQaJM~PaVkf@PiJQIw&{7&; zeEFw)*?KPRR%sa~yoBmj7^_dg`DNA<%RQkRb=U5ED(fOZGe3dDurtM<>#kc$b+dH6 zgxEoL=RmhNQ=6+Yf;<}d(4->yJ5poNYJZ9( zu@?Xd2|0abeo4=Adp@VMXci``I`*Y|qwFOrCu`uw$_U30zJWUBSthv^=$iyBQD&*N z${w$W$lu2kOu0E=Z3+ds+1fG>5-SIAKdcg?)9KPZ>o8P;*!KPTnpdZWW1QEcSn?hP zoe$%pS7_+DTZ#T0D{Y+RX$TC>l{=n>-X)*sr%XAg^!68}`e7uJmmMSCTOA{~XGn-w z_sqwb32B(`swh&(j9KSlSIjj7TFk7fE|Hd)?3%81VKxv|3hue>PSpGw4VmLbi5@mb zOsXBMio<-HKmB<6jHmXZ=7Z;!q+bXGFZ@TYN5l>P|=G=Sr0ah#>lO zD&DV@Zckii`xjXkYT`|XQj4rZ{}A*H#+Vx*ePBJg?s0pp^kLf0WAi;mu^2-=Xia_S z8Sv!(YOO4K(`>G#`(|;VsTd=8_TtM)#VSEo{Yh}2hx`=hVKZ+bm> z9;FP>W?=aubHE$?DrLB65+fqeB78)>#7s41(I}_Xc<*v*5EFGQw?kj=*;=l7v6f1hxm-$?*^S>RABzZ zIj&szZ@NKuk|xjPh|(4p&_hDmzQ{klNqRHqkxjK0I$7$-zViNug#j`(f+Qlq-{WX) ztzLV5mHa_}=WHR7k%_GkqpMey%l*B8x2)yqotQA@X%)6Q>;=m+8-&3sZyBf97&+_G zt~cnKJK?O~bk?8GJjG}}r?oNdRN}dZ_@Qd;vrITi_tOBUR3h~7{S;cQRt%e)Qc+E= z&)Cq;Z}SkEWP@8ECP!}cyY#qQIRtaPO$>o^WSsP7)DN#=4pSd?)tLK|1zft5%#DcZ zqiIkp!fE_p@TQ*m@(E`Q!>OVs;xw?E^_WW_aeldq1{z;L@6@qL5fO3AiWd5vT2gL# zbOsilk7Nqsc&b zf+%Nhl=98b8^`BIGj#Vw!E>m{rEONGzszL-_)*Wz&i|DX|2Mx+)yvV0gjvzpTE*24 zfmwlsm4)U1SI9WKxRP+Q{rI1P88%k#|5|A5(Xw;cl)(6`GidDhlNNC8yk>?i4*a%i z6$pjA-_ijXrZJ6bTpllqFJijt>$9M7vf4Huj>s#A<7|QX{E@~ zz4K80P#I-A%RsQ?TY}LWa7~btHt!y}o|a)%PFqJ49?cQ?mbn^dHPS6vtX1GZh=>(y zp={~PFz?-xKqYE8DpZ0%o>ZP{OjQ8g6D5b|*cfOUG;G}>%!25NqA5g1DE9N_4(+m^ z*>i^AS-emZ<=vQN8k!{ineax6tA0Khr$k0;ibSN6CNP5*`53K`Lr%B~uNxN8ER}Eo zZ8B;cOp7Owyq5nyZuf+gBG`Z>Pn=C#2+^MvA|?Jk> zF^X33Lrlt31YeqPrX>uwbXa3$-zBPkd>TW2VL%1;n2gX!X>EBuak$@7cpI~!VN~&u zt0`X<4@LD)BMWEdH|-2KKZ-3A=yi-(a*jh2?|AIRVRWHl(UhCCu=V+ST;qTUvyom%+^);jT+=Ckhl83k#U}C}P-@p)02FpoOgo1Y=M45N> zlnHo$UPR$=#MOkx6Nrl`or;~aoW$Zy1V-L?(qAYk{b~G{yJciz) zKqt^AIi~D}=cK@3)yqaL-0MjyPX3mr*KnzJTWGkB>(e$(y%MSd~mu>4I=#f zpe7wg^o}`WEgZx4)?F$tkra;q&X0AUArLU>?Uvf{bo&)WM(jnkkuLDe~VjOjPZS_w_t*FoY8?d?jUN+UbY?m{APpC}= z_DUOwDs7ur*`HBQ6PzlNM8!kpQOClg*X&voBulfH~FO>L50oMcGa&1JWrOW^QZx?-sGcBwhD zYnv_IxU26P@M~zu^Lo@-qs zWR_1Jqlv=3G`zF#cxC!7J+xE3kHGLAkSztuE6$*fr|gp$h}W&a`kgTD0?}ML(%ufk z!7=&aZ}kv5o2jW7yBb%HtGu{4CJVjbC;War)d31-dw*<#$kqJe#Mq7N6urZu{&VU4@Q-)BbxS#58kWRn|P+{wMu#F3U+>O?W@{%iJYs!Jr?UP zHC+@))YQe7L-`&&Q`@oicfTH+G*w@Uw2hlDqnuNE=F&&1at^0nhfDk)IP+&mnSc8{ z{@M+T&Cp(}gdz8eOec4w8-RGzYNis@V?c0x*StQJ=CwOrt=(xcS{ik$9xhAGR(IHV zcuFru`J44c1JKk{dw8C)y){eep_#POUx6Djdvtl^^@#$<(N9uHMi^~KTsqdh=qD%K z) ztv53^MLq~$ft+J|8#-Rf8RD7Nym@5moBkz`yM?9pizrxXB_wnlo&+3%v;*1Iwa^nT z&MJzdSf07$y|4PV3x|LhHPYEpz6CxKAvpVW+=iG$LlO#NAXp(9iR%Hr>_o)6W6}v^ z%p5n@e4&=<;#nbK5(hg9Hx%+T%{_HiF)KA)8@clHD(6~!NhOL17BQG}zFR#QP?5o! zhFFe1jib}EDSGb7U9-ry7{p}Gnfo0doNm6O|AR)~vJrH>3L9 z%aJfzj;|yAg z0yMSITzqh=q+vH!DNiF^HfFh zcFiFZ&Wy>=1WBc6b3jTzkz@-O05XuDT)GzK<#R<~*ETpIYs5CVAbA^5vxCN7OYwOk zX{=1iBNS%vc^=GU$zhX|_&SM%!a3@2(Ly9p^sF)@P;!qpL$m5^@$7@_A@BVcv(*b?=RT7vPK zUs`g)?WK{Aasfl6)fK@i;Y0AFH#Ybc%l=WzApLIy+pH1Ob(a0Ml|^q0z__V@E3GE zTRYL-jOCgZqwpI<;iacB9PsOJtm4!70#SzV2Ocr7uWr-4dmU2JW!h9O=-80F9NEJa zzm~jeS?X!7BK57=@JDY}yY#$+eDG#do^2_ zqJlO2x>b+OI8&3sPG8xV1(%vz`@2ONuKg*66|6vO46x@z|{)@q${H$4@f%9pBJCKE^N$K;*?d`&Y0dAaL#z# z9kNUob1uDX)$R1nuON-%%bkGd&uRz%ggIg2KD;&AkOaB zp{KrVd##>r&5Qll0HQjgYpy;owV~Hr#|PJrKA+ZG+P9wQjf9(`%G=RIWD-e2t}7_lPmV`YU1-4T{5u?6bxNVE;QzH)f#zPDe!0`vi6^j$Z{{1O5VUY+L3Pv!Eih&L(x`S^O4 z6dj%bl0ARVoIE;yPWryTj;Hsm7M_LyG~9t#{+?S7aa<7>L%_`iobB5>)Uoo9gHKOx zXO}^5504pC&zmLTyjN<0J>h_Eo-Lxh`;%%^4X(F?$7QOrj?YiE+l#kHQG*};Uf$Hv zPFwN%Uy|z$9{@swyCHCw(VV2_4DdWUIr60q!M^|lgMf}rp!40!ffe9EGS0w$gzSAX=lS!;*LJmyG6Z|5?=^XRX4z|fD`Zo(b^!;q_o-~*r8 zb9BTHbB|K?Kg1{=ujBNWOgjL8xANf9M~mb?R5RY+VTG&Lf}F0O0;drCM0qH0#TWs; zW8xEk34D9D`#J-2|T$YG#KCiN5$Kn+Mfc7^4DY*b)sE?@j&enB@ZD;7i z({)E4g$T(r=@U@--0Ii9@t9|`wCznT%8o(~dmG|k_OE5gQ^S)_!0xIsEPmAo zDBrmo@b%hv7I85a;yeJn$F!fZgicMofwLW05;myE{O~QVc7t9&oAc!4*Z+8M^cJY4 zHD|345M|A-R7Py`erGSc>FrSnTXPlz1?PU=9e)6q!+`0MUXj$EM&)f`ZOE6ZovGPZd)l*Br-KRv~OzQW(K6^+OdVu#K&GX)uBh7^;XWIku zeH!&zM0v4)9=-s567|=)V7%w8V>PN0tbFlq@;S9{Se!34gmV*Q3DD!H88V(0exro- zsTE_JZ?J8W8Xer9+c;Oi=zR6>!txh;?P3St1g8C^CDtsptuqz|VYq#YVf@FzFW1<%O5PYBeCzC1zRT*b z#}AEw&&jsfHpe_iuNXJ{7(G3p|HCV)xm)Z`gSn2u)VXBmUw5;a6{?7MuIlUFS9QO} zkp^2P9oPT{iRK?X@+OFOwnm(74G(JwxH{Rx%ZA?NuR=+3^DeZAJBG>N+dVhq+kYJ_N7yCpbvF02ipdCcg+?6HzW5-LddK*hfg!nBdIw z-{#YY_NOkHVdl0p588QFORw**ML%V>nV&B_31Xn*Sq z?AqKuiw-sc3mem`UekwHITJqjH!@b7%M8RuJ%Izv*}-xvATecVe55!72T?1^y;wMD7U)oMp<||b-wdANn`|y zlwR@o5`%iwu?YN7kM{f2zge@`6Z_|mV(jG#=9v?7N7Eq zD-NiFEN>)B`~rOYcgM#!)DIt7-A8r7d+P8GxBQ?lnhzEx9yJc7Nn^ zmd|0Jh9xXzBqI9RgUxPHX&S~KtpA`w+sc0#A0eG4IMrb&xRzAx6$I@S`g*ne0783Ot68GP0VOV$HSY%ZZ9#scNf!M z$ZnAVU!oOmTT*Kv^}9N3E2Q9#lc^aI?~^f)E{F0eE${5tZuTu}8FR#<<{= zv=@bYS2{H3wnT?)Grdrajbqgu{sXOyN5B`HVVdxK86&w%bV@Z`q(QdW0$nJxJ0JZJ z3zrl{??s-b5ea7{!bFc$8)}_`Wdt`-l*dC^AB~RDK}l{5gTCjIR(rHn1!-Wc)%_z^ zU4GJ2eoNvMeBGWwF5Gk9UV*KRp1vate}J$tYU|_s%7!EpcH1oewz8E(kGLPAr8H&V#z&tA?y-6z4t=#orl7BdMTE#aT4N=D-Ay zI@I>LT}bJne_DlllS$`vVUwM%BQ){;Q&N(09;pQgiD*%oG^y({6-Rv)*M4<43*_Xfp?*nhq2P&NKbNZsI~_I zN6N{dx@g-964_26xPplf>@gw7a%c!3fjLP5Dns;%bx6yZ?*e&?kiz%$B7d{_aucE> zDa74i3ExY1A|niARtPTc&O+}*8uCGfp?qsr$ECuTP}o9zHW{r%4pjJ^HwiB`eAzXO z8;_cT09y)9yG(C&)PbEqPON9ul0}O-ZATRsBX(o*uq%ni>hv9~qjMr~h!J{(&gN)X zJa9Z1XJF^`3MsD89s(VZeLoqT8YGuw=@@S_oTRKkAB|c^o2)C|m=OLXZWI?hj}%u% zjgDuq+NAkgBNfo-Lnkm2WJ2=209QqoPAG)MP>+#+*1x@cniT~)LWFh-V3g7jyM{0| zqe8@h{w{()xio=LOFt}Tb9H1Now_0^a&zlCr%5nrK&}5gtBesf0&TVz+&S>dgTWd= zzNtcDm}m@cd@le`tZFN3j)5SCN{fZZPK$dDHA7i#3ugQy1p#f~T)!UbVjz41IBIHE zdw%PAPK~HP`by6lXw(rza;$20oce-w1?4VqEK#V2NHHQbK!Gk%pGDUmF62axUM=&B zWML?JG2QTqVEJ1li*VP^R4gQ&xl4seeIhGl9MqsP>SaS#+j6WmgKpaSq^f64NW%QW zc*a__=FSyvn5HenJ+oBevX=f8aiWAq2M{=#H*9CawCP9`jIbyLlyOXJEZw36OZ0ck ze0+33YLh_nXgzXjrG6ITRM-qiS$i;MBJlLLofsSxlrGV^Eo-j|I)Pc?Mn;NVO<2?D zPt%HBU!WIaAKu2;1fT-!9v+J`;o|yCAjO^XUL{KIN6@)-x!QvLvr>O+mw%H`BE|_% z!lTqBZ*9AoIZOL8xd{xfc!_s0-mo&0VgFHOWY`9b_J+b0e&xXMBh%V|a#c6|;7?oC zQ*cp(-+v-w(djsp1JTplM@C<0;B)G1YbTv2L2yDsO6%7?4tf6$TeJ zr<9TlURBlp8o~C9&5l#>ZACpoIdZt>eyh4|`;{qFjsW@nqRt+#GBwF|^E z!_;-s)>ji4Z=7ah=Ts%T#}E`>z!LV`Y`)S9=37xW-v^4D1j8jD(JSc9<&uJi5a>wb z@DJb21j&cvm3l@7yF)f?c$hhw{RzfG8Piq6g;`~_Dne(p%nDhtf-xn=nA#Tl2U7-L zt*Bx^AQA7+LhDUBSy@KdsYo*Ov(62FBT>oV%s+`vBgQSNM8sY1>JMF8?jKcr>i*U# z$_Ypr*Vw*OC_LWolGn9oL;>RlIsJqUB!*-%rCf=fQunz*{7}zvpsC7c6!eN-WoI*b zj+iHwdLDf1m4xb!`r|!Rq;^!5p(67^qRL&cd2ui>kaJ=RUWrQC)tyI+g*UY5b)+kB z&gL|RkFl`WipvhZ{0JtS*My^m+YWh+Lo~nhh%=Z}?}mrbBL`gCivA~SL^(c<(Ium&ID{R94i^3@P3oo#ia6S!!T}d zkO6{a!K+OS-vk@vci$$&MpS~nW?5)-%e%}l9hz@qaE+QiWu9ncP#O76s>(qp%A66U zBBCi^rI`oHFG1RN(NGG%*_^u?YgbBC$a&~msO4U{l*jJnGhE$D^eh!trR&*)1DUha zIl)+=G6wV4qoovwv;i!PaAdyLRo+d)BrBF(J!g*yh0vjsVWnoGjz-E{cGeKW!CIV7 zRt)Hlj(S^*4Z#TCOt%){sPme_Icp{isb3d589}C-xOpjMpVZ7?d+?^MtiVIoK!kuf zK&eY2O~=SdDKP|H*>Xpn4?~m;Pwr2y7{>ytrA2gz?~@ExP2%;uo%n(s0w%DPyxXY5s^8Nmo}4 ztni@nzbXOoIFiv_j`9^zxq0OpBiv}V=NZPj%p!F(**TGi8%`Cl=Bhwil-aGl&v7Ew zgOCx>)Eb_cMhasY2?0k2NE>^PH}YBjVIOn#Zhc6%)xR5$lCIQA?W2x69EXS$W@`j2%+%R0Zai%yKYn#|?io@iz&5OA9?~*kfOBut& z$bb*B2{IfShQCgk5t|Ajy|gZp#)tmXF1{4| z{7#8TP#%NCwo!d~oD}HCqf8hv6f0QSk8%`Vo2|YJDNPit$7%SW33&|Jg_ywDFF zrm90)BN;LrZU*IQ3iDQe6%jHV|C*(2yIrQdLNMeqE5@aqe(1vFjTLlc|GJ}?sO52#9ZSv7H*u5S zNrkppU{?LmZCAkx;KL+FTJ((F3#UtRv1#*~1JQHb=;2A0RwJzStY|olSIAmGs+~%R zez)Xz=N4o>l~nj&JU>u&p~*m<{5ZKTKRhZ;%}G!T5|(}Wrv5(;8hB-NF~ z6vq+Q9jXRSS)h33u#wV3u5T_`)p(Zdl9^K?VV>^l?a}l9cF!r185u6Hi$d9tCWI zUbqCy@Cfb^lY#}{g)=fM&qFr8Y#ah(_=KKtNRtxO)&r%jJ4Jg>UrxR=++3*mIRwT$ z)_8fc35$#)m)V1)v$rQ#-$fpQH2i{n1Vo>S)8P@;fA?OGVJ+ti)Gv3PKE5mh0^)>u z9SI626BTbqsJ~8bgN@0Cx^9j|B1XCZrg~p24XIdKn(-CPBk4FLxrxpX6HO|XT59aI zf>;=}adi5liwvWpna*-^-2m4573}oqSlYnx6_KN`3+EjiW6KrRa0);EG&v>ef=ZP~xH$)kGa%`p7?Y0#yY6ZOmCs*tfUrl38F3eqb^LB5JhHx0 zx3-|lRW=(yE~kFp0J!M8JIAuX4#4WaS$L&_o^_`X+o4(4GU{_#*(}P*Z<`D}C8)Qj z_BoTbRo@BTuu*?Lp3*!zfKX@QJZ=P>A8;`oJnOTxe~2XmYI81aCWh5vd@h=L)iw&s zJ=@cV+_#Vp%zsk@8-(shw@Y6XhHm#Zprz5Y?$pJy@%dsgZ>=Jh*3bfkBZG*lJY;v`}Qx&m|X%rP-8+_oIieP@}ippj8?6UOQXQ zo1=<*eZscwz=-#%&@rDKwdr2K)U(m^)bGBv@i^DNOTTX6?P4>sGxOny?mv%=9g+?=sdqdzUG z(Cx__zZUHK3QBzUmdLFg$az_Df8=;j<=}tMHECG3Rh)7$Z#Pz-fW=4fR^o3G(Lzj? zJA0;0bSXsXp7XMSNt?HY50DY`n|NgB z#^IJwa2sh=r2ZNUrOil^E~Da>ka@(|63CYMDKB*nq%SZ4JQ{I?f3m-KARs`uJ*eRK z6OSK`!R{PI@{Nfz6!Ej-bpV|xL17HBh4rg(-(*1W%~b@_aOorN=Su`MK)_-DcMMh& z+*1{s?JK4KcY5jP=A+W&jh&f#7XUGTcl+=0`bJ^cwn#VtJ`sShuV$2~Eo0-DQd ztr4`*Sv0X1fK&^o0V@PV*xh4)hxA5=6fYVWbh&dK0yB=MTUZoGgI<03!UaMc@*M|N z4Mljm7(fK0)fai#Y$nE< z&U&1I1o&tnVRf}z+3OE{eC!Ca50-q$4GUvAAb+X{A(Y(J_Q1?$gd2<}v$t`{P1t8WzMc*@ zUy;b}TlIqhnYAcUuoJn5Uj@`(5>~-b;u&*=@dXp15a3_OhrZe~{u$%kCca=W_R<%V zI!+UeYRwI?|A5Xt@#N@_mq-Cmpg>IsAMoJIHbD3@7-}eIcOe)z88h5h8a++!No_uB zj5j2c*HmYcHgsM*;Io3o;E&;$oz^`&b{Q`k`)8aQmaaSlFm|VBbO~O6aa?te)J3<) zKHd)sdg?ZDn{AN{Wt;^{FxqsP@LG;3mc_i5_gUjy@9u?Q=;YzRO&a>3)Efj07q)p|$^-V#2h{uhOwxy`>H_gL z5v$~!;&H!h?6i2uJBac@K&X5v&=(n2%CuLyv)1mk_>&+($Ga{j@3Fo!@bK^?|Aa0@ za&a4cI2`Lh_XhDBDVw0}9aKu}nr!2M^@HZ``4@MAAD&a(3t1fUnm)|6xfUv)kxt~9 z4opp@LHO4PE}IG*D?ME(TtTjNR7Hx$dp;bs9y zmaX^v`G3W@=(hqeavTFM4!rFNX*Fq)mMV=}R$Q5P18Kuys>vG0)~9o|y7N35)ZtQn zxx^o}V{WT$-ttIMU=^c_v}B&;dd<1EUA8t2oeUhF#2<^%;xHp)Q^AHEajP9PH_dX? ze~696w0jgUR#meVso`q-V0g7>MW=}BFp8x_l9?-)oxJPD>%#32)TCJtY%6vHb86OD z=C`96Xms7((Ir>xtifZ`>cog;f|?(tViIXE7c7GuTkC%6n+pTo#^@Z)vouK6?~0c- zbWmH%o0>f&Z0bX(dG4orwH=eST>L#8PlObXH)%lt#r=^|(Mz5j`o0094K`<0a+6&=nCKecvCY@f@ z{|x0YA{WH3!7G(ZlUuETu9%;lM48Hvhla~L|IlU8K!|CkEKdXaqH2X3l+D(3Mp`;H z^AzQpRgk;ma+{AL)?xgF$LTmCOZD`Sfm?>bBOa>%vpEtwX_Oi%itDg>& z2b0;Uu(+SZirIJ-DoJ9(2IYR*Ve?eb}CjbPgTKoEQf zN?ap2@aJ+geHY=)2p%F8V<@HS1}4QORUjFK&z(sy+{`?5w)Qv6)`h>O$T8<~kf|O& zb>zxNaQq=^%+k+!f|?~Nu^4|;mtc3RsAO5Xd%7}Y8uKQW%oA~ZX}K&o6=xXOekN7; z6{r)*56Eprub=sL73)(+9>f3wSm%9H$|7skzP6@qQFoSkKoZ7L@=?TW{UvZZ<~6yk z2VwG|N-!d+n@NA@qOx33{Oozco7EzN7?PKGNle*xq0yB$tI)oRlOfBpd6_AK4O>cN z;Y>?{ld6?V*sZE5oB!D=*WHQ+K84)mm($%;@%DC}KA2he-q5L&rW?b)7`mXD!|Hd$lyRwPKOn&p+gP(HIoO8qUFu2s} zn9wGrZ3PiNM(OalJi9JH*}MExQ0jf6jc67_1mT4>N8@Lo>FwP zD8wTMLFcHX%djt&GuI=8R#Lsah$?IK$pL1pZZ-Qal`H0DnN{_*p@wNV-X^fe{pMLh zfep^qwpB_#5=A|>K0r1ITK+OL?Yr*Qsq#?ycJI+h&-gV1pD{Ac}fMOmaaUFOZj|F8MGpG;H9n zmGTNwazSt{EX~4l#PxEcvZZ)P>m5)1j41hF|So>Y~`Urh`>H1qJcVq^AGk8yeSn z<~fo#Kj0)&{n=vcU-Eg>9W~B>z|oEL&sD?QyzAWRd>E7-HUy_=j<0fha@X_4M^0vEl?p0p0-^u`wcgt-;B~T zns@)Z7%wXeIajzxTOq55V$Kx-3O9l^dggz@M|lSAI|*uD-p062u)?=gZl*tD%-U6O zvD`QJVf0YR;am%=QB6DZdzCojI+9B5pr#)L>spY<@e}~S2!GhjEJ}qWu@B_hF*_1V zg`O_8BG%lfs2RVCdtT5xvR(C60j5Lu*GTgCx!qt#2lkIzP;wY1pIHB?Th5&rht#l4 zOKeQ6hGrVuPm)CC@yQ)GY9;yIsj~FRa$YF`BY*S?zX@3*TTIm+oLK%FUuQs3 z2orO6;w0gc-YUWZr3yqM&oB=c+am#`lq*(Wg_4)gCQ2v4rIQk4`-hVRc#(Dme7dIY zRm&-_lkGT2K*#f`L_Rr6PdHacHNr^+`>=C_>L-PZzi5^z^75g%25A)ABxR+X^w5m1 zPF+xq2o^u+^0+?jrHSSuxKKmSsYJiCNkHNTQyyog`t- zPwXkAj771F>$~Q*SkO;;5msr^hk?v}D&%$#U^909>PaHYMo1Aen%%5}z%6P5@6l_n zY?LHT`b;as@KTt2^Nx0&uWwJ3t}x@+O*YrIiOKjtx6%(uQarw*b_&OAh6Yqx40eM^ zu%Ugxx3y^oLEW@Vk49`pDiUZ#wRino)dXdukmwxqUZ`N~gP<5KC|`DmCsd0{w;ePD zV!>hui&Zu*YB$9p<6~69%G}N&Eb>AdUu6(qR7pd(gZ|;RiwCW1JA;g7DbeMT`CGFN z9^IS~Kd_Ip2PxhB0wF@R91RB3Z0Q&DA=%f2OG6ITpW(pA0N9Pf!v@2e=rDIM?wlkw z%Gd@IQakH~<;m1Y0B6n&`%ZIf)ysmMV$SnGu^X9%f?+H7i%JGwGk0SA6ViKZ>p;Y~ zXf9D~WrZ1Pz|h#k`qwG!mMduH2b1^%B1%oWg4?pJ-QRP{DSmNL)A(j>h3G>D=StOf z{p`<)X$Bc?77jc@!i(szSu6e*%(hyY3rk16S#Sb4&rQ@B3B4aq76Fn)3=#CW`{bx% z*??-SxecpDbR?F=Q;E!KhJ=+_@e4|C(rTGJ_lvYkU5L&_KxC%)Vd%IxGe$;?+k4S- zY74=bBqbG_m}o&MnuJ!&e)G$Ai2Be0%Po)|n$A{Fu!+=!rzWedrL~bn5@DS7qt}Ho{gEfh|lyREiH=hc(4-nl$ZVySqiN4Mc}9SL5vC? z9*%lg%C}J{u4=dCjHRS|?8BUJvkCL)lTMQ>YR3XVKrrmKiObMp)7$oeB zf2n+^6KAy#a<&JX1_xL5E@NKkDK~REWi4wo3!;hTsPss?p*XXNb5rZJY+T)0C&3 zn^3b`J+j4w_S1-XRU{VXUrkZmWEjhGDoEk5{~kuqAP>F-ih7|Y)NJi^Rnrq{V;MTr zU^eYxY9yPY0~0gpW}rWsAFecizaBI5e=w18a#@7R$t-|_15?BO@l6ZX>0R}FBSe8Z zaKoxA?S~~NW5uIVl60>;p*R-44>va;%G0SQuB<5qB%AAxTCiz>Fh)84Ru4wz?YEH3 z7)H0DZv51CGOw_4vB5Yi;iYUNv%rFH(DuR)qaFJe)7=#cbrXw9;d=+^9cP(0aQ!uysszTG32^l+gnXn1j7ivlJsm1EbV)g1nuflND z{_mm$Gc_Embs z3XP`!tYxLdG9>7@eX02n4@i00Ir6&Qc-INvDOcb0*zy$|@bl1i2v?4u7>jw%uVk$2 zNGX3EaPDgv3@po7>oIs*YLzJ%I9~KFIQi75MaNi3pQ;_@}BixVm8?=oO`bJa#vP|qlmrbZvtfaCk>d))jgE7dpZloQ@@z?o}OFU zbP!Htd$*EpbnZ1@>-=Tv-E#`&lIFK+ZyKh=Q$tmhsO*j~szlS}Ka z=0kok;HVfB5$EE`i8cFk#+|P+P;KxOHFoQy|0PiH{r)&>zIW2bEoZyA+_U1Gm%cK* zr(X@_zw7N+w9~yNC@9k@`laCs)y%eDD*s{E#51v04q&X>cQ?y!Sr ztA!THWq0`cxv}~vIocRl?!0a88P#L!VUFhs#}F-Qj(dzR+F1(Ye20y(GXc^WO3c`` z_2SS#NDk2aUau(mZQu29_}8!-;@I*Vv{&x_a0=Q7JaSHLdp_>JtuSb>$D%fic z`1BRU4Kjvql*0Y>wY0+pEvorZ85Yuvw!Cch zI?P{2pEKkqYm)$EL!fsCEbz`drvSIPek{9qFEU?{zkSE~83eBi3RfnC9De07as~G> zxOKff%Z$(pZ^^>0p~#5t%W9pPoKl&99+-_R!Lu^=r`c;1t$mRY)EJtt;y$ZoLs_a- zFP|mP@P*VEKUGD#1;Y$Zv3wHY)3X(|~($uv+{;xsz-EXC`{5;;nuNm)-`2C}vOTc$YafWB(M?}xg^}&T_ zkycl204Ej_>;x+8963u0$lg65g2;FQDY zl#I)t&gDD;MiyOFxY7is?J8b=I$T|1tlExz`o+o$|B=#$-{Q8|khWehV8tn{LXv(y z)YI|qDScx%jl*qf6pu`}!>{K!u&dIGi%)axDI(a57KPLMR6GSVH&IHXMD{l94}!lf4HM?r7}#zMF}N_(n^yq+Ql_K z6wdZ&B$W67gY&}^reTV7Pr4w(XGV}lsLp5D99Djte(nLEv9=yAJK<}rtA%E>A3VX5 z&-WQ<@e6Q({;V&RN3fdn3s{V6$zFrIhqv4%+bZLP$D#E1y1!5NS`02pm_PS6e{X1iS!);`P z|9l>{c3flD19SlJZEy>cetpEH2@1ky zum1%yCK1p{B~b|k@NMU!@zyIhiu!tbQsVhvX}}tQbt+vyq~8L6Pk2P+`1$PLSg{Vf z@!{?HW~Tm=S~2yaCB`Ut+VhC$xMhRhU)u?>wk#oWg&c#2g+IJ<;lGBh%4d0M9+C01 zLo1W9%EG{ZxOERbDd4d81Yhy}b^j%Efy;$hnV!dex=;Qc6kJT6k^t~*d13sF>So$~}6S0aGdnJz$ilbx za=(3Pj=L3L+t-qUHDTAR>il{Bi7dPq245!;k-iM*vZ-GTLvF6u4=Oz+g?m)=;u_|` zA;z5^Zqf8|LK(4d32VQaK!~9x1#&g3XZS4=ZTr}-EPZpm_j*}RA?>3fB)Uxa1l*s@ zD~1bm?QRP`4Nf~_{$}*k=WJ|^60Hw0={GnG7zvoJ6{AfKol6ja+YkX>4xvR`aJ$Dq z`r@nfwUN{(GRBgE{k+6C)qd$H33~+3#eTUA3N8`Md}x6+bl^Gj5a=f;UIX|u4{V}D zv0pQ|wkaS8-XGVV9vK7~ItugcfO)Z8VJ|2jb{@WNNo&3uP@xzx&Pz!eGc{nO0gpMZ zEBxxtN2RLDwSw=PzPrP*vwK*H#|KhJ#%3&+2`poWL z#!$$9x;n~U{~g}xSxBvn36ts|4BzEC38+-<8VoY|ZxAqWj-o)uZ~-3ivGJM5>FF=S9D^~{bkFM_4}DGHrAiqbh`F}4M9kDn);S%p45~=` zw*zbKAj2E&bB?bn>|g*rW)Hz+FPFIc^@&iRUkh(5U-9~xSMMyrOLVSii_(0+H|Ezj zcj(cxSh{a@e505AF1A*V>(%i`5Sgk;`hVFJVq^QCn?mgD9320@Ny~kFTj^UI$+tf+ zX8P%V@?fYQji>*HQeq~Ya(CRkPsje=8_8VR%e$T{s`BnO?9l+FLRCxtCAjTvT_@9| zLc7ohKWX{Y67YGaBmDZgKG}FAjLml%D`hcuci~*JHm@^R-rN8_lZhXGiEU zulqxRudHuk|N3v#)8btw9oEkC5Vh%~)-(g7wbC`CAdkj;n)d{NxdKg_b*eZZox0=x z_&mUB5*<3mSi~8O7&M&xanj8*fI!&3Jru|G$JjzooH7`W0TYR7q40h?@z-eFDF4X4d~`|01^HV_m@?Xfm(K!Qh|x2*1g!6b({ z!lZ}EYeQ7)y;tO%cGLoA5Lyhy-Re0qgu%3WM8I^uM1rV?i;RXFYVp$nj~qDR*;D&R zv8&6yez*0XD4ofkd#e?WAB*Y8w<}A{B6wigrQ@8g>QFs_a3H40CFdL%@OqhGCD>aI zNAJqb3TD;1+c5sV+HrWdg`NX)GKb~;+?S}g5P>;i)2%lj;QPF#iYu0AKuA53?P*-a z)By3MM6tZ(MuH{_0vTBTh0Rbt<@l`M3=-pa50)aegl}1eLskvT5kulY+wE9|VK1ZV{cPT4kc-?BKQUmS2HS`cWABnq$a&nYpL=v)a0sJgO`8k;Od*)ZETM(? zRCY*W#NS8)@Q!|#t&lhr8pv4%BK{$5-t@oSd~hL+cx(&TfKnf ze3tVCuMIey>O2g|dztdlS)`z|{${yew5ZKPY0ir@*7y~E{eo7$u@y$IKc7iGdHM@~ z1RxCOtLQm0&*MY4Qh@DGZ-YAWryGEP4qi5tHrcz3Mdl&IhC zM&EeeX(^#$u!HeoSz(-ICw%-S-O4yZ4A#!qGPVjp5HWTq`Hy?6u-oayUr^bBA3exa zQrUqOUh-(%IPJy9oZog{TpU3@Wp`kC`INj-C|Yc&C@c7nR@2|soGz^Gu22EyzENF& z?oW#C@Anc&x3ZE^jEmbh>eba)?F-zMN^!?T;{w(7=kJv7y?+U4}C&NM)kh@#I2O!f!p36)YWMxfa0c8 zP^_w%q~t5J(sPeb_9sQ?3_eN$Fk$Ff!4@AM*7jjjyI*hDhzIiAlloVDucjVYVMpSE zZm$2PJY4Fc*)BO#(LFI+{GrfU12Qp=__p}#1NXjXnD6+=cD*mEdBh|QCWwl)_xB@E zhV0^tmV%munfTa{;vGjQ;f1}f7q{o{Fz+~868lh;wgaR0u_Z`H->k;bQwJICHb9bj zQyJ&;_xy1EnSFwwCzDbMG7$)t8aM^~AhS(-9F%qj+ju*CL|dMlJS!hlY9c5>w7wWtFR18>&)wyM5upg@EG-2_5SbdKzJWU9lL3ak$`MOBV@rRn&-ky4N}G%>(Rx|MLMa z+!u@F3wMBeRwHy7dmkoxDNoF#D3pHGrSklZIV@Z=9bb-y(^B6^S;huFq=y~`hoWHV zSkzw&?5$-^>ob7FBW=hHCioYhpdb5>9~goj3RXf-tI|kuNdl6MuzGKVY8?%{WhCFX z_u*Yr!C_|m28eWK?#Qi=cnJ`_W&1tHsWStvNc#%CuLp#jwF#nPkYM2vXAF`WK1G~- zY_FW;%!Ej^YURBayg&t4o!5hqPKWpPhxz;X2nX<8r(jfQeGs`tRN&JrKanPbnJpWd z!^qb+$j;RU56MS1{b;<{N4%zrWaAwCS2vWsuT04~>_2et>E6izT765f9X(CJSr^k*lB^JoANp zP4g5rN(&VC0+6k6@SOaR=i#r~+Zu*1$%zD&lx5N{lAVvN%3(`dMV@xNG5sb+roiUe zxtDmmpR(2{14U@Z#J8;Nn|AfEjZ`aqbgy>>ztZiw9pDpD=keL;r;o-9^VDUpII7*L$Q1!fEGw?K!$Tbk^}tzFVJ; zh3EqQ9VA0s5I3D}eM{ad1UA$~zDFqDJ%|tL$rx$aPLo@l(lJKet<6+&31kBsb_Rum zw40{TgEuND$4_HSkec&Am^0+p0+YJ0Qpred+H{wSi}2!wIP))yrqMphcG{M=%D68w zpC~3uK+VU`kc$f2vQ(G%cDwd0otTS=ReC{F9e1b|5<&ddDgp)-@b1QHz58Yj9WQk7 zpM(VdD2(IYJc#jufy<9&PxKp2R=1d5-}3W4xRZ4IKCU-Sd=tv% zpJ*U1ZPUwEh(J;Va$rJg8Jd??`g<`tv?jeCQv?3a85cm7veK}_+N=JAy8tcY|--~ctH#QG2>iU68Jo`p%zG4 zA)?mRo{2XLTzj~!uSzMp(~Zj)UkL+S7hZT&VY&W#$q5V{O5tULAe9Q&(=_`9MAgl3 zHn?5HuLD|m;^v=hgxc+*AuBA+A$@<*Q9(`6d6Y)>*=HIcYFL<}Owd4iAAj7&!mA#W z=ndcfIC3ucLb~|~%5$(P?V4f&NCLpWqGcX{bEii(pZT*)S45k zn>@GWG<}d1O=7e~=bh{MpuTE~?E!j?qYV+ypKQq^Zah;Xukf5w+icrvaHA$7z6mAQ ze{@7lkeExAGbOvSvG%)hrp z&0Fv-^`8@+>*aOnR^@0fd7lVmOr(4lH^Mcwb8`R0SmX)V+fy;gMvdl8Mes%z^yN@ca)F1&jzjt43y4hdT=NqpEK@@9 zWTjD?1lkJa>YV5k)x=FkHEY2HsjSOMp)9xn+9TRsH; zokw!o&?lTwxN^gD^>0X+r+D>dqV8M!mRdraK?9aG%4Ex6^>O&(0`3;JfSwQG5Dz>k zB?C^Dnke}Qz-*9+P)P12m?mOK6*i@k19`of@CqoU(z0}909dG!tH72pAY+&`?(I7p zoyQgIr*WO}HQ*J=Jxm!YXKQ?V$r*b2=b0!>sR#ESoPl365L0h_&g#JArj# z_oU#G-xr-1e5XLLMX`S~T|F9&owMk2d%_ptVPB7zz1_t`q7}=;XJcFuckmrQN_=lD z6&{fc2X^s_o{u<+Yp1e`tE#j;uC0qp=xO|LbU&Gdn%;~QLNO&g6aN?&=F0Jz1T_K% zC1hVxA170|nNBzQWxa|kww2L^6#U*}}apD(eUVT87L|@yv(SDgGl`QUGmY z(Ir^xh|`UD=Af4pdQ(J4Jwy*eTTN_<+t%!~mv{F1t!e(SJgVN8el(&>D)8nlbM~1YWWLvd3{^qS# zPuLI@2PT5v`8&+KUTQ=r)7>%=U*8!kw}NsQQ8C?h8S}*1Y8ptzpzdb-hz_kD9ux>% zsEZ$u1ua~7n>n73IBmMt`1`?TL506=%&a2cBr;W%OH81lj7lwfJ_zcFk%@=*w^wpA z4+RJ9r!~k({>9nT6ml4K1Dd22_Zm!CEfSoOSWg2O$J%De#sF*PRipb+>|kMLJFy{_ zYYBocPnR6d$+0|T2X402TpK?aj~JQ_1}kWz)O3r|(ou%qKX(yxo+eK5E)ssC1Z()? z$#hNCvC2+SzT%W5d?ykihiifS;bzePfE{Gpmhi%J|s?>ubTfIx38FQ5_^txzXQW zEW?OXxluGZfEJB0tzV^%&K6!yq=+|L?B*VqXT|ZAd6oU*<}1ET*<07T5wjmT;{`0B zP8_LT*kry%y;cF6Jq=q1J}4&*+byU~R%qyP2G+DmGC)>K$B*C~1^Qp#uKZXqb5{Y~LY5)8WQ=$_z$9h?8 zZyOk+Q}@sG!Z@O~Bt%e%-=8W6eLT$NH zb6s@ON`e7YwncsuNtkN9N6h192F@cqqFmF(Y6YX^dw=9AVh$j@FlJfzIFKeIQ*>T& z-77R~{zJcdT2t9Ro4;sSHc>$}H{MT2f64PM?}jS3O&i?Jx}ZAzX&e}pp6=nvVSSIL zK4EXi-Q1X$R|dj7F7JvM0wU=@bW=GV?Cymscas>=b*%1Qx_QkoelPJeo%iqGb<-xEaJy*|P)r-0vIMy|=7BLMhfMnKP-#47?_4 zl#!WPN2zSCux`^^zMgm$U=D!jh>2XgoDmQ^M|<}^l9%Bhd<@hjT1Rd}rbrqO(78bE z^b)z0nZN@X;}D*fsxuI)3z(n$=~49%joZ@-xx;<7H+_fo0c%na@**@iQPL9QVmK8J zI11C?+=ss%9>}r7WvCYHY24LtaSp)QC~&%mEc+%O-*~fhgo^$`Bak(z#Vtj-)92fc zLG(E8?h!v_bW)s;){8-y6G2!q_E_4+VZv17J^X%BB+=Q3@Jl2>lpXuf6`K^=2c+~@ zJAR%^4rmh8HP}fg2eW->OB3IG21Tm`yJ*UAkLf&iOOC zE9SAL=4)eZX6f|95<$Ly4)K$*z>ZLT<^o$C?Bnm2H&GgKa`p?9fXL?izu;g_j{k{+ zIha{E|9^2XfX^o7KODUGP5Tc~W1_0fviH9N(hKLPlpU^|WuBG}H%x~zE)8D#b(N$y5*CNqj zt2`aDjP+|Vw=Im*#r<8{&gs_;`=_ThWu|;S&*_eB)l)kcM`>zW{?D(M4c>)w14yo5 z_n+kCp{{|Mz(RMRfuX5d+#p~~`2j;_Pc$!HGFZ=ul#XF#S}UGHJ${#rFjp{-n#$Qa z)ZaAO4@H$R?V({*$>?@E8k`aBGfwO@J^d_r=Entf>YpPB7VE~K0Q=XrfW_6Z`VDnC zm1~cFvlfSJl<|sPvgTf zn-qRIlUS+*=1k+)2QY{1p?LbV@U%VNuc2P`&u#{d>yx7|=|aj=JmiOi==0jjwSHiX zryIraOXTEoRpbTi*g@CXF2enm?-$?~P#_q4*6kX*jdV8`Xd^$3ehIX6x27O&tn50O z?d0wUfX&|9OhawUByO=bi&g#oaqedCHfvlTfixuP!XII zVym_?E`RrJR?EzpmsB(MO2KSyHE<81G&db|Pf>g`@5Vp$LM=8TAx~h){q&onoCTiC@ib1_`rSaa zJN`P?xw&CVNK8mYDI{s1yjO_w!3Q-~N|vA~)Y#hW?p;9YR8MUAc*PoxfQO95tUOzI0_6pW z%kXhhhEW~mW!dnPGvSaxBLPa34RfP~b9gaK($2$_d@NMl#FFkhw;lQ(1Kt^*D{O3@Y0^P)D+af2A+9_ z*yEP7fqN4y{c?A3mLP>0N)^JEva0TBi@*FMgwRQRiAbnj6dV*qw>%|$Z6r+Bp3YLr z$EnSc?OSLi2gz@loeM}l%aXc4k(#@uWaQ}FOAC^>4Tf{kfT4E?uvR&x3=MxgN5(10 z367hgPuf&Uswh+xoJ2F{cyGs8_KGb$;a<<3@)hu;5o1ag11A(=DhuMk05A^18K<^A z+h|BOeLY?pRa*vS*)`Rk9yv$w`L?5dWg^~7y1wc4Ter<(G!82zoD|x6Be^Lo!IKb^ zI*m1jUH+n=v??-g#pZt;oQ>=?*D1HZ@)$Or5UdcX*<+AvEJ4gcaP?AXwC#8aAqjDp+4DFL z1?MAza6!up9!AmIo(jVW3Mi6be#`Bqjo<(9j0Z0m7xz+yk;9+Un_Y>pu^UQ@nRP z53`@uo@nnX)Gl=?PlV8_^UWf82_uH1*O%BzMLzgkr!#@_hFutRFIM9egNuf}Lx0tK zH&wS_wtstMMB3zo8QCQXDKYMgxwq*)J$*qQRX|aX&>8ODhjq}e5kp{^)mZk?-k$>h zW-pdOKCL%#I~y$$%yoNr+0S|MH+{l;>t#zB*2O@G4Px`GKJ{8-n*V9@uxF*KT@sYB zR;#a+t0pGcGG3prl0sP~`#Pd1k`YmAT(mtRqds_~l2&GC6_x#0>Lwb>mjF_F;e}R+ zK;f=ww$lLpe;7Nb;7ouv3&+V9+qP}nwr$(CZA@(2*2K=lw#`YhQ+u^l|6cr;-Phe! z-S0W)IVN8A+eFFU7{S=7pi2O6+&2;W>%3)&#)H9yxSp-4m*5F}(>)?t58QP;qDq@dmbHSF5IDX#KzP_ch2 zceQw-04S+e=L1JdHHs(5B~B4mzt$Q`JxEEbMz$!|u`DH9l&KgBw_9IugX8o(0rfT# z%imSk`QK*Aa;r~Z+{wyuWyWB%-IZ6uzovbd-X>k1JDo9!Xz zVG{m09>+QT(ah*;tZYNbN$6XUQi@>4P>|RdF<08Tp28)ju7fjga=)TelLX|PY-JPx;cD_ zMqx$T^FSb-tyx(&@aV{waPEtcaUq{}jW@NJd3Pzae@q5_l&n*(JaQ_kI4Ob{~uCydih04d% z01AQ-IsKSiBgE`X#Uf*<)1|dSRZlBQIbb|r<#-adReoXq5`eyzJ~#n_g|bA_v&^6n z>HedkZdy8wKAN4C_2huD!se%%F`WHTLBG>-j1HhtRRfc}iGpziZwIkY0PR}y4k@}e z0dgbgvWM^W%0qtK_5X%mE=RWj>F3VV9l^+x1N$LbzRb24QK|3RHz&aE?LA_+s8u=g z?op}Kn#JaJP_6=R0Z&kA{S%cDq|l0en#n&HSuo4*5+vkNyjV4LvTaGLD(_QaiMwKymdfo}&{LB~T~A;J{D*JDXMBx57w#0OMCu|DF4xril$FrU;gf)~1)JYRwiijo)2f*B zMV_hS-D8l4y64?C0D394C?9;VPOv!T7EIHq8y{1UQIoO3sc~X0rZ=eW{E*oVDXitA zEaA24>I9nRk_}bICmCI>=hso+WlbLHsgr&= zX0U^*w@$bd7CO#fseo=6)hUV8u&Q`>iBW8;Av%g$aI!t917;c4eAU<0&0w>8>3Mq( z?x;P`X$f+mn<65yxb4L0eG<0|*Fma3Ob7>Yxt)<;XJO3JCx{`^{_UVD5G*J@s!3sM zc?QS@eTgxRmzKwbRE5D%h>WxBWfZixq}YKU0CStTXheha22DEflpsMWz=|uH$Ph2a zio+j{#o87Tr)GUf#mmbzN7cR#3gRk#YWS)+)t5EdCIk)#52iB`eD9H3ZwEt-kBaLU z=t7DYEOId!Bj36_4UqW*i%_K(}Ifp#leMCCf=l$(Xej=-z zOoVM~e6J7=;!a`}lV6b=y>@WRXe>^M>gm90^q`O-Du#W}Ts}|1Hi-%J7ActYuL0{y zQOIW*OCTYGFS&-SY-#{wtkPdO{cT15=3e zmdr^o9Na<-z``!FAR}yq$xD``gw0!eIlD2YULHfYx}bMLA!ibpe1a=y2q9j#_>=nN zHo4Z?+4A8bXW&BXJuJx~iMw29q1>+bdR+12bmI=~%I=ke$(PidhsUZe7kjK6={aA5 z%O3`5#V{^(#?$X_#h~dE=xn`x7?f;t1DUNdnlP-&M&au%+XiFicUsOO9`Q~jPgq&p zCDBcO=dxsT!!S{a81g~~^0mPdsdlNrDQ^{d!6Hx3C$$o>B?mqJ=%UhfoMS5V@O5B* zMdFuPX`H!ops;40-j-AB6u7j;Mn{0?}& zPf&t~`(8z5#s9)^;I%s=V}{^kln*tFpa_SZHz`jwJ)91evh6?o^nDfgTMC<MUH(`RGhUQZx?tLDW#q`&iDL%8!5KtM^^b1uojU<>%)X_O1?#+R zL_UC00e@5*`Fm?pM9gq8kt-4AH9Va$)WZWU98*XP`?0ob+5wN(r}fSO&sG`~=l!bHLz##1kr1`tmQ3h2^4g!EUoj4+Xmk#wt@+hS76|-5>-VU^9++YwmPZe6y3a>C5UfwX%cIxv}r6A)SU{CE{X z`MYP`=)O%~?E_@`Ub^QmQ>pMZ>Uk`FA!n-;CHo(QHa=^L{Dk=W?cZB1Yl)lg(2VHz zOqZ$yGz2OCeuVrWh8cgupwG9|-c>W#;a8n2EUsVG@28+mQVIV3EUkH+!UvkkJq+HJ zT(3z{%a?Om;}3Ot3(eb}t)x9Ahi~U0JY*)?Mdm*n^!~Uma$JU=8!CLyaxOF_f<#JC zcZ<#Av}Y;55Y(PUV{N!PIgfp7)iW0~<=CdMxhq?D2v@*1Vh7UepBX>m0{f*R9c1`c z5aciAr%a-u=cIV{tP;$j$Yv2BspcNSzWgx6B4ze)rXp|D4mQnBzZ*GDFhz#MCuwFq z&;XXzt{GpzZ-4D1#ZbBcqJjf0D#2utemQ@B;>1i9g`I9=GEN})0jY$72Lhl-5m%Hz zN8~9|+91G)Ne&H8(H-hzs&s}(;dQbXFS1a{FdA=WfpXuYRUmk$T| zCxa_tXD|4VVMeobjw*wRJ6m6!shAfInZBfg@=GVhE;no$OfZBuz`Tt%9DyYo)O3Ve zc5+IzbPN||2vddmY#eb_nQLV6>`!;!F(XJQm@Da)^kYKU1aKd6->vUmBA;1u;y1Kd zmOZ+Zk&P9IL?P=FxK~gPC&kT-)4$--&K53PR-olIhZ00|Uzr*uPmr-0<^z!gT?nKl zXbey<{-TwA7@#bOP~oAI<#uiK@Q@6%G{`Z{LvN~MpIBL%UL|)M2r4vMQ)!i|%#ycG z0bvwz*-2CA&|HMMTXArRAe5~-uxPk1+CVVDWg?XpFs7~4W#XYPfFgpFE4qj>N}(`A zqd!Wdg*Gzm&yu>1HBduUl}$s}>m&c@t~qzw&Y4m)9HTrFp6-VL=Z2P>EfoBLDI_cc z(fl#*@8yaDNveQjHjDt^7aFDs16L3T1@J-B>m!V{SFKc9H^^ix{k5TmEHUl;u<9dy zu(D=DcTI}ZY>`@`P;;Ix5)_zI0BA#)mmef30m`LY?s!{VA+;-37lhC~pth>PJ${9S zQP;%N%$YtDN ziBhJ!nP;1j^plW|d02}bk7R}D^X(MLr@93=TYimcL@c8^C+z|KIQ(9W)MAdiu`j<| z&;C52{i}WpLcTbyL$9|~NF`A8qGpW7XY3w$8%B8q5r7!F|0$ke<7DRgZ}o%ifBFGVd(!SR&B+5zzlnRtJ-ZkuLh3fx3@v&aeAf?WA!1{-iq!wKk<@6wQm(D|DYxQ>DPWSP_#K- z#C_kTUndmulSZ8Z;hU;j!$&|*dnZBn+Tr$Q6Z~eh{-zM7+QIz~lrZnK*=lD_~NLHKg{x;7($#a z;|=11RQ0bOP)p7_8;6*U%GKW8u!zLVeKM=B9*h(rMvjzlZRztJaKo?l!fU#Q!*A|YPH_FAixZUf`neRJV zl6?jP-uGib2zjk$DV0&YM!51&X`Onzg8p}&`oEbZ4q&A{2G_2(qW=F(3to`l3D~2M;+J^?6Qp zAzlFE5@HTou|bC;h+~f{M}XW6YUPHAG;PX^pO;>)0x>N;Rgs39%J}lQnogRQ%!d3I zuniVIDKlQAsOOps0wAQ%QlH_r-7Z2sabA4Qb%VMX{1*vc8K``Y50k*(tCeh1-%Nf9 zWt+i{2sF%KO%l+WfNeVthdPjAO7dXIL2*>7wH_V(^me(;0_MTn9KE-v;L$^>ns^J> zj`)b@5DhENSYVs3q&m8Vvf7tdYkJCMMY zy~6@>iWUbJB;VmW$&+qH`SXz>N`yR#AyEe?6DwUCC=$i*k8YrCIExII4H5Ct=s%ar zBaSy*(0tjRotkyn_NC^D=GS)HlbDfQ#ZV)AaUmngpd(=kL}v7Z$zrLf72v?S=QrFw zu*b!FF=Hb{aJWNS18eo`gS4Od1oQj1NOm%+53-1=evsSEBX9yKQq$bkcgb1#;Gl2O z|2%z|ZQ9?o-KJnaO?H8?@_z%LRefJ=5}$>G>p$lWM9U(Ul0@})+=E0Y$T5r-ogcfg z#%hMox_folZ_K;ha60~-c3KOy5IB`nQ3S-a>=qI&;kU7%ESi=La?#9_1&FSW-B7AE zL_t~y7b0`}m+2aeX4KaQiQFUN)+bE8d^gZ)=T)r!B4)!3G;ID?Q?!A$h}j?h+OM#duI#^_HVS-C_n z>4{AG2Oaf-Da&kT#1PauE7MfUhq*x#tUb*!I*=^v;xPjn!e8%wL4gtpeq^&7x_h|) ziF&OCtUjB;75$Su$9mI6Uu%1FPAz1PqM_a)zD^=_x zui?!S=RLV#W6>$>kJXvb5eb%9NnW6)Ga{;?YP=+D@eqcxEwQ@;4NwT9UGZO-EuTc7 zxr#!xzr({u{G>MbNm=5sTEUjx$k1vsiHR17ebgCC7=IJ%Ca(pXC4`zwnaAoQ>ymM$ z(DegFEJ&l;lX{C!tbYu|P!ubwHYA%3b<-zf!e@eT9lDyMn5!J3i?Lybx+_@~f)RNR z3?H`&`&7P(dyaWw5voImq}XT&DEs2&rxKzVUSGgA$nEnpXf``t|$CIIE z{kBN~NsZPls~#-Siac$D?L(6|3F1;E9d-kzi^im;k*CG{<3HbzrXD1Picbs5fAx~m zkh?^H(g04*3m(jZaxUO~)6WE#En_+F3xth3JI$I@V2G$@frx#_C4L$~qCE>G@@Woq zT-G42(0ZzR^8&U zR+5G?aJ7Z0y8E_mom#m!5bSqn;v3|h$a1|12V)I!1sMT>&ENG5Sw{*A1Ez{CF-6_m zcAZbx6;WS(s`gA70{;bM2!x0)5>t0OBiq&2&7sdoS)2v*X}m@eX*ATZRV6~BD+5v9 zGSkh)v?tvWqzCB_j2PWe#&Pvg7i9Lw175DXuf0Lih)3kIZugV@Qce*)k!f^eZRnCi zmH9q#40G)ZhJFz7D1mLzG!v{%-VzEVL$-mD8t!5GdGvJf>VqC)U!(y9wqb8m-nPLv zItdP4@SG^?5S!6^a20|MxzikYHeonOR9_r0y$86bQPO{&idTGFW&?kZez<-oyLGb_GQK}udKodqgbo>zx>3&Ly?(<3_?FcUnoVb`r93jgrbZYKgw(1HHEpPW?vghNbWEm&j9rPN@M zlapLV{F%ji_CK$fKIq!35Gnxr5@g1Jm9RHPm-fyOh}xX%ljs#50+{hPtYa-Oswo&o zKkC8)GjyTFVJKwF?;O4|mYvbFl)RqLHb$CJ#e(G~1c1qg@%CFyJxr(B+1>q!Gr0&n zNJKH~7{SmKm1Ko5`;wc`P$D59pFa>1Q&hJ$onI8^6}ccrTa+yyAHE#43nam z3FJ(en6$-strZv8Jr4z@?}yV+2R>b@_~f9c7))*wi9w{I>A5rYlKja0D}{EK0QBmX zW5ylN8d7B!m{hCHVG4+8or{?ZS&$Bmg%+0<)^Q6OkZx-&*P%WP zHZ|Zqhkn6m_jv3ln7#P0BixdWAp|llItM21$NbnwIYhoMS~_XCiAoN{FzlneT@ZkJ z0@8VE%D%z@F385@9$JRNh{2*i;9VU0rz;RchSTFr-#Mu}fLg{EIf6;PK}bcsPvVhN zVm$LPV$##uU-5=!-uRy!4P!+-*xzjh?~=vfVGL|!Og=NZg~O`MCcSrQ*W7LI@C$vw zOj)oS8|cB%Qv!@CtelG-G_vNW6gEtiq5w)#Bu61rS2`8ON6?=?PpbT$7)|=lQAE>1 zHhi6*X)aI66;YY@_@8N8f@x`0mmqy}KBSfHjjK*RxbDPpjo?@KOHCpg%TtZf)RQj+ z25dmK)9g|N9cX&l+>)FopAPsmrul4b)85{?PR4214yqYQbJ<8$@vvj(*%RPhh#aQn z%ZQ-q{ZphO-y8cQq8t?s@?e)E_`DERlRKxqF%kIFZxAS|BvJ@N|96{o-NoU_#_3Nd z?7DLuccFfbRRtCS2Fu6@ch5WaRcE3Y>~4Se&*S%_UnZZ7BV;5*(7|6{wtOX(J;@xz zsq8bVvdft%15?GlyD$z4A0lh1HRhh-{fko52@m|5MW?AH$v>_sr=id*KG>dL4Rk$F$ERE}R_i zI0{S53HrccFtG8fN2N>bTx8w2h>}klm;Qo4IE^2bx2tT;G&?^h6<{JLl=(r;$c1H? zh{+rEMe%Ewv^bQPwqXt^r>ltvf*~C$>o8SBibEuM@wv8T2cn=a4oK+~S+e%|N3uC$ zmxPCdo8C;HZe5PxJ{FZAB$i;_w1>&6uMxey($>ww+=1`~+qnVv7>Za^$phC6KtLXv zLf@@rp%_XVMl7G^YH*!S$I0hj97G)&DQ6v88JY7!NrnE}$RKgm5<^Y=20wd9I#M}v zj-*!+#h60`4lS~!?2MFs%`eR}dWOa&h2-QMu6>6bF(g7UDu6_gd*-$aJJl(~#Jt&g zw)s0Q029M`%JP(;C8`{V0h1RV^H&45@1EA`T6hftN>pqc^a0N72tI5k6=+~DdDdtp zjrB@tpUUjyxnvOotlThI*%taYSWPJta1#u`k%bSKip>bKiC-Zw+|ooIu>j0}G}Kf` z5I91+;2|h98zw3$nJk@1$1P7G>mKQT863t$$J;V`n0>)@N3Bh-vS zIW-FxHg-NqiZRq4T7wAx=j_+p5sGzl+Y@ChSjDm-gqsn%^IL7>qj2?7P2Yi%KoA$c_a6(g5WX0PMk-s!Quu z(fdO!Q=ajE7M}6YR6>Zex)8=lG|t^*>)n$_9cLi`jEMz0oPf~B`k^@t7#;WP;cq;? zPh?_;3{6~93NQ~_eaVT40cKaWnhpyHC4EN}1JDu?uQrtR{jlGp;j05MzU@{Hlb?#m zewuQr4Hl(|MB&|ypCf00*UDiO+T0rj;U&nhJ9iTdq@kU>{t(0)7y4YV=B3zR6Reat zT#@tWBWQZwg!J=Bd>kue0+{IS4#Zg0ZUv>DKmdy@LEsMv5)MB65!6UTLC754kWf44hbqxSbN# za(jpmZ#a4dUG{5o&>*?;3^|?rtHeF~zSs7UgB7cuu5kQa1CN{+%?E~q64cgwKDW_- z^FCU-9C8&x(@f0W-@Y#=b(&-Q3})i+pl0QU+$frm;`ho}PVwlPHk!7V4ykGO&`gR} znvhz33?ElBCx342T^4Q<7rXGVv-P~MZv*1&hw)Rc9~28#6F{Pkj!npy$^_xY{yqsB zE&|e|l&mCZO%ROI-)&kzT>BuHicl%iU)%5XdVSHXS^hrT#-=i3)i3!cxMBMR&tUk! zfn>V%cy?27wO=oBXM|^?8y*MVyp$nH?)0^UV94i7pJ9&cLsLbaQ2_ap++q^i-KyOunoge``iDiuXBCXK_WuEAIjQwXvIn zfdA0Ob`zqT(K1EN1K1lc#AK@eRcP{=eD5~VY+qNK{8~Ndo1~YzlY0Fj8>V2GxSKG@ z+K&O`xz>6T=5D;nFqm9GvIR%cF(kZAJmqJ~{X``se&dkcV{%4lhVgA#Q2roV^ZzCU z#u~N85MN$5-6pAHGe$iN?Gx7x@$$SD}dX^m!O%0A?8>(5v#T7g(p?@YXE*t{^Kpl)TQv zU}tf~IKswZF`@T~GEvOXY(_pvzD(pb<2l(%P7`@g?-hrTaR1t6{E%I`$S~$}Se?+l z&t_PBlKdwdZkT6$4JGDLt7iJ)$Pk1JlL2ji;j&Dt9Efc7XgCGKvTS=qLqSxV{%<4H zAAr5X&#@6kzB>E^*N+ez?suawZP>wE&}2U8<${Q}ZIiyF3%wS@i4X&(TgqaCiSY?RuE23g-g1rc_SAMMMfzk(t8<75_Zj+fd{ zxi=RrtuP`zsaR#31xtMc+JN2b%|FRbCP3;_DaP_R!YpRmOn+2jvitk?0hGQzMfkN< z*ZQ6bCB>MZsd8>-B{Nldj+8v;FI?^qI4v0+;(XJS>y(u#)3?fsqPb}ma zDZ1-+h^56Y9kQkGFO8x4t%!@O7)W;)fg5c`tIn}`k%H!nA3J>e*;wH@K>{JmSs*Hl z(KU}EVcct#uB!zj?wBE4AT}M+kD(mR3tF z(?paU^PQ+KtEWtKLT~9aQh<|-;(0v%fphn+9s!3ayL;x_zExl};Aap2t zFH0P-u&atFr|`5%XP>XzPrq)O;Y-bp87~|`AgSv_9^Bakhj1Jn=fP2O`jc4pZdI6# z3uoq*f9&ZDVOQ*V^71T^7PML}8Qf@=<}@%3;}OR0q6I+qSowwZSVLDd7gr}a5>2%Y zxPpm`5+e(Ek2=YDbxc{4G;jhmS2SJ(I9{DTY95$Avbd5ivfY`Xx&2k(Y(vJ4Q{@)W zODZ;d;OYf5ik`J+OmM|9v^4D^HP5;fVqNVSYE9_1)KRGFd}FX5&$+=|d@_|QX^Gn8 z!3Zp^;i<9NzTRJyFlkY_kNr)sP+ykTn~1r*I6dw~n*rLLyX^p>?~ z2wEfC34HycB%U#L*5sVnxUq2fwraqlJSX&VA^B(}z@t1^o~jxQV0m(*>eWy(I5~N3 zM7LruG|i0b8NAi1#&6B({$Mefl{i+^42vhdw|w^}TBk)BBwGkoyGE`;1!EX~a1Cm-2?+b)@te=o8pVxyhoqngwe0K*A z`>(~Xo0pql0oneI?YFbh^4;#+KArtnUw^~qzWqQG)%un^(>|dU6KZ}8pX9;-eZQVf zhp*!km$@YV2)vFE$ScWN#E9nk9w9$5B0TRBO~2m?%r0JTYaa?81Oj#r`|BGb>iWW4 zj@pA?SE~VEo4ZC7b>z?BZ7wbzeqZ0DczJoAmh+@|u@ezkmzAan0nAbvbY3BDatma? zsYLSU7VlxthmEQ93vX3o#t8X`aAy|>dAvi4^T`TH{sG7t?1W{5doeO~XJ;;#cj9Sa zp4f+PERYTr5XM=E-7g6|{&auk%;ikgruffZ&g?gA?{+LB{M=pcmvcnS7|E!O5>!7| zZ_gAijc7Rj%f1HG8w}=+;cFibfC#Z>KcGL8)y0SOFSZX;mUT{^K&1gQ){d`W&OUzw{tENeL3j{ccVHV^ zxBTLWbo%n{@AhpD`x16%Fz9^Vysn3Q^}j;aci^|zKzx}o@^R@1D?Tq7LbWw|P))Lcxtm~V4K;kPTE+YwaJ^mpmp|$_`+@fla@L3&meaz4p)?RMq~!Y z{S^NV3(kH*tklDpBeVs*Vs6yYLn8#3N>Wa=}RW^0L9IelLMMJ<{Bv9Iv}Tz zjMdVGmQ^yf@UKv{L?r&mrt#4=axf8UNt57UBwG@eaCCKsic0|nh7i(@eGL^O2p@5T z3B*PLQDMK9A}YxUq<7qF1Z-Vxqp0GHh#adh4M`AdFcE2pD@011^W=YbmO5;~I>Z&P zSdD#vJQ`T_sU_T@>W_cJGtW|vuf(!NzR*UdK4KtN?vAk#CO_#Y4Bt0oFSLWYVzZ}& z`!yslwBLKppDCFJbrR0e0Mi}q?iJw308YeyL5N4pj6R2~EuxD`unxP=!3+pyAkA5j zp9jBl@}WKsK$v%d;Pa+6go6d~=@G1bU)nF-6TvhUMk@O9=}$ppRHM?)v4wN<%#8&P zuwj%0bE23;!Xb))>ckO(efWdW@I%>HNhLvns6(BUF#d(P423d8LloW5q%dtF^q>7r zo$98N1fOTtW6*6$fJCWKJW{M^oaEwCz!#)GYnGvyRl^Og27k__}yHAf=X`MKs{j#!)?P^{HP3|2$W-K5Nq@ss(^QdwEU8vq{kJzHkTeGZ-^;jUPCP%JwMo?cybA(waC~2s4zJn5b6rV z32M{xdbU}}&bl{g3ToH{%(xDeX$vIF4n&T#N;B+jrdbbriKc}txPQinurBLc7Rn;S z%XnJ^1n(BUtH;P=F*8!ohF)SrG9NMs23NNr%uRspHo>iN6E*35!)2&MD)_>aa+uK>{`S+8HnA_J7qvF-OtpTba%|=`B`P-c+SvBP{wX2 zDYTIo+(HCyB_h2Po>~S+HFH-hYHc=w8pe*Jea?SEboketj8R51$b)njGj7~ckbNFs zkZ%XIBzi66kpXSchFX#?iU2WIQ<(}D@-O$iXS0-qTz=9i^MgRk>J`g>z6n{FIQ}zf z$;QOY_TM@sMs;;uw%D8eU+Xg;$GCC|qj>h0e^HOG&rnA-TiDgA=*Uxx%_t(LbcP-M zUj6=9ii6-H1dpd*SoK;+1OvEoU~e06U{9KBG~2$+#MnN4uDr)&1k4;ym#Mq(@$~0X zaj}e*r01-^TfZ>vS4xlmJ$-cebTI#i1goU=`e%E17rry)u#jragGq03%#S(x>iR3H zaU0z>l3?(y)?}Dy+qS1wRZ_+@TR-(KOr3|D-84p%LhF$u*QmG9E)2fwU&7%BL(n#m z7*Lk3I~NF(!eqUWC7Ev58;>Z0M;}v5;5GYr)U~GXm94JUyk&Q91S9L5f{VTeco@*M zP9w&5k1+Rxk)7i0%w*WRZW?vq-_LK_QkK!Nn=GSym4o&>Wq-fN);2zpCK3YMY}={* zWA;@A9AqCor*zP`TNRbGoXSZcOe$bT9V5kT6{!4=1&o45-e%fJ)F|)*?zVlfyf5~y zLN3~ATaA;N6tKpL1`N2OPA24oaNgG-XR{nP*0ZZ>)9sB$tO&xg6V&jmVv&+{L&@JQ zd@h$2pKyzta%)X+;-bqL&R~>Kb_YH2Ei(!>)YTEYIef=+KYPN8wIO?p-grdQef@=p!pj3OC_Q&&|jov?qE>)6k?u+?x zbxMhbMZVgn4~Rwc#wf^UbfAey0XbHoc^xV1nr#E%+fUE_ITj%87g<8jAhfq>_Qy<5 zw05SRFkH{?GGhtdR=Tl>t+l%(V${3W1)^d@AJ5<)j4mX9QAUllAD`VaK^R8B8DLp! zHz|~CfAva-{T!yu+nHsPh3clJTQlW^K|-Ysa{?c>l+)9w#({pF1Y(!4Nn#tdNzxz| zon_iCRw=|Wx;O*UMb^`i6@taEVI6_aKbKr~-MbhVo)lXQBfysB8EGHlV`5yhsmz>> zp&Ckt*a$LNI-A$lwF-Lv0KIu8rIjdB#N&$Zx^i=%JR*M}53fDH_P(;%Qlbe{x2PLQ zbUDRVK~4#u9SvC-UU2)}S-Ww9FJ`Efo;0qZ^@|mrdQa`2Dx2`6ol0igNss-pQ_GN2 zGdWsCia&K-Me0}10WY~-z2;mMvm$dPUUlTGu_Q)O9*qh~@J`l4eU4t*>5dJ7KTXHt zi_IkYmT9Zb@tOt-*?uHR0qCj@&@Bm$!O|o;**!vVTVr<4#DHDnt&Uk#zs43Wc8BU!OPL zS*d;o(dcuUVc)CHXr~OG56?u+g;FO-cZnT!0{``gjr(I8J&3t^V%HsC78IHgudZK^ zPjnhg+AGk$iY{CBZx_{u$n`a!J8Z9b`dU|o(xB(8i3~acgA*qPfb|=A49XQaNg8)d z2n-pmij|O(-4TzeFdKEKY~G=T2m7Jwh1gLfH9x~_$&(Pw69nIHzqH0Q8;9!vt!%K? z1pedJJC(g~g4l@t4<2`+hvT!4RsnnMIZV5u;*O6qEF&8?*Z81c#w-^1)MXqfzb!B* zTwLx=qZ#jq5;sh7eskr#g!0*;zg|NKMoQpL42~;%Ci*~+GMs8Jf$bfap<3!iZ;YC? z54UCV*rARDt5rX5xFcf#y6j)eZ_1)Ayn(`6-;R}G5Y{3n7-Qg6Btzq6#D(z|mBHYQ zMsNWrF+q+nII+8FB#l^RBV`k>)RsGwNUrGtbU!S((g83zaYLuC`ATJPVFBT`OzC$; zRurN1*_*KzR5C{>_F-@^n>m5&2ZR>`J z$Z8r4R^bW{U5~3~-;UR~S~2Uqya|f7=c~{4r&C=k?-4hp&6sADo<8~5e2H2_zVlKZbKvh4amMt>KelsA5%weTv4o&Wk+{Ufxn zGpg40E+-2e!3mse0P_=Q3!*1~Hox!}awQ2J2sJD%wZ+?*(K=(8dSGt#ES2XrFsWXA zlgr>pdOtxfZ%)PVZ0_Y4TVj&nT-tYMroZ*A5Jq+vN74%-6{aty9br;FP5)N*IwU5vlkT350YjS7GfcEP=}V!|BI%a1$QiEZ=V(Bo?h)v;$6LK%AFrQ%Y1p5Mh>2#pks+aPk~p6ZXmv#Rk~e*{0lq55&~ z>aF&N#P){n({(we=gmn6x4@sr?1pf!$0MT&+c2Vc9WW)rWvlEp%y5O9u0pE{qe2|7 zf{`KUjMXwnHZEDuWBJ?-57{h}KbXgKc| z$qdVt(k~cJ8Thw)?_H_c5PJuk;?O z1?2soeXC z=dy1@rB0t$XKOEGkbF7VNjjK~G9zb6m@L<=f(Zk|nu(oRVfB2)#Io-RnS1u+Yl>NZ zm^jGj0e3qQUN^z*Qimbu;EZnxjENy#pfjK^SSgM(7J&`U`&k0{r|g5hWG(O1MjvP= z3Z4%Tfgs@=dc3r#Kt>jdgPHNPpML#<;lGj~_d{>~rB^}Na972Dc>ve-;p{l4`SuU1 zK9rBXA_kdch8dxbB;3jXS=8YdX|vyRW(;0Ttu_87g3zV~{plw?!v}?fFjb`81SRts zgdr3J12XEGM_`cLhsWtEu5EZ8=Y9aQN~6e)T}%I>)3D z7lD1a{PW}e(Qc5}>mM*T4l|<}VK$!X1Jy226O(RQ!i{x4Qm&5EHH@cfTlNJ{0ETfH zMb#v@xw&1Xt00RM*jRu-GD+lNd{IVJu^uG^+(u(6?P>c8D59xv3p#ow+Dq^fajfmjBT5k?rXh>GTFmSW&hV_6Df|{$hLBrg9zwhqkTM54l*OtyRDH*CEtQ=cG>L# zD^aTga)WON4^|76aY|jSAEw6@oZzpejtdZN!H-?(w@s)?(T3CE5c4o zq!s=gNl0+M+SqZH=1GzXdZF-z>Ja3h&TV`t(Qkj9E=FpRLom$!_-HMrT;96ov!h-v zXGj_16!!vC=j=|*H?R}t%zq%ptHWs`TlgK}jCdua4p&&yiRx-ogE>9&HW9^fUJB-z zsTcZVf9>TZN{c|-WyB{5N`#&4f}UU;>pL9FB`_bQ%W`B`c6X@9Vz5^SIm8}nn-VO< z;8Ei&9N%)^z}y+ubtXY-S8E`r(fhMN$CL-%*gH!_Od!`VoZh^LfR5_fz;dq}3?=^C z8iYTZ-9UW5?5LzlOGIuOiqr>^CozI9w@{3a|w%{Iw?c-yE%;z^S0*p@BPJ()XnPeZGmMmEpekAQ)zYTzULc# z)mFIDErP==E$$~PdrfBg4J04j%@~UHaxL#Ed7su-Kuz7Rmrn6c)f@aW&)$Ve3?G{c z_7G!3(?jNCSAy0bic9}4y=>ZXO;ME?Sn*&8h*k0Gul8pFKCHon@1}hjZNiTGyq>xZ z2RbAAe&n@ZPTLPzR$&5%m(BF`?iIr8t(Zid{E8qN`ie(i(8dLs$Q1wsp|TT(divVW ziI0iFHV@e53SPbLv7IXOiuUp2%(_BI>U_u{QE)7k)8(V%yd21XT}Py@cAXl@2#9-P z&d0x?y=etc0qxCw+CV%E&-QYM1do%AN#O7D?pd0ZWEwaoygqdj-&;3bU0G8VdtAo6 zdsc<5Fm$i0vlM|%QO)`4vPK~4^R%sa9*Mk*=s-f(7GHV_p-QWqg;e3*t88XmnI(Es zJ9a;@b>^u&p$HK!JZzfI!i)3KV-3Q+G-fjj9-Y`Xm1Q*4Z#KH{!206`*9+kQ4)Zf} z)3B4IR0f#=#Hc)J@LlMYAf?I=88c&|HFD8v{Z4QszjJB$O>-k+m%clfEuUpdWOHjJ z1K;WuMSkAi8S#z@sFmvVIfh5Ojf^`Gm!Xcti1WiQCL;^2OEBe3L(%-_;e1=biOYx zb6|Jh=}eQSnKC!F5z6j#2$FfaKu-H|)5Znj`|vLyt|qJJnccml>;be)*px)2LOY^B z*(@M;ZU$S)l!a{$33?9+kD3<@jOHdncM6++}!C z?pY|c8*~1h-AIxqtMRa^8lDF!IRPiK#@>R%G}j)+JUbCa$a;(ga!i~3{=yE#g`+H~ zaz6S50!jfp%LK<)m*aUmimnxJTmgRbIBTyMt!6qiTwX9>_A!dj__1nNlLs2&H+peg zSEH9pO6WgipNoSf21l`;t}xfOZ`)wH9Ve_P$}rvL8lygo{H;m?bsYwIm>8%!XPTbZ zQ+J5K@6ZYAbfy}e@K2HdVeA~5gyDkrJhpAyGtbzzZQHhO+qP}nwr!hvld5l(EK+qA zr>pQ@Ew{(_7+1N3sh9_`mxzQ(j%cEpA3=fQoeeGZo>#O8X z*cF=Lui|p&1svRaDLXk0fu?&8VQuNI8nwSd>*=t8eI-KbG!&bk1%2+pU)XlmlwUGQ zXKavp#J5thac0O=+*IdXy02s5PukD;`{p|Hf?9-MONRH+{z{QfRZ{tPv z{NVFA7)2@wHaZM>)voL)xbE<9RBV*Jz-_jMP7Q18d%1MgW0&<5*+RJ3V5x^`)wi?q z0|mJQ0!eT6(;7+}_*8&w9{#B61r6DpHzmyl8rQZ{M$~LEEf;3|Z{a>I+}tg@tS$`R z`OxltUCO(<$J>1y9a$XOZRE-ZVAxI7pO^yF?Qa4FzV#rTYd26QpvM}EJ)Jw*ZKK}s zrOU7PyJvF#_Tw9l_e^?w%43R4A;<`=xk2jfApBWa)h;a3WCke)xM0d=g;ANx;Tlc>>RGF zAu~}ZWv|ELEA-2Je3Ess3)qk=ZW%<8|M2m%G5gBy7rt@m-+;>2@UK}31CJMNkYHWu zzKV8$0fD|p2kRH2e)mws1GH9buj1gYg~$EtVVpKU>KCb7$H*!FGXtuKu&4PihayJQ znZ1{j73Zt3=Coo(n~W;Fz_(V3P>Kv7QIIFg-H^&YUJw}sEaRq6!US9 z@~$iXA}z1f(>3tXLCgt&=&HS=8w$$i-~Ol%ISR*~1yl6Nz6kL4!FjK#D2aZAm{T+f zxso4Zra1C!&rcXW<(5stsK3I0u&gE|v4cQ*16L%uNb-$4LU-N47?U=4XO*X&X?)oX{@vZix_nsU)d~ZDh{dOKJx0 zKqHL)c4%&>h>I*`bY(Sg*OY7>1d`|W53q1lKJ5QN761MFzo{ZK8{7Z)CAmgR&uNQ2 z(QmG7zE?p7E#{BJC#BNKc+7!pc6xF*BTK5Z)I74)y;K-hV&mxNc?;Gbi7=?aF@;jQ7cG|~w z^LA##XNMMZyk=?U^C{iTrcBP-jGsUkQ7S!#7Wx~scMFSO+f;yC)~@3I-D^s9<<)j% zo#ss2Wy}f%PzX}w2z8L^u(g`uJ3&(`0MS%0xmL>a2AND-m5vqsSE)khOVfM(3R?z*Go8BE5TY zMwrSix0}h7G@|$W7=G&a9hL?Q$>OM7y+EDJ4eSi5HW3l~C>73F3xfBwx}+dDDeHRO z;)j1@heagHIcZrZG69j(jz+^&7d`hTg~o$H88?yHba>=QJDD(#o*LEj!uBaIvHK*k zMu^j~(ql9)wnY?%&3}ti74wx4>MD&d#Zbk6Yh-MJd9JAthR?MDV)HLaJ4F-XgU1QG zMad+DCqFv&uk3!&>ynFzK%k{l?e+UdF;t_0Lh+)K|hUbi5xGF9=!l;h_oPItP7H|4^QXj=wK|0uIfB$Aw1n@JW8f zx+=@Xq=SL*$e2kmW*nAj>nAnt_Z3iL1WT67+1|gB!S1AHbx&|G%3>FP57e-NUI6pX zgStN@QBq=i9qW4a|HzpgUsgU?Z@dhUWxZ^-x{L?T2R1#q#kF`16)=zwN>_(` zBzkbIQsnW^nBA{-^q`{IA1f>Ac_dZFA@Af~>n~jwirng`Q{?%mb67eoy>)`J{Y6G6 zSN6{;&$Rtk63VQXzP$Ta0!Vp0TgU~DYbR>Cx$h}ZqF+WBq_$?=nSmObuE2!hJlyd$ z1sETyLV=J+jFG;plJ@G%l=%E5!-0Ye)7&1 zIDy2C-ty#Qjr*tlE%lg&&DN=k;~BcQXW&>cMYF%mMT*6strHh}`~|_eFJH%@(TfeSs>Anw!r3=3EmVFY9RHd$?nrvjSwXs`-nQkT*LT&0=)J$t zXoy9;9$e&9;&Vs7T~q?R5SQ`maRc|OjE_mt?<}TX1cw?7kre8BF`!YUe||nQVMAat zLDcYLJ(+B}CzTweTPLmLVf|WtF784QAU?EVFKs&mrq8hpbRFxH2d{h?c)PNyA3E|d zx?7qiY8U&2{&mQVXO{ZYd=B?bl=yjql1-GjxvDKFHVQHS#PCe`rN^SiB<(*cldB?! zI-m~S>6@q9&O`cY@!?q8Qxm*I`lep&fm@uL0>1Yh71G20 zlrlB|S%-q9Wwabm%>hdQjdx2Bj;w8LNR+}h@UUxs7Y?X=+UH{$y;E@$I8l=c$1cZ% zHGw2YG=qn%VEgoxU%D;^4p(* zoEc977Im zmC%PK1Ln2Q?*L7tac|2G%U8AZU;Oubp@|DOM%{0L6@oN~Qd~Rx0L?_yqK-pAg4BxI z5x355WT6+r8gXO>j=@a?*JLcyZ=pA3I>Xj_2BGX{It~#iChUTAUD^LOielwZ~}!lJO5p z>MHij0-8N9oHDYZL?DVF0Gd9$tQFm3^X;Xe{_F1{a#^$1ICNDS$}`*E^R_UL_;~Ws zcQQppP!S=1TMW=`q7miMKAzgWWee1r#Z=h2-XCjqZcs~k^|;!`lRt|;_=hCMOCwD= z(Wsg7$+mm^U~rSAJ)!S5y!neUjA?D4OcH!=6(-=l|2yj`03jIrmeyx;XWt&@_0maa zbG$zoR^{{$GSm9mK!x4~37}K*W9G<#9SAghkUuNv_-)gg(@25jws^;@2OXm1t*|6*Nab`EU|rl5xix`mLq26y zD@UtB3rGTKU?Q+c>uu?aAxZ*(d`S5(F#}XNB6q4gpsSt?5vaj2fin{9&@&!q#D8k% z2)>AI;rI+iPTLW|?pMW44?ut@zi0b@Q|Ai}wTF7Ze?d%+6{a<$kwahzK&PmsO? z#K+?S9e)V}Ab{%6y%$cP6wdA=DAl;%nf>*Musc1;OT%|sK>&3}3cbAeAjs!iu)Q8H zT*e)BPcvM&V|iF>_7FHiP_E>Krv0)BPk#-ylW|PL^L7g<2RE1X=hJ9Nl0V5@igA|W zMP%_-klA&8=f~KFSiu!gh~DEGIK=xDfWBB*;Vj_Y6YX+0{{eFRSOeGt#oHTR#o*hM zNxurc+lBN({`%xU_z*xbPw1P9m+ zGR%k4zjBUddFapNjJLd` zl-f^?$f*og!*A6;g85fDvFLIM^}KQzQ-o#Dl%M$91JjpRfFwUq;Cp&H_K|@d2RlsI zej)^%JBKrPuHx#}n$LL?&D-xqF$@b-k&5nZiKCsGV zkM$}@P}U}+awx+)BU2IQ+MN_67x&ZTw)%2;9Utvq;&1Ze)Sl5h(?y$jzM{2lrW_J- z3HTm%rmF{eva2kMK=p}^dWe3on0K7x-b5$pepojq+Fa!?zKSk|6Ea<)d$%Yl=Bo#! zXOqZ;fpABP=}y&gOXJS478`sXWpXEspoGJwFT>_5N01&w(-w=RoUAhH6ZoKzLg1960^e$X0zD+Ex8&-w=4?HMyC>U)1b>zccg^@;gbLz_WrNFRzQeL0#4s>!Y% zggB7G%fIyY)RCA<(VVxk!|`oYJA!r409bsTwSu$UZn@OR!F0E+|MY|fX|=n5Lz}Vm z(ivRQudx{i!M%kxg$IQ5e)esVVpZ5*0Ww~wmNF-_75t{EEn|N1AfHv1iuWW5&)v;h zapTCc_4)W5q5~X^1~d^4@UXO`)Gl24X8xo}WFCsRQAK02@~D*>R-)qc0vDH?0Wo7B zJ4T<|rGG!O=urze?8L`pyxvmZ_SMyO<%RyhxT{&)9vdMl=FKmbZ=e62RWZw#k6WL9 zixMPg`k%Z@pfq^^xbvY?oi*Mc!_GQ$wvD&{+fOYM!}OK_8>n4Gp|4}rC6xENt9fwX zxJGqfrz+j`A^1Ct;P*&Gw>B=z#R(?<=Dnn_8oxy^FgVIp!#8gf4x#Nn(kqk~xUgj5 zv|Dxt^$>6l@gPRpKFt%~?1l_98Ys^E01^#)zoT>HN3TUBbXSn+#~~1E@~e_=bEI)0 zqxr`hc=rR=M^uv+V4D-`s_O0^POnCdEA5)xh-1gsSFiW(591azg>Hb9o}KkFhCQ9) z{Ql+Rskwa_gW-(cp-XCK1BA88#hvziH|)_on6orAh|Fv(Tq}xu%T^yYN(t%_H%L7C z>C;Tx%dd=#+pL@?%MY|AMoW%-_;{2ebo|}xO2tKI?WCbC-U~TZmlX57qe&dq)8lyd zStNS{z(%oB>MxDnR#{e_8M2^BG<$>+l0dvrG;@Kg=T8d;95+i?fl8C?zb)n(OE0~- z?e)gG?6lM+y10(La~rO@YyXRj`cR9)!=T`Dur}x*ednDV!8K0iP57DSf8P9ICE{}i zs2v^`67&rXr1UUh=UgvhS{R8@U*0PijHU5w8>ZVfp9h80QLcu$Z00ZT3{{g%dMOt^ zy7)J6%X%Q*sNeM6+s09y{dSM)AYQ6|9iZ@ihj7eVob;+XR~o$o51x+iUL8QEk={yI z`?ouKLri|mXVa`j2$Q;?3ny)K4f)#g>i)rd>#stIqt3|t(>6(mrIbXgpo_uvLEn1E zD(5I?zuK%ZtfJQ66Rf_?eR>=TGFpBolC(Dn zM}_%!=-U*o+hv7}m-MPLL7-Ni%}w|Q1pb6i^EW-Smr_Gz4&v=VUTlrE)^aXpoV9t_ z;_z5cXBG4AP`RI7UgNIbo88=ed}8lNguB4SwMGM#692v&C|)u0kulf$EU1TNGAw{t zwQNLGIP^t-=0K`l!ezIvW_3Yi<`F=WTFtew!rt0dV6MdsUm2z4LRMxncmxa) z^d}5%*&c#~ekiHKi_EohdI@nvX(7ZfeZ?wltdID7V(@K_$_lOiYvG(_eG(i)k6+EO z`I6t53zM?1Exjtb`84+P8{=t~P)psMX4OOIB-japd3LD1`Q35Vv!>d59AI)z`SnUz zZGC9gB3akS;EOgv(cgR-p-86cR>(17;~^M_%iAatm8u+ZKd9NHCSr( zbXYh4Mv>=i=|Q*fvHNO0_1Y-5Fb(yQv||~RYOV@=_|tSrk>9bq7#Vd>(uX^*X4M(( zC-m`N1XJZpH$9r#kI^ux>uNduE90(VA;4ky?IE6O{>2wRZ|Ty=3U8^6QnAu>K7&j` zV5J}h3PywHA_`u&p3A!SDV|A(0!`KISWaVS2A}v%8~+1bP>f0Ve~>RWmj8=VhF6WQ!pIfP^rCQDA zj@;Xlrqzv%Y<00Dy)_sEV;TT^`{KWU3=aqu0MY=p03QCp{<ochOCO7+%|Fr~X1f*bvW{pp8E~ktSZ!c~FhCb+7Lyf+k3P)2- zYDNxHHUH5Uo1UWmF($j#10ek1|C-vy{tZ1$ZEuWV?eh!2{GsaH?H#<7S43pb#LNJ| zx#s>Ir~tHUW@REPL;&INWwX82f7NRk!IcIyU4=^(uB;t}Gaa2Z{nL7|Q=fRxUpj_{g3hc>?4ou=MSpv^1q-BmbGS9rVsijeX9 z;eesDCb^Og2p>X&5RD?qNQWbQz<%lQ@^OJS9~Us5A6K?ngWq4b2X&h* zL?wtHK36A=<7X?a&#rV&cA@kdtl81)7iA1y+-0BL3|ZzO{1bszR%ewE%g^ZcJVzGz zN5~?Qk15|KM$OM$A=*{3)+S!`b~q?4F(f(yOH#s3ncWH6>!|M~{0+MN^Gjsez1N)j z9>wtfllW1|Iu00ls7SK9hF+MPl4BvE-^SJO_R)jdeKTv>T6$i>@C!OcL^e1Q@5T*H zX7Yt#H@zgj*A;uqDHI2_o!B>5n#u!3%j>Dj*7bB<1qw^+-tt^Vu_~Jx{3ChaJsQfLnBR72FJNI#ld=F1j5TLr9N(%AFDbZ z97JaEZL^+}v=&Sk7Y=P+5PLav3wb4|Of?1P#>upQOjL5xMU&ae*%LVpLS%Md9*|Yf z6_4xEZ7O40GBEe>Xqo4&IA(0x*4vg>mY+I3QmccgV_h=Ykw)*q?B=B}L(sad?-JoBe;i@Hn3mH_{W6W`)^6>rJjnGDGgXsO4RGd6nzTlaP+ccN zYI!y!GAL}FI(6}VJ7)bbsr!S(E^M1gL9{gcT;EQ_9&y*duEH*jH8{av7MM9dHt1kaL=v3l-Wx&MuCQHjg{z9<;K?;N~yLo0{J*+BQ z1l?{0GtFpX(=0J_VUu=Ur@Ce-KH-tu*b*FS2k=^xF0`O#lF*FP zV1dyyVG@o+E7{GmHUz>Xz3} zJ=NbWHOP)|eQP^__S`ITr%IX_P>_2FqEp$@Zs+mxT8LFw@!$e9et$02(nM>4k1uT3 z2YPf8nvYw^iZb<;0`;T2{@rMVY%`6r5za+ub?VIU70n{aR%JV{$i>ttO0hlSaSf|M zVrN#fq_n_v&vULEN<3=1BsvJs;cQAjspJ8{=V2#lR-1J}nv*+z`(HLnd+zS;m0%L) zP5cP_jYokIztTCU+Z*_X;l@OkaTH=e(?7yEZbU~Rtkeed0%D4~oFoPlD9+cc7}NY2 zC*`nRF*cwljDf_D3=ziF?4_|qcKR^5nWJ!%kWvHJ?pncc0~Kc>tICd(8>@-o9zp|o zaa>Z(By~r;5{PK}z#krY&Hksc!d4}{UU7ae2Xinz;=gFmUm~59=bP-EArqlbe1ow8 zfto&dm;Dzsf@x3*@$LG|OT8@}R;|kcH2a33p||2ylh-k!zGlC$;>5=z+*(6X@$RIN zpVb1R%>-Wm+$QL^NOugepm4}WBe5Jo98bSry;2Mc^cT6T zI%jZ<$8QwwBRr-<;G(<@LCZbRcfwz21w8YSpVlx)ST181&-WZhMUXEE>VT|yy*0oB zgOgo0+dF~aMN@vA&fU_PCBs;t=lKGc56c9vBkk}mz(^##VLhlx*( zNiUFTW00C6EDX=<1_x~KfUbRw3%OL~9pO4?_B%IAX)ib+jU8k)nQMA0EkZbD9I{nA0Q0F&xIGM} z$Z7atH*-sL6UF2==!SpW$2y6PtsRY7CB9|<+3Szr4HIL%^5!*DSNdaHf8Wq^%>aBv zJ4k!8dH~f&fS5Mfm|>@Ov*3%Sa5;~2IaTU+1JM-afk@fV7d3S^3sv-EpLs(@+sT}) zz})32yFGfhb^tgZ^)@|`14DJf8)V^d3tY<~oaw9ldgmHv97a6e7qblI)p*%%Ox|W! zvl2F4uGR28L+RzTaJLMwu`$r0fHZCum0X!qK;~daYW!F;wXXZd6ZkkA#GP?<8J;{c ztVrHy&47emm`TF+>37>R=sO*`fm*{5KgCvu*cshyLlV|ZUtKB`+(lT{|_nG>Q zQ6~u{6|%kM)~Z{7SE4SUm3MX@85iyjm?n&kJSD5*fAiSK`+G(;F)Ch2i>|ED6IY7+<*}u(YZRCB-CV1%qoq^78h5f^QP%4F-E5h`HaPBHpt3 zfmT`!{>bd*A<5xb8?i1)W?EZXx>$IeFgdGrtDyK*8l;%Iek$QX#S`NvJy{E@oZCu< zFDa;1&@cGP?%oR<0i66UJr=Dqzd3332xbc1s={0?Wsw$F)V8b|*E`#1B)_Lg;MRKg z9)Y9Yg-Wda>4N;5h|hPVZ0-rfAb4c@vDLW-{8!9-nVgV0tr*1ElTniOD#p{7@(O}FMamI#${J$~PER0;O$o{*zkc7;_iB4{=C|A`IMF?KZMh~m z?RijvF6^y7Z>e3lb2vim`xyn<+R2%;FC3M0sqI7ut z%db+~jv7lGWWH2$i9+R#vPSxSqH){N*oeIXYqS=RWtlW96_oCC&1qWzw0i!?kG%Od zjtbN^{yMev0tpUOh_ANYX09#Ism-K|4@XG#Eb|vN z6@$n_RXe^6v69(AN(t9P#11%mziUpFadt~iKf7Y%av1^y?63rlYE*D>@)TC!>w|hU z?Zx50PxU5a=|lS~${a@?bnw|GS(29UTX!q6f+2CxE~Q;oq2ue6J`_!!(v#aUX@&Xk z@iM9o(@EAWex2R!*lnNFgMOs=Tgek=>E$g$SS3HjkgyzBC!n1xWC5KxE(T*s5Q19O zut4+BCzSy$e%T41`S3YWlt*B7GWgI(mvZiqf2N13wY!m~#tdPa2yPmbkpgVsB-M^% z&d^?tJe4$9@B_+iilX~qRs`ZZeiPvli1LP2=`NY70AtR>dR#9EI!}L%{=d`3V&-qD z>2V*M{|9W$65V>uIAs*b-)N0V0qL`->u-R6^w2y@4xD?U5SnZR493phi!`D&J-3(s zVP-z@!M22Vod^$~UDH3yhsV46y=XbkG3fmg6wHkyXS#o~=PgpN3x?l;hIfS*FF4_; zSmem}-_Q(h??=ThDwp05`fBSCmz*dwgviTeKcSWRv|@KlT6U|lq3VL2BCCpXG`&ve zb3%Zo`dZZoLX6mCE5dMM9kb)dp8_mOjJRYO|HPf_luD4yzjn-Y9dd&=>n2&b#p&G1 z2(ye&LH2N#y%S0^GWXf&-Slb6pEK0um9;n{6Lh!$khHYv%b1Y!@?+7nHBF9Uv31YY z=EEcCnIg(7>1=Npd_Ioewnkq-#@>?)DMxkU8dDGA=6CglX02mkN=f{(SGy8p8k^p~ ze(1mm+(*o}^jw)~6;j`#)$d--C)ZsWDwsDTDc5ve@i5mv?%oO=e$^)>O?pHJ;+d3>;_YxmShO#dE9GYsx`-Qx|ii;MC-=F#3ML!>X^9 z;=l8ssWH|Nbg`87&w?$4Bk8#gdaEI@_JK9R+B&qWnME%ZWqGR=tt42_8?r3|5X5aa zB3i#DV?;Q(LSckVrhM5|tW~$MPaR>eop726BxI`>;bu`!X-}!_nw4_KKLYx4)q<7H z4#bdaN+VHy3WeqiS>VSmnC1q|CeJ;7`4D?XF@HHP3KW^&c`qG7H7^&pz!LplsL{p$ z0$DFgLBk}8sJ0WSL4V8N9iO>=D8^_-=W@)r)kJJHBe zHOxhxA9LOv;?EqgpqJ_@g4D+$*KZ@?b_-WGUqNcqq!8na@(BNM9zQk;4!P5zRlMbg zG|T^iupJTI>k2dfBM=x1HKRJc)?MEFyz+rDM1>6Yrg4$tS8<|$_AW1jAINSC=`k4e zR;}Zk!jT%98yjt#P3C;&`G5`MnkRI6JM_c8AV65}>FP_~RX5|=E4r9> zC^wdd)ek*k(eg$$uJRA7b9nfeWcmq=18IoD^V#&Lho9M*t;n{iwdmm8Km~Izd-D+` z6uq&A6M$8<7fNym1_pB^e1?L=1JD3ZGA z<%v_UVUeBR;hdT|gvp#}#WB=R4Lb5;hqIC5VrT)y&`EhaB*V}EF39A(h!cT%1kKHu zhW!PP*sUE@Axya#psofMa<_y?`5BP`u<&ec#_NaePd!DtGuqR6GU~K7PoXgWi7ZI< zp7vYYxyyvzj)+q$o}p*tcxqH?N?xOj>Mm%X;0-3)_KgQZ|NVZ!u-Q|7h~FK)8s-}N zwied5KYSpm1ACU4TAQQ|Y_2W^EeRz~^L{)^?@g<*q!~+z2BGPwhKQ=1w5o(Jnw`KB zj{G1)UaMor>{!6FN`p)NS((E1nD_u*0^bl?twOL(3t=1LLogVp@?)=tBl9etbr_sr zXbu=PV(>x^tFpe4Y=$hs^_Fd3oNaz#Yzqn@mMsazUMM{)9lOBFHojiQz*e+X!fj3^ z#Z~*V<8IDML9R;Wn6W|qC(HMmC=LH?#FE^k*_5S`DARz zYn?ds7iVQikee;NjdoTZr11>YfW$(wV)0v^JVExpGP&Ow^&KOKxDD2)T0S9cMtlaK zG+|lVk%u4F)InzGzpB1KJP`HK_&(6C05DLMP)yVyK_(#gOwdugT2+!A==B#)P=%Pq zq1xzzW%33LLnrd()9QK;BzvufTD1i1^=Ujdr~MkPWB}Gf9gx)=$3D6kobnQ<$^`)u zs~b}>LP;98vEN!9yCewD4Efi64Da)Kev}PYYPYOS zGj{x-d)!PR;D_KzBb4fCp7`wXZe;Il@*#m!RZ%`67B$DWy(@+LCuef4k~9ivkq(Z7 zJ(>7=rV7ZKJS|RN*OBP#?>B-kXgotHt+6A*8vN$y{F{_`y;>MU67E3>)P6!5w1XP6 z^&7C%8Spcch8ZPe8Q!s=N}Inzq7mBDwodAMBl7HT@S;PKl?3YXqm9Z2ehkzEAOD4 zOIRn#w| zgB;vjIULHH32MXgq;^oMJO(?aSV@|0-=v$!7xX2i?7z6nItZI_&{)EQ823816Gx#x zZP_*S^5*|-fkxK79js_VWtLrO7COU18stzNbZDB{Mzpy5!9$fX^_v}fzg2l_V4{1O@>I&~P?9P?$9e0q%dsrxxDA0}>=$Htu;oVmG2q~az zI76A+;DqEfxvWd(75ztyv0UG^Eov=rI3P-n-; z6X*g?2(mafr&($+M4i)Ha7)7N2b2##Bo82LS6Bwu74e`*9bouCp( z%H2gf%~ym-Xl1zEH>*6RlS%-b33H>4!+v0_ZvG9N9-=>pF}-u$;L3>H;f9Qt5*7;i z{hyy^kl;Tu0zbOReS@hxte5-?MNAFOCT;P{`J9A?{MSD=I9CaSK!8JWIE3LvDIN3! zgY)eIm0+O677 zeXRMRBbAieaZPPF+uhM25ZFn?Q{XE;jGM3gP%T+CwuPF;Zi$C?cz%=*aRHoZMA7rQ zP7DL-I_BZ|O$uf_SPbm@PmM+OYfz62a}MCI5c?XLZLj&oC2<~C5;k_uaHGF7!=+RM z#FoN(0(AV@ko4pqN){oWKiJ=}XoG&;c&8s#P2HXsg=hr@cbKM7ppPe6b26GFE0Kibqm2p2F?6kw+=3oF3 zH$qopc6jwEB;BMZH+rk%=Rm(6w=QMuF`}hasdx=D3G-&$jY6}-36KtDSbOVVi(k0A zxo=4kJ`7;DUU=_$&R$v8o(x@190hH-78d#o~FcK#SvUIJ=eLn-2T7m|oaO zn0TB#!Sd@dfb-EzOA2oxWl(SG7>}gGv;XLulWjo8d{F;SfZS!nI0Qz#PbRyxM*VOr zuyQYS79QM-oB+Fl@^lPw zJ+RYd8T}lpiHZ4+`keMpe$!S<(vl?{WP(vN8%KbL^737S-0OOs%E+Z!GJl)OUi7tv z*jcvzNZ@c@zhqJNvTMW`*#cd03Rtgw$}btvW(s6wIXaAI5m_NAXMdIB&~qC1Hcs*D zg$K%vSHFBk>y#&8#H8DsXav6(pM&3Red+HJW|oqP7B>BO_SRwMombz8okGbMER^fi z4;pO1{fveg!?UXcd2`;$FF$*9zF?;ogdOvq8C%sPwD}-wLP8{&emmy zp+*27GLVi;!O@+`z9R376sZudI(~m=c2@mDvzfJPr&pXO$$eKN zEXqSw9}s!GPj9I&CSNX(fNhu02fx1zKETI%^KB%T9LobT&eK2{K)R1&6do+(&gE2+ zE@y!E*a=gkwwc>}N{Hb=BZt{FaX3$~5N!<(NSdh63ADe^{zLS!=ck{`=2pz*BGB-jLUzjDL8o<)?KnaCxcUbsir#pL#P|k z_q*EF7WYr$xHkCN7PayS?fu$OWCbA@vF zJIOk{G4~HwkOIV2d%0#Gv6RNt*A=C+USnqxxrObLTH3Zdz|1@hbMIvJ1BTwVxw!@8 z%ZRs^QwQ6zdqSkc9V3mRQZ?N|JUn~3(;?MHTB0GcG*_)JxF&p1)s_G;_$alS=DYKC z{Mn^BW?Zut@0eAZp<_KayT2E};>ZuEDei`;UyO&NuT!EGxct%4Cw6ONZ3!s}*r)Z9 z-HioP!pqwvta4hJE1$SB;==CXnktt{;l13K(_^LpF$L71w8^ zhRE#Xg55U~D{G*WHs-6=Lc(-LuFtliP*T8NjMY`awl)8Js2lhL{2(pB-+w zL6dCs-(WxGEFf-EV$JJ`w=vJM_mo7#S?WgC@Nks(O+b+oRixLx2}>@wz@UXF=#&$66<*kkdhl%P~M)nx7GzD$^^=a zgCthM>pfEuM#o~~{5G-gu=1{3f}_3yVcvc2d&*1j|73kn+m5*P2W;k>?CLBR7-2uJ z>_xTqZV8El2LCD-=5Kl-9t=|G<3QR{QQW#eaPu0TG=m)3@vF<&cC-b!NmX^G)M=rL z9VuS<=SE9~m%=uQC2?-2dF$|GX3Bk06yGY^9?Q**r|XLFRbQdkK#?xg&}$ zqpAo!InCNw2hb3jgmgtWos+*2nQf7;gTLWAN(2CMM{O_6#JwqD7CPNRfUNe1&t3n3 z910KVjtZ+i^QqrgEc(R=`}DHoSZTW>%RuG_f<7W|uxT#u-z1u%*`l&4X%?DB)q6Cm zQ>E|A8gTFjiGC$##BNZ&cQ(zG3Jf`r(KcKTeRs!^uWP#gaHj59c?vMOqDz^@-F7cj z+EnY+IQM{@!h@7&NE=;9asLMVDc7YlQ*%L;`YQ7pE11UxLfGrScN*=x2hq);^^x*8 zb-aIVW_vx3d#47#C8~hqhUGN+a}@qleg6$9(7G=S06X_Ab2>=|nnOoyOF!+{^vv+6 zZB417rk@l%SE}%nGbeh(O;hsuqs=$*$$GjW&v~Bms40}4EPCaqy#Wpn(Oa+@S*z)> zPBv9or%=cdeTyCw4CbFs6&VxRVgsvy#^a(!6U8ROVc5Xug%3@U`SGjA7((>Df!_i# z6diSsz?ZlkSMRORX+W?Az@R{!&~2Y`o1-b<$4=+gHbQ5^p`6Cfhh=T5*xGhVxF=ce zU5&V;qeLrq!x7OcKLS7QX+rKW3idHOSG}pwz-s}%!K_|j^r|J!6>oA%Uuf(3wHTOT zR*y`3EOW$-zyZIP1EBSO8d&A1N@WN5fzkn_xivwR4w|M0G*re9%KD1rZhyA#xPMk< zXltbd%MX%nagY02rhA&g^z!Q^c3L@Q96MP@y?nf*^2yMhZAtn%oy!8gRj)P%u?RoT zrP?LogrrK}0h7DIcEwXrcfT)udU~6iSo_GzCv&ZlGso>o@4&&0#zKlx;%D5{lH-@= z_v4mz%NY9)^L=prHg~>SbVV9balLmbcO(NCoMWr6#-GDUFpDvs(K!J~yF){xbI=SmWsn^alg#7OHsQ zAUTMV`QK&r*RIBdk80rUXLdv|Z}XntCV6k@EHg1i*~GIosxIEI=bpYD^c1K#O?};Z zY8nK}*Qfa!-U;o6eHHgQ(0Y=+o(q))z)>t*3MU|z#EwN;N~c@vxz@nNx4H!H$zQQA z3&g39z9KdD6#}9#5a2My1$nk8ONSoVU}Df;!Hs3A(AOrIbz{#PxoMCX>^L%nusLT4 z$|IL?1{0r6QMVj&^PMk(EOx-&R_+*?qD{t@ z`7sS2rYaT%tBg2WmS*F7Lc$14lJzI~beHDvj^W@eq3w{`-!Pe^Jn~~#G4L3AC?G0G zIA3Cdo>m`ZlIAwtn(~rX^Dg5g=Nzw#=t4B?`F^1`6Nm6YCKCWua;gD_gu zl11Sw4OjcFokUBHJIbfC-jgu3|E(X+we)|)HePA!M5b-aS!8j}8H91x?%Aec`?saJ zYslX}Pc~ok3%00&=7^8MB-ff5wSPfLRMGujyHd!-x=eaU2(9=2`BRAB_3j#=)Y|!@ zjo)u1mh_51~7j{F{X){;6FWu35Xh;&oQs~quqsFt7U+Z(*u{ZdGHY$Rx_Tn<(!pqn+=P}e8 zEA3uC(+C7BxD6(il^S{G)FC0k`73vC^k;hn>6k6?Vqz*mHrt$iCITMn^?a7G-BRLT zktC73rf5ovcZ*40FzirbS)C{jIO>Fjl82SC#NNtjif|+mYYq+I(370A(DGRS*9QJ) z_sO!G+C_G@S8*tc4FQlfKG+u65TD#N#HaRt70DYMDk~$pN+*FXm?NAW6)e1Rs5>)! z4QY<*FoM&kMRMMz#*GacR&=F-qFWTkiW;h*V0(=MfyWpQYMTMYDLm{mAU@i2kHR96 z4Zusl_ioMAMm$7Qp5Z|EU2R%kLzXiEZSx9=)Wdf%j8qxio#4rx_6>eDrK;q^Ssxr% zX7rZ13t}W@Ib)8%YaZaWB`B$<(O?JZZarc^H#?FSjjY|ObtV;q0g!eehIH@)>?Fjx zXto#<*^4fbt(A-y*mlun9BL912o%eG9)i*B^b~hm9oFW{xYHb@8%6d$pa#XTRcTecmMJ+WKmxQSuIOydAQ-?s`pzYUCzq3&szaW9N;$Es9k2u~M-2 znaq~=Q{1+_>X^H$6UCU-dkrG6~VNlyNz+7GruD&%=K46zheyjZ{tE0LC=kBz*pXAY_ zU~&}XJ`*;hD241s2w3M^%ce*NSD5hwI%ey}=o6BTk+V469?)fH&w(p`oc=S-sK?Cz zMc6quXTpVDHnwfswryJ-+qP}nHabSfwr$%^?qr^ts+pP(Z`J&ZbDh2ST0Vy$2ma$= zAT=xyie(*4Vl7^d#P(}FQ9hzq@5X#!U4_f+7{@-g+PPZr=wv~!?cbCj2A8n1EB&cd zLUBnPZ+rAPsejEON|czsiadsyd->#Mwd)v>sIO;&Vn1Y zba~|r?oEw_y-y_TCcY$HDaia_%4POFjD0lLUDGorXOWcuaJT1M;TE+su_m}&oV8Gz z#w1IaI$6%|Vo~8ipShXPiz@iMTF;GqS{v+L({eoTT&5wa@d804&dmj>#0}92XI)lI ziBs=FW~cNE^^-<`R~ZKz4mvdvaO3_vnC!rhR9C*sxZo8Sd+)wgo@6jL#lJ^2{l-(U z^b_X_suO2E|98}MC!0NoQO)pQ2APo}YKMD5*&9l)jA-(YzJXONDs5U>FtaE*xtaS% z9g8Ar4M)dQj))Xd^^>I8T&*TS5A%uBU5AOv6?Za@YwnG_6y0@z>6F+`1#z3lO2RVL zfc}0-f@FB67gzty-W!Bqv>yIpGk!#Ns8ib(S)`zP}xJ`eCUA_QXKPnO6dTp#s!P^`H(8l zp6l#}W?DI(y<$t8>ub&yvO=(3N8La7PU5o-TUZ4B6eOvHP}~DLTg4=b4+{Q4CzKN~ z)^fZuFY+q{)yx(Kp5EBNE|GFxi zEIS@rwz@k-)cJKH`f?HZZJmX*pXN5b?bKuyuR*NUA5{57lOx09?vs@KGFfs=eC=wQ z{isbZC#Jajc1<6_EMz1Y{stBKhtaejEU5S5U?f2xNE~9+r;w~i(|@E-xZcl<7)T(T zBi&80eNif;^^^rINwu`QE)ck5^lAMeGgz4O0`dk{qkqNO)FpmX4^l1~HomsHkZ-8t zo-Ix{!_7vQt4z`t*c8LNl_7-7R1VCg6vJf-+j-1E_E9 zKsYV!v+&EGp6mf7VX|Qj3r4}9Mn{kL_LD=#2V#LwxJZeM@68iM?6cNq` zJmLsc&2!;B>tJXCWVwSzDH~V~Ww5v`ITdEXYv)o>g3UR^0haUgKQL6_G^kfDrr3oo z#E=G{xo{EA!kYV2VY<9knS_NyNmVI``}`L4haU6W$V9wa8BFb~(* zVmB!@*F_SMSlB2TjbzZFH~0|#s0PV_**>*w^6X(^_r4zt=CK9EY$p$M589KA8n9g3 z*Vkaf#C(HZ%YF}DU9$%2NbQrzhICk*3z?(AAhieSXxpBlN_fylT1bena zS-q=83NOGlXpWX+U)tb;99gGM0C?VSB#%4y_^vG$`-L+Em#6%6x_;iP)qO)T*Y1+b zXv^Z7@;m<~B?2@2`vHVuf_@nCs`@!`t8XFOW+G%-Mq7_vNd;^s+lKERO;}iY`cUa6 z>VOY*4p99j3PmPRt?l{Df?jQgnWX=0K28g?acX5-TOt(xy zth^^~{=v?}$m>gGJSUJnwn0$me_>b{m9ZdjWV-7dIM^Cwewyc~bFgE!-D;%{H(O>k zsu(I#&suV!Y!N9w!Hkj0=~AfoL@C)wd;1Qq*!DrE$?j4}i%XVpDG#iwVsYq(*61SH zF#u&=yGWQIgO1feTJfqGEvw^pISjV*G_ByI=MqMm*!uQD z6ClBeeeSi#ADYGl)+1`s%9pq>;_Jax`Qm(F*n6Hyt?N8{N$obNo+IyT348x&O>^$; zjx%F3dVHvw=0_S>Xr>O6?5LgNZ9GwpnyJ0RUQqZOa*HXl5^-ZlXK%@VS(EffmidSe-y)P6%q z!M{YfIZsYnh0V##B%c$M%7T?2j$Q(jFr3C72en~30x=x4TMVSq17M@$KwQWTpiOP$ z{27M8?L(|7Fh4SiMaj{~o65tYp52B$-J)AMuL%jmAJ>du{Yv+}f(S_eS(2YM3XDE4 z?h$*i3~-7=P2%*;;{~-IdHL5|wn1anpWZjFur0lRSLCTnU%jN&sF%Gv9{00!?IVp= zjUlg7Q&{Si&tUIrNDNR(0DFta!?9aI)5&nRwJ0;}E<Iv8~y!sjicH`M#JeSL+ zN#R5nsCN9+VoQM5Pur zU9=>GA-=e$l+LYhRLLW8&(|0H;LlR-!Mt z`G@f<8=9dRf9wP|Gi$b0$Es?&I&1K67On6e*qW8KgJX4syKj&I>=ELvAMuZ>XgI70 zgGtp~-=l2dD$FB@yD+aeMKe? zI!Lz|-;T{P)9)*FLVZZcz=ZWslHNT{rEaM6XCTrQ`8`=h=Qso-2=d@3f>tf-ieo9I~IDtTAsc^hXEWPIU{~4Ht~@>u^=YM(2{{z-EEAA z#QNYdQdoJ0g2;Z9W{!mC9rv%%SDtAV*W;03rRtjZOw-5$f4w`laUi1Hce1T0o5KuI zIEv!6PonWP2Ua#)O!bSG-?tag%f8~D4_UC-th7<7H#6wUGaUHTbnC}UB{Gdr^;hWP z+c20Ovz8(MNrTdCX{-}WXJ*N+$I<|9r5?{76%@cBA$RZD_T4WLkg6-;k(kDx=z%q-2rGnwq{DtaiV^^OU{y3I2JJ+#-fo{lRPbu%J zXjG_XmC@VD=aD~Sn6vA@A_qw>MdX)~esJ7o!uRq^$L8o9V<_5Kp`iE3GoOn)**;^$ zfN)MGhAoj;EZUeSNJf(yrQp~_G%5%raV>EL=SrQBGs7zQLE_n@+m?Oz@BtTv{VJKv z+oVxSs7ATE4HKD%9!kbZ{M%!UIz#-0oIn#?XkA8GYu>3E+xRN@Wzj7QkACpvaaftv zW`DG6O0p6gnujw-FB%v?X0o!EF6RmT3%Io#zCXv!qYNo$-IVauw^$o+xZ`-SjE+bn z$5j0y8;*nAc+NGj8`9Q`;~)-HzSfLSgnLG0=~JJ;Dlckqs~{Q_2B&g>QF~o?7XB@q zpc~629n@t?LVvPtp|odsy+*f+S{BYm2DYOeV&$amLD<8F1!l`VO`-}ly4_UtcijCl z^M@ULkq$p9Iz|SzQHuq-z*91Ui@pl=32|C%Q)nJAycfA~fk5~4z;h&PaR+siFdqtM*nWxH6OW-nW-7HX#UgqnNHTm5SU0m zfFIv<<%l93(jYnO@#IwTmV?|AXX3<=%kNqor`iS=aQiav8la#_P2hFSo+%~jr@hL8 z;Q<>)ub_`o4icTqJJmjcrvfBqI9M>R!i#!5OTVUA4h)tE1r?IMK6a&{M}Z6s(0}jP z#?R^O58iB40{dF`yg8+q`oY^_{!=qPtA|@Or%s*_5Vpe?nD=6s0xgkm^pygCOGxQd zP!mlFgH3KNgiYeWd<0vHR-hxqdoR&HV7%#x)>1uZ5lAlHg~hrS6fP*IN(XH*EDLUjs8b?;ZO3uJOztZ4p%GZJIkm+ZO?^hk1;pq$4;um z6M$mL61X5Y9v!8^0FTiM+9pv{MK=Mf(jn_%8ZP_XF_W}~z+FW@9GG53YAJq1=`2*} zbf3dh?}kbuwuqW-Fm)UOk4N0Tb~|jnzPkKYHv&ViuW;%ByW) zb4Mp)EdY65m2Hq(eV_gH4Uh?aWfFV1w-ec{Q>XwEEGooIggim?)|pwImJwHF1Mt_{X?K%G}r5 znJ}b~PFi`j|G*gJu1sITAeM)%igw)da5qEla^0OurxAdnUT=lbSRl{f65>xehw>qN z*pWe=Q$yp@!#M*EAl$Jsw~FPWeH`)Bw;~`>B|*+;AD$_%6PnsZttSV90{2~&%k~tD z@Ph8mv@9SnVge!um}aUMwXv8nXRriNIDZK`j>#ugmzN5uy>v_lP z^hg~DxO0;m`y4j5uWt-HMC`+km#8R;%C&=?d}=+4v$|i4)#gBQteUlGkx_Yl5|NX} zQ{_)2+ptuH8Y$MH(9zam{kh2|Q6p#EFCvdn9)ZJ)0X++3agV`|chXs%`)}4am^%9H zK5C^F*OyhtwNWeOGZ+Cdjd3FD;czF0H#O0=qcK%OS4!`-c#V*G7iwOE0B=IkiW*aA ztWbmNGeAPGU7U0oGvVIY5r!N5B@;lt>MUZaO)Q9v%}a9nO0vs3R~A5vrj|3T(+3BI zeNZWS)k1XciTz;jwfuKU)SWqi{4|s=uzXx7wZp$uokC+u^xH4O#fYR)qkrQ2YOFB6 z78CTe5Z0%h3Ob^Q36BWFh@~JuiU7^+pJ9&t&_#zr@atXKbIcBIoX7R$IJ6 z7BeDeq*S%1Z871z=m=D=>y_KmoNaF)yW#(7k9BLTtmBwhubBv_!j7c82Om(huc_|p z#W)RJO$6e59yX132i!fRj;vBW5xX0vAYE}O_`7rAuK&L?BJ2t5Hl+wiiA^cZf&fml#b%TJP$7XK{e3yYDY=1mr%U+eXouO9;E5 z3Se46gl*J^Y53&;C6^WFySurr!hHR377LTHs4$&XKM^lNF;b=Z?C(UJV>QkCU%*VV z^3_w|>cG|*)W3R|jJhojMVA*o>ERZ%pe5?SQ9mYtpSN;o>WAt-x0|GS0HT8u(~bIg zEQZg!uufD`>cmHPDJIApVxkUNh<{5FD*{G}5fF*77=&&G5`JOG5rN^|lXVyAs^;BP zEq`UlaN(37tNcvw21}C(Qr)I91I3Il8hSQFN<<$=<2e3qhj0HdOMAB&)e zl+x4X2oxp0uL4?uB6iqBlXQ(6ZS^cKQ5``OS_6Zdk5|<^!*?pFu;9d+qvef$@V`|Y zlOjuP>e09C6zGtACgWAro4t*7D0%o8_cvC``|rL1u`bR?RsrC~aw^oH5-EdK=-j%# z5Hg{ttD@eJBpi)^&?BQ~>P)m~@r&9)sxh4=bl7V6ig(Kg&ex4{pn$@#C>+;UfCEgn zi$Xmpq9ei3A4D!){h{b0L?M4^g(&;h z!QP#L4|ZpXZI1ZtA<~YPIDU62&*&;g@HN*?f`F={Sa+Vmi8Ya-w`gi3b z`;IuK#P!cZEwb8wLQWyR@HltyDLlX4xBwU2L&1zNF9XYzs#!cN1}ffdS0{>yf} zSC&WU<5YVW0dlCn-_6SShH3NIGThU3{@aeBe$H3NH0|;>^=CkyGkn5rkJcNUmzqJt z{U{A=8Nrs>K=d|wS{DikiH3)hKyw{lIR?=$6XmQ~2&OW6UAK1&wka3eb@usp`dg4+_ zL!!laAkc9=ptHuZzav7SdGWI!Gp-A1N6aV1O_-^=^vhj@OgcM# zKI9cdizV;-UR1I4#4ab1=>7C({-vYFi_C8?-tOn!rzF3zf+M3U|EXC^Aw?sIGQL}{v%^f)g#})Q^YqB67LUxDbonb=l+}e|!f6>p2 zhT1&V8?EJaOHhPJu9HEg(~u*Fy*~Ap^vQA5@d>uP^Ql^XWo7$szg4=ggQQH}ijUXQ z@oAAypjcH&Xj!2bjfeFl2yFu>h1c3cJ9Vr?ld z$6p~oey~;i%v8o;V(UkDGo^++COwr_BXGRh@9>c9Jbd*Z2&_EmgU^F-RZ?eKKAuC+ z}tHKr=(Y;bT?#Oao!MpH2h|gC~94~Mq*e= z5CGZ7obasj0{r8%8oVQ(Hs=81Mlf@VZnS{fX%=S=ZD}Ob@ZFL z)3W&=M+MzwmJ&c18%cuNP3F32;%L~+Z6E%??mDnL3Ogp`}O~~ zU5S7$sy-n{wDcd>Q+$g7RVyzaDwQ0`|GusIkqax7A%?+X7ngBSy?h<>=;Bj2D=?=z zgwbzoAP8JaK$V++$#M?rG?RqO`{Pp8v{}(ZVvpx-HW$J0_Uk%FoIq>_pq_o~+x3!& z?BzMoxZIdCmAGU{9~$UCI&pS}>Kcr~^_(z6_T6?*(Xm1Fc8fowKIcAVe+fMWLRDt> zC;u;r!O^jZrV@ReuQ&H+oujmm)i#u)pH1@tx7qvpDCt zHl4`E?7CnJX-?Ex$lHnF5mx^=x$PIvc*JKuYhE_xVO43t5W6+=B^T~Y@cZQ(8S=W2 zH@+%mc^GYaek<(}LA=Q}8|dNuUYKx51+z!kjl~q5wTmJ^R?VP! z-$P@vvefhHa?IrwVH7`-xdT1W2)##NKDZSmTifSSlm&nIeS`c5{V1Mg*PH`G*Y=xv z+U)>+RJd?L3`#aZ^)Ng|z#x`acduI~k1@8xtb7GTFfsREc+01*d{SpFoq*QRZ#W0q zCgR$Iz8~&6JzG`3I=-OO0&wEn@7O(Qu)Gx{t?ScIK#iTg#AE9$?M`q4=&n`?Yr|?{ z_YY9-e=^rb$5tKUUkiK(+u|JKmCd5T_yIdJ{m?Z9hDT5mz`mQ8Do zR$F?Up`I=Z$emlSp99_Y`DSqcy&pI<1>&mG;@C)mJqs}7D-N|(XAlyx173oGWZl7o zWQ_h@M$$j|KUfNAm~o7`_lteatXOM{)+Ari)a{b}vm*$B?#Ut&40)154FzV{j8 z4L9r%H^9=y3dFK*XjgAN?Uoy7n-u7lI6Yiw`fuvbwz%Z{Nu_f#r%31k>I};5`t#0U zjK(1+s5U|8#67R_hBGZckGoY|APlUbD!dO#TsF-4{Oml=eRpz&23X7$=tE zH5%ZuT&H)ryvO-bojfccA0}y~P}BBgvm0X!Dvcx%H}yuENtm+s@f#2iwKxe`*}Ij& zOBX9B-f05X2+~Bhj7>3**Utm=-Y#LDiNMK)BxjPuq$zoTbQ1ED(8rHzZ5~;BE39B1 z6lDD9OR=DqvmX=lT=c29#GRFGvkarB@gEH+CS__{2)hy*|JJKNGnRe#;WG=tP1+La3qnn083--v;KVCu z#tBjiq&)99YfeN)C+qUH^Fe2^SFq5p2K)n4FZF7UB*_>B^ve*KRzq;MRV2N%Lj1cN zA@}XRR?7^ma-CxNxUIEOT4XjHmjyc0l0f~F%g!+t1zba3DeB>q;8UUOc5uf*e`hS1 zm4(o1(f>Xf=zs&}`i?{_E@SBKRB^g@4`L7}{y zJ*e^}2!;#O?-NjPxaZ6smn4cP&E|xiMJn%WwMinFw;%X&f6GM^Gupe*wmXIR1%Ku? zjJA}q1h(t&SOh2=M9>JOFxref4B&56o3cz8eJZaXnKH*>$zyo`6HUj=3n`d)~*~lpKOkqHU zQEzy|j_%M7Wq=M1w}W`F!lYfzS&D9fjB`)Mojb&i!^lY=-tYUl|0!uR1RWkrI-jYQ z|8*dF&LrNDR##p{{-%>P+#P_!b0`u+{hAcL{kA{i%8wRK*b}=~+v=^dFG%Q1)1YCJ zQ*grD{l%yrCl@VAyjePa#sQsymjP%&U?_AVoNYBdjRXkvzZLiFg$qgBuY?at5mL22 z6|h1&%GOW#Q0;G=_Du^CxK4(Ku6c;Zf4DI?`^>cRImfAd8Y5&Z;AGrsD9mj9G*`7=)n3qLBwHbf+`Uf`6 z?EjKHFGQ7(qmdAnZ-VfKJcZ2Mc&}?bzo_e(KxAJ;3X~U=apF#^z0;)i2Ob8~^DV57 zS^`)YQzF>(tr5EMpFw?Yyw9Wav+cjA0|VM-I;5}Vo&cNU7(x~|dQ?{jP@l3*D%-A$ z{-)nZj`xfFA&5~SZ=r)tpWowA-J>Pk{)6OevV7cd&^J>O{?o7_mGbT(P&IDx5cXlnn(d1`0*|IY zg6s&H4ccH(x?c);`U|U{wY#A2QD}a5*u21TYOQKnYblJXn}Bi8XPaVB`+xQoGt|4! zGK;8p0MKA|AaC8AdVC@NRxsmJu-ZmA{uW49Ae#A@A`#W)|z8%B60Jlr6=M) zSFFW=13A%OfBxCch9E>YW-~< zNkETA#f0(^KqtK?t*-mrhoO1Ij@|_RY=-b1hW}q5bWfRr-_py1y@Mmo^hEB+;mESY z;Xnkx8Efqo7{`JI^hHrfd)q|R(5d+eN_Fe-=1ISC6eB3+jxDTIl;@%sI2r1-$odza zHd6%-&Ln#Qu0CyP`E7$P(r`FzzO6opYzo&|E)Tf{)Ihw)5q}Qe!sXU=NI-OLz5oDS zDS;G>GK_jWFY8KZ`|!;U4@oi7L5+B4)m<=}64*j9xx$7as`!UWmi{6YMpvuwuAJO_ z*3CX9Cw}l`m)C^+bBAA9%B%f8Oap1^qa(>(F{hC8kW)tSbQ{b-D{0UeIM_Hqqo6SV z6eX+l;b@!O(>nzcmie*s$*hmlcMh6wJSwLEfrOh3J&W_d8x9}-Vyc)WN$ER&wX4-A zbB~?$u6>ArOWSs|kSXLfj2X1r6_n&_V5wQeOb=yy_X#uRZ7B2p_K^>*buI~sbl2NK zsV-HI2iM+iJ-CR-s$02b`-s0DY&<+2Uir)SdoA4yH|8z#LV`iB>90eKw+h3p#fTUm z0~_iaN9}-~3>$ETia5tyAYD-HG8KaG$kJ@J#p~O;ZRFg|$@D>Na1e|I36ft5zoU*> z)??cni+BiGH(X}L*m%|v>@mymHm}JQA`J*z%n5F0=OQo2fc4zCn%1|Lxzc{pN_u|!Z~Qy`=f5z_w@|^xg2d%#VAg%h zyK+S#W3_wwnoVpL>?>8oB5&Z~IFKJ)o?Rg01SH1uh;f%hBd{PXGgDDNXr6hIsoRPi zAoX+-tY6;~2c3Wr*BmLla^za%b#*@Jc03Qf&IO^=6mb#DNBVw4y*GIMhRoQRe8sNn zZo%fzP=r7rqB`|g>!IP-e&jwFoCu2u*%!k1H_WKWQ}(C*M`L?<^WmqaRypgXqYv1t z+z>>Q#d{U_v&=o=wV5G|J{+rqoHV?_Zd+5lXIHleFJ1m3IDp#oQms(EnfCp4t(sm8 zj;>s<%Zl873cJEDD{$~GaZn=uoq%p?X0(!)hj-kBfh7H!ufddd<8h8RY^PC&a$eUl z7?Y&A3I!tjy;szv))|_T%ShYk+Cq%yOO_KRxLNN~Dt^itdDx}*-ZZAY$7R(n5Up`B z`8qz{z^kRp6SJhMtB)T9fYU>0s#yuexgWk0Cp1RSPg+PMTrYKhE(YNr|0b>=I>-1$ zk)SdsD#)@9;P1LK>u}Dk{@S}YYQ6*Ux+>}C+C81veA48cUd`DMIC}R+uFh1VB2D*; z3=gNruIA?cuu&|sG*mg@4|f+d`P+U0;t<;0P!|-UEX?ZxtgoUAC*{;oUo>7HX(>5j#cQ;xk?m1kAZOlt*5n z>5mn*;7@f+aS$c7V%UKil2wCIJic@|-`!e(&e)~nZ5??AEm6BMrSBJ%`lf@psZ zz>sNLJ+%kjrX4o0+n+Z#Jf3?a@6e$=Y@Nr)^Pkw<`Zv#8AsYC~Q^okXp3@&Tfe3a_ zw;%KG#8l)+-(ef)1cev|KK&L4-F4KTKX$2N-f_wmE6EG%$mYQ$13yv>=ekmj^s*!8 z5MnZ@>t2MFwRO53pkn=0#5R8B#AQ+@?xRXgGgO$EHsDUcU?L)v#1MK6T2+lb-W|Y& zE7VG_&dYrFidattS=xJ4(xMzH4p3<|dPPw-_Ys@lI!t2aNAE@UclWu&X>#zr-P;W2 z-#;0tk>(VdMAK?1=$k|BwRd}Dw;OPROnu7_vY=uuyTtMoi>ymhrf;A$m2SyPKc$>(=FG%+dIS}Ep26-Bj ze{eb-;@Y{Pi&WL+6{W5=|NIw6~~Gj zjo`RA0gIx=*owgXju~{aZks5;FKm~2faX|`{%BAUkS3Db6n$*z(4 zm%qFgxn_NjU)fF1=M08|F}~Gaq+fmo{xBL4%N|8X7QoVVR(PYEG$8HEvd51xKmn8o7Bjc991eFscU?7!S$b!wK zi0x}!4ug}@1m%f5<5GmvPW~AiQys3SSlbjRnM^5xfSQ&gf+p5%(y+}}7beEBEq?;mdM;HJq_ z3O}30g}`O6+`eWwYx8^~wRwa&k+jwgp-~AnQq`(VP|V%yN|vq;bP3^%0kZ=#gJxpw@|~=`1(;fd zp|CAJvE>{~8Wgv*TVVvF)qd62gik;ib0movey24j^b%hmb|r}v1?(3v)o+;m-D-Pa z%X|zcTx@-0$|leWFd=pF-DU5KPwb#Dl{HJK$q9S&so(|U22Q1Xu!sAw4g0>SoT`o&NO^U|}!U z2!G%fYPN%?Z8hI2VEsA+-ArQiGdB(97yV9}2lU7kqlK;R?#hl<=!rJ|sf?FLjEV&d zy$=E&{Qh`GbS(XBAbPhRjdC+xmMKbx3#NvQN|6tOl3Mt>nBtWns+S9>)DxtBH4|>*Q)Prj z(e|n$O4(54%Bg0G@1_*eBH6Q$XM*$XQ1$CEK8XkMSyqbL3O2Y;ySPYn^UvG$Jf3>0FGR{vD&LnS8Iet?SUQ}l8a+$O`-`FVF?B?U`jz}dn z7?6Ek4(WMQUg@1M4&mG)v%-$#ccsm*Sdb~fFN7mjh0Svy%W=AP>1KXoh=VJ;rsYP@ ze1685KxW}u&~MIlr=bv)-wVBKq2d@3`|j4^qgouOh$#3sveQr`RBWjeJIf~RpE3i~ zpY9(4P;_1%7zL41QTCDS_BFc%7AC*X?D*<=X1Z80OE0d)HA`7sPq6`ZoA~00*H5IZ zo8t#NQO2W=@I!e}CuvbKm0R=wjL^af1>8XN3;+%FNOS^gdNw7nep?KWu47&1#;S&l zXb?lw6^c=?(D~+vcCkOaLBAKrF(^N!%}j+J;~VHDi5be&h3J(`DY)N}UG%}3Ysq~X zjFiTX4#5~znT2qh4h-io!?vrGbhWldcQ`jlPV0|_1k)J{=96jOmjS2zEYI3KL<2cW zcKslu`|(&pG?}Sp9C}yrf=zjks=mmMsB@;!)W*kFeFq1#3-HyGquE5efA>Aivie2(7R`GiB2hsDU+GEA34i%MSeo?BnQ@z|QjQvncF_<4-=^mW=!sgp zKwU?Vg%Hf8W%j{6lZ#DoH}IluRWQEz$X&&vD<%zp1yYY}7pkG2Ug&Uhlk&3^%|InA zd05vk%g*R3y!-sRQzCn=mU(y`5f)>*(m-$uq>hi&3$gj^uG0DK7XYox0Wq_4;db0m z%A;`MOARo@!$r*HMinDjVarh%*OL#kj4V)QoHWB97z58x&C>;IgKpFy^<8jdsT)HJwSkxuid5b}hOXQXak{RM3< zCY!LhkOS@0D!IB(f%cDJY0ulIX*lcVH+U#MUv7%wlw*1(y9}0PE@M z;yS?M!G{VREzO@@$&xKWX4We1+XNR$lTKk^ZeM+llgbW25G|~{-`iKUGb>9rs17Tv zwUbF}zQUm-YCk>0>Zo-~Tq{>RWsG{*?2X+ou02n5}Z-UZTM+O`6 z^nxZjA#TZx^d5*{7MH;Bl8xu%th~UBs z5(9^a%oF+}2^A)h!Cii6h7Y?9FBUVQwbKz^3maZ(lV$c2#yo>*hp=wtG!b-sXvQYy zv^|!7(!ai-NH*9f;_>&i5AaxOEa2%M@S%Rziw0t&Q)h?pwm9p<-~yBzE$rzkUc=Tw zXqL(!V_`QKEBrKQUl}y!FA3UNd9Km+#uSgzdZR5{6nHY^ANJ&RLs5e*pfZVPfyq1|_H2!l0_(Dhgjv zJ#FniYn-;q^M%bavJ&z(G8lH%s+OW@xiHk&l91V4g~W76Rl!0(%n&Lghk1>%OC>5u z3TK_c(HwG21=?zu+&;jK=Wht(*cp1J^h=E|i7GKLdCgRToB3?Svztd_Quz)>iz!I7 zHTM(3`%Ia{L$P50)+#@zLsvbrgSHOQgxz!Crp?TP(}1wzRcupUgC19Y&h7ifGOP_| zMHzd)yTE<=`>*%*JYGt?N{Lm(QAh74Hf67V|f??9n9;V&ZzfhG5B5khUQ?SxP)zP2_&<&K?gSEL*;iET09(hF&C?zz1oYVodQ2bF}| z5H0sr^xFSLjjmW7Px27ZSj?nP%5sd4v8hx+tt1vOg>M!Mcq=Bw1LgZHm!Ckg(CD;gEd?a8{zs~zfdG+mrY7x@cb8ZX+WLVbf8Yy93gfjGc8#EE9Ptc_R# zHt8Q-rf?WP^s|jo&xZY_kR(B;^_56TEMPZQ6&fGAkV^wXvq^DyWR4VVZq15frKGoM zlyo7)fQ(6D-4|@Cc6hzG`zjY@Qs#{BgUJ>_MfO%WPr-y?Mrh{-|8F6T4qv9o;S_pNQ^0L^dYg_jnT~aou zR9_AGH3&9L?ZKPmK>)k~*%LFKd>@+&TlR15XB4mWVJO7Kd^sy5j#pc<@qe-bpy7^8H2}RR_s8^h=u2U(0 z3>YGeBL<)_^I89zCOB8fK1&Z)3+%N^{Vorr8go|mQUAnzQ@e-sST3q_YGsA7l zG$QcBS}fJU+f#D*Sl-w&-<}t6Hir2kxC0<}&Z^eC^;nK1SNk)*8~LF+W_2>N|Kx2u z#)Si057q*v7vQ{}r)f9HN||%v z2SPzja5WH3YUxX7GAS=1m#CBrlASKEZWBSC{kwk4)CCwHZYX}GJb)m#n6BB8GOJX> zXhz4PBb|0TFqw0-bkO9J{k_7E3sM-hvh&AT!P<1Um3VL>6I(>Zlau+mA!~ULM^akD zauS!*pR{2*drsHeRo5gj6(#dV9QLFubvGwbdQhK&T0xz$lf3Y?c~PZZ^>3C_YhwpB zjckQ`KS&!kzoz6L+Rcg&E|C2Jmb+p0EsB-9hR>xSH2HdRA6vV&B!L`#Vb$DwySJf} zKVtmqwppeOmMrX5|w&X^7C7f1ZW04y~!|LVEsUff? zuxT$9vu3sKz3%BEv~f66GP6GUASFp^Fx?4mXiP1QsG8;ddHRECDo<`j;y7Q=+K81T z{wO?&0)E$C)T48eP&|bfw1;|p0VfZR21*R%uF3|^4A4HW-)Hm4twq|Y6b&W<+!)kz z;T}zpg%F80?>&xfc=1z7<=o-kijtozKrs-`?4NB&(pT3wtI)`}Brw=|=cu1jq_zN# zq(;su?mZMo#V%iEz-vlDTF0McqNIm@GE0j$)`K}fi`QJo(0_B>+0W++OQ$E zcCEIf`v#ur1_JM4PIJ*+;GBdH3cwi5M>@Zbz}}*z37f929%LoG>|z4rP{V~;Sg2s} zS(d;B$S?P*2?s8k>7n~2+gz!uifmjDp9Q6897ZU_ahmnl{}m|b=hU`p?LuzX+UR6N z%rUVucjW?SsKHZg7+F@N6oE*Rx;FkNnGomyAQNKdVE@0)AQmD{CU%bhV-Wg(WkOuc zOkDrlB}DZ9mkGtSfNP=J;&RA&aFQ?y@kmAlx_V@=j0Pg(#wL-LmZ4K$pp^=XbO|dX zAt9k5k(G+eWIKGm_so6u{089dd0ca~?W}njconS8Oqg4eR31Zl1Xd0iNeLGwM$!q1 zE6$)$fgm9xqoN=qlOGbsWhDEg95<-|DxU|yfp|ZtvgsCVZpuK zgAITbGFb$oF5`nRDXpQ4e3F6#5oI1Rl8o=*#=k;-1Q*^CL9!iqTo46zB_jic-rg$) z>>7eCqh8P-!@K>il-xHkoio=A;HmEu5FlYK=A3K#RV#sk#pe42-WN={g$w`;EBh1` zlrl?}8aVL$_`+rkl^6*l(=Q1THpTvHDPaeLNkxuF%1FzA5E%eP3a*R4Yl18RDULfJ zy-&s75@Ve}zkzWTZ3Tjf<`JC}lB9BuV}b~g_!9ju#?C256JT4TZ5z|JHEr9rZB65E z+qP}nwr!i!wyit4$w}_RdAN`DTuD`S_WHinU-kp>?M(~<0vw~jfU*Z>GQ*2gL-v3j2^y4=%Vdo1Z zrJ#aKNJ&jX1p*Wy9R^xdBm&(3gJ1#`@J)5to7HR}XXiJi|5O0^ z90%ry1f>9k{GKsS0SyEbwj&`P_5&aS4GK1}Bi#V^v!%z}0~1I3>QI(c^s55}0Sn2q zwAgEfr+jan2Zw%g61fTI9)f<;uUq@+^WDDZZ+rFK=gavypuMBN-K{}c@a@y*L-<*n zpZFTR_V>~HIUsz~2U>W@WjPhdIX$^@Jwi}0Kk-FM=O4S7`U&wn?Lj6S)fW;0?Y;WJ zW?O^wcMvxE+fse;4b(WIx39vH0C*WA6WpW2sbPSWr zb!7Tv+1bdtr4K_bZesUFd!YHlGy1|;ub1DVjdN$bk%Qf=52nlKX2es!BFDll$Nt!3 zqJ4Hm$h>bOxafHysIDh?Y-qbyowmJ^1+K@pU=kv_RO$nY{Y?)^!`B;`qsgpQo4iES zQ-h{93V8vHZE~OiVVilTcH))0w z8(y1&DfRjGpj+sChCkLv+W9sZhLk&rZss>hMVC{(TLj(s_=A}6{P7SA+}UyBAf2GO zfDsfBe$)okGG(u#+@@kkWKm2)4|6E$rPWw4I>GA^fEiD{{FL*2Z+9f-xS^Rz)c#d1 z-lGfHX|G&TqS-RYi;8p~5u*`{HhLmK3JGVbIPvIyp1w(0k8CMK0VOp`_e1aTPQlwd zh^#m|U$n%QFzUi=x-#Hti|*3W;E0*8TuGWhzqbl_A*iAKRN1^H{gt|Lk{8=&`44RI zLVq#6GQFltx_W3SyyMqV1m_h}d(w+k3d0>B;hqYX^>*=33jTFXFh{mkq`0m0Y)-zH z^72zmgq*N^Z%dtdsEYTX?E3xWef2vR54xi)to23@{@ThwAK~3xi&LlQX-J|7b2ld? zaFOb?v{%y@gUQ1R$n{x|L$3KtC+<~|{_DMNBn{}KJIsIs*KDYork_ODtdmdhAVKO4 z?=XaU*WOA&_L?m3O$jxO1#~6Bp>EU5JavhRRA!%R$c^1!g29E=1WpcmEH`I(D=U#R z{B8$I&$>Z_RA6R|G_D^>Z|;J{WwQviM#J-B_awcD%0Q>HGQm@8sQWc7ce=TgYX*XYh*QbGH@ns=dSd^RxN*i)zeN^@d26dK=LxVM+xNw#E>SSx4d8JB2}PGy^m4#u`B8n9TxyLXI2Tt z?nZ^WSeHN6ki8MAyRmI$wA0;t*)hHpLs-{x#zR-zY@W5V=g#qPb5!SB-`k?n{N;*8 zA)BG4@JQsX(Q<=wqPM`zgM8u^ex|r7!+4JA+V#szh8=zRL}x=jVGSA{mRrh|+htc> z*cUhZf@M|uc^CtPOvRc?HqVhhRZZ(mFk7AKB8ssurYx@_zNcR3sy3Wv*HzZtuX~iW zi-2XrMbYiiL{rmd0v=jZ6>`6#*GrMWOA?vCR?0>R7Ujw-avHxMsUc@Fpt`fE{>on? zx#Qt@xW1XE>ppPrc4c58dR^pt7J~yM8mu(w54q{4bgRbNqiPkGtqbyVPq^9ITAz>; zrU2)Ocqp)2QurbaULK6~LUo$1vZ?aB4}bspMc7OY5dSMCS~Z!hSV zZFG_L0pw4TA-L?x{wK**R&yxgSd!%EMvG#Zn2)n(-V&Fm2xNj*up9j zpRe&vGdKDzUWV^$UtSxm_@Bh%${YmkRuR0|mtTR4+sLfQ0WPw=q8B#cCnF91in3iw zTqJ~*K3#B|8CfiM-SYZ5<9uHF!_8!AQ-#<>#0w4jJvWCX15xtEs44o1d^fXcb$xU< z1lv}~74EkInAk#xvTDD?MLkuIFdS3TG(H#diXQUc)TRq5EuNEHnyyg>Lmg+5Sj3i` z`h>_+xF8P5I%yTBY3IzoJAOQWx5HCek8r~zv|3Y?b&x0d#HE9ZIq*uTV|69ACRCc1 za%FO=X!h$S;l7z%euP(uMM3ZQ&1a8?=A_A>FUD`bCb$B6vR8ulZW=3XUAW~>fGtx_ z_mnvXJ{Lk+4JTn9)Y`N6HCkyMU#)gx0n4hnGGfldE>9C&^Xghk=T9>?ap)lr3dzBQ zcS4`25Nt7hN1y1=8G96!JuH`;|A2Sviy0cpwW(_~IEO4-9OLRD+AQ=|*W2g>H+wRBiRSjcd1dJ)WlHt*I2{G9!@fw5!=5?r22r z#nE==*Rg?N7?6eZ>1T`xzU$3^d;2qwBRki&+~31osyo^GcegYIgo+$U9@Lb^jaF$HRs-?OlOFn~JE9@aInF@D1o8U$9oFWxc zFKmhQwW>Mz+*Zypj2+0$!B9+R4GbNw>gp{jBwqv0lx;7E<%cvZ)%M_DUZbY@U`VGW z__VqwhlqA4;?p z^;+Tl!qNg+&r~mvjkdOpK8SS1GlQW>u9LS0J0iPMBQnC@AL+`9_qUy`F-ks(s-xTy zTrCb>qWx0k&rYDOw+PF6w`@e1%ti(27zMw;J8vv+MILVSx@F}3;e2Ocd^xZ)tD3P{ z1>cR%NNj`#GVt&pC_*~)fUTbfa~qs9f*Yxruhojq&oapKJ)7n>Yjd|EE)0`o7xU`1 zI6ES&x#!%%vDzY$BOB^Q7=Smb5Li&P8d8M+ln3X$PR#M+(gTVe!p-V0f z9p}vA17h8A@u6!_e)rNzL`s@y6{|;DW=WN$xbw)W14tVZhJ?^*33Y~Yv;d6!*Vl7` zN(u5uCR3Ez+{DusIe8LR73MVN&v~x0>?BThp=-+sd>BVlIxK#Do1XmR>L^Yd+xt>! zM_E!RqaYEnEW*7%O3hErk#oL8t+!d zcf(IZS+nOBoDgI6$8>%9jj(O@GJ+?#1NHJvfx($d4}?(}?@@VKfG1jI(Lm%yQXtds z)`edAZs?Z_h5I}AYCk4CmFC1ho$Ef0H*H;k9v*744C8G^{zbfDa}Px^zx{k*4)TA0 zjss`})hlpv|lQ%!@ z$B58KDPH_WenZr>l`1-cDVn$NGm9sK_W78k`#ZIp2$R$R!AK}Ch9YJVpc5e4DzT!J zq!%Lx&AHk3D8u&3_SC;;sg+I8IcZ#2PNQgSy7;M?&UFApB?~1^MgR+eMDed<*h!!&(7>_B0W} zmRudL#p|0P0M@Rcu;kJ~q}~UuMAuw%OH=Hg0Ypw?K2Et>fxJ zTHJLM%-~ypj}pO0;U{;3oDalQrcc=`PhDmxwW59KNIFaf4$3cxhOcag!(ngZxh+)} ziL+A9_AcE-tU|*l2+52=F<@U#+^nz{&2elAcmG>04n{uQuK`eU})R^NtYZMH5rMPR3kW9t@LnP>>}$e%tK$XHk!0CbKv$jF~2iY zdbo`FIS8Qf4#t0r(bVgkfxhu+9~SA|#4=L>+{y`^_gw8uT$F6J(EsD65fZTCJXNK* z8vmoXs7#T&6w_J^N`x;K{3J*FwS&$7ID$Lk-WpXck_w6T2SfzV_{d&QG>Wk$Grshz zk1FWWc2*C+$w)$c_n>pKbgijl#wF`h!-9fvcV><(T+i36%K=2d68 zzptCh#tUtH1=b|M31u{j;W-K;<#>D^@QgM+HJwghzd$l7de^)hfUi=t*%*-30cn9= z7-oQ7A-~0HH_*S`8%9L%{hRB%W2*k??V=?2S^`Oylve=v}{6Dif!GIJargT zyfFO}kigWZzr_*+{nOa%9!(#PN~w0QTsY_WO72fQ#IJYtVLeUYD|gd;fX}Jm$hTKr z%u$i9+#Qg!pmcdePri-s*4!Ic;mXN6-vF_V^Ld|OTeNa6au9OmJ~lp4te*|}yiiE$ zQoIb#7!ZI`jjip#ko=xT$uXAY-$gyab7HiRoF80u#KkPO(3OYo&LLWdh#+8x(bgMk zaSJ@h6j^(*OQLSA%m|4k3NxRarn;6~n|MF82M_Z)+X@fnsss>)0j0a8z6uW0)lKT? zac#Pj(xiorz?^6cB?*Fvo}4(^K`-BV)nT}&g4z0rb=W+(bIEJ>vEb<5FF$S$ntgB-E7e3YmpkvGEjB zUDXOIEADpY0EuZ>8C(f7QsnoL>hh%CmL}A3tiY{}ns!mhv1#repH3B{#J1=v@U@yd5ggebkWIC7@aqviPMBIO>&Cu7wceq)Gk|S{v?txDn$BRozv58%#AQmpIt(Q?KFXM=!qC%q z1oT_;{I;|}Z>52whURIOJ^q&mT(&b8x`XgSv+!)PgG85WTi0)!eZ3W+fF(5gM z=rnB&m=V0SyM0DbcG+I90BlHo{`lZ_PDykBm4y8GN4CMi!ekoj;PPSx%JC+Sz(7bt z0@HBFM`9;Bt0F6*vALf9f8m_~?MDVJ6K^woX$*j9{Ek1-i>9ninyHZR72=Nh7odreB!!9G~ z?U-f9#G;2tAwyVcSFXTmlLqWgJ(czg~|4ng}*Q$=v#RDywD>tPAdB-#rEQUpWi)#tXC`c5-#j(%qm&hsJpyNwqBSpyKyTD~-G0 zx$+(se*2Uf6(c^xbrCIvI6K9qYS7$uJ2Vicpri_;NUe8@TcEo7%oCUNA{M82ViIBt z%`RB95J=m*1z#or$?w5jkrx#4kK?VpU6Hs^m`-T79^$hkK%L?bsQ9ygr zB><+%M_S~d&e*Vv1L)$CtyWFLmGH$W90koP>?3Cfa^yneag0MzLPb03yW=Cc56VQN*qs+b|#DWNXSIfLQl!VmwiaVBeDL zDo$bXxM;&rQ0>b1;_{y~WsJSPNs91KOFy)Y;G}P(_i~Kr)8?Zitk)IpHO0%CcrT_s z?Zc2E%y%x-&4VkS8xO7q1CJww$i=w%pEEU$%NQqCl`oe1HC?j{TboLI)iRk0qD+aRYEzq+^mtEDEpl`rHB*%85`NLT@f<-RiIexI zmr*U0{F_f6d_=k$_fkm#=TrOUlVyfh^4P7LY`mfMbX+cX$e@yQ0n*k7AD3mnF@E(G z^aaOQ-eZENCL_K3#0ktB|z zU!glrM_#4sULQkS$otqDt5%hp77&oJ`-ryHhTu(EYeOf^N*iM^|I#|nMfA=04dQ|( zW%+uC8kar@;=9$#qAlrBuiY@mczafV}fwv(lt>QbYbtj z-k!sI>3v6|N$|(?A@@a~6@FzwL>jcwz`A?rIp=Do#3xT8+P(Z@3EW*Nbo$?TUVfJ_ zli*b8nH)adzea3NnJ#_AJI+mlrEKcD{x`uTQ#~c*Nckv*7*j^5uiY3zsuDIuzk;3x z&ci3l3?lO&sd-%4sO^n9YLrGLX0Cte=!_#^Lbpa}=GWp7V$>b}*s5GjH%Zr#e!DH% zm%>$65I9wJUN*s#u%su=KuCM&z#f}(G0u-DjNqTI>ok`e1k>~>ZR>90uRoazl<;-@ ziN{a3e1T($>np_agRH@-RyP{xY02?@YpB-cc&g<#87);2q{_owEgU>!agHi?+96X z==ZF8MP31*U6FTcU}%oAN`$-$Si;5Mp+w;%YM#;%0NLHtjZoy^dTodSd$hU2F*8dn zy`kp=#|bHR*LNl`HL&!+K1mg1g73rG!Ukv?li-dP^d3XrZp+I`KIJ6Q)W(Q5j|J~5 z3@}$rmo`GG1gl>J6UlgU=rv2F*|72sea6@$w7mCo8)B})5|f%+<$9dIY%YlC9k@L! z9vHFu>GnI}7<*2$gOHZ9R#1_C()=59EK$DN7C%VSA=-3HOM|J%2s|P%S*>m<<&Ir% zCOccYO2kdD6e%IINA)qH{ae4PQ6p`SW;uM^#Qbiv6kcXIasdQvSBYz)Beqd;*@O8~ zJ(tU`V)x^%$h%X`E?9>f%|w;CJZ%xY$$T@Fwr&zsjyu1!jxK+R@;-5+?lnuz=CpTo z7#2ilLThpVY?$B(WAKvfJjIxbL=KQ#3lEJ_=y%G~NrX%5a=2obmS;f#OPT6?qTxeQ zp+MuQwQJCd>%U!UCNY3cVJ(MnD`zkGI9b2nKwMx3xxsgXa`WSl7?48Z@qe=T6KihQR~!&6g|Us=~mxTFY)eo*gB=RN?}CHmOi4)eUo zRprpJ{IKrcVq7wmR6^b44nr?`@U*Esy`~iJVaG9|$d*`D+?sXYv(nCCO0f8=_nad# z^*gh_tC+l@I*l#Hqvw8;&ya963K_f*Md-()vUskR)4V<`xV-7-k?F5Q)NIXBh?k$_ z5B5{fyG>5_f=Z#vrQ`C7v0mw$z3PYqZ z_zigwpTw>=2kA7Kz^^~8E)%xj?W3K!pts_=th8mPRg*Hg)*u4rzqtk(F?#<4JTKX8Qp0l{z zF9O<)z2X1H2yp&4Mu3x(GqWXiIV$eWz&s8r%P?k>}(@j+XB0nKjex7MMKm1C8wrl?$&S-21hfAkfWZcag&N9)D&!?kW;7Z}dZ7Xh+wV(4AJ!?(c~)!*hv3L+zIZG8>YX1l-T7>K!!6)KOmxDU)e zkO9cArKA_se?`uP{!IXba1Gny6XjO@LclMnj2h^bX`larGo2&gibzgI&fsE~ndzs* zozqNGTiKo)2Pcm1-)`B}7sWt4ZhW%6lljN7U9H8XrX}Y`@Sky8xpCJxjcb$HY9jzI zORxduXQ(SJ?q_XE5DAC^7LlDBkpk!t2&g?>gW>0Q-o7p3`{elh<|k8NYiV~jZ{MXU zTparv+~Ymu`Xclx2#5e~w%|_AkIN^$keMlXT7WDekZ~O6+OIdnk4P+&XLg@PYqz&Uf=JJqMrf=Wo~V&7yf-;UB39?#)mAT3WEz284o^WBLR$lOqG8{nt$dmjsYbe;L(2 zB-F@W(}z~whnE4(KpR177rDLN+O$;KUnxHap6g7gm8q*?i;-+UF2LD(Y6$nMqTeHV zsm1TRe55wAmomNp0vrkqpwm+*Cvl(lPmCexTN7_hW#za{{c{Kg=JgFhJtZJ|W>3(m zOWb&0eHIJ~Kh4M1Gr$nI!LN_NHsGnhKcZVzKxSwBVR(JCACUGyX-D6A7;bl0>{v|9JD!&Bjv#@_eyXd=tej@eMBC#xN0C%GU9|KmO`a|Qe20reL z>z_0SM^)*vKj8Y90=|2&+)(#7r>S>SKYhDUuK=!^RJCbeU$CyS6ZwV7tv%m<45dnb zEc&Nv-`z`JxJ&vX7dFBN-}oLGYec6YKmU~y1Lj8l#jYu{p9Vn}-*7VV}$u7AS0g6c9;w~MyL-`45WT?5f*bnxW*IeN@Z>b-cSG@gu$cFBw z!)N+e2O)gl{-62E@W#S}$h;qq`L3`x{@2=A1f(%|lYlM`bMpZL6HSaIA7v7$!-+QL z-$1Sz9)*J=9C`+RP*`zUY+GUKv!6|*`sB@Pv(%;r>&2wUc8SegzSr%#@*8_I_QMj? z%>cPSxZE#ZPk-3@A2QOs5DLMm)wwk<>GbOlfRbP&!OYkb>dN2zxX?pZJ3D%U!PNg` zp-|bj@3|DuTxTT6!?+D~Y4Niy6IPE5VsmF9JMjYGDI7`Z`;WF8}vtzrJbk7cfTy&d1;c+O57zV_ctUf>EUS? zJGI&+jmR*tX>WR1HrboM_h@s8KMai+!a@WY^=`|JK0;kdRK=4bHKCj~J2OnGY$QFp z3O0lUC9v)mi!*H>?TVl;}2CgCbJg12;aM>eklhb^6LxGft(#cFz$zy|jVxtYB0Nl9YX1_hVn2=W6gG z@Yaim`0uaB4(_11@bZGJclUtRO9CcqS+`ARSd-ZOK(WZp+UpVEpZ3Cv_ z>y_!CmNNq%%J#jw_5Z~fD8HAJRi&$A@;BjJtchJ-@kws^QX__*IiX@RW~P?+eh5_561guMr`NE3&WEOd zBQ5M*qk>RL!pq&}kSy{XDM5V=h84Crp;(4a4Y!ZY#Xh(ISLj5VAgW>DF_0G(@i*q3o51uEG4&1K4^PH;GB;yd)N+F1vyF+S4j%`y6CLUn<-$F zCR>-2?Jo~k>i8D&AV@V`8!?J;yr1Siic$!+NmA3m=jc8*nF`w_%;~9?J!kp+b;{$c zh;t=-oX%#v6#EL88=a4v*Ama1Uv9WU1p2-r40g$s?^Ga4-3+2Pp`2g=vd*P&E216P z!N^yN{g}mnC4Zr(yNlJyARD z7_W3nYsQ1hC6+O$ppl>FpG=&p>pP7P$R=#4@UW*+^6m{gJed~bC@Xz-^O#)J3A;hU z0kU78AnFrIF+yvPvVDEgG%*k6{mKcoF_yWyTfOSqm~&5KWArN?XS%efA)Q9-J&HUN z=H_`;mp`WiXVWTbW7a zC6d^rwt%i5)u5jedE5vLCjq)Ae{vAc8=_aX=N1XKEW(L@tf2iL&&+*MRR)lirgWx) z=X26WHA$E72fE1#XPqQ;M=x||))TVx)U$-m5df^j_rJLwrbFvyGRoKP)WjRp*dD)e z2sI(Ax#FRcWD)CBE$qs=V;nDHQKr0oVhw~cL~GY_3<+^lj=$afF^~lkGM6ALK-4gm z-@6Ici~{dvfdX9RqSWRF#l7jhmQq!bqFXZQyJVbt0drtz3U->Gh3w&k=#@)Mic1%ar^ua`i;QmZPIcwH6(=e7%%vTc~~9kx1|%u^n{8M!e|c_EL|{(N(`o zrkxMloIH({nsDMl%=pIy;nEd)&Y$TPFpm7h1B36$m|kkW10kvPr{CSIAtbjk2K>(w zxg`~koMVU8q^J9foGHo9!| z@6is0#-bdV&;1n(0my6lYl7TI^K&KI)-NIZGh(M+u;TH{jMHycdLKWY0cZ@f*3*rr z%eeS?mr^nUW*8Q}rH^;a-V=&xV(Jd=-^AU)59IaR(Lu!={_%r&$r4hYn3Gby*ZrWY zd=d=2Z6@eCs)XunnaiIHu%~mhxR_sOO|_dTmROhBp;fD}@yPrl9C+>CnIloO_4S~y zJOPK$5Kn;ol71DaLp4-qd^sMECnoojw51@e-8zwz(0Q~2y0-|Dl7(C^GFu`&uibkS zdFZ_FU})MAi@YS-$kc@J2LA%xL47)d&`Q6m@+&{)Dk{ygt*SBn;l z?Keu9@Jl@P$AV}n*k_z1ZCcy~EmiZTfOxkk^S`ztS#Y<2t)krYzd}fiF;Gdh!VA0N zSsH2p$$bmjR`~)(1rT}A-7@dmc1I>@>oIzbf3aESdZXsb;@u}vIJ`~Wz^99N9ynIM zXal5L2acOU1ox$WzJ%#n%q-bp=gYZ|oh6*xBlibAcoXwOl-~JciwFSyr?F8>#e3p9 z`<=bc>&8O6noS$cN8Gw2&1+ZRo#8yLl1zrE_pr@?J1rckOjhNQ2I$X3IbcGvd4&cw z@j74#gA4*cD`kQ41|J@!0B+$cX=+{UlhXU{VQ9g}KDH_Lu?T!nD>e*2Z;wbp zLScNfRy8&}%2)ae8Fvt@)Wz&Hsfw<=u7(iq$ZdS*9_=DAOcj>blH@>Ly|0xA{A@aj zrP6#5BIEKOUvmcEm|CiR^4IS0X!f@*GF@tlyoQ3}K>51sWMKg*^K@sH44Ir)_Pemi zCzG{mKc4fziY~k}IY(`4Zk`HEE&Z54*xN257E#qa>=Ym^^lucnPy$K{LG^XIE6?g4 zVhPF>(}-hTpivLPfb|#UVSLE|Oe+E4$AM+7>NOHTem3)5pSmEjeG?XzSVhZM8BKO} zaGW5)py`k}+XA)#2ad>J0l3y2d}v3dm2BxZjLvI+o$YFa_(9*_{3>)u1pB5G{t9vt zCy2umAkXK@!n*fcaP65T)0?2P!QamC_y`U|JW!K~OT9t_vm^ zA=4y8p(+dT^+nqTXnFdT4=tT&y@!i3IUD0bR~V=UId_&bOu*|rC{|7Zv)Wb_cktAs zIL`RYb_tv%S9X4HWbKriQm{d0CQ|IvmIMpEm2}eh%uY&2tHl6K#a&KKU#e}5_zE# zJZ%{DDb6$yk}O(|=?)iXJPg&Cu3<7W!FPyLK*wP3mrUNuDM2pSslr|Db_XY^$dXk? z|NA&xl@ek0w&SDow-b&NhgFBV@Jk%+O*uEi?w}ghg-OtS+;KT@2u&n|1RD6;V>07A z{V%>~j;}}n$Ik?K&-WN5N4GCj%J#4ME zA6dsfDw|1)Z}83JNri?newi`SE4X}+Y!%r;n6*%J3FNhkC=DOf?_j3%hy#&FAyGa)l1u;8 z)!e$#{9(aouEKw_jIGlmCx<_ugeJ!pxm`OvS}`K$>h0ByT1HF*usZ3dE% z?;KZT5@lgD_G1^U)mc|C(n_C7joCeN#Qa-z1sdZ$VHk?D?GFjU`QANo^MPamqjzQ! zSuXQvDM)!wII?`p^kZ(c9Fp&!%sobqPXZneP?Z$G2o;>Vfe!j=cYg+XL8!AKV*@qg zhbl|jBZ;-=!Y-x>aanY5!Qef!M*keraR3PP`d-=2lwB@p4y&yL7~Wey11zxW7IwY8 zdEFS=m+`L3h0iGmtADrlMpzTE{VEm%LjM}@NW8PB6gwBtdnv~lSu+Ta&7J^QuHurrG888eN{mme&%FiMItSZ;+969@z>0=+f(Fb&r^P-}EiX=V zaT68n7=yKYP~u!eV8R91hQ#w8W!U8!cdRd4X3oY1qB8NKD&_a@rer#Bm0K+ z*riJ7Tng3A|7I!*V~+viqws8BFdE0MHdcA|_ZOhw%TtCVNz^F`;pP0OD}#Ef>692{ z+&Pv3V&?H;aB^+Hdr*ZlIfswHky>~o`@+P>b6qT-3fhmZ=mQ6?j7)6Mx5^u-e7{lK zC(&FfmNksXnyRX@y2t*_oi zh&=x4QdvwHfiJm)uFgmBFC;IZgY^PUrJrDxIi$78r~;I8a3*FybQ|3xrjaq*sgn99 z!P8LH)nxK%Z@elXT4WbLNrip{8x>q;EiV!RUZd&~6*1S4miAPBRs_ZsAk=0KOH+Kd z>l$koDY{bQeaVGpEm%~D|FF9E`{eEpKDt;UTaVzfLGJvBXxN6h8t2raKCTn+`+S^e zrm#NBgKZ~&5cM%Y1cfn8hN7+u-=N->uiEnUoHTFw7)F(Gh%4JITUtsSn?w}TEoDGs z;idcg*W~J846|LEU3=F~69|Oz0{gyCPzNG~0kBV9+un$JezIg*v0?Dt=1M|GJO{N3 zP%EeeNjFffMqeA!@D9GxY8RI-==_`-8w^p-_jrHNrP$f8o0iZgns>3%V1`nor7Uqh z?9tnx;+!epnd^Z<3GUmIHOe#qlwN1{HyoR2Pfz!Sp&aOnbM4YNkxF5~BC+43{n@Py zk$;A~_KUHvrxvckWLH(5V!sL{6AzjeJ`t$wVa`|PPIw0jfxIo>4!7f4U;(R$?7r&8 zl_slkMfnF==a^aVl6QWrj)nG@Fke%-#Khg$QL!*rO_qN8xHx-P)q<3TKv2>YSf#^J z_5vl{1vDV^w`W6`CK~+}CGBM?3qslZtcxCF#nBuT`a<+Bk!G(d$I2C{bZW}h5Utyb?&A&R(F)CSe(oa=c zsd_M*?%A8O&9pbQ$9(VB^#$xEx+zo@iW5Sb5KB=(tF3ykpZN5_D2}dk{Xzj3cYiskc2OOka7fF4y zSmbwUiNTDFbQ)+f!`FRLD5{8u{A6eF9vkuddGN9p9{yeCXtC2-qjU^ zTOm&t%c{$0lnlztk7=sWz0GO526~rKIyZipu|`m5{Nj=iOu&qVqX8AX(>(j1?mkAK z<^@4TjTv)6TGNNY+P^IV_=p`aEzonQ>itXs-`0Jb^3NyaH%m_@z zld-dr4hQGqs1Y5H=&_NUXL}_Y>MJ>dW*(N&7!8V=D>tG~@mXgwFZm&;{gB$9> zegW9r1y{qbP^g12$8s%h<^e^{P9PrM zAFGy+uzycp)?YxEPkpH@G;=H&xbM!q;LS!$wT8{0cGceL);D^CJ60&)k)5Ls@%t?t zGDROLg}fVlVQ7G=c7>jR!PL^3%=cG4A#+w(T~lpyDQSz5ai7)Pt;yR;KIDRH0Ht?^ zngcYdERpLy|1b!5N}UhUl=KY6-SA_$L{i}uYJyD(O)&(m6*%#CB-j_&A94(v$PIO< zlB7s-!!R%U3r+uAW4m$iYc_R0IQBI4; zgSNc?vF7fK%B}~~C!m2?%>UO*H^wOK|L;-dc=606Q=_Mu4sr4?%$KuwSwBS7EipF! zoED1vSoFjYVP`J5jzz3$>+t7!7kEO1fI&&WyMPkC1zFSbFHgL;8;@>rxmV`qaXurd z>ThmuSW?qz-5@11)H$yb-ql-9_5zFLWft(CU$B$DD~G(**qddm>>{hV=yRP126j=Z z3abCoDBU3D%aI&0tVqq@>%2rOSA$G#m;dFD6}bE-4q<7B=2ft*2yymn%7K5arEi(C zcG9d0gCMlD-8W+Rr09K%mN;@%>E}FdH0tcTVfdGzWqVc+@G?-~0@E{ED0taK);?^^ zBA^{2LSECyr$aO-&A;}pi3Tfy0n&Ak}T zu#Re(g2}ah<}JhJE3xNhWVnfhd-iD`r|fGy9BHUk`P5?|{J_qWx@bKD?pHbS8yhJ2 zpzOR@1OL!Dv}wQ}@{c#vGfHLDHO?{+_JF423ks+X>Z(i>1Rj3Him;=n)Bg6PlHS9@ z+NB`7X7cp@6&MNOIh;CDD}3kdU%504q}xo$Iu3OojSF1bX;R`)`g1;QiP{ew#*qmE zWtC7T6sSZ6HNLGwQE#W4YTX&X%ohI@XqiqfsKA?MI#B`ENyZO|*VYok<*~+_6(Tnb zZA(w>xu_g4x8h_gJ#yJq@x2$Yv@Vy;=_b#5QS}k=50{E0Q%-9+`*f`J4=&izYiPR; znzP?oP1CslseW`?PKx1%)iTgjUYCZK)N{-TO?jT0`d_FApLJEGLp#sfr8^6-lNor`B`pHtwHAe|xie6O1E(wll2;I;s?j zlcv2|Jw&=xkl2QnFJ7t8P(dTDOsq5a7^1(4OSZOv+QwI;)@PcH}In5w@4nK z&vQ5vl3d&%1wDA&l{0ny(*|k2Fbti_t3rM@d`_Q>ET+Hmv`tWnHGQkVn(lbDh z)+G-5JmiWls(>wFE=A%HxBm#7dyZm0HOU8j8fOI+@jF2Gy%|4Nb+HVKTOGTA)Re?j z!%cy)$(!N5YXb?%J{0c^1%zI8+(wL-zD(sQl%2R6sRC{9NpBa`k3GURBaABJ66~*IkvVCM5mdJz} zSn(%;9vz!%PwC<@gc=c!w`Bcv=GtE*J=)S06{;b_>Pc#i0tB9(e7pJZ-%4hRv}7aY zo1XI)kb2}|o<(2tYkoe#Vj<-^kvTlMmY|EmL&>mDhAmSN-PdDe^kUi2NSx?CBc0M# zg`CY~#ZpihMTK)4#cBkaJRbUq+mvp4v3R4OS`uDlJiwa|$>-5zaX34A&6dJo5Sr1E zj8SB8eXRst>Il=e2%E?xL1Bfc)60b+J=on?(pBT9(Rl};*@VL>n&+@63Unxhl&823 zs1AwL^HFI$HX)$o^1cm&$<`M6&^$$VH;(r9@YWjo2@iTN1;(m1g1!i<_|W3b;A<~j z)-hO^<&BDhQ6Jxyj25U_nLP7R&rSUsXeRbPMZBQjrhgGq!`_c7f>v=7@3jcN#6a|} zQnoH)$ebV##$L``{9lMgVhbTFQM=V)+POF36(P{uXM7PR^Kz^^81#C3XGxxUC0TSP zr|$IaJm8ARZLe5HX+m%9YVSneA!Om4$Y;VY+@IRXSL=rOGEs9?$W&QgBCfe@PLoY` z3_8+&v8e8<{Tb?U%5e`Xm>_UR@GX9|Y)K%duANlvs0}^FiI5g^5O`#ox zLLf0EFhM-v^L^-vaLoM+$aHj?ctysf(OvhXQN^Q!C08%HRS_Iy9?iq#HSSzOOA(!j zRszp)DJb>lKF-`PKJPjhMSNGHY=1Uc0ZIE3_V}3pO8qc**>Mb=0jos;s@Yq<=r{LZ zhv*qoY@0kF;-Ac<7q3Ek!vJQps!_SEG-*G_r>?M}n^7vK?6-Oc|BI3+K~223mt(*r zL=p{N@~-E{QeFyC%ZedYn}hCZl;Jb!^1DTQjCjy zQBpW1dnN#kj;j-v;$3gUtE`BkkWcULFJ@b7^2i!@ajycK+ThnU{mt-@6A>^%ivqMW z(Z-$j6&Peyhu+iK@hG`MM3^tTT z=QmaD50;!TOqy+hNF(7_c10&|*lrAH9F=rx@@}eP&mtM@64UU$dY6~(xnmmVs%uMy zit>mq*?WFI`=YJ0mP|8#-yp%DNWiDqYO$@aU9uY7+{n|^=17_oMK+CX2L0eq*GM8H z)s%EEri}z{CjL4s8VX+{=S12=G>oK*9KZ*b%N1{3vunXym0?oe`k+S-u>rv}I1yb+ zoDY}n=u5y}bz?G{oku!D#$A0r9gi@k8lHGB%j!-+eJSi))0<;z86Kv%n-uX{M;RyJ zfE+K!3Pr!OtY&4@-zC#@#NagdEx313klh1klC3z(*2PHl2Q@;{nv^p%Y~M`GBD=_X zuFIY(qT-~zXlFTj_{3&jKb=^L{e=Wj%5~}z)IxmX!Gr_$r}?v_r4LDvAGe!SgB|H5 zG9@0AQ?4=lB1+m2UJQQ(o2Q!anuhO)Jfqa6T+8J5gce#AGrUROEMuP}`*GQVr)Mv< zx`$UcP)H15jrwRH*VlB69S7I4kVfs@f}Nj=5w2YXu}JRSb6nKXu{aYDy{_2h>q|Q9 z$5^K!85?(fK?|@aWGgC6l-F#id^iSmol4}vfSfVvm$-_b zf1FyH&#DfuWTlvSQ6nUc*LylC2@kfXp@;81#V~a{G2a+t5tXLf)+x6rB&N%@UnJ{ z;W79%#<8jz_{O|eiU)cgWkYvM!MO2Ph944-7zMq0gR5N#v4@YMC(bX>M_pIsj$=}C zGbopsg@vk_0JpLnWw$G44_{O`nT20UeeH@29d3(XotiX+hew!ml(oNsuMvU^+pocG zG`bOCxvt@`{Cw^EMaSyegJsq>$xJD(8pdBS!j)97>#j;h;zO}Q0&gyr6&03DKUsez z-({|Q)1<#hcgf~h{Qaz3ds-%>`hCE}@1mL8;gMjTTt^m7g{<6?`GIA->r_qvD!L9- z(pz5CEgvl{_R=vx!xUFByHmlZTbh9E+Bbe$SbsUmB;;-3Hu31YXOMM4L-tBD9iWsg z9sf01FY!CBjXR+D^I3jl1A3aHkR3fO;ZVUsGLFR-xo|i#vNV zW;A%7oyLKVPO*&o94Evet;CJ=_jh**b{*NuRHKOcVlHT`O`0xB zAYn@g>5U`o?*@w|H>c3zRv|?~^RE(ZAi?PYAvSo#wE5Kyozm@8NjL(E;VLfG&A*bn zrhM&wKkE`tka@4kw5;Tw7+IDr_EzZXCZcB{rxY2WorHgtm&L$NfE-Y>W~{+nQ6tc7 zO&xIbhraQy+{&+oUo%%6U~bY|P|LHR%QUMDuqwAtPuwvHi97x#MbrlFF(7m>q=80O zg%ZTuq16R(d+*@fYm7XKKts=L-PC5?LNydJ_wd5P&Sa(B@W*?-h5VL)hb~6L`Kqj? ziiWGm5sBKCME4qUXUQ_m{%9z~?g#;e_9xC|t8P+mcO5QEjAt@XK;mWQVt2IXe1Tmk zUHXXo$vx>lCbv~uVcUz_-L)xY@zja|33}bk6DDg878(K-9!d)Rc%5a_dtEB?^sihtOLnG?00ADWAQRB3vgK|8n4Cepjfq+8HRLS zV%Ogm$vXz3SJwhszJc9>p-ik=!V5hi(251ZsnzUI&6ud00V{`A`f?iy;K zK%|1HbEUv3H@wTj#GA~zhx1$J6|QhPlYBZLRB5!f%gQyUPLqMLXnnh+YDD%=qYUAD z9;R=v(S0_g6(qj+j%>>OVlOR&LA^sz!}yO?&9fVN13ol4*&ij+q2VIa-6=CqNqXh@ z!4V7JRQiq!l$9^fc&&RW+PqzEvzE~BLso7$jE*_RGj=7`Zvd4u2`}jH30NPqXNA+{ zxQj1Wx4sp3sEU^@&DxPhWW{({BuQE<-lDARkjV8Nmx^Uk`@}yf&Ae z&-G8!wBF!mhdRYH6HTOW+h^a1+#%}z!)GVDZ`t1IQM{ALtpT16`EDl3e^l5!pmEh* zXI5sh6B;u~5E=5yotamU40t7j?MARJ$K2Wx4asqgeQ_-7g>X|q6s0Ks1Xjvql#+}? zA?NaP@b*)?0nQH&agH!cw7}Ef?n6BzkhkIiC(`!N2gR>C{1YZ_Xi(GBw!u3DTXicxosB3y9vB_jI?+!8%VHU>x@94=d&L>uy;6z|1rF4Q& zxJ#@49c4%m5;D`r{hgOIy$YZ8Hqub$6^>iJkmX`hL*;eeL*VeR)-whS)F|(aD=)bx zE%jZc%h%(5*mD-v*#x%j7nto+ zMwr@tLTITU)=w!(eHcGVLH_UpAAjc8#U4y(NixN*R5@$owun&e65nZ0fv+mWsNcAQ zMip|;9T?lDk~L9ps+Q(#5uZY5ws1b8&doo{C9*GpYQ;GPsVp6Hw1f>h3l+KleYW||dN(xfvKq=K_ZMkK&L<+oGB!+Q=lo^&ed zs2T1Yu`>o7mN}gP>Z)E1(vnTde5zcMNVe z_zv~^>{U~#U7qH+%o@vNY$7TUnY<#V4Gghy&M#>B9kxMpaau@T_c_2%Tp`?Sg^}W| z)+fgchk8%94=nbhp(S=G0fwYju-CR(KeDc9vzsm7$Nn6DPCQA`xsZW3CNz1vhCk>R zFjV(6Y{Dpy@_Ey4luLk?Whcyi#%(0gEvd3_tJB)TVtQhGg}t84?>Q^5xpFB%9Q9%Y zbYhgKyvtI@63#=ht>;PSFzStWpF6~@1&so)*#kNZjWK`8Th~;aH%(*Vq|W5s;vYmn zW_J{Qv%LfK$f=bM8aFYPf;@TwF722#54yCkHD@TiM4{(9*0up6X48A%^%`7-?e9|E z4Gsm$4g16EjU;@-#@txOoIJ!v*Q2=wskU1*!H2M9>M*Y-2h-8L`Gsy7;hpW}Q{1*T z^$vru1mRO4b{-oFbL*9bpQnNO+xC9iD;CYVl&&X`djzh9)|qTPKdKw}Ts?i(%Wm4B z(ZwGN!`bkcU|wQWlBH6X7_6L06f=>uKm%H~Tr!~X*>@G{j1k(U`QpZimpQ$AST&~Z zI{40xeIp*zAgW9mvS=Ts#`j7wN*-0?B;O4&{b*!pKHBIbs%FD`NG~05vmVFFutN#^ z3EMpdqW*;)%(x|AmPmbWhgUnoS;6Mo!n>@~rNSD@U0RWdD{Bf*cIovl=0O(L^`@eS ziGt#vEEqu%STJ-B-0IWL^X0n-+_q(J0^G~2H!CVi*cSU|Gq z{tNDQ)s2-}mxn;AXay)lyvDF)gf9X-#ZE#u+l$x3fkDAkh{Kde^6}b_5UR1@n^E8Q zeF6c_fs%)yLMu-+Hu(t1B2FDD#p$jAL~5=arPfebN%iA=wuBPNvDk40smaB|&>e3m zUrJ6384-K@W0Wkt29uHEbO|ONdBa%46D499EvGDSa6?dUh9d)T&SHdP-``NWl_2TH zG2%U0x)HAjFUYO|Kz4%mLsdJOR9(c;K<5=~Y#h7f1ngS}H#U|&40AaI;fDD7H3}Ac zfh&(S(H&cLAi0fwo#C%x!y#?l^l)(K4gUHDU>;2tv*}3}V84u-%$m>ii(tRl5LF&@YMOHU zd^V$xXRL}YQ~|@NIZp%OYOj7QqT8U>fyt*7YGEf*@F)O-KAQDU{ z$0)38m2%RQa=<95jg)9rcvvO3=Tw@&+=BG82MdSjp_=}-0;kX@A&O}7hk1ymR|Zy`BKts zmqdu1DcN92?ql-Pk}e8#n&KTQtt-j>(A}aBrpo3{noLO+Cxgvyaj6Rz_+8u0L{mT* z=cDW+ddZ2ghB8CHH7s<6_*i4_$-7%7y_vR)rhEvut9%4hITfFTB-JE_fh zM!_&-CvqqkqG36)Dm!&M&L5K#Xg7zHBH<8{E&gpTqfpIg`zQ_-{1q#p>dGc!6&coN zd39UNeRH%=uwSts4I389UcJafZJV-4)Y{fexDCl%QN&9k0HerlDKF(>86iE;YY}W$+>xsF?9=`dhX`XLs5sdIVHYFXJ6b`=@6Y^ha@J-$%AGj|Yk- z`X%TvzV@8nuBxrsPJ z^80!F@q(ls+@&47Nnd6*Gv0ohx3#-hR-5CO*Hu4ISxYj>8{5E!U`at5!kHQy>!ARo zDJe(oKsGknG&VN4B*M8tQSBw(SugJhy-02qcg zfSV#9M?4@$Js=jYuYY9Zr%oUu2_OJ{3f%&rYy_YZJ`p2u@7Ur`I}U7oin}@?ZdURaO=b z%-l={*uDvw&@89}h;R)MHlcY!67?AHZ5D$7m<7apG!_gMtH31o<>$W_uMw0h2v;Cr z7F@fYb8P#Kb8vVY_z=`%8#n(~9jJmUVEqTJ`cWN#@-HC>RNq+t)492`-U}0W^+O6W zJx$~WFW`+(-;LIXYy$&aK0(>j?E()v7EuKf zFbn!qdSY`8>K4G&$PsMouWa(Ad;FGMaz#r@ev>U(a z>W=mR?*}G7wti;22S)%$fCgU@;4OewaMr(EZ$>~J5paG8e1G>YKkEOF0Cx)jTf>EB z0MQJ*Qv9j-wgK1t4$Y(Afx3ieF!5f&=MK1fx!IvUF!$6HxU}W{hWc^tt=^Z)JeTT- z@n`&Ql@|iuhriuF1Y>Y^Xylzti6-d#=(>Hop|TRV-O;W8N}{s2hx&JYU&~hyj9*p8 ztG!?XFE0*rAm5$o(1)7Mgn%u6Vs@hgGiLwq`X7GjFZqd|ya9jpx8BH4f1KZr4b5K% zr5^`BKW%|-2HNqxAi1I!z`pnZ)3FE4wIBO(y3@J>RdCG!-OKM)Y6LJogrK(W<;L`k z^>&T5w(mc|Ii`KrgfOfOOPlZXa-hTYq zd9H71FsGk9Hgo)|uQ;@)c6ta!)6DdekFMA%pLUaGp~Cfc-8-$(#_7!Mc9p}$s7NH z`SCOnAaqaQJpY6p(qR}YI22vAmP1pqZMSn7!2As z&v>(Q!$Qfbqe6~bB}g;(_p)74Sn_hvWl|oy)KW|zp61aVkR$WbP3+0-w+b0wmQ5tY zpmaMAR3wQW`VJ$uGF&c_j6IUo-eOHV6$^fm3{xj+Q!V+@UM@qB0xkaJ3ctXfBX9Jp zp}p1@XyTOi+FtH#;7&BM=7YT|JDy(X{}>!VRlnzfsi zh{K#t$cC){#Jp`$O0(pLHJju6SXKVT0DSa1gqKD*)54Tp*8!n58Xs9sTbooB_bY94 za$)_!IB=FrT6vOwAUMbf8(77Z;OsKY!6M$J|vEHsc>g=4m!DG0xTWI2E`A`co*?$g} zzN8-g)-gQXTI+2qo;a!>oS^Ac|W2UHl_ zrtLsc9J>Xi!T!CsSiH()Z|1{pS%wB@x8wF{+NWKXQgMW!vsgN@+w z%UXpHgrWdEiZY6cgr0_!e5uF<^vEu&J@sSgNRHI!U=7v!g{7%aca;9`7H&BN&^uik znKQ&ifTsEeMn(z=y?9AD#6pX*5V(4^oDUakJf66e@N^aj0($i3XLL|DZ@|Y?GVF)y__pO&jTJ8)0~VFtinad!2&TC{O)xra(%ktuVHM1pION_oWPSP6cHbEe{<2Goq_& ziK6`kE0qyiqYiLkznNfLeqdbD15+E05MdEhdN=^y2MrFuv0M1s?cZfNyY+^{9T)c3r)ez+Fnqf7o>nt1P5+28 zD90t>8R>C$!~9MW4+t?M5WCj_k1?hS>Lc1y6z#BDufuZnLtnh~IBzCW%!KsMd}KX4 zyCJW2qP^{^Gy{LXNsR=r;tUH}ehN1(Kbc{{OIN9f_EzI>^UU^2)44P5HJ$haf0r>+ z((x&?T<1OH?fcfId*J29FV(rxb;zT9vV^s!#Pl)r>EULKy(5Kt$Sd&`I+g|cQ$S74 zpB0W=Av@DyPbqYh^1j45=kTL@ zz7wZ_T-Gy$pabN?OZ~$`BH?VP?XaP_z;hsikyV4MAi*Ilj76%UFVI1FJpt6jH$57T z?QFGt=>jpdOS%^vk(+P*DY;D(=XmZs#l@J@-kmTCID_(S0lU7V1$^u^{U!|kZqh--@HEMIJ%Qq6^_~ww;{3Ar; zAtpGKYF;gA-;faFS2GmpMlNP*NKK<&_MT_r?+vF=wZFhxI5N=lI!?dklZIzVPlfjo zsH~D76px%WlwK0>BmbseSVY!?+eL2eOktP)sw`N7>nv1dPKOQ{}p!oK(*lpXB`<~9JPM&XAq|K}(g(K*u6N{{M9!Zl&&DSUU|NOGpU zdOY>oczW`X78uEU-)-x4fjOPtQg*pG`J%PDIfa{@cFKodR-F7H45_yg=J48R#^l8F z2^UL23M;qJb-Q@wbc#Cr?*36u4M_CdKeiYZjDLk&^EVuDK!mt%u!JMM4uXcXr@v?; zC}DHW_$?VNB-VatO5%;InQ9Q!A)-+%?;Gl%WgP}4yNqR@y2<~xYQxXP{4i;$IPjB?b*GUOj9t92`k9MsGQcJH#|qpPHnvkL)1 zD!Jt?v~VrL-Op1d?V2rN6WNZlvtVY!m6kQ$K?_~_IeNbHwtgAQxXpzGQRx|@?BE)y z*?E{p-r_p%o=j)M5t6T>T5<7ldgRg3T(`fF(uXK_EolR0 zte0{xcvkttMaQ8YcNRAJ$VtQy|5k>~_F4=YS7*aS_ji3Enj+_B*yjDX;wsTI4nIVC zqmwXRocW5}xFd7);~H8^_E@<#EpB&uM&`swmh_p+uhZos=TF7O@@{t~k+DY}Z+Id< zx$L2{#2-8kW1N+=Zzu}NudvQ96RkPQkK#i47_)-`iz-PeV()TUdx7u69;^uSwjb6O%EkmKUjHPz(o>K3AZZ z3X=b3DB_nEoVg6F&0w#M+=cNS!bw~D7beOzgcKhN>E{q7LT^83v&Y6p<#M*o7fg0I zNlsPts-NhKdBaq5Ia|-L#qD-_e8VWu;+H+uMbv**O)O5<^cGH$?=)hrx2c5G?Y#bb zLc3wg_h(cv)jcJ8{_++*yjdniJ%&t(zDr|o1fsj0stdz(lb5j~nb=+Wl!s_w^46zy z5tq#HnQ?O|b|fhhz2r7r3KL}n4}Y-k-?SGen~=Nf2QcSxTlId@YW-NZ5RTI2eN}}K z>*%V;s&R9?4RX}-d-*)`!K$+I)R=D)P#3O8Bg{>eFxIKrB$GkcOYMmYWDj8h zv`NapJQ=GX;@D>Hg3xSjXD_gd$tcyHA_r`o3k#K##WNX`wz!!~XDZF;MOP}8x)-E+U6uiHWpV-r;GTgJ2kgdGd3F6#nPBMo!=Pq!P z_Fl@ZV+_LJ&$21d(M}U9u6aD6E|`7dGO5G#J;o>&7Ou?j5mFOuRm^g^SbUASdt!x_ zuTP@ir=lVV?2}ur(vmiRr|t)JKDxZXk!~h=l5VU@896c~t z6r)B7S(=91R2U5XDqj;Eei>BKS+8BE-l%l57TL z_ivt27jr3G8_3wTn`0f4BruCb)1$=$)<{*1;Kb8kl)jBEDbyJ!=;{VO0A~Yxq{n-P zrFsOlspa;KwA+6}bT1;YgPKSB7of};H3IoK0LdB8aGB^wLI0HhIA7kcMO=O%sH+TG{&kjdbfke~ z(GV=l%fvC6EACXDt->$A1odyb_`3K)& z8+I%Eipqq_+t&-^#}MQ{l1IzA*%y=OdI&zbiigqlF@REy9}V?w2IYFq!2E=kseW4O z$i&7PebO~%bVZS3wjw0gb+g;}sQytqyv*Ug5Ttqn3 z)iNmtMxBpsf~N}I;U3*aFdL3C`vBZI|MP*caEiq z0erF@u~@g9wirQ*hkxbXr?h3V;pRo0_AA`HM#B{Q-B7Il=%v5!#!wlO(=5C{(f%tf zei4eE8u@(hUhXHMiI-dhIGKYYVex^OB|G~CPS;1e?d~cev(jnWXtXIn7X`m~# zpLw_oJCqfniwQ=BAP7^s%hx@1x_A;_Xfn6D z_b%MC`FKhatJQ%RlIZT%o*gnODh=PAw1Vj2Qy6zcST{$!E4;-SXO>}N1DZIB+1(35 zTA)`YMjT*D>137-6~;*c^OrSk7&4&{7DPMX+g)^#LcR%jH(P=pA?gPyJ^@_f2D&q3HDr_TcMU+D9Qe>A)DhPwl?s(*pH!1c~AcN*Ux zn>)S<cyu%bn+3?kVsO8?7j*ghjEgw!@?$uz4LjX0QA{-@MuLW?@pZ|W2a zmoc(`C1y0KZIoc?(1qx`V_TX7E30#C{Pk7Z5T?sQF4Lo&RXCVHBiSc04{^W3I}wVk zH&4R{_neWOp2yrh6i;KF8+#{>anO%S@YBVX11}?0?oVAS6Q7ewa-r9G{q$2RC zFOPa3_FumeNe{p1JFV}(n=L-8K5r;=6w=$reUP)+$r3-mY;QG7M0R<3Fw;wY?RsReYyt z{)R3fRi~W&HOg8K+oGJsyTJTfd$k*7Qz#h9%^6PnYP{TFrjk6oraboZo)F1iAdu?2 z-FDVswr7z4r0Bfy!w|DUU{zPSQRh#8=l2+eX!}#%Z)ae6h*Zs%K+RlL4-IS=SaM)(NR&HDjLSKIJb~UR@D?EE@+~>Pa(p>QtUn!2`?oR zu~zc%s1RaH>gAEQN}MmQY9aFewvsp`e;EPZm8sdN-`w)+Z58jkpanZkMln%c!vePh zb{<~gu8n??e(Yc}Cc0fT@Ra_FrPP(do0KWzt-_hk22F&SkK_hBgX_qndzt@+JgvtW z0)pa~@aGzc$v)+cByLH+yosF-Qqef7xZphz?DwaZY-+%S z?4>vZ5v2qPBg+O7sn>W!IZVb%Vg?juVpN|ZD}B^hL1jDAtBmjRkW6-@mfT&rqW(^o z6q@ab-Z7-q9#r#SfV1l}$+gy6O<0qe6xsmIQ+kp&5utN4s>kWk>ceDeG7j4#FCsp9 zhX_v{>QnI3cOuFi*(r%76I<9}jT1<-qhG>Zhu`ENOp6uj4MiQG5Y0nWKi?9^=Yo{YlmlLXwtd&>Z6cBeV!4Nwvk_jb z7312aiUgu0q@Yy?FCMCb{T|M^KOPv&-zQNnOvT%%`PJ&Mm(Q$AI?RqoJnwY#p+=1E zh~RXrR3eXz6Y$Kt$;Cj68FO4-^3P~sN)bBtZ_vC}nj=Ek^uDRld7>V6}LdntPtR^vkT?<3dm<^9N zt+!{_ONVW{Uza-VlA?S;tRv(Q+$bFIT%W>;>93DWO=kP3T}DP_F+|M1K7F|hTRX1M zB`VmWs()4VL!h8KqdI`VD^*mFnLg{briL0uC0qx&LqByfUBf6ui?L%S=OJ1izEuo6 zm8|Bj-I(W(pN*`c_v*kRv&oI5WUlBs6#d+sjmJrDSNg6@j3r|?gC=#LX`OU`(}24a z_{7`8p)E)gIX+=RE7}>w=6^V$G6Zwl)Kx=Djq>^^+8;3^cUgETrpHEDg<_6_`3SpH zAlW_8H0;)Z8)Qu&t1uEJiGDP&*Ka6%vL3bT<{8-MpxYAOk&)@pKhXIijJ2a1Jq*8w?=$o%aZ63d zkil(9R{GeLde8|1*!_VRZ!xjR6W)RDpFffoua@ML1~ZE5#Py0V>aICXS*S$|(OPkl zk8)eHzqq=7ANMFi-ax8xe0obycP<&IE_hcN8kxX0@9a&`ylhom-m>at>lPxgtS`yC zBtnZb)ypTYiA^EGbihZZwG5A!sdRkwL*(wPgL`hcCe~FFletV`u}8*I3O7HGDCMax zM-9!u$9OgL%<0p;9wl=ZnYRkSRGp!@ezbd=MjNSKsSQ3pxN>Rlce%uemA0s)8C&dP zZ5P0TZ;Mfrat%ODW&T4efWwF6>|8U_NJB!e3s36#D`z;7Xjm>)jI6WJ-pKRO#NQwB zUfJ*bPaP!?^2>wAgDSow1q)=NfD;nk(-rw!mHR21BXrq~DLGnS^@TNKJ)64L&foW3 zhB7NWQ!er}N?_cH8>P$-o)TNirmA&4ztMBuZUI^Hi6YzZk{shW^*uJXIm*}fM#Jb) z4y^Rk1z5;W9%2_Q^iiMQj$%q`s(t~Vy;gza&)~O!B>aAECT!X!tmf=CdFoM08Fi>? zHn;{bhxU0`x)Yxn?g`Q{HELJ9{GB79*0dhiczX~dqXB&7tylFbnGvx_!{U&lGH>R=ccQ3YR}h1-Jy4K(YqQEX-sxmh(d{URBYxag z3XI$4+u^`f1=dG7XbBy97`SJniey~45?@i{ZB|dwsL?B^XcSwQFDP`pXA-RqkWpBHRw3E@FC3APi_vyS&LdHx>mt)8o>( z^=jy$b842zPO>J)hNDyB9@VA#JCu6Ptk+yEm%U9;?bsWTS-PD{g(kdscbpd@Bq(Zw z`t!POkkST#WW7+V(H`R-S`NJ^FaOoLjE`Meu!dQ!^CW3MdBf~HYVW6RgGO{+*grUD zu@~v@d#9;4mB_3w9X;D=d&czkF2;|cd_2c%9pf!xhDVG$YfvHGPmXn##zS|SlI-RL zqG~nM&ILCFy1kAclCAgmaN14(nX5h-KTdzXPPy&AW9n8+crMC^Fu8Sq2kUK#^1ZbV zqUB5!Ub9aDJMTHy*))kRB4ET_Rv%zH6Sp%b&#sxVfPq)PV$a@ZQx5Mlm-QCVHDdJe z|3pBSI8%jmA5lE|eiSD-bW&a^EH0WFAINzNeTCup+H>-WU!MqCrES}}o!j9>vo+P& zg*SwbGma&f_qNvP-6)f+l$|QSG&>{{pwTfuZr67YWNIYnpDi0sz#X;<@-rIquie?H zXX$RT(SVYoiEH*ynyNNx9~ok}WwRf1%&S2>Ju}VcBfJJW6Mg{wYR&6}E_IK=8eYNj zy4ppeE^gy1NnG7RxAzdO`nlX*R9rVREgF2WWD(q1^J zviYU5A<8{l@j;zCqC76(cSo#CH@*}iuP-dJHfrDiK2Ym+TaHbyI#@+jYj_bSA6YEx z{#Nhp_w5l$&Y8PN_nZ*v#&NWPO&wnyMknard1~k~?SY7}b0YM8bWAah?8K{_{aT{~ zAf~Zxt4k#r^R93xBfT>{VceH=C3n*+nvYic$XNLOnR)85KkY%v20M*5p|(P4S_x;{ zk8n|4i7L^`K`B!NZ5-ir2E6Gff#@vF+YmU^m4F@F%FST=JeI^OHld-iee($d3|BN) zxWUf4+T)$=@ly%g4B?&OdK!xD`fjrxWg<-@I%^1<9?SeE_$_hi;CSQa?)((09m|ei z@IYA?ww!q<;4jvI4a1r}X9oXXh509P$-g`!PM_*jt4z}oVorst)_H7A#aUrX(b*hr zv9gnHqsYyTjdA*~sT%JE_-pWN4)tNZdOTgc(|Qamn0vDlKHa-klV)jd?4F?a>}Alb zE6uzNML<^4(u2nKu~!~?@0zz!&hFE`?J$Qd%cmAxHHJEBKS?g#=s0U-(bX>7-RPq35Z@#_o>= zJ`KrBr|V|LX!A&tY~(X|`omEkO!$Bf$h5a5YrkaCpRPb)RVFg|$GBbJqB$+eWzZ{I zZlnQA-dU-%YatdoQX4#V(@RSWDs>u*MT~TA+eUmL!=ozQ9L)e|JkEdJ-j_D<-OZ-y@KOEMS1 zlZ<_br**lgBsZrzLP)&?jKh|8QXtaRMGi&OX2*Yzza==>Y8%z`th&8Vs6K7W!I>bH zv&UeIW0=rAW&N8t9q6z4?hmq56yl9+WTw0!Ak^6&dbT#cjr9CBzqE{k6Ad~Z;{7nf zWbW`j;pl%5<~k0w{~ImzkN+XGH?o4};rS0A#7M}<#=!cY6B8jP6Fc*NPXCh@Vq{=u zV)%b8wl{&PBwwMk$w-B}FiS|gyO*&@Kuy6i48bzGNJyu#ENn@Tkl`%=|5j4^9kg&) zaN|AWIs1alNFxz*{s_PzSpU?<5*r3;6JGy_u$5!}P&$=)mkaKgc%2?E&J2`Jdv z>B&io@IkKu-+yDqEdXwgp?&#$j01EbtTH~t@;MTX(2z2Xk|M`D-A;EnA-?V`O=|xFoOEAFAKpMih zeE}Fz=h+VO9Nc}#(C>H_XS>keQ>`woAsiZ7yx^Z_o5=Z;MR4^#q_6C}>iIB3P}dV@ z(2lRNi5Kn}qra#H1f3Yf#Tihqqux6CJtJT+Upd_9YkTch@Sz_9-ap~0i4+o^?2!rC zDd>DDht}b$iGSS3il83&*>D(e3HxYihA5^$0NfybxdPg?J4a7l*?s=m{!{U=pFY_J za)1kQWCQ*P*4I0N()g+pZcKo?Bgn_w=i=QCWKuW;APBGrpst4lje5&Fk2kA-(to|X z*Cosapj?Yz-2vMCf4)8@FBSC&F_-!;{>9p_)1+4=WECajujog9p2sH!c!2og&7E$c z9Y8!h-aG+9@dSQ9x}uZF_wE>*Ka#3}T7v+dO@G%9j#7Wu%kNfz#~ zI;_E4{FrPzSX*E`KhMvs(ofR;PucB`>bE`d&rTTX7B230o96fH55JwXctr5(4p4ld zYcM}u0QjXNT>cM^7382K63hY8q zUto*BG^fIz<%gZkJ_>k(sg)`!1O{0CT*zYo6-!9Q4Na^cBweb>MCjvbu8 zcG3T(001^1(EAdnE`Vrowr_M6`sVQzFR`l#6%PXq?ES6C77&dB9n4<}z~}q`sy3uc z@2%5}KK2tKGp7>@+EjH_n^w+$3&{(YlLwLbwt0J>NHT@t(({@Y$Na2IDs zPuz2Y3V!%U{nyz+FmUgnz;qaAhJ1|(U0sO}(;COvl-9qiws>7K;%o(=p~&`#I|Ak@)}SNP|g)C*?oNJBxr-w}M;b zFb8(!(T2jx58vjkU{fC)?VY7IUzj0%s*@p)BwSeUPhG|s!VmA0wBpBQ?9b+7F1JP3 zdWJVC1~0~D*M9v81uNFOgL(voDLbCx@is;|13}hTT!K2a`MNhV$$T^da}g3UDXaV9A3qgaFHr@F<>Y{K?spFH^aY*e4cOGcsFC8S*w0=63N5qDDJXnz znJPu#JZh>D;X<@J7fnZV`>ckV1lnDCpaQA^;bizHBca*N@#%bbIKyxKIgP_*AG&G^ z9mxgP%v7nae0^NT(uaOdvNk%2#HC3Z*Cj?m|oo5VK4m<)Zw71Y0vc32(od_M3N0Q_NqsJ;M55jGaTXFkH|WuWj45ZQHhO z+qUss+qP}nwr%B2rM^X~vdHrMggMjGO_G=XWGJP{TcPvKf@0K(F)|!VS;V75Y8`9$ z8dTOTv$=2kJ3a^&15U>!rnqBBsPFzldzyhr?*dJT!QoRuFqi})thU3oqv1?Yx~Mj%UgBDku=W13ohkyOHJ#Im_ky%r8tJKG6F z@!jxpLg)Bd1;!lV^dV3vz!J6u98I{K{Xz__SLx0{&A1g#a?Ih9`T%D038NxxYq@)1 zB1I}<86`R_+N(?*t{jiIGWQicjyOoo1>NLQ9gUYy zW$5o$f<#p_H#f?SO^S*Q50<#})^<8;Lov!qweptc_bEUh>*!c~X{`1UDVj1;wR7M3 zR2_*jKDKojD>^g@2fm5P0pan}Gcq#a6_?|spm5X#%2VXTwaH6a_TPTv1Hv;yivOT^ zN`mzh{AFXI67mvI8QS|nW)}#R{|T9Fx6lOUk#$#FCw;QSXyiB)7lSI#j9!NBF-yYq)+L)=#w}j5PD+WTa;8T*zoN@xD%%JEBPh zXq=KM@2G58{(pxnd*!5dr%4+_&At$C%a00kPrI>jSG{+}64?F^KW?~^n>-Q5x%H<2 zBbjUYw~yoxB=fVxCf5}F5QopdSSK5A5nXOOfVEw8bHljs=r_~ODM<+9SSS0y zhk9((?_VFO(QMjL!3>I{a6y{5S^2PEAnA`~+b~={S8)AdQb)G89zKN^sB`c{VkaUr zyddlva>Fx^X`aQ@w4yCtQ{J!VJ-R|om`?8*rsfmeRR}>gj;_fj=9q)CfKs3fJyzdd zN2E3mG594Miw-hRgZ(M~F-EJJiboQu0}u<^Wd@>dRIse0kSxWDobih;+SDlQjnS)g zue^({>!%5xW0sB-xBn^xf$tchi_*DFD@vmj4%jEihB#mJ7H!`l4(YpYn(M(!C~a0V zXKbLr0k3;ujDCN32fCfGt!uy+U(@v2H!~k2FAI0ZDl^inU%al9NoT>p+eBA?Cc6xN zYKGQNoJtZ?oIZyk4o2Hg%AqI2h2?re4r$$J)lpt~p}4jIV?Zk75yNRXC|-QBjLb}`z*R~a`WZ3GLz!esPwC=*0RU) zfS6ywHxuH`j}qAs+e^p{7uGBZV>C$=50Xwu%a@ujE(6_B!fR6O>aYX4x9mWkKHt8M zJzuTLnzpH5NOKP;i#S+pt1d)#k51Mn4a7J}<@5dOy0@ zIe}mCMdU8+knm6(wJ<$O!g;Ro5rh;43XUK7A)HwHSM>U`@=cd9`xW~q1s_~EkSX4r zHyM{$3lv|a2bS-)GTL@xs~VPNevYEiKZKRti!Om;Qr23b2;GXmfvulyk3Z+2Z!-jk zZ284)D41ujgqyA&<1K72U|0Dv%pN&w|8ZE?{x>@~E%BQ89@Zp0x0SL&3VjY3GUaWQ z_#)gG_MN6&QY~h)QaqL!v`917!cHpVf4Z}*cBs*ANgp$l z{)#O;Qcc997NRZ3S@Y6i={!+cyB!6Ox7Wuv0N*G|5}WF+U6#cuQzgezJm`pdPZn`^ zExq8sN?{cDRx|f^UPQveo!Hd6P8{hKQ~orsypoo+ zOA0J_=8+$ZxilZ4#p>oz?A`hFA7IkTRd{>VoOv{sxKepkIH4%^zdHBY)5R5&&<6>4 z%C?y&MPA!TjYcs$&^^HVqIMRZ>~!R7y{8l_Np#$TXc~j6orJ?o-+;EwP>|yoQpev@X2k?<2jVPVdM$WWOJilk8I+s>`f3yD9OxOQzn9WqH_LZ|* zhAt?_-U1%xK_#`>qqFFPMmdy-!OSBPFC&!nYE&8drqw!zAOhH`$jWANAs0=fqZzX6 z&5cG@>)4DDk0w&aK_|u2$E1ZbSDCoHN&%_bnQu_jmxhZ4t;JDvCbdRDGqXtv`vgVk z`Q$&!i`lUk_oQ@rZ_x_VYxBt})XuFk4boe4Wr)WH74Q99o?^6)GU#P}6E>H2azWTK zp&Pna9-K{H!dcPI-D&`_B3BCTx7DKG|4JROaq0NanWN6_S{#jnl4lMV{m&A(y|_`Z zkHhXGtFULM@hS|%ZCN}uZbNb8D1L+JSz4OEXpXrQ@|+9o8{+}_&QtgsXo__IRdx~8 zmdzR;&RM+d;47>}*g>~}d1A*0D`J1LsZIPzJvM(6ri1mP0ST;U6mXrtqx!~_bT#+d zg}veDcq&mUhU5!}(mVccg3ejd*Vm#+gk5;WZDbBaa&7q@g-|3$=`NjglHP2CHigk0 ziKlHKJn>7kn$zou_Ht!1)1Uz-sv-_7^EV^u2AIaLi~WGb;`98~gHLoLRu1|MDs8&P zXlL8BSeB!2Hw=PP98WB$ESHUTv&w2+2OXj8`&jE5^`Bk>a5CV+ZCUU5)(MFv_!eT@hn@f+5&MI+s)|0yzmmr5420KG zb;`(Bk$`8do- z)bzF-3;8{^PK#_Vrgd{-+hcets1Z8eyQ`uL)znm`L$N`lW$PjQXJ`ANp*QK|@M{n7 z$%U%wV2Hi6B?zIk=4X%J1TYs|zFfDy{{_g+nM88w9(szp1J3)E+icu}rR0_Y_^cZx zo8&t$B&xO`AG$bkqC`$r08-U8bQM&57|!EGwk}JL=(EmTd|HlMP}a5OeW*JZw~E!V z;U`Xr;mBlUPLWsQ=VgsGMh;-Q2v;=_EP4D&YM7T5%%Ej}=h3~y# zEo0ce_`n8A&8xPI_zE?t=CE_}&o6M_hzky~r)b7lgQhKD50K+-;6vj?`S)6_lrgf< z9n`}&**6pN-qY_z)q{OD*rW9HK#Y~M5$)7T&A;n2x=(M^>Ln)DbwmvWx^38Pb`}g= zVzva;6Z3=6;`}+WqvuIQr~MupK)TY3{(%fh%0Fy&7?HU-_w;n>GURjaYaYf-*#%&o zz6+k>>P5Bqk$DG_phsG=Wd0=+P7}(#?Ov;)TvRPQnaE1{LLTGJ0ff=aIgj%KJy>sT z_<}Z$hv@;VIC)9|hat$}-EMZ5L^(xhU4s!UBCPO^Cn$`a)$872hRL^d;xDD-m6ML*tz)j zwct$Xzb>;=X3r__Jmig@bJERG-6SB?zh zNf;-arJQ@L!WzDNXB>b91xQ52kTi{L>KSq{3eiIO+o4(2kX6uXm3f@tt`@oPF}Q!2 z2Vm3~q%EJ+P9=pJseFnhmqM2LJZt2lCCoqTE%=b!yEYl5%UFhH*6%ei%t0SkEcvlL z;hqE>WNadF-Mo4uV#)5hbs;f661ut@I?L5Z@L>G7_OoR3p-OTTJ7~%C$*fA`iz1-& z`R#}Jo~RFTMpkW>G~?OGq>6fes+{mn8s&q&Bw05WDELD2uhO>xirBx>Bl-AmDab>u zne{tHc~(9ZUQYxLF2MfcI@LpVdfr8jW7sCST+>)7iynf?mjlGXtw=Oq^|=DZxag(; zH%PP;%XnXonAa?qO#j-BR%-cVp4}N2@P4zk=GV+3;U`?a&~2&r-j!#yD^IIwf_I zr&ZTml&mm+xsB#+%; zoimUhay{f-3IriZwL1suR5Lw!LKuw?vH(nL!!7Qgfqy}%5{`j2FS$W)xuw75D_cRZ zz*oB8Nxp$d_l%SB+uW`6@N^2F3N`NWDNl)a-?Ab@nq?RaC*0g|HL5(_F*4lDs6~=@ z{=aEoJINaP$XM1`>|IZ3{b|((NzCP0_;t<}C2w}ha$?tAK2ckny7=AJux`9WKDM_@ zI?A!JV;8^T$4B*Ppdd@Uk@E85Fvij^DS0g&L#LrZjHH;t#kN=Z_0I?!S0XY5f+Oj7 zux@@o$2t;KLUzqb5!OlJrK)~PcUGj=&L7Mqxy*nOxQ?Bk;dS*=$>9FiJld1=Rl76S zZAa6aR|6A+$0?hn#;JNbw#h>s*ZQ5h*%2hH^ap|$-D1&3GEq?IU@@*%cKX~aRyNi)=uR42kOKb!7_K&=8pBKdswvn8wvVn_AyPhb-Py>jYA)~c3 z^ac+vO0uX@j9Zh2NGhP1+n&s;_hXx}vw{BV_pKn7z;FX-e4I&Eq8?q4@ke^v{S#my+W$xv4T zLogxY_Ir^BbhC#O2?{e2I$2#j=edEyTCqCG8G7om*oXRv7Ha0~)3|cm!I^mYo|AE? zUFI^?j%V$7LX3#B4S@9WQ zwIq|4b~wsf_VVf@WK&OYCZG}L7cB~1{^ps9Um9=KXFEFF`X9ZPc$%c^4!PLKmZ|9+ zpHBLw4TR%XNc9_iOO;R=1;-YI(c-_n762m$$m9{IH2qk&~= zg1 zoFchILL9p0X-R&hy){l_rBd}_ahyY%7f_K|sGJo*plw4Rl;Y{QqsG(57V@5k4dW#^<0av~qzgwQui;)(O%Chr@E z-)2FQNMQ={@)uI8<_ypg`t(_R4Ux~^8B5LP8zC4`!{?`$B=+YufdggCN?29h;R0sH zTH+OS8SOg^ttfE$V>LBGCUPUM!$<4fQQRmulD=NAP)n#QzAe$Cx+SB-+jhD#bc*wb zmzv-hYN5`cV5 z%I2J``DK41U}uGoU2VuMsbfu15#`&sNHtn;rqJvT&?y((aL|1dXblPEaA}2`-bC`KLt9+ zE!Ap9a2uxs4gqG=8-vd=2b)+fRM6PSk*s`RgMP!=ln!`(l5RwYJi?`ko8y7fly`QJ zgWYiYLAIA8lS6><(LCq=%*Ei=sovP*E|ntM8NIAa9s@>zH1?sxmsyKe3P%Ys#|aMH zaCi}_v@FkL_BwWj3At~e1E;jQs&u-X31ax70)qr(cE6`fmG8qB{ciHEF!H*+;vxh@eOnOKVTHvIiA4cdH_ zyS3+EM8XZtOdWB>fH**vsP*+vOYDF_Mr3~0FgdbHUMaRLGocxPpZ=t(QG4x0Nb$L( zUk5Y`v{&NHL(XbUOd?w061tO5qur|w!=!LNeaGbK(yMqtz=Q`%i9e16{&?Rr;Njl)ZUhK=wgNdN_1Y_u5H1QRNDm}bVU$(cWeR4eVuPtf%E$gTVG0G3ARfwBL?WT+(`&rMHnX2{}HqU z7j9jqY^%WZV0CGiq7w<>^WN%yF85&}-W|^RA3fAQPcIV%Mvy3r9b4puziQ_DOtw)D zUqq!uu9CG8eX`BNpi&LNEVYO3(W=97(@V_ROwOo`H*A&<_yuEr^gPIPC6h8Ull zVI~#9DH7~+l2B_M6eaE$eB^~pwo7;DJ~`VspPvv7EE14lralV|w;T3oBUyUO)6>FUb8;tXCdEQmuc`Rpkf$=;>P5)dOYfM*2H+sz5Acz$z)Ii`k0tjvp~n?C6{yt z46AjEB$eY9>3V4l@q&-IAKyi|6g3Xp+**3H1r{%l@g^f1{G@ zSCzAvaFqR97v9G`kGqMjX4W>ly6g85NLT4;Z`+(oa-BTCDhQced*x-BIvCLEk8_ms z&!*%KBGuPq7POrR7PxkWg;r&`ATsXr!7}O&@xoVL57+u*CZE#mlC%25wyj z{&P6N$%*D(#@&5uEa7869%L5Pj>dONCut=G^{qJw1(xiuvIWkz3P{Pp%HE zA*}$jWN+l*jMEl0;Q?AW9r3=nhRo}gEFGmo#`s@q_}E6P)Xs+ zaK>jJ6VEtN0G>?4A0}5;hvte+bE~j=Q7-%6P8Rpt{1@sbx}L6CcDTH>8?YY^v*&+9 ze&Tx!Mhh=ym#|K0TzBwO*<^V{ul%AT52(hAM{tkJj>2>zw7?+6U_`tKC;bC!a}I&b z4~6Q;L1Ibnux;{7LJ95Rw}r?MQER+K)_Jf>CtbcolTB<73gQax7{)~{+a5_2fHE9r z>4mdR)>szqd}>5mZEiyh{p>1huUy^}j|m0-fsYAxY;zt#qsOvabKEgZ8d?!m6_cvM zeJjcHGA8(iUZ^OQpIMv%NGQ_7 z6%bQD8nPR7-7m&(!BSF#0T&MCDw^~P25qCkLLXcVgGs@oq?wg>* zH%s=CiWjz9u$6l>5W76`Lf#jJJO~e_HS3SC&Lv65d@~7vc_3sfYKlh#*x1O$Cyxhd z?6iI^DcSSnoc$=mI8t&iOJXC7!XI<5o!XL&wd_nbJXzc-G+$k1RB^ zie!eKjOyNzHrMx$LZ=yh9~D}Be42y41rI@ROXG$2>LCfUdrwt74?6oU1EW^`vVLmt z(8?CR)l;&41qpq}C9NpRi&FqDu&oJ+X#ADP2srC-bP?-L z-D&hzQ32Umg(Kl$PIil5mplZ=D~3rpSIgV!m9_bCZd<$BM?*8L^A);cK(x>zKwS{66w}N)0(*oc|)o^MHI~lQ$z@WX0EbK)iXX4zWOR zqUR3Moq&yk0`suBUHcJlEy4~a?D+m;PExy_{}|E-S2I|^mz+gC^T3Ch|E$MCe8nEJ z9Wsylg51fxJ^{_N2Wo@P$7sbNuBYQyETu*%5~I_rxmx1duf0%7wK=XL%rBsyZ4gQo_lo zW*ygBvL!Uoe8z5QKycwJAiV*UFOs3H3s1UK2B0bu8rVc8ynt zR@%dx&ipZWN{LY@DDd?VZyB~SNuGVOI7=XVBmG5wNbdhU8jm|H!IpVcPSw0hf7z;} zZbz=8jweXCMy6J|v=Dh7s>5g9d`%8U?_gtZGJ@&AcmS=u#E8*g&uHN0(c@qz4Pf-b zIL(l&8m*d+iNi|9V@lIZCc_rGmQ8qJ4+~q+>efN6t zb<(N?0TPqaw(aCCe(E5y%lerJyOd;l4eK!dUWrbpRgKZaQMq}W&ofTiISmH8TO`zf zIFTCbbmK8fE)8XX*1Nw%DXEjCe!XySt~N}}JfU{v2jRkK&cJdLdJZ**z1VIN4^~W+ z1rp7}c)6h6Ts%TRDYa&Pam0n!5wd1SMV)-Eu0Ir8xzk?2L%OUf$Cr9XN{Q9Waye^; zI;M*0YV?Ua`~3EDv^&j_F-1^&9ZwHS>!+aKHKzim7W2%b!BJeQHwASIGUHIQ`nSF; z=B|fy)T-~mkYYC@rnbM)bVGfVe$dN@_}o}LRD&BOXF=_oVeCdQwa+NAH`fY%Kk6ep z-{`KGE3M-3eDDWw6%0T6|Kb=~|6d#BpsS$DaR3R#3LKa)8Fn%pNGIwJn(8|A^00QjR_TM|?KEy!_7~0`{DqnW=^C zKk=E3J^4L-PzW*vglB^!5FtGesW*2(cQkB34s!o2asMoJ|0vkLf$`BF{KBpz00E>6 zXcl0K2EgO18-clr6{I&fJb8U6>G4U%9}m#E%mv`}_jk99e+clfji8)?az3sABt!$q zMsKzSR5PH(dRCAiLj0eUAh`)-AO}Q!V`oQ41AuLg=5-ED$VDcAok0Yt0PZo2lM`qr zpdUMo0@!BI?{y4lCRV;Bq}%UOt)V@fvQ;yGmkPeQ_!u)4G zHvqfo;rae@L{TArtDsu_g-))gZvd}t{MEjkWdADGU+4kne_C*!1ODVnZT~`N|KhPNpj#i_qwk5d(8s5M zC^q`419$$ETm}5;YLLcZu8qF>^f)2zO%aE$Y4nDtr)Nh7M_Tl=lB4ey~&UF zj86{$>!bdYp9Okw0#-Zu6Z5eFR9*5%0QXn^!XEq+^dAG8m<;!ij# z(Rt(F_m`bt9+|i>9rmZ$o$~k#{_}_p61XK$J|5xpRvs{@+T3r=vSK7+Kdpfzd_QW& z)`dHb1QHgJ=v!`Hm;;Hut|kptx)|YevlOn9Gj$xx%D#I#)63EyzvOAJ&6p^5ryZ9$ zJj<=iH%IEJjifwf_?ORjSsalJg~ItFT#+Qwb1Q_z*mS;@KYCwUbE7NaQZzu9cA5%r zseF50`Cs8>nDlgwPe(nRB@4#V&QX7V>9lrh6x3D(TcnuET!8|@b(@I1UA51;_35O`{Sg3qaZ$jLEoYskV+~dfUD43K^x{hBqPXnhfb)(K1 z;0#@j)u;=%>E=bSP?3`y{O9z3I` zTAXE^%fw95v$SuK7cG){Rhd1%c&QdnxA!8;5OT$nVShY=fBml-j|lBGKPjUX7SkvW zU0Pjn^So03+av{8S7vISJ}RGfPa@37>GHQS>{IB*mw-$0<5&w6WsP6q7+(=3kN%Tt z<27&?ca`;Z)E2yjCt~j?t;;HYwy66B0`uXE3AUT`sd!OUEMh?hO>@sE-CLkIO>U#G-|pgLY2qg1fED{1ySES!!HgInX^&k>-0-q`pr(8yxI>KHl6==8ub zX<*c=L7$JW4PrU?G|io%wqOA(>1qil^nUn|F^l&U&9Mt0?pj0V0czCQqZW);Rdf83 zm8~};JSnr?3nu=A;0&T-kUj!hv1)^-iFGQ1k&Wr@1>b*0=x$`; z#1dfLOY(6FeIoPmiD#WSqsXMK0kRaR9@{4F7^SlUboT502czCTCjBhHXojhTkDTh0 zulKDnhZ4Oe$$wVt&R_X6pYHlG+e_Fgk5_#=`U_kje^R%%n-WzrtjhQpxzka0%OI>A_|LO;jA z&VafSqJ?>MFmOxzJiM;A8?rx_-G$2w2Ys`rJVd5@-4BaoRm~eegC46sYmxIdvngtvBPvM zYGgbtkx>RxEZvS@ZqoC_S#eLeNXjv+-se5>bL_^&vLLY?J@18^p+&NMQt)gxLf|A` zRRN&#X*Y=+Lgkkk3wR*QDy5>N;yB89cLB~i6 zD~E7&WFpDgcLfddT#G+)y>w^?f3Hoee}lJY29Xew&IenKW7y3E9z-pxsS5GW7?#-* zhR9ex1r3uQ23FdOLz#}6wGXfN8jCqh_DHV{2Icf1a;9i94mpSF7G4ptWjaDV)%8>{ z#|%Ur_gMmgQsFL!EA#zCRCz2laXPooX_#Gg(<*f0!VIMql!StB@nHx}FJ>cL^w5~C z8--&7&Dg%33|Ztk*V8!2+7sYy!T^X; z`-M8baJg7gLr4EeBg{Q`p1}TPc)hSERu5^ai=(61*f)%Rn9ZdLp4d)U+1TL_311(6 zRXKK?3SeY*$K;UCGw>PN@5B=vrBr@2OMYJi-aDJ*_nRk0znaS9txMd_7T=sB4L>Z_ z#R{Dx<{!1Xk|Jn7B!gN_lZF1NZF?v&NsH1dTJ_X$B8UmeEOMWir4#y$~ zf}S;?Ryt8p+61sEkQ+dmxh{F>6)DWeIi=hY8ZX+*X7O~90AEIGgjlrbU(Cp0J!e#c(uBA6$D@FzsE!uSgT|1{r5YyrYr^mZPvaZ`n@oM6$Y`D z$L9j6b^cJtMfUQ^XMrgP4^7PM=9@;I$|gOWSA6@9q$$SKN__8Tu_h!%X@y)ldZI}? zAjl1{78s_Ux95ndJfnBJb|l>62BnjYH0EufzfGH;1s7F)cu@9NYiCNX1vZ6lVJnGkEj)rLlG@E2da~`c{p63 zmF!#EOD9_f7)B9ZxIm*33O(yg`!F^ra(a9hiGF&*_*B{_ z*`4ND?KWV)k)=8moAa6wVO_QCs5iVLa8;vM7FiCPutYMLg7=ore+dwqYkWOA&#)F$ z-uy&XQ}JMx_^IX)ucTv3QD@;P$E;Y`d%r^>RxnZP8UadoZ|3Kv51R`=b_{YsNY@b` zXKNSQaR*(3Oz7`6xn_{;Z5!>%tXDb~)zxSF=koy11MSz%BOnE|ve2j$qw ze037w?Bjqx1wmwA6%olF!c|^d$+;r^95A&Mj#jM(bl>F``N(%ZTPD)Tox6z)gNp4j;#cQ|klN?r41&o}Vu86YQSC);RZM5*MTN z=RaS($`Q+%6=itl3~oFbC4M=3|7okeH-Fruw`c+UzFU6r_AM1dJwuSC z_3ogAAVNnK=oVyoLJ5&~d`I()LElz+>rlV#3wb*w&jgrLx>N?Sg(cGdF78H39Xqh= z7v5T#nKof6qDO+v$cIo{lsZkqfodthNK|Kgu^p{+I{QSyA(HMGGlyX=lirVXG8dlY z-~*!QQZZz;5BKrA^sN?i+C8Q-@I_t>SgbU$WJnC}*k}~KXm_g};%VY}ADckGmKG;R z)~Ar>ar&*Z@)1Y3sc!I*Tq~{fJu^3=jQ}M9f`*k6zoDDTdRkZT)n7TkwPxon9d+XK zjF?1$sK9pENPmTb)0GDq9(mrz$C?Yy)y8>e8|YoG&B*ALb27OKZSDokF*K&U9l)yQ zSX@Z|Rn-Vpp40qu^wYY+sBtnx4c-cb?R)Q3IEJ`3v9v?6-&*hup))7&34~eSYNbZUS~tILcG6! z(DBy7A_Zph`28yGE24UOzaMMl<<+JnGRxu{G3yJb&a8p*L!2b*w(l-0Muv;J{lOI}njCQ&$qyIOD9^_#n#^z1D81z8Gs=s*8c&+Kd&`O?viiSduQ z7t;}I+f<5G{A!! zg)GA?Z=0^?WoWdzeHTWFw;*57)CtLGf{G{T?miYX+VY_wi5fgT`~Ovw*_iqj#A&)nmT&w>JD!#ISwQx{S&u?5VCGcgmyT1x zMb&zD71JQr1qOTFWz_H|gzg77{GijH2ylE-1I>4X5;FemxZoR)(u1*nD(j> z+wKlKZ6hKK@turZv|L6Che9^l6e_v|d~I0hjv=$@8@xjzo0bk_%ABkNakD$EuTE-9 znLX!B_Un1YiDvS>_mHswbGuFC%dZ^?iB08(9F)e+UO5_0V9GzEY$%7a1_g0wt7}B= zX3LlS_t~xX>$;#aZ-T;>}9EnjnXs}|6%E3E=A|o8GrC=)fQHAUHcEP0x zPgV;_Aq5u3rpgOfy!dkcJW2Q$NgeMR4Jv!k7>)g(CM_z3y)#lT>Dn718yPWFYE4{V zrhHBL*JrAE<*oX;j5nJh%8<^AJ`$Kd!#Vm_N%h<8K6@W~CSD3fOo)M|aZ+p15<1eb zEcw9K_h5qBX7VB`rkZWWo^4qSo*IYSrQs~mI-Yrlu5=XE6>j?zPfluuWberQ^)u@6 zW06#mrzgvAd2;mNc2*%jAonzF+2_ANO<8FN0#{=ArUbKQ4utB*#bH%um$XeY=@nFd zwz;Bz(}O&oohy#5md`(~=C5}y#7v96q6%aWGLzK}a}LjQiBN%ng+&v|{5|}vw9%~V zSP$^fEfndR^uDh1zo(}_@XL${{ zhkr&IsCj&CvN79*NvDGwo>3H~1m%$7g}u;FcZ&*}+IJwoogF7vu0)%tq@ zti35;sTd7v9agq%s3tA5L>=6pqa_fqp~9lH9zYTa-iD@?iDqJ&I_}nWf4>ohU&sCA z1$_B$z}@|VCtz^vjj@A+*h|EP|AaU^iQ!Svhk7?_a!M}hAwZQQIhb|N3=O0cW74Dz1n z$|l42aG~c8Od*g5LVAU}@Ij?U%W&zJm*<9~yy*H(xn>=FblYnp=LTW?Pp z%zCjbBZ&UniX{^0^Zv`yKN2{iLx~@8RQ9Lv9=s~;s57c8Jl!qhD_%#1Rrx06S46h& z3NKB*O`Ue%lFic;Eg=m$@no{+tlJ7ZeYt^N4u7kh7GIsA-5|=~)a1nKivuFVrT7-+ z;xN@G%(tK@Vy&v^I9A)kf_OLE23XksM#1-oRa!k9n}Cj5aMO(V?*zI}jddm*i(dLm zjMB{bX`j9Z`->WjQ9NOo?|s5LzKv8#?7TB@k1{HnS?o27HvE^x_X9DHPV&XG8gZqD zc$1~~9ZURipB{@`U+Y)2{{>Bi)ad&ww72{vKvavLuF6H&8mUk~<@+1TULp57h`3}9 zlF;q|MXBi7OA0i~`BdYTP$*C5E0o7d2{lX`%vPWOV+}`@uso+315?!0b27m(g-gE4 z{(97xp#}zxn0vW2eL+c|MoiE3X7BYP=IFnfE9Z@qV?;AY)Q0ddD@LYc}IT)#0Nujd#5yt254Ak1LxLzPEby#(l?`L zyngHeDsT9q01Iz}q7>^I_i67VK`C4rm1y;h$j_`%X>~Xyo=>dHcgk1lSS-=%9 zgFx@PZFir+bftozp%iVtoT2yCe3ev#B@gWrM~>Dwb>Qv=~=+IGPqkX{1}x2XMK;Chtnhz2Wo_#dFDo$ z)%dr;o>`TRyah!d5us>c^zeUlXxM0Tcy&ttT(rw!y&zp5l&(FyjUxILN;}#zo0Lk0 zBUOq~CvHk8>wvuFupSg(ojbpa3#m8K+w8w=ES)TB#zW;H{q{c0qo)f)FaB~r52n0q z-E*%n(R%$955KiKgzalJo?RE_L{bMS18ZIGgY4h}AJF={>8 zINJ@>>rp8}@SO>6{A%%u|3%q3_J|fNShQ{2wr$(CZQHhO+qP}nwtd^SyXR(-nPigp zWqw2DBz1PJy|#v-SFZyaOLvIBBwA4jl7zYuVk#+iM+huzXLwaTs72Pq8J77Ua3}uG z#66hJ-GN*aeUesSo8S(EZ8V9stmYXfP&wu%xK#6`IBr}oK~nd`y)oA)GWJSbBJLzc zEqNB6l5|*wJi%RQId_w%skGowq(u}<%T^d6AWuYS#;_SoNQ`>a1CMYT-1(H6yn$!hCP$_CjBcSZtp^nR{c%U0BwNwk=oTm^ zhJgL`kuC^Y+M1}}ZTDX(A^xy(6#20oAEu|ufTF=zXg3r(;Oms5P7SFmR@K_^Ep;Zu zX#7^NNv+kW)mP05!Hb<7MCbY)P)^P>_RhdftP*?Rb7l#X#jOzFm3v-rToDDZld?tT zLt^SQmZeI@ECv+X%jyr$XDYY}GgbNW7cWFEbPRNQ7&jTDYd(&44cLz~`##E*(b{QY zGF@?BL$au=%#jif(a}5PgbFDNa+qNjvo~{FdjOw=Dskhe81LUIV7~b`Kt5OXy)>0o za)_<|{uN*LisIQ@@dXS&Yo789QhqD7^?}1!$-CS(MefT#5A>vnTXg*o=lI2c-?0xY z`y+R_GZod(s)dxLG;fe2n36|Kr|x$$9(-C%$RQJnwv5VIAt`ly?Cy+u(MKu}pDObh zz=ZH`-iu;%Wci;c>mYzCLN$J0*-_17x2EUB(F1%b+iCY6O%bra_ii@hY$f||Jw;ga zEzYGOvcJR8anKFeQS`OC6>@TsT zlbN>V%Y5oQHYZ5Ztx`x1?WDsOO99Q!cT%sMQJ3g-K^*FGnCtJqg=o+b+BLO36tAW3 z9X>i)NyLK%rlnnhO6}o~%>mU5mqDayrxlZ)aoPh4K<X@PtQTTw1E2WlVs@%QUsJJTWgc6%V-ivQmB#w4O_dd-0m?l(7e#nyN z`(h^lTEu*~l?nVdjlKNZ=>%l6GWH{k^!~X)4 z`P5@$M-}fZ6u}2o<#=}!ZD!n5@4fB_`_>3rmDkS+>!)@kQSGsfV;Q8vD8igq<3 z9U!7r1QNNx{(C$T+y>aN=;u=@#=M02@v}KCs(A}oq}8y#Yex8JgUOz;ZPpx%W=JzK z8Ig%vM)@iPF%@taXp|XPReeowlp(tR3OK^lS95{hQ*8joLvf`$YNAy-s>@quQi;-8 zlqnO~J4f`Bsa6uZ&=r0s#~zCxv0w)iaP{XNI&6P!z^Aa0h$$|gf4ms0Q~WgWe==*= zsMjV!G^Ms81W0g0)rlf7*0LAoV>HfV$QXF)(k$}uEsu-Q)hL}vf>YJFf{IV#Kwoh=@m zl=~njxkkUBuE5`>zH^kfA2d|9vbkU*NQrBb8+>pEa6@mOleDQw75KJ;^R$VjU2xbe zOFLN7NbugO_3At`MwEooxPkZ@!9fg!3EDqs^dRFSRsw=a79g4+Ar`Q&SNCL9FG{tF zo0(J4=VZNys-tk#JB%_QC+ngd>(k`^U0sbG<0W_NDYUwyJR!xLq)$jLCuK~Hu`1J&5d0iv+AI`wMBO%aoq_r8ZqdkGb0hFCebq-w zMbd~lENJWRA-rkj#~2B0@3{19NE;a=wL^sh4rYVEumV0_4zVbgz7!=_1QnXJ>&vWtj^gr9beKzY?^O4HTkJtxk(>&LbF3OxISQ``_ zX^AVieHg&?7{TA>e3rWR%}H2@tr?&cS}=LiMzJ+zc$~*(fr3yhrPyi;yh(o*S239E zpt-~JZA*fLh+M8tts61xX@3>H9)A1nx4&AkCU0i%+?O+@9~zWW-TXtoq>R|mesu$q0}#I()8iZ zFI0|!aIsq%;hUTyu{j!iFZe*`aLM~3j`BYDLRy=G!|psl!eS$-%qVCywUw>2;%;)f zE0G+>G1P`-s}a}zb?JkbF7k#wmfCitPmLzQxoG95(08BOKiJ+%T{4I@3;PKWJ!pjI zZkw;x*D87l*tzZ9)_W{lLx3Q_zMsw_df36d@)YLpzu6(` z)hipHA)vDlY0hg0CvHb?yd9%t%vnRS30T<1@syzw1x=g(H$Kx$d#yeJSEAZr#Wxh*gv;^}q?U;>_Jt^4C3E7*OURP?nOvqKH)8|Q#EHdV&4o__C2TFTpI%gbxEjL&`Tqx~sj!V8pplZx96 zxzn^&-$Kr~QYNjei2L3K`g4lc2$D<9 zJ4*E7%=iVfgW$5#1*R7~i=q)PIVL8NOP+AJ36h?geiPicT&%*>C)ezl^-A9ISwVxQ zr`CTf4LA>6pH5a#Ed@E2>)p_j^0}#8k=3Me;7*8xbMkIl)$P-@f}hBs z#Oa@H=qq^_ZjUO%a^x?Ckkfx!Kjo|<(jwEe2t!S-A3QV z(N1J1y`;wItz7pqOSdnZ?voQYj+<)x1ixwyfwFa%)G&DX9s65MLrrw^M0IN2$D^wR2Omhkh*!=s-n?XZS7B+A*-YJVo{V8>@Dq440sSSKL!Lywk)5DU*%U39h5MF( z%cPiuBRsz-`Q^X6V6SlUbx%6V^TJ#`R3i zc-j1@JgRh~55VO@z$eAX0s_JwyPsr0qj`RS4p^00!C~+L@!%Xe<$Wt_pwq+*V+7-6 z_RQTwWxipCrfB*Q#J&hHiC;?yg3Gp0W4AY1zFs=5hSSKhRN{rp#39#2HTEPh#m7}2 zXm2h7B!kN%yDG0d1Sx*8QVG!JmDNOCOZ&45YqCtx%6g*$*6aDzJeqMxaHnZG`(AXc zVbOvq4JHC6{BbmdtQ3{EqZb;kpc{ka1>!j-RUpK%LQ_PQ2fFwUf`(ZjQR_qW|w)qnGi!k`e4TE7`f}GNB za^_t8E?x^Axv<~WKCDM7hoM+HSdrs&lytxG>e&r+{u7YT_Md=!b|#MhA@KhJ`3x*9 z|LYn4zd$}46T|-p$k$q;iPo}zg}GsD2X#x!56BN1`tL<@of2IN#T&|5X6wJF2+ENO%H&>$jHX-0M*r3)7911 z;>yamG}tu)zrhLR%=|BKsQOyHzxd%BK`=OaMu(xXb=;u!H2kX*m;lD$03C1s+uqgH z0IaI2yT1g1*Y5y_p|hx@0HCJ+)a$5!{e?-uTAiBO=$YKSztev`K;|)*0R6kWx1;@1 zfQ7C3Ur z7a4%Gsj+7OEAheOdzi*S?!5H<3kzV+ZYRYT{DwVX3Vt9l0doMcYk0J8c&r2F%K^k!HE>MXy}#PJ z=JzG`?;Wf`c5`3#y8OmTxI^sk6jfwZ?_m2o^AnJ!O zHZ_QP68mO>Vf@DG)9vjEq1p$&ta|kaSl#3Mle?U zhj*6KeM+Hlbz3KIYb-yb`D;EOx4gvGF$1K1XmK$~(E8?fc4whap3imRNc(`^JMu{J zmwKyU_4HeTIC@e5bxdA>(gQEzeRUa8Nd1HlTu*HO2>kFLfo%ZP20sKgE`N~|_(OpD z@gIRYN=Lu>s>m~4V6wb$60ysz6wV}^J5w@QEyV7)Rxjvum57yPDQ|2ii1FL3V?t#9ZJy$*e>_>DZr z+BMT_m}?vwm>L;sX_;SoJ+FGEUwDH3s@kEx_-mEbfx#=j&J)k;#evQFfiFHuUHJKX zxrxj5*ic!&#lD7jznBNEzh7uybWZ488(V#yr*%2LF0;S;eYy+y@l@mJ77lRM(|G0@ zSnHlzG=hHzo0(_X~Pjzbv%n-S4!zWJXdjk(w=$lKx}y*r-Jq zaa{7$18*AavQ{o>WLfqNy5IPjhs%7)*`ah8U} zp`>8cWC-Gj^6^wsyJk7`a2-njpG(yKTNpoeD!(lLnW*q|QU)Ucdt|-BkL%!syW3b4R`sRL^;)y-{JsP;L5
DKh@$rHimKXqyU4ebOQ~)a8e!7!wgZwN@ zA+?Pb7tbK*-W#~&H#CC&{m(83G|gV%PEr(afl>8)Rt*@sUVu4FKSzb3+~5zwY-Vo> zS^bjc(;%xalST#waV3J?G5Xf(i5b@eNu`gz_mw}LrtqszoDFLt1SsGX)#lP+{n5i) z7>M2MGa@1CW)KjUB27M(<}rFB7||=~s26gi&12kxW0|!Frb<831{xhOkc6~rNWQL|0HnFGd3r1Se7=L9@sN+ z9wZtC6{!H-(EmNzt6U#T!l0VJqLZvKFbCBZM;sAN|m)0^}(hrL3r~r2lGYP?e zg89w`RFaaf9ebTb4tcakM~I2u_+)p2LGRj~8^~by9z`dfGeC-uQrJ8d7yQ)}M)K zm186)0fwQ57~!>mq%VZa6 zMHn+9%p#)=uLioHGfmJBe~kzz^=yk-wY=o(sHk_v^1}NrT(E__3M3dBWEV~C+}y{T z61AYTBNxI*Hl1J%dc*5%f*~W~Rqksy;%gbb^VOj_9LoM?O4YKtAl^-H$OM`+0B?n+ zE#^f4P}};47)HfgP>)Wb5^SSFuQg+qc(a*Sowu16h271hoegp-r%fzV5xbT9z5iF! z)IL7?81LDTCPitYVsYeFeRfS?j+hV&<#G2kzw`dP;U!SEn>OO-0bhk7qV{dvRlFSc z25s(=4vCAX^HgeZ!bPCr`OYLo&@3e>Gn@3yvtkmOsC?>bDy)acPPs3pGgZdIoU_iT z<=nsH=m>+5?c>YW!=FEGbAA}Vfh;G$F0W-dbailN-u3!f#0RcP4J``1K-b_Zo5k0J zh;Y{!5{!ekB(iCExmgtJ-m}j&_HNvPZ8;Z>0T|_W=P8L3>=IPqck?1Dkil@y)J{qt z>+VPi<$-%NT7sj2wUh51LW@`-^k(fH`D#JqgwVb5E%1O%XG=- zVBa_so}FS3Tk9*SEBY6HDs2&GEV_(*fZyL$|YNS_ENa;`nvR@9)xYjfT~-}H64>`?V{55)dzwYv_TUrp2nl| zm(fbEQVlU(N}p6iu+#DK;xg*o^j;Vlbk7GR|D_vvCe!UfBovi7z1^fuHkyt1pU^P^ zh>0B&B~EO`kpdE~{+?C_qSkeQi2*EufBpl}hXKTP zQr(zgK=wn6k3(`asbq|5gr=>865_zW;`XIqvS=x-Y{{{M<4S1$@FnD3yf2sJj#9t6 zWFYuwpBpk-y2P$8zEl~E8lP^LQ$NsyG0!zK9MuD%RKIa zZKmn)@`RQ>Xo=FxH^Gd{*jx#%kmH=wRVyvCxk7(YnSZ2z@!=B537>_TeX3_ek{v~l z2Ny$NVKVry6;C+`?Jj3B@mm0O-_dWHcr$(hM#7mhB4KA4`Au?9#vE&Zu`%|8=RonE z$Xm&}^kaRZ>nE*`hcuG}J^sim6~((wIGtefV`BK%eXGI)gyO&TL~z^0Bzii*X%?VA z@)?4RcVDmK#dzg1R32Ugj@%OYEM|uZPS~UKH*LgbT$kpb5wU@?Y@+C+@~d^EqZTBLC%un#G*qNhB{{_(l(z=M$P6!{Wao+S>siu=x5YRuD+MGxw z@1qK`#cie)gVuP_;w#j+Aft~M(pUeKM^k=KM(rQ-gIr)EEPk5FaYFk9)3FGg6~OGn z(=Zu?a|6G5Ka#Oax^DNz!4Ou+h4fA1YTzgQ+`2gfHM;R{df}l|CT3`XH#m(tZUs3M z3r9nMx88Zp*?aWVTpf>NzS%gq*r}pj@gAE?O4O?{h~3YqUyxv5@`FOKcrbL- z>*bHoVB|PHb@S1AXYNW4fcEu&)voMce$7+H$r^a6orb>d9)Y2{{hrj5^h2fd2!9f? z|FhjLws4G2hJpGHG6hUs@zyKA6q*i^BIuuSqGVuV9k$zfA8+N?m_y_zpq|yup;f1STKat=)#YM%N#rE)C?TCdyGKtCB z2b^~GxER~2xuaBHL+HHF>i74?lo513Br&5(ca#Mf*mL=;=9YXf{B3^Fc>mO`CXAVm zvVDv%C=a}v2(~DRUPe+os>yJ&NfYy=5|q}@yd`v z0Hn}aKH`Y|=_AC5wjPh!d4B;~zq@;^dEicW%5AK(cBRl0lEa1qiqLH+tGu%t*~=3Y z(@gpK_s00O6l*O@WCk6M_b`X?8bnD0AhNZv*a^+arxXOtPMFHrxsCD_r)1Zm`5teUrCN)Bi7Q8gbOO@n*rlVep1^~{zn-te zlPz1hiF!k_70CHiW|`KJ!1CXd>O>0COq)YiBltKD6Zy5L;R$eA0T8I58Dh@(VV+27 z(Q+jG)KGw;OPlQ<`9bh0!9(~{%w13o5asq_Ayqz?Qe%q}w=*M42~Ya-bIb zYnLY%W~aFKtNdGK9JE>oPrzA+C!h#?mj<~(pM+&_EyHPe=GM#*z+g1Yz)pAg>QLlA z!W-lTI0qnPx}LRhKmS%wWt?L{&p_cGjy^-+sSM#X6h1Nsd69cQVLi4{B`2aqoIXQI+0lXf|6hb@KFkKjKbmlPp0040{9M#SI|0b6?~Ej8BEEwUISEkuErz za5xIVm0hh6TaLzK;8S8?(Q71)x%VNHMOpDmttNtph4(~5YEj?%rb`GQhw{Fh+)EL6 zySg~X&d?gcjWMd!6$yJhF0`x-od6Wh;v~d;hT{&PXhd%Wtg@ zkAdm6#@_gl-F>V#Y(>ja`j)qd{V-3v@9A5c*b|^@kc}YR^qykT>oMI%gLfk_-88l#C&P*BPw{>6DgMD z=nQyiU|j&GBOf!$xP>A01sR9XE?lxw?k>VPnCL6fZ#P+YIO6@&h?1F)h<5Kno>-|a zb8I#@y5W8j{3CA1kxt>`T!sr599Bpy?qf$ z-mtaQ`IJC=o|VHltvvl?a-uST9nPya1j;U35CNY-SZ4q1BIT;NgHfc|{MUH)?K z8VE9`y=S{3Xo`aUNgA>t41&X=ss@yoXefrjB~pp$+(1R>MD}rQnBuvl(ov_G%=3{7$dUH;saM2 zD%L#iPd!)2Ytjm`Z7p_4{)Lo=#zbo%fDu;@{H|_p>;p+)4^*?dC~cZPMm79zr<2Nr zfkhWm<>JBmR%<@-JGuBkNI^9%kVI{Zd-}c06M=Jv$kUMy8jZ8GaUy*s4T;DbGUjfD z^V-FvuK^*|psG)l#acGc(RM2&$hqk9$Qh%D%>Kf8S*up4a+p{FTWd&3y3KAvklW!s zdc{M63R?KhyQ5_WV(UesCiMr0iheZWg7wzbp zzGvt^&z=<+x2Rv}j!MDkP(i=DY#X#nq;+?&>niGO3aNVrL*%1JI&8{^y^|zIMlIDG z$GYcAuGTRE%g@Bv|oNGV+LgS%+16=s* zAI!ws2qbj;+hPGW!=EU`P+3i;a!aVK<(3lEI=mQ4ehpWIyC-P2ormy~{N6%IqBj%SIxutuJe!+QV}{@)#(7EK9ZI$m-y+qws;1vXCyV| z@LO2gvgePX$KnSGtygkN7eu#p9B5e+QURNfXF1{s5H-(h80ojHCB?~*oSWX1!`Ybf z^RL70qpK;TyvBVceZtczeBaVqeA)Y_77vyYT6;xDW=Xa!{^CI>Uw)bKhpH#j2Ozv4 z%tm*lJlr7Xg->2t?yH-BGnec-G3dNI22GJvs{>1ub6Nhv85Nphbj7)z_3m*fn;}C{ z_(RiwXf5jA29f3-cuq6b5}!r?HuPZ@-C6X~I<2*+-ds%X6YLGR`A*M2jW)1V=^}^U zP<)XJ-oC(JwFoaTK76L+Ebi4m*CJ(Z_g#NxcQt8jXvP2b0v2eYxem2gzBD>#R~OTV zAP(VHNn}(k=G69kasSo9{$fIOe)woZ(iGA`mF;~sCj-l}&U)vBE4|i%UpvUoK(^`X zD)6|EFm~Unf6^d@wJRPXmhE=u=$@)3H!bF_(lOjRGK=++CL@9{Al)`~6_R8z^#7O2 z5O2Xa-j4QaV~7-;8nj=*+){+28gW6g^Y5w1V19C+0;wNs$V#f`nSqz-K-{Z8YGeu7 z49->s*DqA(ZVr8xOp(Q{_D+Z)AODkN7mE;g-@8@5A}Ko{((uXWEXS@SK^oOBMLv{f zLpadVA-r74s-KNYiWw8OL6^V_?tVOh5qa15$Hwn9jZPQcPZ72Z>rRk6q)v+f{{RYt zMXHD9NNjl0b_f-GLhmN_*{hR_ZfIO9j}6)XP{x??xxpyYl{i}A`7zwTL6FK??BM} zQ>9g2s$bOxF+1%TaH~!T$@fN*Yf@XBcuA#8gj}2C{3PAT2_+rDA!uH-Re` zsev<9`5V6))16(D3yZ;MGzTG`w7LFtc6VE%XUY5ESSE%*FxpYSWg9HmUVG^jn3_dE zNpm^_O{&vH>mzJRV55Kc71B~stf_S_eK`ZG1C|%(wD)eKr8X383`8=^?b+1dZW|{l z^xUaq4;TszbyesE@v%Bis*70J_Lt}+bWy|`O0qsC`MqfLS8$3np+Brm@Hu z`#sm2_WkRb)mVE}@Qa5M9uM^$(N})ANwc5xFO&iCb~rnCtERipjJ4D(=PCbNR3la8 zF;LeZo7D%PEMY!4Bgi=86{HXje({^nlW3u#upw0NDB>ctSP4`^DRH1mzz8vMWf{7; z#@HXzar`?Bv5cDh8a(b!#Udj!1i?9Y@)qmcG6v$a!)(qbfWQx{bu3v}>QK~APiuR> z4 zUdjb&1J%3XoM8FzjNM?Ht$$y81o4g3%Kr2GCF4tmKIdXLrU+kD{DnLb)Km<$4_DND zTzVq{I4^jz^&g^@^B`*f6Ke+TA8H7(WPRF-?ZdJ(OB^kT1-m0JPCzmU^5I|-(vpwT zIYanzbxI>4+bN%KN~d+5j}jxN4cV zEUu&t6F@%opJjFBM1BvpDIdo71S;FP=7w7kSP)LQZ(Z*pCc=Xa(Qlrj#vBRCWG~wQ z-QY4FDtA>503|&>?~BJKrzHfl;Paz&YKK!oN}3c6<1CKd2?JpR|Zc$}))u&PyeYJ7eO(PH#b& zSh@R(gl}eb^l=g~1v=1`*IemKWu2yhY2?BeP*p~?nxi#>k>iFocL%$Wuiwl^bxLH| zImeUcv7I4v1y6Bby)ik7*SN!et2_3=TUN=TeZFYbgxv&2?me-v%58n;` zp2SEoJY%JBbwqPN#B4O=r=Hb{kB|X-#<3R#lH0Miui#;{6u&alvFwQ_+wn%m`Cl{S zsPOk*Fu?}UqFWHPZv!3#uVO}l9pgIJ>w(*M-&_6J1!E@B;5FW6H?j>NlsLjUE=$s? zus3_r1mDL`rcs(t@1*OMlN+b7BNa(?sGY`JD5g3ne#l&*{Nh&w3*#fEB^7%&9C@XkuG zk=_iU`BV+!e=nAzXK6*+a#>K4?f`3Mt$Nm60IeaPR ztWgJ&xpGq`Rz(B-uCe0G4p$N9v_O=hFJI}ees-D@&uM2Y_pw>f<@-JS9bfD7Fg<1c z;ARw#467q}rMH`H9q4p(n+=GCO{MIewEr9lYWGHCe&%1t2;iJ@`DRk@s2-$Dp&Aj3 zVPy&!GaytyVpL=Cpmhj9Ut{C++8Zdr+f3@9E{2$&DIr?gCW{MPzk(je=wuQ)Whlfh z+!i}h3~Cp4>@Gm{Q*Q*i5NNPYNJ<=)mSihPW;)FdenK+LdInAgJw%$i_7vX=>lDap zw@%2hIk|3oka*ivLb4) zt|+IIi?0!VsWF5R=pSi!d8%Ttp=cFu)7sTlM|%7uoNKF{Q|pWYTsi#r<9!PD`m+>| zVz65LucudUXpzX5N63)UJ`|}&!e%N1(=W<~i1_6s{N~zJg>Nb#CyvyFBaAz7(s!+^@LIet6NY@8-Tn{L4rfK*Cny^dD{*&hZ z9|>ak=mBvyqtcqHMfB%36S?gE9`~g-L}=2kJvgamj0T9k_71luCWPaDqBd9@q-fbn zspBi3x}y1dy7(GJx;VHG$Ao3hjls+J+*gUnutzEba|!WIR^z3nr#h%aS0_UgqZ?3` zI=35%zr7f@r}%t0bPeBMuE?!xYnv1UO6KN?LwLf>5f1zfQZ45#Ow3`kf`e^w8@tI7 z61x+ZQT1$B9$#R}9UaQM13@N8etP+aKx8MG*s zAzouk|By)qJ&Gl}GuOhpwaWP$D4KJ>sPNZIVGW{xcyedta@J`(qQsA^%odh0@o7~Q zFjTjiU&%hob_zb7K4>SV7cg0&Jtdzc5c?N#3@h zy`gTAFE_5qE-g_oy@?v``XKhkH$UhuaKX=ByJKtzWxuMBc7vH+0P_i=nm3 zfX!kiI&~YJV?bpcIm$^TuZKCvSk6<$)ijJw3inU(J@GHT|GcPMa?3wG8kDUAq7=e% z_g58sP(cdfjnb&4nK;P-a#Hna^5M6#Q4!sqvXghVfQyfkX=opQ>E;7X+!Pu>m_QP* z31t;Ka`r7jdjpffOz+`wCfZ{V?Oah7*)#V|cy`rLj(ZphK`N&nR{Z$3q6FL$AXNN$ z55aXgY8v4xF|$9=-#$JmF71zLa$q}lW|v7Gj0z3`-^3vF2B$*fV~@tGlsU`f7;*zS;g`>vg! zcIMVEb&kk>^QHb)T6X%|u?s7Vpi{ZE{N-Z-h_>Z1PDuNyBbY zK2jA3gkqj*W;pPE%r0Q0{1sM<0DN6_&Pq5U=YO(2?xx}<>{i3+Ulcm?%?kx)=8{dE z7`LFELX^o=Z*x1>-FxV8VW_hneZlz}LW6`2k;P6Y-~{LaTxGBSIggbtkM|Npg*uP8 zbykgpbk@AqH=8#&Kb}FE_$_?N>pA7F@Y-5E+rW5MjlI#aeTvPB&lMfoEqmq| zSC*u>vtI>+INn;F+UKn!U>lhWn^87`#D<6YQ~Cr zPYqYGzwM?sSYV9k4`AgN07;4VSxi~VX+bN@!%X#kEDET~I_!vJC*4#i7d(B=Z2G#T zRDt8QAZm3UD}C+&9Yc?;q(M2WLIk)5m8we_1iY>Cb{VL$`dG6p$_(T{hu3(>5F`5Z zmkjcfur4H5J;g|yW_cFKKi`i<7^d|IjGOmuJbQ~;kO`00btuX9YV#Ugl6*fY4<0VM zvz20++K|#2=f=iL&XRq?;jOwa_n0#OiWwJN65&;uuDU6A*asCp%#nPnu98uL2NSNV@H`u`U&Z;2J*-&x{0_7aZYHF!3$Xl>5Bw5b&dz;dT!{p*}$9U7Os)`d{|EILE#6J zokQD8ipWKZh33?)+c19!x^JJb=z9O+y(AcPF)*>>(V}gCfM)2XhCF5@`^k#=JZXh# zGWGs_0R(7a-mlSOm|F}kN0qDE1q~X6tsI30p#UPZrNYumH^{9CE_%K4rmWSa9U65h zCUxtqmhe)0H5P0t%%4#M1@7m@a(fNgrKcJH9^BFv5`xuHf+@CyAX8|FB>C&^_$sS_ zx0jFY`z~TZ%10DG!n0Ps>Y0~cq+e|!#{kVRySRUg1aS%DF@7o4wkNurv2Jbz|k;Nd1Y-ID?SNBh9I~7 z`iN0esQ-1-{x+B-YNyZQobuGvABy0BIeI3_aReSiBBcokfh2W4{2HaD*AiqpfWFc- zkgs&C-XoH=a~?BTzB6v+@KSsvVhC{F%A$@IUt4>`$ft>HfkOC(gg;Nba8L)aQt9Vw%iU$;au&20evhpcc&GWeBjA7~L)oh#CY; zMB>1{eMoC-Iw95CP%wsQq7z-BXY#L7OJvwr%sYZQD9++qP}nwr$(CZQJhNGqJG~I}!iI zT;^?7MMY$N`MhswSJdXaG+hIXVspt^#ai&?$~?*N7i1Uip4d45_KS&pT`je?afOAs zOUUV)!X@!__)t%OR;p$USgnX5VX(Fz-Sw(5?*kOUvAKp_u~Ni@o*PH?-3Q)xMQBec z9Sucq?&OLqKc)aLTkVy6zR>1j#!?4Hel>mQAmW5~cHTZPoQ}rwu z5_SSgsv&gHp9jnn5;CtvXicq@#M4WGOPQIcy3h?hTU`w~09y#k1iSFvWbq8qVu01`i|4&l9Q5#Z*4;K8MiB zK@7SYr1|1>&-1u&C@iGU)fE&XRv}17$$IV60d17nZD7_0u~Tt`5g`Zo zdJeATp|1w`Rw3IP)TB>FyjVhM&Rfa!t`Cv36lU^HWGYvT9Qfeb#DhyBof8lr}YOi zb1yFEq9M}uccFNv3uwxA zM)#l02*-akBP{>j+VIbeFfuaz_ws+35hi9v=Krl3Y57;;@Ly)66Xcct|3VRQFbq9A z*VH|{EuenFwoakBy&DAPw#(zO*PKV6UtMQgndPZQ4Hehh?vL{PKZ^3EC@jrPU=r)= zoJ=_nsHn#7fYj7i($v&e;z>zZdZw0hyC#1mY2pfz*Je^~bpa1z2=X2?Wq{7U z&`Qlrq2nCu!Ri`-)!N_G+TYdG0IaB~yMB?)PRGFG06GF>03)OUIJh+9kdcbpvb#fx z*R}@UtEc`oIG9PB0apDZBQU-tz{1x2F?z^(H2jEXR)7uem1aOqU}c->egZRizaj#} zdiz&av!hd2CnqByP4)&2j?Cx<#sF>p*)#wa1Y~iARAVT2qkRA*d9Y`-<7si^fLLgH zrM*`dE+#WJ{9*`u(|WM1fa{#y#%*gE0XTrR!+;kJPyoiBao4*2P`;q_06)Cg0944A zzGpu(KYiQAgIbEpt4 zU|7ANU+WwQ1SAzu06nm8uWo-yWAr>t$wQ5j(}N#yT1wCIRLc<08GWu z<6>8PasPo4HFdxeJ!DfqhA|wg$S3&EOiZH}be~Qyu{y3j;>pYxH9%@#ub)SwJ5oAD zE=|i=-+|vQT@y$ONKh7@k6zNBSXt?*8Qi_$u@PuJqeCOWx&}K(ptfB+ub)g&P>7#S z*c4v}W9#Xw9mXGv*XyjGQsdQLRQ|_TmpP!HOzH6(nHBwDL}ObhL-T~_}28*6y0U)M6$v)XE9 zko14L=BHJ41@o;1vY_R}*22W-SkGYpZ4%BU0jM)jTDfnA6wTNCgs$@hztaS^1+;vP z!~fT!PIL-K100+RN-FFT<@{8{*T4W#pX{6u{{s54k>KpvN4lr%`N5D1< z>sP?Ga}cJfr4``E&^?kBjN{jE?+BE>x7)+&2lYYaY8SDJ+BVz&7j*Ya<(IM_NU!A^ z-pDs|ZU)TgN0xI{Q|yIb%#?m^1I5bZMRvcH;%XPg+Vn&A0Xw;SxL2~iN7>~A-pG^c z3WW7nwNlIWkwYCgoBAjD!NqRox2Ox%9<1YQ@_Xdo_U**=dv(8yW$%aX%|$Ke-}7IH z438{4%*^}IdSqkxhW~l2h6QR5l#W9?y^?+lq_GUxyr~cl-@E2$jVN_go61u(I5$mI}X?)SUlU0mJ}p%0UXWx#GoH1?7xV zAIZrw=Z=D-4J+Ql+Hu!F>CAdVIP6Bu0=%reBv~r@S(})oU8Pqm13Pz9!2G`g2uy-g ztTs>4`*lpA1m7^V0N@@4OA`2Niqf&?e|Th44NK~1tf|*3oAtd$^nAeJ^kB>{Y9^nq z6R{V5zl~pjv!9KJ&4gXRh`Q&3QOCE2d&vcMGuydKagB0yw>v>kiJ0i*$Fbio45O3V zauaUS5S4a#{={H79NAP9F^WYQbu-xWmtW4kG=^g}L*(M!uf2n}dMSWyId302DZhh= zhGuYetdBxK_<8e+0Ci?LV!as{bjS*V{a}n8bzbNX-=PCjTRIZA1jKPUSY+m#B|5o>pTWiQDTcccZFGKg&Oq*L*Y_s5{gEQ?8Ula2Ra3tIE#0Eb2-1aj>{v zoA8}qep_KMf4CyRxA)vQ{Bqr zK@a|JN#q~YZm#$7eD6Uvvk}0-p-o1% zs3XNORoVy9_9D(vpvR} zgZP8%?uQKeKJuSxUDdHw3&1u8`-T_f%aO`?a}F#T853BkHbuosAjG#S{{{MQ-Jwtoie(kQuDytghbX! z2VOH=dTRDm9??4RB3tX zg`x9xkYN|W$qeBph|F>_4`M#tTZZj)!F}^QqH{$@ip8y;GC%x6OWO?`6K;ztajG?vNRKZDuXgxyc$tjnVJaZ*Q zKA~sK_jR#^&cme?J9tJs2NISup4^J<`*#A4p-zzMp+a! zS$iv?)_IMob;FdAtLIo}_$G58wQ)48@t=lOmQ1<~c-*H?!gTxW?W8O`!WB9Q{0ng2 z1R7_KN&Sk@GHJ^u+>b@8r7YvbW2VR}%9tlCa#(ss4h?}oNSWX{-rA1+l>o^(hGyjm zhLK>WfX316)cN>IDKxc!=az*rg7)USBSTUjmp!KUG-#~W)0+t8D~U$#F+5VrC93Mrp*w8s|0+v^4Rv4 z>}n(0GRB> zl+H}6E|Q~wHBaFv{9}0Y6|!)M-^P}ja1|VUx6`AiIIfkGbnYk+s;u_ zJPp2&4{s<}Ox7~TUOmsDD#eifdPJNj#e$r!V**wvBf?ri5K!FovmbZ%(2l9K*Hcjr zz+nupI4HUFbiBo&*daR?6(G@JV*L0`u!ns|xg8@E@?DL8(1>h*66;YatXMfLOFLKB zHYAf6QqPc4?}(SHkpr0KSgAQ2I6c1-3=_tK_RYZ! zg2=!jdTtD9g%&enJPX@3O;PJ_BjGf+sW&m1M6hZwh&dau3M)8nuE!l}FCh)|%A_y` zDX!AK0hkA@x%ZSQJW?DZA#ijmC=0C&Fnhh7#gce-b=+Zfqfi{E76L{`F5ys7jv#QV zWR52ZhWnNwiu||~yuPf@#FE!Z3Wi_s+ZR}JZJ0F<&S2F zKA^RKIrA#>*zYYj^UOrIZ#z5n)os!8O_=2nePly^vq+w8heMDqyZ)`ukl_-6ZQEJ7{AGPBs`@Z?8=(lvn?G z>0N_TU$fD<+RZ(&;AJbh(;Sr=aG^0|kp>w(U^bZ)c#($3cyKg5i*pXGQ6(zh8s<|+ z!1X!EzUVyu76q&ba)K7FU}#$lf)mhutZa?9<$+!fK~|GY`C<$g+oa-__prhE5nT7Ekw7nLkCYMWoi{2A>aIslDedD7_ zUMIy}1CDKOHiu~~SH>g@eV?%FsYB&Z!k`iL71TJ`0 zB4RE+x4_){C*K?{D|}i=1N~`&tlojK`v@g3b9|QQaCHLT;a1DD+Ouc7EK@*Kh3|(_ z95uM%}=JSIjDiYiG zIQW|`Ep8l~luLEQ?yh(eH6uqtx8I`;{bjX%W8wk&=cj&NQ!PU|r|lFwRY?;Xf8!4o z{Sj2xt5E>|aB|I1VH7Zy6DY~;xPy*-f_*7%h2aK(_8a;BiN|Ugf^TLXj$hEs2Bk17 z14L`hJ70EbXEAMBDKK;3;SX+9PaY);Q%k$w^E-weGR2PeU*>^GG$qPxG)W7{+bH#T zTr|M0_hF6vW**q4ydRQnIulUkQSoe`;0=WXuJo4*Jstp2S!|~@8S;y53;$4E27SnC zZgDnC3*$0c?l{~^t6RS{J@#XoAvDwts$KT(2ikSH`5?&L98*3zLuMDgi8^G)-w{If zg!hHVnIMOhEK$$01gcZdy(GUeq+}v(DC+M$C`1<4FyA}J?|9qo$%A};V( z(3@~n3(8WyItiXuRkv~T(wI41_HusZZT38`P`CB~+hrlwWQH$vG z5BF4V@`5IR2zBumd1nNvQ&<37vEHw{<<3ib(8{r*U&#yRTuk;MqB%^)Re0j-pQVCR zJZDQyR7lonMvXI{EpN#f8a1JOpXY*x30foLpCCG%iuR+;y18ohV?)=OzER%H7+tO1 zV~8TO(Rw2vpCly5G?A7?p#`6g-S+gz@{62c-hKV&bGO`Jh5B#GIk|y<6Ksu^Qc081 zeh#1&f(xnqKY#Zrd5e84^2}L>#Z4tiNsx{6q{2Dha0M_a;yeBvojI>~(MS4)!zlS| zL4VX_pEaf`+I>|QcEn;RyzuIjH>wNrMlbb$iG2p0kFicDUFwpyb3K>+RYM-?5gp9EIxz&kh=3nbHCl%Gb(Cx)>wu}l9DlK#+%Dv!3m$BDsF20=I z^Re)NXpP=|lQ=>3!s==53B)|4HR&Vraln&Unabk1I^Lkazz#@P5sA@Epf)E}cd(pO zQd6a9C1X!N-UCUcJsKeP<(6mv@mMeub{F?7>?@>b;LsGMs{a?!*V@gzaBJb@_>)|r zq*1V37}KL?c6=@r0S;A*f6@m^rMk)|)Cxx(Era+k2RoV=pcy0`$QB)ZlJh9(kcr z^zRcLPGr`gWLZ;l02&Tve39VNxbyA5;n7QKm;Co^)XE{c?f}tXC-r1yncsf|R44M5 znr$d6yz3MSnoF5v4EtSm-Pz(mAHr$HE+A%>0W?ktpMD3}SrO7+jd@fTT0rwYhc{?t zWNRkndaa=r2*hKOXfZp$nSNq!3(RG_$Bwm@4wUW&fw+8#Q+w*6O6uR>B?fXS4idQq z#LHxkuOSjrFkTg9Wl(3+Z&5aITIa_dT#2rgSqpnti3n~*l=~aUZ5LN?LkJ-oC zj5d&YghxZTH!AcAIvB|{J9iIcN8XKdtiv!VX~`X_lUiu$t-0h;VY_lKmKgCAIgGY~ z9JPAFk2GqBsxGm&vzD#^Ykc|oo%NsVrYtu%aEknz9%#!*yq{s`QuM2dL12CiX++AQ zWHE&zNMBMVZ7Qshw{&#$Nl(^_+FE1Ig!?r4j{s#p`2lhO@2P&oE6T6-MJAQmkzcmO zzsk$3wcAG$splf9z{j=V>s3OBHm|36_0rL12Ps*XPRRy-7TJz6$1ZNY5+B&UsvK3$X zB(CgiR3a;$O!NXqV7ye{*&z@iqC%EpvQaCctklhs*e&pRT!tS_WU&TUI8q-W;dD%! z#&Bx4U2~{Ap+2gae4CcsqIq{vyk`;<`6sZI2vQkZl=jtnf!gd1A8Hpx$IDe+;HZDJ zFW0qQ&`DYo=BSQspZhlEa|kv)7&Z2A2#q!hL_nCfs2`EBO`xlT@pNY>Y zS{&DX1TO@4W7|nJ1lNECwZ|UmXKu*Zt+ijtdn#wsW9>PSZvOhr2|#a9=9rQ2Mz;^7dXty~kq`cS3GvUgyRM*6Pc=-ZK=p1yM^RVZtuZbB_%Mp8u zT8w=l!B+!HQ3_+LE^WWnStG>BNYOaOkpeZIB7Tlilr*AFK35GtE33sLaWYIBtxNLoL{<9Y9oKUdF{lZ}%d7@+n1LjXL@4o~K&jkzzS1_pJ;*LWS%~&^!FEp7 zfZ+FXrq_e2`N{7b2qRk#Nu4F>XE~*Mzajs0G<2&>ZePL0ME?3>dh3c1AKJL|f zgRS|zbr%A;7~qBD*d%~oJZksExtq)J!{^@2sdCbUT^K&H;O%YHU<{5zWAl2=ux?km z?*Zo-WWDHDALGAcQP5bT{mfbhd}FkNpuc~8YR3Dr}H_H3w%K<lH>62j?OZYMNziOief!m13mF$ zJ~?yIYI7}_69>djby7x)Stoku>pqs?*sfUW=CXoM#J4hfbMAf2%W)t<5Pg+L=EbR3apk1N|--4j(_}a2o_|m|I5nBUa?gh1jjB0Vi%n z9$dC&!0*GPVi^*MM{^R1cL}Kp7Z#yHeh07P{TVI=l&~#f>{j!aL6cF!3RaliJu5B6 z3P(*_Ab}w+cIaZuP0l!jzuaA31@7kye54}C^`Cg0z==eZv*3Lbp$GXCHw)DGBV$5b zXw#$p>W6l?CJc`#?s^rk&0?ULi@}5p-fDwvf5o0Prh_(2QO#gXuWOAyer(VK$5KK= zkd0KHSoMjEZLi)6c7@05A3Cc9X+P}IC_76@Ec%79`zNVmjPHjdGsOUoIfJ8QISSE0 zho6|UZ`uwNF%!wx(a?$Tr@M>{R#y)J8}O~tF>=seG=`oJl>3n=myK7w3TCFJ1Gif9 zlQO#d`dzEg!09OS6>_wWB`MrQ?7GsFZah4q!+#K9`#Hp8?7$%VFsA!*IjHQnzE}CW zxQg!&GaXfb_$yZ>{bj&a<`7j!J{41q`PDt=EF+QMPZ9AV;`}{1M4IWjz>zRQOy9L)E5pEj1=4(|}F)jvo=C^0qkt%;T5Ncg{O> z2H?o87mb-Qhr5M9(&-`>5#Bs1yg|4uk|+SydE4%vi7lQIf5C{ukEK1L6+N}_6IR4^ zpwq;v<6Mac;%)^pZ(N+{hSX_^K?g}vMvO{QhW3^V0f3^*8nu%{F>13Da&&gy&zTP6 zs&~T22P4qqsFI}$bz~D%WA}%m_Ptw;KUy&2M}2D@iB%A+2_K@sUAVGNi*E zz#Jo^nOZc5m^e0kx4+b|)AUckrSKV|vb~P2Kx7ki4?<*nc5jzqDT;A+G|;*)bT3=M zc&Gfh{<7Cu?)lah@b=FYg6=(&8tuWN`#*3BZ%2jv^hd9`!TN^1adPKbo*;>d__o7tlfE44zaF$s9_&2x-~=6g%E&-`IaW4g@ z3eT~UHN(cMY>t1y5)Q6v@cey4lE%hXUQpSW8|f@F;*BL40^m2%Yi{Alx3r{||BwP* zf?YN>OVO|^v_;HtLTBhlvug}N(92`u*PxJKU=YeDt^TFfrKeGDGQFB(6#Y)b+~4 zXR$Y4I-yTM#yM3jQ&qZu484f~ zDUu;`G1S^4(nTg$@x6{+(QTZaPNX^R(H-gG6<1$dpQ<|7kbPP5Y#Qb}~lOe@X8{WB!pLPX!r6|P!*L&r>|6`_ewgE(Rim6GuXoRHw;~@7u8%QJDclI*es}~U zj!;a35~@&BK6?6XbS<1XlX@uTdbedc-(twyxM4*622Fd%8k$CG0FCv{yTmFeVXFdH zQV1Jy80d$m9E+m#q&SQ*N$v<$R@2ocW;BcX@ILYyxMa%RDV`d$f7O7X%IecgaYPHn z(!;NZ3`jELxL)&K`%rdt20xW zAP`5FG$T~fjr!R9cz}V6(Yq&gDp}0Jpq0Ei5C_~Eqoyj~`GzDgQ_UJWw|MFM7jaj*<#UnN>(T797ia{0M z8rHq3XqrhYv`nKn_rI#xfqw-0*NXTsyW*gOtmoER`UHLO$JH#>^pM)MnQ0KWGrMm% zDAT}(Bz=RCOW@?bZ|E2n&$)qX2xZe+6OqTs%rc2e(p!z8C^iy;=tTa~^7smBh&Fld z`^LJ&Oh`Xy)4vXC^g4(Df46ot?lt1?+eE2t6#X%S~vEW+& zSPI%1!M@n3ZX=q#pEL8|AVbj!TN$@_;|va_7IB`NwcT(sqggO+G;eGx+gFdVnux7z zJ{;E{SZ%Gd<%?xVSM%G8x_&!06L;Y}&g}P}EXJdoAV3RJ$Sthg3^;3MUXSMDi1IKy z>W&qB9u2r^w+6<6x2ec>#=T zD6huwtNmjuIL`ty9KL1;Wvvzyd@q2>$qu@ML*vgAO zil=J0cn<4by(DNL))e?1(bC1ngL2UB84NGei%Eoi`!)T3kqJ}tr3k_hv^*SG^eQ+m zha{2j-2~~aL~#PEa01kwA{FYgm<>;vp_b=oGdK9U91=*<5#nDMkalF$Q^5pUul44AsG>*8*AYZiqIf@gt$9Uw9BU&g{euq0;J(BoAX-oHeS5 zmZ}x20u?mIml1NeMD=u;K$sr1YiE1(&sn%>O+j<`;Tm9{CWjTvN60W?L=5{@A{p7o z5*i@}76Hv#0he0r%kHf-WPD}ueza7!Jr2z_82dPXa7U?0V6Zi>?cu3grZxke60fe| zMP&A-xP2Gl?h~H5CnDs_C@3+!jAEGllu?LxNs{k$ya?FAPfyXwNQmmz`>`|E9|kJA zT2x9*i8_ouTx_`Hr+>O;;~!XAQ#6jELPsdxUL5OprW<+tcatyUSp> z-KX8zB7_@obM>7q^vkJEO8MQ8N-^_wo?*Gq z7;^QAlcFvv^~vCw<`9)~oa5BUG8c?&sk7-9RYi8OHIDM3{&d|gFaky7SZGoAK-U~a z2zn?NWBrSX(S+62S}`uLduP&LF4?9q4%KTTx!khMSzpfF{MaExM^U1kj`y?Z1C$Ra zjU@xuAWOQ=i~I|@sjKRq5VDtcf4_y~w3e}&Y@WY&EP0utNC(ox)n-kw%rL{i;16ul zr%GOgfh{tiCeuPR%>MX<{+C%ia$3ppQIR%h-v;mg>h+6;?JJ$8T-<5E!n8~J3^Zc! za}d3LwRoueng$5|;4enLc3kSMEC)+lxn)ETHQk5;fmKYj+KZ9_{{HOz?h#a?&<8ue z;Bnz4?2Ua~dF7-0+(y>X#C74tVKuwCDzIHdSlL;9CH?3}ap+&}_Pkw&4o`%)@=XEw zITz`fyA%f|!>6Y+B9-lEmVvS2t`ap%$6652>n%ohn^_NhS)~1sX9T9u<@K4;Q!&&_ zOf*JRkeR=iP!j3HpEfg336!!jaQxNV+T}=_Pfe^%bOBW(^CQr!%P*g1k?X1dJ0)5}YLb5wgE##m`?+Zdx?u zpk%Yp2{QTVnV-{o2lFe34C$z;*I(YK75amdXKe;gJ5k;!WhLR(avjEe0)+D$nH3?7 zE3%&H2qx2tAGop`tq`cnb5(+(`xHePiZNyyiu|dQ`HdlI~SgnWhPVeCN@Yxg%-qdGX zt!A%p4Uck|5oMNbTE5pnL7tK5*}Wy*)WGJkIJVJ<(!V$=o=7XZ-02FVv_mw>J0Q4? z#a5d##K=pCiR{A%r1exPPNPz;4UWTBtUtu{YbiZg-ECF#*as#m4?6M)F`c#!kG(9JWP^m~Pt&@HjzQA;zvftudI4pdu?%75{;9(ZcH3ZM`f zTAvD=JZY+}aiPMHPeG8~l^+h%CFEQh#JDM06hVC%TcR<@^B_-C<)*==m1LOL*87lW z3UV_Eq~c`%k{(FvnET*aDP0bDs11Y#g#L)eOi?=9FfAzhE&0w~vjjyZaC>Ag8@wtk zQ~Tb+jt*#E&)K0`U^!8H+02=%+rfHTO3Nn|5wG$)0GH0pSvE$CGMVtwYCmf++@ja( zn1!|>3#-N7b!U)hc!}SeiM~+(J6W5LX>+T07Kk7M=GVZz+7mv<)_=#ptUs zekNGHcWK-=w@Yy8Tt8yH{=g7QS~Ga>ablbzOB=(^i0jE}N$w9_i93gp`aA9zvQ=u{ zj3^bTz1H&TW&K(yts?4tA%t@i(6SkD#LPI^9p)wgDX?5ch?W*VQ-X^KBiyF>6D_`QNR3fWZ}BeMt04Q5&H$kgIn_3WU-cQ3*%gI z^yw;I7SDPj`OsktF^?)EnMC*$fJ%0`X~{zsCcH2N9kPeUIQ(^3r zHqnpLJ1kU0{U~PVJ}I%IANueIx>dcWGeXz`##T;dAuZ$!h?Vd?z$1lhj<#B5a4I3H zkG|q|V^W5a!I8#&>>7m2h|j_$#V1xM*n(1bOMAaluPN{qvLe7G=ur+)IR97yd%KRe zmB*G77$)zMV)d}5Yp-8}8j_M>KNq)rZq zac3Vd=bg5;T1HOdreYO8$=8bbV+)KgGzxgxLo;xLS$zx6t{8^Tt&_6`h{sL&r#YRz zdasE;7w^Pt$?iR_5Ku86$ybv6bVmgWgT_ovsrX`P072y2`kNjQ7k*0H2!lOcC~ex8 z_iNOGuq_sb12_5*f{2#2&j8B)C@zW4Y5*XQ?xc_bZ1_Q+mk_1p^i{1e-||;2D!=mGb=p)LDChE$;2Ds}#+8RAvf zi*Z9*pF>xwz*H<#5P2YnYX*-dZuhP$>p7cQ;(LwOaZ)6#TvlPG&R#cNlB(A!2wj+& zpBaj0`pJ~hCK$~5g&x%zCq9!%lyifpob?AT?TBipEQi#bCh9zudfvLDl(rBcJzllv zc+y>{TC$V^xk+__1v+wkgT7^~>VYu~xXVHN^bS${E*&8XtwlIvlRuFH7(ESA1wNNJ zQ^R{R;1G_u(mjbW)9BuGN40x_@+hXUS%o zXI@R4Ol#!LJ@IKS#@evWEgMCiI~6?>yV?Nv9l{(6yC2$Y1F%USa+dW9DHCIgwn_F_ zeOrN=?6R*x@Z7|QZ(Ox<`s3Gh$E)!TgG?&qht`uQq_kwCTw0UejneDV zbX^O-r4+ZFqgB>z7P3FQ{LmtqnP9cVNB4ey{RkC-MNpFe-Sn8}SJoseW)vgGhM5vAQ5@WInBK-(vQ{(pc@91Q;nI6>KdQ{ z{v@-ouK`|NX;ocaWsx&8Yq%gF+}UCTi-MnBn4E&3z2So;)bKlwQIQ(Mxi>4i00E`&+0)WQ?fY$P0!?kaho zrSjWJ0PO3Zot^wD<>KE$JhL!0hXW(e6teP4E3SRGvOkxM z4SX!D5_n1%`m2+hO-hx^Gz_~k6Zb3@Y5fP{al_cWF1aYNkQf2RUg-VMOTndve{!|O zv+*6Um7-kIqY0EnRGhTnJhxBSf( zGB^-e&)5_aPz}KPs*n6v)Hm3F#do}R(6#vy2&19bAr`prXY@9g?NHT2ox@*X=Qrb* zLzh+A8&d{Uy`-1&M~sYc{|NNX*nJdEZ~w>y-0n+&ac33%_ZP0v#OC#t;U~0~du;=< z?|0Q)ck?M1+4D;V;G;J+5b$odUMWjQ9U5frSIU9d#l~fF6@2uUY5CXb{nzjfU;fAT z&+jgHf<3tZkJ93A`R{MpH10M3jxTms!V2y~2f)PNT1$YR-I9*J-V_x~Gvm{nx8CLl zgvV781n^D2AM?WO%&2ViImu}_1M^RG&7Xnh-!;ZKT#T}lBa_$BW*|Lx-09zi?wXY1 z!OP|S7s+ux<-XPF_uHfeJt?wEK9#7%OmMxM3yYiR2hJnaaO}Ow`;JHz{#rf>7(GK! zE&&~FfZF4C;Hqpb`JXg$a6cI+h=8mNi8c6UH46&HThyv@szAMoQ- zAJA-qTB@H8pWi(0+I~OUn_8x?(ai7VyIsAkEC5z9N2%3SgWr0$V#>{4qE}1SJInoF zfZI1ftG~aBJ}j<2-SvG0dC$G+yY^qvKf^7)dNryTM>j8g4c$4Xy7$R3RtTD^d%gR* zn^R!-P9JOomRw$bHNJqq%WhJxtE*mde5!}el)v%6U1xs$ba^Bb167H|d*GiP@Yk)n zL%SXgS5c6^MeFl2#(MYKcGq^jqx{k)W#ce9j@@Xoco#m6T_iHTBrW1UN1vU=fcJ)$ z1s~4IjF8Z1>a}~x(D||nz}L{uY@wLjX>YtREZ*5$ zbGjRJp1qHyi1iz}E;?DbBg$fr6{+VpF(oLOLUgoZG z9MT;@-Aj}IgwAV;^nhJvF}O1EQYC9-*=P$d34;X{)v2x#CpPsUeNsSyIQA5aOnyJ= z&8-d|Dt7e7vV=Pdx5jxu8Yp})xW9fpHz$mzNo`U$!SL1z zd3u#~udH{v2ypHjIgfK_S$wASQYmM&btn#!xp{8{yeM#eXyD;;ToytU?caHE{Q|8T z5upecuIF5xD}&N^&xVF9^o8|{M1=fRjdDK$TbN<;oifd}y~ z>w!KemGXk{1BpE3_q>84uCYewIRy`j=5bmQM&{%Oi8|SQR4#F5ovD6EQ>J>;i!#@_ zET_GEo+bi6QFEy$kFqeqwR;*s;HHdOO^%ypcuPg^V>pA}TWP4#S@^M{rPOVZNWyx= ziSOS_X$SH*0IEJP5?9seN)Ap=O*FN=LTM=IlQA>Ry7xSh#6=cwlUnQAM5#5xlLSSB z&}yj|UZ$Ir1gqv7+TGwao{YnELW)%ums{?hl_$V#vnIrZl_Jx?21z6wIU;X`o(uQV zp_1IspJ;+pi4J4j0iOy9(n88C1kSaNmi1T~SS(tKGxh*DlAi_*cjemNrW7rhQrxt_wBYh}s%mR$b0|{0r9mGioda7|67!}=ZI)@; z&Z0LXm4M7SzrMSEwyZ4CeINrW4^_{S|8=@JPJ%^cjd)l-HZat^w#7C`?6GGU+ z>g$0-$SG`0`YC|zn2opMT%5K`-{BNAH#K99D+Y4`T7T@V8fS@!w1YraL#na2vVdz8 za8;98EjKv~leF!T=3{Tx z(kl1C^R0#`Qe$nrN){E>7RBjVqiW2M$J;{{BIz{N_6vZXmZMh40!4dRkgZ-~LsQ8U zs(LCaq%SOkmnmr+uF4Y&d@6HX-1H4UA@Q?L!DyIV5%lH0lJRf(V|#{}PILy=lbxOJ z`c#5=oz0ran!o%TO3{RA%wWUFivI&|K#;%Jv*Th#x}09*`+P1GN>)?VTW_6yzu)H2VT&4+ z5EiSwyg#B~Px!8%=j3xoeRMZ*GZ0AATlH;n2+wn4b%WE`sk~<0|RM3#R{ox(3|HbxNC70Kq`Y?`hidh%&mFuNn6J9`{$RMY+0Y%QvP3r z!h>`P+w>z(?edSdD)$YuzT2wU0E|=)SS1h38Am*LyT;-!+CfU?!(WcQVoka;VO4~M zRgTLRH0%qh@Qn9n>Aw+s^Agt**{rX6vOpa)YSNr}0%SVk44M*3Y`a3`_{ZEh<&xRr z1#351Ai-+iA6=;QRIT%R@L(B)1WKexs8pyAe7+jj&Fe_S>PnFK@98ka!7XbJ zF4++==bZ$tmYir{<2U0Mb+pMu55SgpsAaM4cPPP4272AX6%(2oj_K)yV-XBoT&m~R zplhkUTzQ1#-k|`8nG>9!7l}h$18fuTn-ksf&*DBrnK6NUiIHxA>Nm4-ref9vJY2+b zYii~mlRiY+qj;uYaz=6c4JtUu7|XW@qOogYm6--CoCCuIeOJmykb|n!x$yUObOh(~ z+DF5GVxVJJtFo$QuiG)V^YK;8l7$@hgoWDV2pb8ni&4s~-z&=8YUNoxq{esZ1jT^p zK{nOjvlcC;s-jmYn)l0RQf7V_Z9LtXzfuCr1Y?5tbORIt9w7-D|wn-E6==?LT6iWgSppzsg~uvDVnSOIsgb%B)IQ2I3bOax6@pB>&PIivUPRdX zo3bb-E8No6qs#k=c-SO4rpqlUvW+(zrw4)bWa4O`CY;G*4zp!Gch(DcrsJ&z%KHlu z!Bge{pP`0H8Wg9tnzdXn*g^JGw_vQq}Nia@_Yq%B{qxZc6!}CLB~g zPDd(!fzJIYSkU!rIuR5kb5D> zs}JV`PC2YwS24d(qiig?q_kP6&OyHIddE;N4W4@9m`stAT1W5ZBvwcOb$MI|X3NXgag4Dl+s#*G1hs0hOep!$G&7R|82+aX5Qsd>b1z>LrF&J z$=z>d7|WOKwD8ZO_f1p)*H)$l%4Q*jVVX2r^(w83ys4Fqa5AidQXW1k z5`BsoO5I-WkBM}Yszw!3UqzY5wWU)NhYX9=Zt$=7_(x_+H3h~`R@`hIZ~+ua9kb5Uyj|9al893&cOz2u#9PK!euwZZda#H8Mqc=zVY6( zs7Mr&lH`%T1eQpwx&a1X4^PN;*$Kd?>lV(THg0OER@5w$M%OiC(;2i%LeAgdu$wVK zIB0$??=u?s_U~DTdQ-kKS&t3)c$a#FkZ+jQN%&L`f6NKHPo4T4LuWV5($^l>P;BrdrZ zE*^JpH{^^ce^wYG+;XIhr5#yvtK9OJJBx7gDzr&FT{OC}!5&9^wV}T(^TJbS#(;xZmnbwa|9w^Sk;akFgU}ypigopHV?+Da7}q*dU*(54(dii?^J!pWGm1#k zKIogeb9@+aMSj3fhOV%$S$B;^=WNk}h?+!nXeKRJ0^1Ncg<5;DU$|Zs^&!&q?6Sjx zW36~g>Mk%bWdlhLT68U^*>421h2mV^g6Fs0gCHO!NsdIlUI6zf@n;m5__E|LN@j-K~qz#$k-&QVmZ3WXHq#o-UhAo{bPjnqhFt-vAm9X3a26>ddd zXx%4ZgdaoC()_A&j#q}jJDlCEh!BzwpZmRJ~(H+~zaiNJ9Kpt|_kie-y2VyGUbWLvJ!vJ?DX z)AiZgoExC5rY~DIGa*RE4;M{h3|BTupbv!~87jsdn6R=oNl%P&n;9>Hn$;81G$bWw z|1tl~mK&ZcUa;443d$~Px5(neY)wtxxWnh_MNqFGZAuN5(B5MDmvdkogZ1RLj8BGH z(?FAG{+7HYl$fR*ZHmwfe0#z%9MA&{#fKA=B@;|yw53y9&eeBeUL{W9?cKg5aQ2f4 zH`|h;!0Qw~CD>wI`FZx!2Aj1%*IG)(?;phjTa>b8DOgo|bk@pllZeygdb-+A{*Tv< zP0jkfjnO8kfzxv|_M-z7a-AoUs&X$#L!&X|rgvW>1@}MJjhzR?Zz?o<@+;)UHw$+9zOI<%14l{ zNj(uBb2i^MK@FO>{jKT%YnIh?oU!G6dyiJd=kC2s?RuWFa*^zgV(o9~(!<34-TOVo z(~9v-*8SVtu0srM<|^n;NG`*!oq*hVZl`K!?-G5rDNr@&fK*1O^Vwwr0biujeSf`| zMOGku!R(B zxC#lk_$)uUKHQMnZOzGvEyo2}kB2-tG;6T_&bWH=pbH#uWW}Z%)!gcqY8zPqc|Vd9 z@+RWvqv>DGO4e8PIUY2ce65jn=QfqiK)h{S;3$5;gs??Tqdu=kk8GZztiStI%TWam zH+_&2@pndG+O;mX;kTtGy)W&9HWoWkzB8LQnQD<$ycXoHKq&Ma_}vD#E$`}bB3{a6 zEgrn4k7egx8Q8tD-E-bCd2%>~t?&BgfK=-0S|B!h(TWUFqX>2dkSGqpLi^299>yck9ynFW+?HiYKY+`j927amw}K1 zZ#a4Sl$UnyYjsAYNWL?zpK2n=F+T-1Eo^ATkOdU^^1_EOzd%fd@eVH8J z&Kp4i3&5_o1JGvfw_-5FesGnCoDm{fK!BZeTw!($Gt0+OCQb8m^)85`99&I z1azv)Ow~TRc#n2dl#npND{{!tUwDxw2ad~zX)Uc1=cPRGl?u}kV&jB7DfbOr-ns1* z2R=CP%j;bxSQnIKPQq@!j6Xdv;VcyENgtM^ycuNuwL#G}(L>3ou%yY0(Y2^gR)a*c z4}W66gicC3wIIH)fW}m@8~&}O4GDV@TlgwPC2xnC$D>Y@SW6%46V(!7wbJL8cVi{T zd!iXo<8;@DH$8U&G6YsSvP!eeOndllc$Koxh3h74&1EhPJ#a(U(6&*1n3Z>T24s~! zAEe44VrX19K54g_W0!E!rwzA@a(n~)KF!>mGE zN{3@t7GYGYqW)d}TyA>wa)P`|R7>DUY+mMsU{B=*6;V^~`wDxlP$ff~?YizPLQuy$ z>lPWQCfnF0*7MBP_U=}6EkYKfl9M9-h?FdWz7w$K5DcEJh0KHd;0p6 zt9{A{7<#3)Ryxce z9T(1r8T_bSlzH#TPgm9tlv zD1O$k-l}On@lheuXt^Grtcv6u-|}#gF!1pX(+}YXq|=^bvOhz7&-FP1uexip`k81% z!K0g5k=zd&`Me=?JXvQoE-n)#^)W;JLxbV+s*v_~JpmH9;Ke0TOQvg@^;+a3m9}LG zO>X|M+mP?|(9z}Dls&V(ne{gNS_kbb+a?xex_w9pOZ0V&)PN{Ygv#4}2E2%<#H~;h zTonq}svdoxBB7!%S_0S4g5p;4l5fq}!h`%#SnL7NJU&K0KkhHh$qZpjE62|n zrw>Ye+RUNGhB7|mq!ChY+1-4<3u|k#LAG@;a`+{nV1R0Iz}KqS*>my(DU{v4-7j({ zB!1V#QEgwa&kuhdP2&q;HPfvl{Gd;bT7Y(SEob#26%E6Zh#OU>!Y5r-o^n>J{*5YP zF^avp&->yg#MK0Qim27gl1+j%kmZrt&^9*sT}`HD-F^#0;(7^(@K`EG-6b{ywfcZH zU1kg6LgI%&y9`P#P1_pK$t=E107086{9bBiTR+^(FyYyU&@U^Uqu5O(C%n2?<&`aF zQ*GlFkfC4ps*$p?V6oIAyLZ~RY{;?lFLEAi*PWPdY}(6|l|4izabiuYUHi@A&ySLU zmA{{yi$~R`+djk1$p1)u|8rSHG!v%d3_SQ zJ^W#RQ#pl?gY6?SP1mji!&+zl?P7PYi(`~R;KlG<_^{YrtX!#$^(Os zVX0Fn1fNlC+=nJFA%3A584E#58!lTKA_kX0i7-}a8z@mcGsbrye4G4SJQ_N=Bo-|O ztgw%3sc&n335hF^OL_i^FL}tq*_->VKc{Z^GY}U=L4lj%8-Mo3VunFqH_AR+>Jv?F z`+yI}tCY<5X=eVcY3@_T_^4)Np%J8UH^D;eha_)8o zR+m@ZWWZ{TB6@q4evy7%M{93PIoc@*Q!K4;N1t_5ZhYWogcgX&qwF$E=kxK$r~5sAjca4{@%7jc=ckh( zi@=b*DAuBmTFjU5Vp9O=4mc|BSoPG|VFYH=^gwFbJ3(Af*`KUsoi{L0K=lG^hL$$U z?q1t}-k)Y)D7PlQ)Oy*{Jig%w@okQCZU>AAXOSuHjsc6&F`JABG^ReUQ*Ct<3(^6@ zh9!!p+A5A>+tb&_-+kU0a){~~u#r0F_WFwmh@&ZIPs?m*rH|LgxRm(_?X4yr{c+#% zm~P_2d|(vLY+h&^Sz8+cWiscD(8=KbqO-5O}`tTO$)!K?S!~S|{-&jRM;;Uz? z4R^S*>X;9|NRF)GGzl=-@1~M8e`#!POQPL5#&7(B zvE&c(I8zOKv2z~vH#D{=^Bsjv#KGH(CW`&KBAqEg-S2&^bq=xWSyxfSyLUR6IEl9> zg+Y;N?{N3vL>mqL;}<5|^<2)=z>^V#yU{Tn7%$?{shYHK5wrEJ(s9g!_1lHs zu5gYS)ERjN4)*R>Mslv|sOHlaA1eZ?m@CF40F=9jc1x)$hJW3*lAo_PgQyO7nb2M%rXXZEhZk~UaXv{UE?u~Hn4p7vu$YgwT(qR6U&Wm zL;9_*K`giaS?~g`d3fyg;1;LG$MM<)HuzZ|S-~IMAt;UdQm6h~pAZ|PaqQYuzU;KC zoWpI3eFIVuQ=X&)EEEW5j=ym}J=&$pPS`y%0&PgGe@l}qtz%qap_+ugdu?^#bYg>E zn-zO>@;Bd~NCWAFp8{Bv)pf%1A0k@m9DE^(`|*9Q4%SoNdn|?v4|s@&Q|w%y2qpsO z;m5bbVl3oA7Y$`-{toSG%jh?PVghOSyc|1q+XAe!i_pa*(N4QeySLe@@0~uzY9#u? zwCKddm-U1*)oaG!we;F$Tymh*D_HRp%8l@oyVWkrqAKlS^w6GkX2bN8LRN8nBG4UL z`=7iX9(qc;tU^kj|m$oToi;;2o-5j))qE)^u~&7>uR$6{#+oT9fTSj zRH^l4#B|_y4gzD_yWfc1sb`Q6Qz%qHP8JwcOnX7=BF%&J!vq^a?r+q-fmxAG^o}%P zDr0tZ$n7Jzl?Ngqt0DF+M7MQ_jlO|cAc^CNPP{q#xq0p?P7P+tF1dC|&ylxX$!!&A z899*%+h^O#NSIfv=-~u1o#w942ZFZT1!B;(B__P5%{E-!sRrv%JRod`fKHSlb^1+p zTC}KR2`5uq@6frz%=ZTqa-EeZBSb|k_cv+tqct>dq^G)dLvxHrqRdng&(dZec_!E& zm@u9eid>;e86dw-e}Z7GGNDj6*WFu<2k<7iGJ3FNsV?gaOI-Eo@?@gK6RM*>rj-$A z*JkGm%SG$CwItuM3Iq*yQgz~zcNp(;34^9lQKP@jZHk?LT5p?LlIt~85v;YHfOAo7Vi)UH1VVCJxEmYJ>R=9wc~+KNVU*e- zbX@yb6UCVtEeg;*1^dkN4i@G zX-p_;r{)&f*R#C7Xsm=BF1ytxTUYep06iULB$AbQ;KkYDOtvvXdT$o_O0_Xa2)dUV zJ?+sOzRpHsxRm1=c5ehUEMbG^2Ir`I)Z`O36OMAs-bO9iSKB?4wIGr4QPU!>q(7_N z#C#x3Nu$$`=k7k${ib6O{!k+kSh8C}G44T|vxRWUwtxKYJF@{hOJg9Nk0ToLHNw)Q z%v0f<;lWOIvn}QTrC_i-=_qi1jqebvLkP!(I=>;=F*{xt2cXPAxKI}%mT0|SJYwrA zn8XX+89m=thPfD9{kATRFr)G0#e3G+W>xiLHVv=JhrJexR<8MCL72cf*LcvCWNR)J zxQBeh=-V|NZ4v-PJi!!nXGTgk($hZ0)htuoRO_Va&um-b(qtNoj6H`yo4NmKUlv+? z6Kz_A64N}rQkcFGx)Gcq3>*~JN54ODrP8YxcXHWZxp6Gauk``Zjw$xf9VU6P7l3oa%T`3^{yewpH*xRHp?+CV_^Zh##u1Sr+K-$bMZ^Cx}d{YJ#v#W_K_c9bE}V%sFT%A51&LJUwDJd z8U2)GX={3^bz=W;z0g~<`WPLz)=V&{uu&rfr(b%?z`%Cc<+l|^Q-eow4i@>3sL+`l zntk;sTrq@CU5;9p>rDFk4bTvv-D9n; z(0Z$IhLR5EL$9~F)sVd^^U1Vc0@HIh6h2e*cET}zOZedZZDoGLVZbgf9Og~%JEOQc zx+CEjcIQmNjm3SsyQ8IL@hfAVQI)u8HOhA|Nxs{{W{h$y+e{UKV0Cp`1;1}H0YXJi zlTPl#w0&U=UHK=Q?GGAPd!NG6*72hShqRc&a*4?@w6hSr^=rhb9Lgsaur<~R-)yRWKw{<{E zdR+U#Fx!|s=jtJO5z)ED<{|a_RNMf0!(5QRM|#?YeEOD_()62iJQC@ zwin|zHN$r^48~LG#a3scy;!?y`AZK5foEoj-^n!m zC4ZDUk}O{8rOCHA6DX7>w&Fs;qs4C%Fe4Y$I;4IIEoH!Q&&M+%?;yw;>~H+xkFBP2 z{wCGu>2jQ|_~ALyukRDB0W%l@NqOuubf4y0tqU{M*A@B;be+l77*nkmpvUcTwgF{A zxrg6SC_&z2sHlG)uQOu;|AfY_PpVS0TsC9*lthrGA}dVfDJZ)tQ#}MTXpbs?t*HZ< zWINb<<`VYHE{yjZJ*W_Z8WeT^1^>mQ?q6ITr%GE9Vd^`jtSt%7vROm7vNVr(>Cm45 zan-o0X5|f!zyiSz?wM5KXVVxcgQZqYln}xRoAKIy%pUuKRlfJP9MGCaqedHV?rxe$ z9GrpQ87LB*#P6bzBLE^lR=LWs`rMjF%8Dj{mI2?ZHb#q3wp;q=~)mBuhjufV4@ zr3*x|6VLh{X~~k$kw|)E+&tm5V=8y~+Sl4%CR+Pz>c}!rD9Z>V^1{2;X;2EkbeJ^y z0uUXYiEczXlH(X`=zY(3VI|Q*hex#p&dV_O-m(4;|<)zLrQ(*Q|X-qQ01G<#C=D!vf{8oPeQcwIe zbHDkZM19-;dBjaFM6ATnNDehZufL*~77S zNl=bEGoMj7?C%YF z5gRe~YdRc5!>o|j>=!kcF&iBBZv0`1u$;*8v^p9)#+L`MqlNR;RQFlC)lfn|H%(rH~%d^njhhr zSZH&b0w(6{@lAk*Xb#e`E5)bSkOH2VY}c=&w5`fdKaVM75aLQJKQK1=duojlq{t!NVeoKix>^zp8 zc^|@Kshs)YOjj<)nm?5mGn$11Ii-uY1XhG7r)Y{~!^S^-vu`--267AyFQH0Ye1g6k zbmildWt*^$*vel(PR-!1wM%x*zNLmBLmEA#+sOvTQ=TWD7f^@<(f4`bvs~2rYP-(v z-UYmV`_@ZW{~xU3duxOPAUQBI3NK7$ZfA68AU8EIF(4oyARr(LFGgu>bY*fN zFGg%(bY(vsg2!-4T;%kAS(eR5_v(Q+7{Q1oh`mI zF36|+r6QlP^VZ2{>OvelH<~U=Tee*iG&jm;^784rY2To{}98rTM2^dERSovbWDJdnHiwj9s+8J<5j2N&Y zg4Y47D^oP3WNA&14)RkZ&Kl|Y0Fx6z!RV8SgTY1sqpdVczgbq*dg;l@?yxokPq-k9 zCu`(nYsjLpRh|%z7)XSaGFpo~;f*&3Uwm;e{P@qaWj8!HJzcF2h8LHw*8Kk6@#${| z!&j^G*UR%?N7<|6%i){h$?))3!!HNJ^X1{X`_+}uXV;}@d!Hdvw$Hjvd+)NKJ?Osp zq8nax!`G`HSKaWa`_u9tmy7lB>a@3?bzgpYApbwXFhc5s?8NADA0Zxj>}Bi4F!mv* zox`}ee1-q=ILFe5K76|Ico~nCt!i`bN6|w*l|GHoY^5*pe`7qMhtS&Kdx)}+sfUIW z5$Ur{H?Na%pKu^0VnsFsk?qunJC0)}FORxkp@_!rc{lv@^Dmuj`fNj=L<^i=o}9eg zi|4zPQ!fhfRJ_gWY_yUj@h`>N72eH zayL9&ovhAZoGlKQozrKYE!OMh`Keeoe*Mdb_17=fi}kWItT-4RuTIw#+Q-oQGBM&k z7K>+GeduvUOC|UiMnQ~r{USESn+YwzT+}Z@$%rMaUp$P^^hIn*m`KB%xTz(=KGexR zh5;J=^o$HAY)Fgw${W%$oH&h5`has%hXdO-&BtM&69EfbH%@3UiyHzm96xeFth<+U#qw-%v^^9B;4QxQZ5i5}j{u z#S<5xhwpkTp3S`-)2(=--}{npMH3&T7r)|WyjwKJZd?<3QSWy{7QeBFA9E*Uv84Sc z-KaCco^90mrfWrhwuNUqa3=rrjoNOy`L=I&?Y=!DE$}4EE>$ttHSMkyH`?TBZw5H8 zlMV>*GN%@X7jBp05%Vm8&b@Z6GHSMKo%tiXRvnEC=^Q~3hJ=_%Kb3umi1d4@-)p?ERh`{0bC!)^1nMWk;ER6nzd0BWWzS`K!W+hY+Jv5zdHZz0%IHAE>F&ei?fU2 zeEDX0efVy*UY+-E*Y8g5%}-hK5!%j)r0WzyNdHHNY{$}P==NfS!3e}*y`c1ikQ zFHfb%#o=1^&hmBt?s(lVUtfMU3qssvI&O0&W_bIZiK}Q54`h2go=vGYcc5oQVWj86<OHb$H=dplmSJ&t!iWiSx1X+AO- z*y|O{9Q(#VUvUv;&cn>y&zuLGmR9HCHVfYkXGd@T{ow;KEtwO0_@HC?%P+O*aItAR zTue=TRG%l-+4<3{?$-_bhDXcaj}Mp6zy9ha1|VLa?-RGH?X(=M@8i8-rAe4F9LN?b zPOTC1h4V#;yt^cN&hz*xcToa%(?zkeJahykCeFO17ney*LS^ryk77r`uCz#3pRaxR zjAz8hsy!$kp^?ye`zT?wr4KV!Xj$u(WZUYKSl|lV8pUbrTefIDtheYbR|H~!EfXtU zhcS6m@H|d(#j57o7R52bA+G~=$wGs8FJ)21O%dJvt7v2ya}i@Fy}+ZFIf5A_;>i-& zPslya9K^4Xnn)%Ep3#G|L@5UAke&F8wOmZ#0K~eAy(ck;0TheFe3_MH5r1Gm4wgr$ zi#TGbWvws4g4?WtL+UEg;Qh874NliL&ugtdQ|o=))X0*G<57{?2NVfMM#9$YxM*?H ziMA@kv`h$Qiq8xA(Iw)5 zzEDmb&y~xS(!M`qEksWdZ%4m@ME%%Z+tQ!6G>^?|uP9OU2II*hw77Y#^;r8bVv#w8Y3yVB{Wm z=rdN1yYlpq&7 z2>Kfvv3Tw&-GWxc*P;*0I$zsm!Ahd0+rl~Tw2nC(5irawda4nJJt>PW3yAY^E*6(P zIH;nKGoA~X$_;`bawU?HVJ^~0^QI(J-6sRmqElcdl4y3>>c|IFXhvOp{fGwHI|Hec zQYmFt(wrb#y~viYknP(RiDhC#*X1%NVu+GQ=Y9p>t|9Cp%<8hpj^;`kc6 zsL(l)4EkfR)e0NkfKeyNmqM+5%6Qwnj-qH@I0D8o|wQwwl6mr%&2O?B7^X zT69H$dH~F|)VAq-SY~9AFmU8&#g8+0{?jKErbxfDfxxKWJ$5#XP|~c1EC2(-1p5{P zW0>UVSUW08dZV&nh29n7v{V)Gh8ig=h1!c{#1*+;wHL)CEG5(Z+SWwso9(Q%q_s+M z+lCx#sc`#U+qbnXKeW~cHCwdl9NEOXO3`BX`w^k9b8L6$nXL#<3Ur5KEUD#?!_M+u zVD*Lcv5$TDPNeI{{+71ydCTn4d0iT5_6cuz$XPg5(=(ASGocwxptr~moZuh~%oQq5 zWrw3vp|F{R_FcG+Oj(FT(r3sB0i&UtU^2r}Y7nX`(1${T!p#W^NnLbK(EIQ#(`zlPAz>+#zsO@}rz=ngtIv&_ugU!--o?$4Y^g+4j zDFpu*$Qw)*N)(^2eMBF&UrJVY%JY~)w&anWXxi&jtW6yG#3YRt z@Zbhn5dw``(4#Mww{1EPmg)R&qpZN`R7jh49gRwyVdl!-1y=k@d(%hbbYwsASuZl&(JNA$NSlD~;NA{o}Zm2wfXKx53r+x=M5}wY+Vs5{EKO8_!`Q`Khq*&_!WLTv1Oq zkL9*r%ei>wS_NhXPGMpKYgM0Y@D&G17r5SpT)nncd8TDT%1x>{ zg;b&FD*izhc_D})NnwDQuaq;7OcclaxPgk(wnC@m8MXVsO4GVcFD-;tiBk=aH=$QN zcMPI#X76yBf$l}2UP%=bdL>e?z~OatJfo&>Qq>x!l2#J68(Vk)Pc@?5C?+BGOPEzb zzs$L-Wvy>Hr>#mFdL_@wOsUOqDsNa1?O<&Z;cGph*U2zevqP6bTPE?yh#oXi6@g5sJ4TXxqscPCqVKd0; zYZqDq&8As~UJ1%dU7cjO>kIXCzyJ@QJP?ldz(g=!SZo4{s2i@p`kIp>v#uEA)TDu%Q| zxDg*Bh@tZlQk6r5r@lr5FleYpZpx`EoT{D!zzY1bw?H^yEL~M#`&JTR<1#1v*+7@NyXXemTMHzMgbz~*ld!PI=+`0Ro8_3 zRt0Z&k9M;ywOH+b3yltATQj^}1Kam!uZ=>fwh>!p4_K#XH#OtzxEp!C67*_}uPm;) z#%7+PnYv;&OQ3anrl8dId_aRbrN4>)?WX(93C4D!S4#~GNUW|#Q*Ks|wX-#~TN-sK z!W>&M91kEIC95t-(^@5|32wJCF|%Lt2iJ|dD?}17@I|V&9pTODu?%0X;;SjVq`Eaw2M1hJa6wmtsahuOEM0|2cTYWP%a8)EPwI^&20FW9@@p*r zgOaz)1;KVNb=jFr;k_p0q!C8unyA!ESbAFOsPD0DsWF+JQW-scbhgk~=)+;YWJ&hc&s-g#DaMT)fJp6l#$;T^10*U{-Y zi7^!~;&o+)*m(*exx4UEo!Nww2!=d$YTa>(YpMH?C(MDm+-tf`dgiUICZpM=Pp_Bn z0?ioFX`9%*`@`2DorFYFZuGd6=`=dB#zezQJBcZD&&3z5$^=QVOtu877-y>aG)%=r zb=#|h786!aQo_3rj3f|*pE7! zLIW4+s~BDsP%;eqLtdAKG1u^cK$ox>wc0)n;0D_*4MC|<7 zkrw`>dGvkq95|Dj`BovIM^bYknj=Y;VyGugJQC-eL$2x7nl0xIz|9%rsCO$IJp~FY zw` z=!8W1fY9nuk8T~xgZK3o9yYJ1%_sdtc`Am%zN4fv`7O_KdpZrLcnMPnZkmjJq`2ud z0#jkmn#2zEQbj8OW>#M@ZQNY5Q2GihPSdKg^WCUKw@Vt;=cp<~{LPn}Mm9n)}7h0ZI`^rP@rS@C&2%L8Y+A3Vh zn6pF6THi9RPMf6b9pa{}3)$kd3ml@_r?6c-UF-&5alG-kkTES^)1uSSa>dnAToVr+ zJ6>UHXIj~DjrEm%db5ozZedFS*BR%GZrRX9oj5Hn2XUE7Z6XWJ0V_*^?WIEe{hLu+>5nbT?lqY6sldXz?FHw3!W8)aLcKwr^rV!QibqFD=NzcxMwkHHWP*FCC$w~| z^?D9z7S(IKD3WOW>$7GGRIk79J|p4a*y4K@FcOB`U6wC*mVBEiku*VG>$O9jap5F0v zfv!^0=h{A%E9778K`{xLCoZ$9NC&TFg_gCxWm=tbQq9Alu9lO&fHT8r7M5>L==ax?H<#w(Ls*iy*GZ5LUEuANZ> zXMMF}Xt>_O%rLbsc+2BP(6mOOUUOC6D{T4TsqdT*SGH8k`H9|0 z4vgL>WU@vNiIUzVi+ZVpDRIVIiJ2HJXT7Inxtw}4PjAt&Yo2yYkSZXuFHZmMx(b>SiEp4`&6K6!*u4B4vrVog5aE)Gw4d2bvC8!!}pLdjNd z+iS4N69bd#Ybv2?mKMSDko5< zFDCMPp%2U_HkjI8Gr*1-&n8Xk!J9^6?*IS(r~ZV)y3_QX8BLGs0e70#o3{~yN^q6k z>D3KW_o?D*xvkf-`q-5w=_^#6S?eYtG*P<`R5}W^mlkU1UTgex$(LstOcSN)9az0y z&jU`y!!Iyads3qZ=ns|cN=fVaeC>fZlS92LWG6gdw!U^-g^kg&LCf6B4ZE~WiF&>p z+?I9uTAbOk+AVW*nd-9*zTzNl6qz=1b>Z4pOh!uzweRa(cQ9PprY{|n zwJn@IT{P#rWpK;p7H;}!pWbkK`pZ1_=JIa&h!YT>^cn>(G-cXD!=N-XuVtA<#-W<2 z!FVpIwx?(`ky}g2>YLnpxo3mrH0a`8_O>b%$fQm5{&-nl%UZ7_+g2s)89%mV%c!=+ z(WkUNF!`f3+2|X0e0Gb^+geQRGuap2HUXsv{%K@hkqq*TIg?{jJ@fV?Q$324m?TpQ zwakSK)^@cI#Um_CJ+(D~ueV!$e~Q=hwXF3@v26uiZ&K|+OE#ybRk2xD!shA3R~-4w zmJZt;Z_+yr{#cf_m(5Sa;Ab};EiVqwkI&YtbNv~P?-%c+<@pak{q4c?KR;i+TCG=4 zSEsAbpD&LtPZmHrSsYz-Ua`O8Pf~sEOYT0Gh3QJ*RcZcK=fxp@l1f6FgW=)g?3?BB z(c3lhLk9!;MBC@qxP#%zdU0}m_~7*DWZ8`e!;AIu-GAUGI1YxN>O&H<3XQjmbNt-K zpN0p+SHr{M(eU-~Wccgw-SBkye)!w)e0VYZIQ%>;hQ-Btd47EH+wf|5b-pQvyncZ=cmupIDPPbb5h;mz^y%i(BvJG}kp+1usma6J6i@Y`@Q zyc6ZvfD-RW4k6}vmz0E-?<__Z5PBl(=G@&yIg+I&$sL2v)8NlryHJc zYLxSvs>`!E%H>&ufTmYX`Q7pB?U%Kz0Dka{NXJJ<`i)QX>-pmK@!{e`%5x5>3^$G`2kc-1v#h$?oN{iamt>TZ;Yn z!!r^3A0hB3XKxoG?Ts+67b3$)3w%F1UoK=rh#-p?FE1{J)w|`<0z6wEFHT+`zj-ss z^V!>Di1G1}Jhc(y#ifWc=v|8Jei;5WXKDEumOl9I#Se^~LzF1Nx@OC^ZQHhO+qP}n zwr$%!Ri|v*w)*tocHhApykSfuGgoA+{r&sf{U+DMa&uZLol^KQdL}otz^0|JFk!L|4DR?;Xb86(>b;1eHU?_*$?CNo72QoqS={v zDj1)ws9zbreT?ji&pf05x3y2&|L*0zyk(IG;*bR~F}+n{== z&bOU-%}2y54{rVZ9$xi-q{NP}Sr|DD$K*@NA85S}veMRyi3f^tq4vdO9Yk&Tq-y!R zzRtQ&`xE~Cg11kVs4BmyY(2Oiq3J}1X{*4RU`QD(pO0J5>3T8yr|f)f&c*BdKpX%1 z7UIUbfvTWrZPIPSCItxxF99qN5aKQn^1=YaFbcyE z5>k@pE=UARNU<+aN`$9SkV*{`yv2L~PI*BhFz%%3K=hi(d_ z>@$Gm6Ywh_-APExg8+a)Jpu;`fm~gIDTFW|#is>qLmb=yh7Obbrhg}LgMLq9k(7y)43)Ug%$37%C0LS1E;Qgt1 z-gkqrPv8a#P~s3CM92WA8bCIKb_6fD0XwU<1ZvSGY~Y{G^2hN2^p6E2n4o`i@9Hn| zCk-0%0}mcB=!m9R+n(0RGb1uLIy#fldIZzy*00-a7?+2m(O3$x8s}|FwN<7a^d4 zXb25L1i+5qMG?D`cT2%CdKDM5-NC&8W&kb`S|i}5-^-bgLC%#i2uAjhO(%r z%%I{wdEdUt_!CGZz;Gdb_ltefFZ^SF_LF-23wZZiC%(S8 z{@$K?ng0IU5TsKuEC1V6e0LEkV5korX9RH7uNzC~e^v$B80yva)vgK)DC8)BXLkGb zicp9*rGOt%3x@*e_6D5F?=`Fs;v6Uo?<+ds{K(3l>Xd z^f%G}5g+J2FaQ$mbkCrYVZ5v1Wg5#9%)aj$G86u4bBw<8{R?fIn)rMSJH!tcC2dP51M+L24;`!;VUoesVu3NjhW>mgc z{-q*-K|Ty{Tz<6iKt@IFj&{wxY^z33f!I1EhcK2a#~n&)<=o3@_EXZlb@079oSTwy z1p?{y4ao@P2)K)+12Xgob(CJ{h&t3f-QxYDT1q#{$Jv(|mgwbdZ;4DOT_5?uc7@KD zHGI1c2pn@y&FU- zR6lig-BpGD6#c}woWYl=lfcdMH%ycIHXO|+>SNKeo@|ymDhg`xm5}I?N=M&eWLYC; z1{>C=5FMF3(u`E*+>6Ps{;|P2pX?c&YvpWQVHR64{X~ThmB#6VC>Am_BA{DxAYXYN zS$GW|D$MzI#bfJQSM5R3cR%4hOF9yFPU8xDlv&VQ8UHpWNqwROz>{-;uE}PnkX)}v zVKn(TqTnevmOshZ-^Tsh$+X8ZKUldS^{ZrrC&n)fru?0d`!n!V>KU9jOgE9)OSp-K z`N63+JG;HqR3Bi4RX$AD*E{iKOPh#3M$zo4!oq9N-=_7p^Df#0RMuK31HFUfP8s9xIN?}NlpWuD~a=i?Zq$)wM#5jvjeuFdUJV0`W~sA)euKe&X8T>Vdpd&O(R=d8E;*(^zUxceYe z0PW<^5p?H1;qbghvHH2uaAJK*a~Gwr7r#)Zn1Pto!%HTCVpTtC+ui4|s-g9_!wVcW`WQ#+sB z=yi?3`zbi)*4Y-WeDf^!ofEJn_q01wz5|Q~zYOsOkooOi(*0If@KVQOcC*i+wH0rb zOuMQ2slg~54zd|K{*W-4y*37T)TwqP=QV^$(6omR$F4kO+wFGTU%cym)VKNn+l< zdY*{1Vs8mM?-~ELPnhx-m@dySn!~n7xq1m$z_33;G83Y@%KRaFY%;+*c8w zCDbWUy%^AtxuUk_*lj#HR;=0J)jS+l0Lx!lylR$;6~ECO0~HEf+i#f6!Qc2G5rpc}-!ZMsdiC>_7H@?oZ5 z`>zsiZq7m^np1At*_UzHM95ffM9DL|mqJPxx2M=Lsg#jF^!=cItJ690oW@eh-M-%` zV54Zh(MvjW%D`2>oJnyvK~)%<((f}^MfL2P@}bfFK=qi}iDNSRwsYD-)^UuMh|$C} z&}_z3<_032n#lF!W8yxev^j&b5eGMIJDqp&208wVdAB7YA+Q;iGLJ`Z=-A)sd|=0; zltXl%F-~q-j_Td7i7v4E!EU$A%v%@oyZBJg1^agkNz+%WIgzvtVzId-{UDZ=HiOx@ zXkHtR#t)##@?0d32RrNN8=QShpVyUj3nEWf6Sg@=&#GxW+1b}7K+)oC#k6uD-hWLp z8b|nVELAOLt2RFYR9lNThgH=OKYzdLHq$o(qjx!D&IrvE(ss|%@x%ob?oh)%OKP92 zWMDkFe`;UjR8Qgw0#2gFUq9J#1xBGZvYb(ABGQJZXJV{#lImBdeZG6tR8P>!osGTV zKocst?O;d2^g;WPI{D#<=1%1<%xc;>nrJ=tYdAGz1@W(nt7vE?a!vXaWreeiV;^@i zW|Lgm>2QQIIVYbp>#-|clVLm5fjlJLz#Vk8$;P0TiPvHEic_rWl^?=b+z&WUAM8nD z457k**3WqDM-#%_%Bm7h*{Q6YWG)+UMYX0tC<{^OxRG6WAp(@ zy;azL-?i)e(9oXhja%|Q`!dI*9I|4)_;g{^73OdY%F@X!ZWqfi6GdHVDwoONZ=>4m zO$&T*i6i_Rhss$;MmzRp&hH4xQSugjw_fLHgfe78s$TEjv%hg>l^gs9A5lG%WW`CA zi4dNZe?syu&rNPy_eyczuUD!xd2~zmEW6e^GMMhJbZ>Kq^IPh|wIts;%fmVu4Fb>W zi-vb|;aTktx8eL~depHwj4L!tojnI%l|GEj`SpfEY~QiSt;Cki*p7~^hZLwFY$2&H zO>?znP^=RO?S_xV`lcVq32~ZUa}?E;B^n+JR@?Jorx&YPP^Ch5M$9Lf=jY}%V{zPr ztJeBp$0}k=j8MS+2oMlb@(E7+Ql^SNPF4v1N#+I5x@PQOJ-*LiHOhM58pD6*kFI2- z{UWu;X=q`+Hay3>|DF_onUCbbjBv z9>piDL`L0}Xo9U4guH@Ic^wqhhGpJv#}z5RN6!pOg|Tu}Np58HS>hpwbo}mN*$rKZ zLTE8IgU)SSQja0S3&w$kP=qci(?MSxt#;b_rVKvVnxLq!mXOt?-n@_L9(z>{YL}iG zSxo27KR-XVexqBZwfO0Krw;S17OBWh^~D)Uia20V+h}jh?-`P8PWPaO9Xnpr)wol! z9K%UhRF!v|)rqRXhMTTBFd|OKPnjkT+36D3MP)>T?&53^C*e!%BTk|m$;w=_zbfLp zrA>Ud$!?@)o;$7mlOm?1!MAuVuj4Yq^5caVu)|(C9TSJWaVc(CR5fY7-aLE3u} z7jqrvhIW@_sI=Vu^H!-d7UiK{ZGGkx9hk$-niRA z4!qW^z7YG~tgW~}B}^m(H^k$Yn=@M;-11FDo{cT)1jd%jUAFCvu>}DJ<9(J-@`r+1 zse1Fi`|q`C{s}#NQwzS$+X+o7Yu{Kq_0Af{2^^F9aqS`Lr+wD((P)z>wQ!K~6k`2( z*c%_BErS}jFayi)v4HS*>ETxxIVtU1#*J}ivi`4gSU`L}BZGUlfrS^((KGWxOEN<2 z>CNh0{h|Oz11@z@q5{9+P)gno{{p>ubW@&Qbk(OOr9T-DcNA-<$xsobl{#$)9N=<> zuUl@y69ZINBYrP%b)rPy>Dx#{EbGDm?0Etxo%#Es6zRq=!Sdo!IGB@#o^u((`Cgcj z6B#xw2S=aVAE7B&8;*J`n`2@>A1JSwFFL6qNxU73F8c8%9m8X~RVTS0daUA!2R@fp z@R14RV`bT#mrXvzZkb(?{Ir1LL{I6Ewd6J>JC7i1ZeS0k)z?`_D4#Cv(xV=ai_@ir zTs2&jJeO(#!=&b5bj1uW*5ORuaGLK$Zq<&etKmlYc+m;)Hi8-3LKvy8`n~5`US{j z(&m94+C#y>U$SsFSAC86j#sAft9yDD2wgk!7MOD9V5VX`In$$9D= zcbe=P;x9v-mL{V2sEYjskmR6+KiSi`Nu51F{jFJ!@>(|lVcyRKTF6MML3+@kx@Kq_jyQl(n zvTgty(J_g!lEvQApY{1;NqqEj3H~dteFAQnSPnEF9u}!tO+0GypP*t1Jo{#a^{%O| zon#|de}YI9rpYjgPsu6m!nLHNfv+~1lcHKj&k1wGCt<^THe6P3SFtLW!8mp0A1tN3 zX%>$N^16!;F&90n6}Uk4xb`f;p}(&O9>LW0HW6k}k81`YV(PPH^vo7LaX}Ju_?4Km zZD{J5t(KC z+PW$LaB?>TnWvm0o|vI2AAz&l*`?!(zNV=hr5c4WwtKOfKZ#Gh<;|~VT@&&r0IPdD zpKll>OK6dEaXO}%+d*5x;o#KA^z|b+2c=Nppu2hx=PmZm7aaDT$KtN}sTdW(NZuMC z7^t@9x9NA(QTTZyPq2+PVd`uLuJY6=K${O8jV*X+*~bqnRT(zn_yl76Ah4jX;&7js zS`@H0UWZGDn7{rw=(B<;^WF9k_O`$ChKr1@zBP>9)Km~sGSCfkchwuNJr;`>FKE){ zOT~95u!VPlM7}x$eE4bLHJ90-LSxtoTOJZCHPehY9RLs6QlHr`;Rth#fCc83lV!7YgFc=lvS84(hB)9Fl}o{wba<89v!@d zRwL3kcL_8*SfzGs_)8r6XiKS`&S6B8YG!oQq8uxF;+H!V6)BEMH~ww0j_|k?Tfwfc zeA)LF3&XeHZ#O!`I+M@{wL6$wiCkB`Jr!v`9QUFZ0|k`F1gD95S&~n5)UFROdd||D zgi4KF5_jk(!DhQdlLdABz9Zkc*28LYtH&KlUv#B)>F5YletH&=;LETb0e(YECeA)z zYTAlA^K_4XoZdqFbYwL~DEsr>rmk|+%2#M!Q1Vj8;^z9}{^$d{Ru2Kr(UP+XW##`@ zs!+3$^h7W-r{5`=b&*6Rgm$O<6uwSPlg5~MrMX~zzhzu~@=xD20gMEy<);#ZTA#>< z`&SqD&*Fu{CLMe((zBG{-Jo!Iv_XG`3k<(N8GW;?eGx3_ z8k1T1`yREgpSxgbA3bsg55`TZD3T%luNE!yV%o*eT&=f2?=^I;gpSX@fn?!*BpqT4 zarQW?1wgN7KP?X>rpP{)fYTByyJ<~r0NK^yMk})7letDk1fG1>!s-3l-sH$Qq*c#_ zqz|z52U0qT1E(Fl*;eO1Q+D#NHV49WkL%KsJeMbel)kD9%9M%9MhIUkH1aAKHP63? z7j#qXPbCE&N&~eHb&1G&+m$@U<_+oG^W=aWR5h=0_mgLJ*FKhiE4BTXIaB4v0&g|2 za8+1W8uzC@PiU|l!o}H!4exQ%mpKz!pC5w-L>9@u)Bl!(6&tN_trTJ=U;RM|2A;eJ z#F2@D^IPc3Y|7{e<%~7r#dOo6c{Js-5)*}UBK?jyRjn@;(jgmrUq5ppr$%R`uuWVz z+bPfB+Y%=acSm_5)R4o@^szmCS3ynmThi%+M>h_3TNWi(+SZe`#KC>mHgN7)Lp0>@ zRQ(p*Iy$b&bA;92S*d{-=FP~dJ_zoe+dz0o`R+>3rQRma^h;#Ncd!adf)K{Sth)+v zpO=vj_WGNUZ!!>KT=K9UPtR_InMN!W^i~ z@abh9pl?dt1a}K>!g%~K_6)s_lz(Bo$Pf4Nm*|M@J3Ws~#*iq>*R4(CVEJ6@WXezH z@xQ^^FM!dA{OfyQ>!?MW9-#incTn=Y<2dgHux%afSFLi&xX5%veUf@^Mw(<0`E+tK z$5o53dKDi<#N|-q__%us@zD!kR#F~xEI#_@go^%s9m6H2b#p(&-tW&ZjepI-F^fr( zWy2NW>-za@40g-f$FpT^Kwr7;c(Sm+RGn*i5^^VR6)o*o*B_NRyW>i%q3*Axr=|PM zw|{~m;DK{yifQ2D4%I4<^dYtyyt&L0XxEj5dZ^ROPZlntq@~qc-qaPBO93@8AnLLi zJ(l6ghOBt>Nj#-A8t~A^ z@a{)aoLT2abiv|L5^G=9IYE|La^vKbLvY7oSSzTCP}`~!QfZ~6QmwgCGONcLh? z_0Kcir(x0)P=Z%{bJv*hj-l&pUfDHEA2VJ-AOw(#kyvFwvEGnO z_J=WXN(DI8XVAXXqaiMH{umFX+P|t+mYE;vT^kr>22RtlLAdW=qi@Pvb=Pq2#bx*A zmPv~`Yj^~1&Ir%oJtG^KXP-*EQDGmz1rNQA5RyX6Xw#*nSgOF+Tqd}Dn!NqZe)qzy=)|7FUpJfLBd;BKM-d*28-CeHC~N0_yxvSeE3n?mEM`*; zxeQ`VSwyz4w)v!xt2q|S!9>t^@694JFdqv9NvJZOfF7(OGbt`wQF0fW5~HnPTZlO1 z#SGEyzgRp5?N|QaL%_d{-Ur$;Rb-1E=@~hs^1NPk#CcMs6PPg*g8*S1;@NlT`y(Y^ ztOno41}S|bvtJFFsA^l5p!dGh-3sW)H8#z6pB|@5n!~{O_BBkMF}LxWc}IRc_3k=O zzSLJ`s&#hcO)0UnEYl0E^U9O6OD-K<*2;)lknyLSkDL`S>9=2Uzg?li8ybHgv0(+M z5*67(Ix*?|Tu?%u+P z^C0s<{rZ{T)b`pKZ#TvFamt&3PuU0i#@s7Iu}ZbPph_aA!@e~@|6Y*7JKG(Sm4(}a zWvL6ANa1$o3X9ic0}tu-Rqf97%9!o63{8#(8<_IA>e_gMMzA+GyH>z8M~ zvRT8;Bx!6*ICi-3q?OM!;Oz`0ycDd2DhVu^`B#%#J3{|FWTkw9)h9C=v3Iu1UGLq8 zh#8jU`Ws&kH)FzE`e{G#^2X79eAe?DDe5kBx;TPL7&2F@?uY2~{L!eh*}@%{9QKau z(Jst-&{Ho$PiSbcWjPKrKxq3${B5%5K|pdsJ->57vB-Q?6;4_xMQsj~1e4X`UD@B< zY;g(Z2u|4pa|DI}&%~y1OC)|`jzJ}Ot-K0`;sC#w?T?BKG}!x0?T%2s*&B8O@o3L* zY5Ya%_{w0Q#Z(p~?+9Sl$xPPX-Le1h`f&b&pcH;Busz%$qG_i9>MeTT8Z3xB9tdz*ZyX5={AjUM?0=nZms*V zjxEL{*i$naRknU-sL!@nc{?;e-46qkbe{Mu3+pNV9%oRkU@6Ymq@msFx{Yaay2WHt zcBl{G-L`IwC*Pbgbd=5lpi{luebHtO{pc-9&v7QGtQ?saqVIO95syqcSAFmh0fzuN zGUloVaq{eNE2;3C5X-qHLl*3TKL9J14e0;G)!F_>uFlHz|G7Fl6EnwuR{zb_IhdH( z{?}aH{U2AiTBX|#a-m>w8U7pVB9)%PF#tf!06Yx9>=Nz*y@0epNlGduoi0&L0JK0s zaR1+2-Dv0g%EO)KQx_OKINgBm^{&2>?}>7!m-1f(im83c=AKLja*} zkDmfD924UPGEmU;CtVK|4vg?`1{Fjg+hV97;D%lufT3bQLr6?R2@C=R0w7T7uQ5dM zG=PfW4gz>U9f1Hg7^pXrW5vLhqC-S7Gm!89tZiyz_8+3g8Sl0e#p8HLmyt zw{T%UjD5f30r+?7)&N66L;m5P)1T@D5KryQ6FYb(CvZVU1PbH<#3QIMf7ScxBLs-v z00}CF>4g)j$ziVHAHW241l=rxcO!!VE~LT$5W4#Ms~%gzg|`s%g7Oen^--a|p@Qw2 zu$BZtPfozXh3gK%}H3fd}va7#4Ok&(s}|Q@G#SmEO=}X88x^a8KYIMA8A^0yu)^ z^+o*h2<#aE0AGQ?-@fff`$>rm4FiBj@BkZtxdjVEenrHG4aWJIydE4NkPJXYkmWG| zzMkJdO@dF-fMG78KE}UZ9YXQWEUm4r?!M{X>{FYVU?A_1|2<3)k&!?ELqki&0Fn=c zyIYEXDFl5@fZzM&Ag&>R1^*;b_j7(o?_XBmn|`!l@Vi?LF9sIlL4X^72s>C5@QvbM zh+qH3ulDKR*zNwJFMf!h-S-Ob&aR&or(dOCe60lR5!B~&yg%ynAX%SX3{PMJzne=q zU*@{5gK!A+?Y}ElgaT){3PD_*KieV^jjCT#8&VQ2~UYx+;0?L!jg z?C<@C0?bFiU*!W>Bta7XLK1)?Jb(`Wp8ck__oCy(?QHD!2%$gYzrP{_f)NkCh(J3t zc(31$!|vmnyGptHfUu1nm2e66Hq9T6Q5U@;vwR zJk7hIq&I4bE6Jw$@n}^(aO+u+8w*o>NtXoG5EZ+Vv?})G{tKHg zIw0((>1F&Faf&NNY|i4RC%L-idZMHkj1s!soSP`jJ&;LXA7x+fxql&%i?Tw(?o-_U z>5M`X^`yzgrblY9X`(pqAmnSWh(w{1rlxSvGIWt?2S(zPp=2G`U z=fxTl#a9g$N1Qg3T`tawyoWih4I5O?aF=g|V*F#)_$w*Lg*Bvy@sZ^9W+L3Tqs6rf+=Ml2=2bbh zUZJQ>fo-5^|2(PX3}R4Hf828rQ%0D^nTRZpEOqrlcuz#!ci-j@(IhheBlLu$;>DOZ zS#9Y~VX5*h;pv;|+QvZ!){p5?Evf`augh4?3nLV=!f9W|?==@9oYpPV;v*Q($} zISE5MXQ(bE*(TRJrvc|o68%sWz;Y3!A6*+>y6$t@f7B`3T$-{Wgu_Y zKu+&IT~}9zp&U|Fxdw6W$_1N4xhvjV5KZzdK~^$-ktbX8HicbYw@KNgd>{|A)swTX zyD}9|i|ETicu>Crk?FMV&YbOqIFT2;llJ}yDNva8$o1!q;R)6a(eWIBudXsW^^M!~ zr>N*CHfQ!Y{B#DH^1hJzDJ(Ke44abL)j?>xa5$6c?StP|nNJjPJr?w=N$$wh3P~Q( ztnoDg1oy%@-zT5=d@%znLN!g~>ScatoeG17+9hi3f`YD@qLqcP!^P>7#~j~XUNp!a zl`Q4;tN3p|shn#zEJ?8|6G6;B8(d$j>q@&4RJm>Y)BxOxyH5R*}`1-s^bnov=!VkYp`M|_DjM41cc1<5gJ z=T0-VYLnjZfL03Kklx$Su*JEk(fczE>+cWymbJrYv0isc-J5Kre$|wsw3*J5Y5SvZn&PTnKTbnI% z?`zS}U$oImH(T zS9JB-XP-tU#3^cNC-7_d**l`N19dZu!7Z|Vm0?=+pz`Gq?);Dlsl55NZz4D;69${S zSSI`3fO5L(!Y=}&Rm&Gb-$FYe;pM`69&+HlgV$i|k|0JkjxFqgJ|rA^D*8W?X{s8t z*Unrt#ray&bt9*bGn4|?kR^JI@~JDeVP>n??m5-lqdY^oBGaPH%Tb1Z`g$H4kc1fi zN(%l<>doEItfaebwy=p+)YQ<(y%kX1wLN~@9BSrWQ|Uu)%f82FrmWWJ*nWIyW3GOm z{UCot-jz1*=J7#RBxmb;r#i9N{G53Yzt3O~5$=O|)&-Z~{B)Y0KCp`$(tSrlb5q4x zaS|S&U$DuO87X2anE!U);y_s3-;;%ObOUqN_dj7QrBX=ut8@y2jY}fu*4rSHIsL8u z-AkVxA1A?ICI7pg`{R~>bB+}Es!JvN!$B2V84{7)(fx%aYpGG=Q}tat?r{3)#P%lT zgOt6|yFp*tZ$sloeys=|`Q{c>`Y8%FV@?m>g3kd9XVhHT?g*pUOe&2lo<=U*XGY#y zdXu-)g-WxhG%+oWCXvk3SDQn5Ho}!IZyHgHmLSO(=)@9p&8N;}=N6xc>UB7XpT759 zXZdEToQ%wZM}q{&!?>-TWlqsvGg+2qZbHGemKB3h;moPf>D^YpicUpwkRf1_PN?@U zlzH|;$JT4cbZ@|72XgRgOJr{4y)W3Jb4-ZBU*cj(+V^#yaQhw0wwc@7Ote4F)BY6o zt@$gPN^Vi?>Cb|-O>pX*@iOi8S@;4~@O)&Ky;ZHRSeIe=9?BM`8yS|p8nuxvY&)CA z%Tg7Cn@?o0Q?Dc=()SGxbA#CI4V{Ru{ev&zm;MohFk>z4zf~|Ld~vIckNNa#ktm;y zKq`Q|Zoe8`hnys(Oa0GO?2pjr<@49+?4f8HMnK(*+^^YeeF-daD}B5JK?t|>x0Tt; zpN>z&jkgv18%ZjscYIkL^}k~-uNf8uvgO@c#vT##i~JQsvY(#x;T+#iwo`9@mBC5u zr8wV*tyy({!E^wfb9(HVs!hHgmZs1)RafmoQLW|O2WuQ0K`dD{WfkxKwnz6hf#q~} zLw#BEK}*nT4^Vc@Gna+>d~X9W4MPMfE~ywn#GMbgru70sXfPgGa4?n0h8jEZQyua0 zqkJqCF7KT>6M%VE!5e*hKC=1kW-Mi-&ufdL$8#3|h>B3xk($$~JJo-g1I;JhVRGZtGL?6ic^-fm?(JO+{!}}a&T7rf zfdZm@rJIWL=v$Z&Jb`?_fX}8e)otrrmkUWAEj5#xJA}NI#94ROLc8l_L$aNa4Ato3 zp&SM?azpJb?cFKz+~S)i+)*mpg;n&pt@?}U$P1S7eQ_znS6VS=(T|I4PK#R@Li)tx zOdH{BjYT#!!Q?>8Qh(yiryl#=Uai%M3UN`2yoY~4`*FpBNdCpUwr1vu?kr8o=Z@%Z z_i8NezXbE#q>lKT(cFtr3*@&Rc-f>L3}J6)Ip5*QpUu(rclXA~cTipglWbUbps;DN zuSvfS+EQ@~zm@M#Yt=Y6p%zzcykLoZt>U!(X!Zr3P;H8BCAcV)P2-^?YN4L|?RNe_ zxf&~bsh2x0d$7%DLHa9{gt@b|T)IJy7}d6s2;T^6%h%+%plC)1^6;fN_m4>%C>+BA zNy|a2fN2{rI|1;rKmzW~GA{7s1L2a6dQ3NavUKKTxceiSm=BI`5{7p=$PBDB4dXNZ z8O~hR(jQ#fr)>ual{eUvf{ zvJ!RQ4uv&Tg8@hpSJ~ON`7Uo})zFs;0$wkh`sLj`%F?yeQD9bsmCT+g+LSkHI&UF0l=fI%hKfx6E0# zm&b@fA4@E1+WvAdbSOg@!-Enry_cLVZ&a4u@<3_Soz5fJaM1TAa6f&~`UDQZdK*rV zZilOf!4pvLBUDi$1LLDQDzgfd#m6b`hV7bK*Zxs;UVZI0Cm@KsF5iN$6EJX471qAF z2Brfilhe1DB1A;9Vt6?I$#^7fdC$}~>hi-^Uv9Qzwfmd#m(Frd`8Nzlwb?Svjij72$JE79JDBV2znGt$m7b)BW-J|Nup`;T%0<5A+a80X{&cdxh#^x z(sLDXKDld53hRvSGm5tVq?Qaxw@0wg`Zo&nqT!3`j=BrCoRiSzyB}lfu(R!B! z2A{2}-W^2=Vp!02WT~xXju(ci=W_j30KP`kQ;cTAnc5CCgB$5^+%wEJLfcAf}FoYG%zFZn9~$+sfIz7d9Yb- zYKxVsdDZPj22BI-tAjD%uWD%JXxlJkC>R>zYhVkX^cQxDq!|&`&38;WptgVWuotP) z&h4a{Bpqk3p;FRv(F=qM(Ctg}YjbkSJc4eXRo4qA?F>t%F)yCl5^=a0pU+N@4TfA3u@L}I zmtNJfz7k#^NU4}XcV918p2zGY7bV!5RatysaBfy(d3pb6GF9Gou9jR$`?A=xaBiq6 zm`E(|X>0P?3k#lOY8y5=J22T6SRmwyN?{ZdGBf}&B&}S-?cCMwaKP>CA(Bc@?JQou z#pxGm=7z`jEP5M{h2|>}P4Hf8x)XM@9rRm8m)j@tXNUh9m`i;iCWF~=OpRFpG4Gq;q*WQ00e_6R=+nz20&R$^N2`qX)UC5s(c0@RJIk0hP zhsW<+IvFfscxk*UYI-`Rnkq8Mi5IA_57Cis9ZuBDnJs~Dh94hx5~ehIk(!qkYrjl?f*MZ^OSS8?e>ifXigSRK?}K%| zj*YgCXGy&om#?}k^gMEyvf1`k#j1Xy9ljR?Gp9!Zo4iayILwRFZ7q^tup>yB=RX%S z7^LklU>~p0qJE8)U4m3?d5oQR;(&bVDSZ@oLd!t|K-Tm|;Qw$9A#t|#*}yEKx-`o2 zJyKBRd#u@W`dK{FGS>?G-|QRSCv0+1aZc*ji4%AZHt4oR;;JqDGamSLVqe=rwyF&MUaQZ0uA_3= zpLI`3@dxPa2%Fj|Cuha8Ij=-*J}Q*RR>;Yk#hGt4S&C(;YeBy@#qNR~jOjZIW<5!O zB%kNXS@ZRtwU9`br3iP2u9gtAcr}dQ%_B8P+b5-}%jbc@e1~nO#@D7P0zPSf9`gK(v{-kJ zY--|hBBUhWT%Cj`!gn5l<5&K|D8V20oR@vy?a%um z{#LNYn+xz3#E?uZBm{Q{8QXu0Xc0lgSImUWF zNbZalgQ;k{608x+yl|d=L#4;i%xy)*Vmt!=#(~tLFZ@h@gO++JtPKgLJtTjYV8Aj` z)`042UHu{8OuJ-%$Z+95mUodm&p+(dxH)u+BP> zHLLN~azTf0xDI;~#rzBo)i}e;lyx=(KF+9G%waKsC zP0b!sf`gMP( zWcR^k&qr=OsdoK0POl72=7SH%On$C_%fRz3k)r2%49Uscru%2y$|~RaWe$j%lPuZK zA()@wOSlJe4#OIvZo%#J)78*fFP7CGq;Z|ynk@V4^t>}em-JQd_+m#FSag?f)R^mW z!=wBbRgoB1__uKHakV}@ReV)jDS7i1xbpy?-cO%qqx)vuvrOU2&Ii?HGlurLH9bbC z{IJ+jNlp7$2ZJScRJ@)#*#n2Pgy_cy$Iks0Sgh!1j&bz#^^Is|#MnG@%>AaPzLJha zDK0v}0{`a+*6jY|FY(#+u+=?_w7URwj=v;l=*zx1rcE!OElyQlSve{DfU#uhJ$be1 z-O+jz0Bd6qp?>K_EvnL^$XoXuPW%ZA`WEe`f5$ZZ`|)tl4#dlwui;@8hwak>>8=z* zr9QV;@=mxh>V-?q@$1-rUy`1bKZ0QZ?u+i7T}i@6ueMYzo10#z^Nw)6FjX{fnsRcD z$nn^yOR8*C<+dQLwL`C5wUxohMX4V{X~we=V07)mRP)LDSVI?)JllF4JYVpxcrqiSs1%u6LU7BkqT+WkpNNz$y;i2>A0fM zSsBfCt9913#u9jN;64ZC+#X^h^2%t@eDDEPM11Z#Uef#9;gyK?zZ#yzDylXgIdh`y zPW3F)vctL=&wy<~-g!hk&q+AMIJ8JHd&)kz@~=6S@uTz3tPqz+rgn|RGOmP*;Tz@1;UUAAO5qnMCVDW*Sfa6@(QVOrd$3T9Jc4L!?NmlSh6^y*eCdpIv zHg+acN%&WzO}m?&U7O#EoPL?zskds;DX}+m@JwvXA4fCaLzhnD`I}|Y^n@f#o@gys zPwGUk2=*qN1|?hFqp%0&fO-@|={S8#pD`0c*+)hrQQ%90Y>qN*HD&uwcdpw}b~&5d zi3%v~oFAoZ65v)OU)Cr0*j4P2viVI)VOPBj>yXPZ!d#pBG&@l8$hUPf2hY}?3pBpQ z(c2rU62m8RNGY5(xmBFUeFC%?IHs3xjmZFsSGC4PL%*)p1bl^RH4KF%9LMjgf{T}tiLj##XrPknNky1MoweD*bzL)SSF^#ge7e^*?IdpW$=SBO9 zGUX=HJkix!d(T2rJ4Cs-YkG3~Edc5(|5rDtw|*)gD8*7rLX&gOP2`+W!*+qhr%mST zK@gi{QWi{XPK#cC$KxI>S1@+WOpSUj4|;PQ>xnLVb97aMHn-}OxGdOu%OV+KHe9EW zrmWuae)`M_o|o@R#qcEG{e{8JctL{llE{S3h|G*ZiMJ8|ys?_`inogiHub0@xw%!D z#bs0HixQ)7Sp>BPQx89N$%$4lcEHzZ+;$>J-LYfv1LInmi=kyXj{+r~hTY-Z)TD0} z@WYx>7f$7;W*DL5Fd^ANw#ck+?-i-#&(oxi|Lj??w)1FUwm4NN{_$DyD&I$fG!&B~ z+e5oWf<5iLSO|W_$QEveXQd#H$mkJnem*YW#+4)9Wi7OUYwlb0^pZz3uIz9~R^Iu< zv2YmfT>PakgKxrnxm3dwp9{lZ38m3Wa@XKa-Vw>Hfpt@@omtL+IAHUa5_HwKkhz4c zxP{Wi60;N$?JbXIb(KTL2)kC`ev0J!Na=1GtMwfK@uvp;<)Mb}C)fRYYo*Q(Ue$0#S@JJF0QG;zPJXYXbMRPmPPJx1w#u4QbA&X;^b{b@oA)}3i^ ziYqP)-5yz#hxPrE5%~2Oeh1}c^5%YjD!&$<3kFV+il{rQY)7!SKHpLsd+s~?+o*Z z9kN2Q>7ra#&$|I4GpXzAz2V5gW07NWA$qREsf=y_%_mXtE{xgGNrfh7C}4QG?)MdR zzT8aum^Aj(+bIVXzi_!TEV;2jLg(Y8S&*j{21(W+Q&+^dg{iLdNLL{@hJt<%LfELx zV{i}#DLnJE-fcK)xQW(l2qoR~2bk=R?kTSvs$b#tBMsD1y`z{n0~(}k?8Dt2pcAk& zJwDtflDkf|VHs?&H$T4H%Sg2MM139foTml;1Hk`b?4Ftg3D`6Zmu=g&ZQJUyZQIpl z+qSxF+qP}nTQeK8u@U_ML7Kgf*hy&r+sX`OOP;^2~lrKn`WdG-N%l2x^p_#fbg zw7sqWBojFPlT2V^VEG@5z(l~o#QGmE{yCYMSpUCeLi2yi1hy#u!C69FVW}Ay*m=q= z0tr}#UIgafSNRYSPzgW@^Mr(3qy)5tgtVlTK=a;(Cp;&eGao-zK06srrq@1Kt!~;M zx&wU$R=xCgp^X9M1c(&AVE`IPWo5gHZ}&EXIBGHh8!RCacK77~KHkyKv)ilyq5vJ?7~EE1*BH_c02|kA zk1>AJBV;ehS)gE>KoA!j8w;?w^gBzpM=&r2{uoe*6Y$O;pBBnK3HREeoyWF_`drEY z2mn4ii+KHpZtdSF{wBbyFTk=3)Dl9-^Q#jexYNK9eAs6NWRc4bz=S_ds@_ro@o#UI z0SJNO{QAGHzPJ%^?nW>ztsm{DoP`40IL*@p@qmFTT3=L)SMw0c#xW-{IA_nDpH&AnfnQ2#x_o0R$E_ zMA9pe#*J`n^-CpjH)m&HpT!~HU<)7Mq3ng*0k7srdjof$86M#YdXdjzfeUy#^#uWc zl<#(s0Du73`)m{iu+xBX0AJa;u>P+7kQS2P0KS0offa^>0|xr}eRKZFYcmNIX?^{& z`ZjAN05!2u_3_!}2mL8jQV@6t0)7P@^8XAZ(kB2RqJTgV#t;1Fj-W&Nc0=3s^I1Z8 zmdG2_8!PB|%nk1P$>CesiR^>@ywO;fU@2{7<7j^YukQ2i2L1?39V=|w2^oIflK0l^qv zocV_z0EAa3?t=e!NmZ!F_h($6U=;T2m_S?q`DYmQ?`QP4Xu6-ivpqXH{fwU-GFTwb zT*qB()UzLJv*?;C`BI}pB7@hg^944UOS2wME5H^ zbDZ<2CHGRDY~qbA=`0QQ)cwg)@uilM7GqxuLr)#MgRU~LKGiX^Z;e8XhuMC~7@W)& zWtJ)q3STiEynA82gt5d0$or}}Ez>7=U4dEKDg|HvwffzO2g;uiCSk!DI89egW-PHP zj-yM5LAFAW-OIO-nP4M;37 zMDL1tRHv~UwwgDoT$NUX2y1KI0Qvg&+_-CS8RnF@71f4jy)I;Bo{!t(?Fw_1FfMH9 z?8e8jFOg&6SahfDNhYVsijl@KR2oDAB2!)>RKsfczOH8ibu!N!oLA@?88tL_2QxGQ zVv%5>zyH{8pmyj2?8IMAJ;@di@eJGOn57dA}8D?TQ+V?m$WsV`kJY z)L(RDK84NXx`Sb<*W%cP*@5GmWvU<{))oTeDHBIQt|x;J%h4xMaGi;xG(cbLrnknh z=OmZC>P(NG!ng7c)WHr#K*o3m>Lr^v!uk@U!-B^Mz;4p?KcUe%q|7zCZTPLO1pG6|Zo1d~xF(ByIgvxRU!r*jFF>&hAvuk~`Y(r#(Z`l)#cS*SJKJxx5Q)7{nK7)hJ>fQe!%eO?el2!2%Q zG#_*Clq^jw%#l!ZW$hr5X>n5`D#cJW^_lUOMq+j&r!GfN%weE^aUEWL?FIVduiLKe z1#?#1z{M@`_yW4r_yM>TN0001N-Wjq8_TnvkVNG?xgU`P4kC8YEpxL4HEGV+uEq#|qJCtCqdT?xplQo4<2A9;2oN_O#9q-oNxBWw;T3znKVG>$4Gj>UAn3|-%ZREgPY^--MgR2Y|xf1;4a6xkjQ_KJsRS|LpM2+iw<`2KF2hd z6-o|0AFH_`8}C!Dasc=H`FTy`g{?L2uRf5Qs1tlr+1Ubb%>R~wC5@UoK^$!Tr(6P- zIr|V4{MHg$TYKg2<9L*q*mmkPT=k8za*y#T*s2x`ue$M*vv9DgDfC~#Ti{^2qU74+ zEGk!q5P7nxMt(>jhV5K)kcZb`wz2I^&Jxd-rkRvaLT(_fg5c{u#$Dj%Pn~NP9ezWg zy3xGal%^WpN2(7@W}iUxInHpC@W$Qr?NR z)30UaorMyFvqh=SHKZ+@I7?hJTS+0eOxLkYyZAAPEL;TbTZB#-uT7r+FkFHdlJeh`>@B-&^H%GhMctpUn-t=%ez z>cmTga%j$cNM940;pzfBqnx0@A1CPp)NRZFD7oHb^dQ^xD9rpfv58Om>lsuid>1gSS%7Ei%)>KCb^z zYI8#ZvgF;7wrk4>4f#vj>o8b&OYfqWk(PXcs5=d-vPAn-d(fa-zYmR zjjf%8!H04dO(&#Z?KF>6^<4E9jp}3)WxkFD-+P6297@{BPHwy6HBiRe1M1yQdWaW3 z$+;^hum`(Hb>!34XCZC|xm!1%sT6SNv)GFDhbsDBocBCh$n$$P(#v0YOco3~JLzqNzjf>xKc!_?Zk)eAOL^Nu z?y`;c)8sIY^ho~oDP7v6mvtNL<`uICb~F zhVVQWI3hCgT7-sO3*4s$bK$LPMfR%uhuX*c)Q$`|2@E;ko%A}5WIcuz=^Q6@UgnG9 z-!9hy=I&1qObBm$_hM56Q}yO_z?y2&W}8*a%7zJ55WLRcXmwr;;qIHR$V$rfiIaqj ztdv+;yeQMSV-mM0OwH;#BG-W9%di}xLis;KZ<5@sLL}#Rp+S+p8KguOieV8`N1<6g z@-ZLaj(@k|UMB9kFuYb|w`jJmE>ZZ>^m@}}OLtTkHSslAl%54P?CErBxk^8js z?*L89smy6iD8jyO>;o0?MiKaEt^?^upvBxM(Pk~!63(YeL_ijTD2o~uzOh;hRV2=+sZMu#rNZdo21sA5RIZibg`VY;x z(tBg<_a^KEzD%WK401jhhp{RIi`ROAnb$J9N)6@pG6djml92BaC?(Ho1i`XtrVCRb zKbJNrrW5MX?YnzY3_bcf7L4bD8C zq1CaZfN?O#<-S`OnXLov=ppfWF#q^e!S`wAPWZ$d`@obXCkih|6HMb^!fAn!c}16^ ztGI*v1XG~ZD|I_u@DmvrSyOP#B#*v4qJQ5}L^NegnI;c{OEVKJpb-m^ige%r8x29; z_`Z*%S$Ca|xvLyd4zv+`p$~A1+;;csT5#N2d=U63>4&S*BM%WyDQOQxKTxQ*jaO3x z)R9dmdJO4D5IRp&?fN5j(i-P6C=WAbIkH@~QEUg!aMw2@2qtBL$lIiCsUcb6$P&h>I*NK0u}9w^E7{L*s1 z8HT>59E`530P~1BCP74A%C=>uum{ZtUfvG>T!H$`&%wLGBODX;!8^ygsZ|3lum9ys z#kQM|uDW(3#4mXuHLYOTc+KjekjymHK+4sz2!q8-1LPl{+=d^r32|2h54NA=l7caI zCL(ATptbvHM*GSVvy$`L!p=knB2yr$@p(8`*YFe3R;*z;X#~9h?;rN1LnGyH-veAe z4xcRoI&2{#cCsc}*9$5w@7XUFo2JS=&w?#y{*ZQI>+yMr&(53B6qk)l;_kHoWs(v< zK`g$#&Sp`Oxv3Rt97EBd0d4lov%c`>Z>@*#IsefIT`WPqQKcNh()RCw0(A0kRtd_K zYNTbh1OyIu%)uhxH)k)GK>W89vMoKc!9|8YbB4ftYvAp#uU|-If>wXDZnfdT*K0>X zW+21*JnYSmbQn3Wl`r~Fyx;*GS;-=xgL<+GL1gji63K?k>u-LC8M9=_icS~D&2RrA zG2T{8{-6--&c3#%dVLHT#{|3Edd&@9(itSA(gxvKTpuNUOOFS($_}{2O|HB3f~Et< zR^Ki>9(JAnW)F>IDi%Wcuk~6OrPN-~PS&6@wPy-o+NIi=j4r}X3Z^>@tsn^p2>`9?)3lOp{r@M*~B1C8IR;Pl)Q1z}c z$(Y#3xlU0c-*mwr(u_8;hY$8pfZ?U8LcAo1yuIlgJgV8O?S?EXH?iXkKpdkYc0?$4 z&us3c9I~D5P8w&*do`lW>{7p>{Fsc2@QaM993A>}E#tISJ7#ObIBn~?ltIZ&*-Tz; z@3svxpJ?>|n2&cH&>Rc83*6K3$}(JJ{*vz6KN~~Y1{tB#aMb1e$Hjs{)KVf6nE)`Z za`Mu6m8mCMta<1$5693d;FpUvS*9`T`K|EwR_CjHqm>abgAMo9Zd~|i&ezy{gq%PL&t;1m_#v#Ms;z)0n-pQ`hNS0;-m``qZ$kW= z=__N(CT&h~d{+L{WPtS(YX0_S1pAV`1cRwO zO2wAk4UCep)@Ndhb7I<&qp?N|o%f}C)rUF(R6E3%^8SxTw7GbrRO9&Ti`xS)KF;_+ z*ho54@ab{03!9T|7eGs@b!wg#h~d~t9(GHY>fWqwYt#-c{{ly5!hM>t|9Z4a{mI04 zO7T3Bg1go4dXjipKfxc4O_8ImFnLl?5pd^{nakzloy2fWbGK~JUln2}sliA@rM z^nHJu;nOQVA*~hr8EJdM_u=M*S3;Bv+gOi{vqhm5Rzpoz#Lw=@B&yMG%*APz3S-_n z1L617m?YF5t7QE_fIeyv2gZp!^JWYgL3O@Hx^FP60mZ6{bF(?K!ln;~*rkP%Xu|wT z2f3z`s`MA@R4VlMcB0Z?E+rxzakL&}$8zhR@pCu(SNf`2kYSp({itdkL;SLgd=(#G z;8D?p1d9n|Pg~Jz867sFS&AU9R1`uWWyQ{HLrcMTYrQ4Yu~v4oGJ%WMOiI)>Q%w?) zJeF>GQ1j35oo@MhnKV%GOnZf!6bW*!ng0sh8Yq`H zRfkAhz5+On>3nb0CD=%_DAzl03DtQL+=p=u^1%0Tz^j|L4~4-##D!&IBmNd3KfaD+ zE)R2E5>dHN_>bk*AU-r9%wBc>IggYie_px$IWBgFpZntihzZ_<)z86dyk)3oYZvs@ zwdY36XD0E7kr!rJSOO8HSDpDmMWnFyhKmwz>@6TgXed##L9~uldUxaQu**^mZVOp{ zST+t$5bQ>pD`JpPkFKf+lEd812ZU&bT@RyQQXARMPR_Ro$Cl^l{+F(!exTc+=4%!~ zQT7L_;PF!fO^2GIH6UX$nb{EREEAZqn9d-bPY_s2{<;pTiy-v{V`-;MBEf$C{Q+z zS9prf7F`F&N{m@Q^p-qXGiXUmXhNXm!FrbXwejkJUWl^%{;Csz=y1t4s}4T?@*ay4 zHo$U?}6k^Xqd9l~4`i!eg`nQ45PAMG5ZPPw7uDbeR zccCsJjdc*J88RVelHu!JQ((LXqV|75`A}ZS>Dak7R{6w zK^AmEVfm@tI-@u>s^;=loKNSu`Hlm8>fTM3)(odIwjaDgrOv+X%zsIKuEv;&Ms&=2 z`w&1z4HQ1m0Fox)e0hW{$~wV<~8JdLTc!)w6Os><)(>& zHA@HoLdjO44tYJ{p0Nck2H5`Ud)61EcEtLG9@psx{A2vuTn4z?Ub7DbOLz9u+>t+I z_PNkC3bIY%wQ;mt?ercl3SP06c)M=D2T5*CcH>=$fj4jFpH_nlPik11)^#PAM$~U? zHoB^YB`>9DRXn!tu6PlYf7ax}!Jzxn0rfE0nvTvXYzE}e?I*8S7=cQ#Wo_q4tfSjw1 z(gDfy-E5~abc`}7Mg+}tlrUJImZOPe(DRBl#MZh4X@bt%P<%G}a43(v({;2IM*kn! zB0OVN{$sM#s1ebW$9V{~F_jB<)r6O_V#$O}vKTBXr0#$veji)klC15u8Bi1VGwtdY zGI25a9ck%ek+k1qLO1gA)f)U6c0pmROqnNF^PaI5r&syJ;)#o{Qd%2lsHMELhN2AR zgDUeB@tb)6N^2=Co83E0*)+K*J9;x8OGwhIn{*1xO-6c~<2PmMv#d_!eD~#F%=84F zXfFNFJyRX@Byj@7vpOH%jaPe+*hDu2pHMhEb!d&8pJ$hjy_SdG=PRtnwYPK{&c)3o zq&nKG_V`_VG2q#guHm8RP_EUx-au5wEMb&EB3ud`I*Ma$cc|2CWRk4pm1@3++lM-{ za6eD0wa9#EO+B39(TD8TA7mM8rSQZTGhV;bVf~G<44Dp(6PYGqIbHFf#o*;w$ku2m zqo_FU5!1p@AGdi4^6uSe@*0vHJyYr9OFaOqQZ1^wVd-tk*9*iqfhBRGJX(#g4zrG^ z(`7bC4$mIQ#rk33EH>DXtDwT?W<)P_q4V9ClXcK%D1Kk}=gm>2^>|S|z>D&%{vo@l z*XpAl0LYJuyroJs;mJxw$pF7uexUSvOT-H10EF>Vwc4w@VB7W|RP}v_$&;3GKkpl} z-1Ip2>V_u_|GlBh3N*Qhjom=wiKj@0^u^_JB3ce!g8^o`-}&CdeOS^A(O7$PYZ;wh z|80yrVX|`7=BTp+!?@rh^~9PBq({u&mD_V6x+SP&mL4&o)&?RU#=O?cGu4dSVA=NQ z?GFQ?k^l!YSB=${9Xi`Taj&-}%v}8V7nNrG54B@q238kQD6t!|<~o}5z_u{?Dcqbp z-_ar&bKI7B=Q*aSQR>wBU2YfKJ!|F|sSgefl$^uWc3By9>y|7JgvVhax6P08+8lbu}{i1zgJ~IKZ`nT`N`0S>7nyp*=L*cTc2c z!KpO(`!_N)?bV=3kT=0vZ6cGjiGT11B|f5($zhe=!}IgLQ;O-y{r6YOXfXR+0?-97 zZ@60%g2NDm%@t^EbkTxfKC<3TFB+i6>K}L5t?T39x$xbK=k&HuFfbD^ygEKlMYYt_ zHqVY-pYy6&g3k?ae9AMx;MMZ;M!XH;A|)%Ln3ZXu7Jwh+y4I7NU*4#HymAlZgJ7fZ z4imuYOFK=y(~8@=>KRPVzUTI~YLDw*f*;OedTDV1kGFo;3WWG!baAF1VI^TUN1FaX z8&owCMV`UJlwfjd zmG}c|yL=_B5F5>)MKN(NR$N#SMgoOR;ao*~mt*~tyhdqOe%c5dU@r4-2pO}1#(x;K zj`}aehl^YDZYVX06ZseK?T}*r1PoqJQ=HbvcXyp_L>2E{>0GceK5B9LH5CS?jubUS z-T)HeuLm`$aBe0O)=s<^%)E|=rtV{6kxf}JM{yojXYDe1wU`~XA{fHmCX1~uGt zun=68f8-C2eYHj{lGZvqz<6jAZ!gTI&2iky>HVy-bS9FEaoL;^YZkk} zHBGwLdN)+s1s>Oh+d(QyU3p1PdEf@fllK);ULrHBhF%_^N|s%C8+jA*;3+rgKM^ox z`g;#}@jmpWK$zqH7SU|Y9dB>hA#r9A&B$I{xrvBdVlGJ_u!~k)U3hpDWa0v0$9HXU z9uH)|9|&XV^~94|jQM_8rhMWl|7shi*?GyUkwLGS;`+6Ex|bB>^#%J!@JB7j^jzvS zIQOJ9X3*y=-73hg-Zu`nk;5*+9MqKNFRzkT+T}^_&9OJ=21HSJ@q#&Eo}vEmMqtfq zA}8Ujm8>@&3xg5G@NkAKa?!s(B!m9?)v>|T1CnJiE6|)^3j^p8g zc}RsV^g)b^fl%Qv5bGMLuqCI6SXr1~2Z>Gz>pZa;j4Bue^1!#tYuw1 zSShiLr?={k&7Ma(Nh)jt$gn`Oiath)+#LUyovNOgcIVT4_RnhlBu$hB0o_ zGncqdC!9YZJ|Ir5H4R*Rb ziJYIZK>qLs;kw)n#9!x{?XEVRgXAz_Zn9ILMurIp4i49d<-4rz|;;qFkFL7_+t(LPF&Uv6v(|QKPaktC;n>UeBQ}{q9?QsiBJ3 zduu6XB0AcOUFR6(94U7t4K+qRs=yX@^XvdSjC1TWj@X?mPYb(rGU82W!X_K*qhZ0Vx>$e+8>WY=~Uff5_Jr;a&_G^^pj54_vKw<=%s<0_xTPDS z!5A1ml%qVzhVpraZQB8Y>??LMNcchv=i3C8CU1Nd(j#aMT~zj2Q`3Ebuk5!I*WYsG zbscqVNgcQ48I+`VEnT#g(wF%ITHH~gn!VwRI|Lj8q0G1IKh+QEk{=-qDQg)xgULy# zj=ONBu6CssVg+}p*_sEFi=9wly%V(0RuY9qDf7Nt3AH5jd#JQ5Q>?{qhwoq#4Tx^0 zkwAug-Sy%+3$;z|UD7Jwe7%pDq0Fw9Flx`_qSyEq<8zTNtADck19)5j1oZzRCl&^V z|Ad@aIsXr9`bAER9BltXp8oIr3MUf_=l?fyY6MkDx2}@ZuJLJLzQDYv zULCOMtFXri#HS!20aci1bB91cLPGp~hKET|6K)c1O>pd$5=&<)q%YJ z1x^mmLIieiD~P=&Bd`EcQc}0Sz=@(Yke9%f07C#f*dC~Z$gUAs5b&=(Hw4DsiymPs z9w#A!tx{khA0HnOfx0|kYiJ=2JN|#=SAa15dHe9T^}Tv;909oq)Ngb9L2g$8#pDoX zdh~@`f&0M^0l^3WDF)$S9z?j@`!4(N01meRgk5O;Yp^k%Q|p%Xz`Xr?w15Gi0Df?< z?QV7g2!6*-2)MahE3qMt!2>vfa0nC_1k_cf0rnzyf&KNLdte0>W?4`BlZ1e+y( zfm0Ab1=KqLLj8XOrw9L5!e8J-IJ<)i^$izfT@N*>3weDG^_P(6&iAAg<_=(ku;ZHi z)vSt+p%tEHx3&Qo#PsI21H_A-UC;<)a0|Ms=CcJ9ss97q34|EHP)JA!DM0{W6&K*S z$qDHbcXM8@WT3hG|BKY%Zy13=HeGz0(&5<-wT0lfbbPIwUaZfHV3uN4D0y8vT738JoN zdcXY@UZ0vC^dRipojT`TiQzy%?H`0qAqkmLxHrIW{)Nxji68t9Kk>I7gipT*#iu}_ zAM-Zf${&8sIBJmdmlnLS-~LL%$GZI?Snv1BBjjtX%M#dzaHsZ5UF~pY} zGGR^yg5JL_JP?DEM|9Qi{%AjX3=|;Xi#}e$9()u4eg%nBKj+cvdM80XtQ-lxZ^eLk z>4zQlir&lJ=bjd64H+DO`&)pwJwoxQq(J~cfkUkIAfF!w3<3&(AmTVW0Ar6|)7J{V zed7TX0ub0?xG&&Ou(}1!ne9g?Kv+b0h=1osvf3l6 zDCtjd-}WIcX1Ns?3j+h?`bu6waclQTAM*)~7BA4RANwOEpaK#u*v0d6AawZk6J}T- z0og|XlM{{;0NS3;QhO zRvRkfIdrJb_hs2_2Ud|XLWJ)6=yoy0dgrG$bxV#hq7~egVMJd)m04=qCv?ladmESi ziZqk0H~Cwr+h(>Xy4?rGB@0UeO{<0`*PZ#OUBrO&dY=6^m!`;^mzx+Z>jXk^-L>d` z%a~VSJ!M2=lvCm4J-`YJv2}32GsoC^zxrb^)W=6TBq~fBCYO(g-n0D7vGj!MM3rK` zJ!Tfos`rGCRNb88-CiE&rBfzC9Pjc|e(;z%DJSo6w)ObpiJ9+#DNEZV2*I>N){W<4 z7p)QhT}ts5ieEun=exT#?#%~PV`(~G@R{)9z5q=1g`sX4HNh?_uV8n`cBM-lc|9`g z9=MmxRa$yQrQ)hf@h0Coop3<%va;JWBQj3Z$1J?4c(HfnlG)`Wf zBoXd2r>o?IY5i9G@Z|3Jz^5CTxa}zFG4mjB9eH`MDVI{l=$akudKQ}1Tq@0Bsc{Ht z>T||RZykEM0$EKEYTZOjZeuovposwaN;K7QtMhX%)=I^$LKSw`t!uo2LJyi4C%Ewe z)fK2Cds1|9&rxs-(oAP~Ao7bsGGV<;d8JxJV+_Q-aFHax;J# zMOe7uSt4q4;$GbH_TI}adf#+z9`gfB%01RlK|O!6+xwfvf$96Rad7LIQC1`00uD~r zx@3?MoLR0`P5TuOe^RiH?_jm^EHWr=%iAyLq%$B<7Kit7&lJL!+{z}gf@f}F${~0c zGN($vX`tO`P!pX=$SlE4CSL1pJfrAdfe7U+gR!B)o4Yzg_TH>{DVAmscu#jK?k(_8 zDSlj(^k|3xyH%=MfAC;8{+KL%mMDHS zSo}GRINr5T<7iHVEE}3U!|4E5Yf;c4rO8e`Dl0+e0gHAfw0OOF|CNM4%b)Z33~LWf z+OSa2PtgtX?tIyGqnS=vcvTwpt4Ft1mK_e6M54DqM8>8ZjBuLAB;7`>5@VBbD9@{w z%3RWO$SH-x;CF*h8GwYk+C>LqUjCL$jHeyb>Cx{e;)G7dBDQt;lpfYbSDPOy$?-+W za6^nVAIAEowswXYz&`OZiLG5+INL~H^0YY6HDEhf7(OIe_A!+eXhemDlzB7S5?kcb zXAn@jJFnKQ@zCo(B^|gNJCgV?c_+)wD>o@(+}mMiL&rPUofI{{P~#l_xPSK84mqsndZtS0yj z&QsBZiEri2h0Mtt2-GUEdp#V?5tm8RlQA#u+HZV_n`fDKHravv8OdQK#->dPe{0dI zLXVxgzNcrsu;Zoio{r>F67F1$t;TLpg{;2am^G1VR#bYXm_NDyOPoxE%f-C*#!uIC z;cG;&QHNO>8^b0T6~~W_d+xW0ReU)2nCSVn+GFhY5pwS=LWceZ%2D<$5P>Cbf+Q+O z%2IH#86P3=_p#B*+n#IhaCszlH0bEwVL&=aIH zqr6wWvYMLClx)>1c#f%a%hS{I44RNC(v9pU zLXxs*0o zTb`FN)`uMC1K`Z084<%#$i4LZY8+ln1?r*p=We~fZ1LbX`0#XM>}io6=Axi&2N>Dz z9bDA3mns{UFNuG>w{S%hi;<4lG0W*z4?OO3vBW`@h#_nNii`v zzuMG|$zEvG#HW$CiQ1^}J7xdX*S9i6L|4VI(!WOP9PanTdQarYqOQg@!|&$o*bgW= zd-@MhYc`}FnnXp;ENFCvHWRuWycfv4BLa7vG^|X1x|?JY!^=7idu(xt&}TJJv{+=& zJ6Ci0*G@!jb|NPcS1~0}zJJuE?>D4E&Umje?cm*U3CuM6C@Y&sxRQEan6O#+|J|>5 zCdW%+Uw2mg2AF$dC7kf;k4kV@sDdcIUz(edIRx)&?PnoO3$j_xc`?)-XH{d*a@4YF zb(_|AtEl9?+|GPZPXmF))jou`=c+Z+qdBj1=lu84y>sAb(kCdYI(Sn5Wbbz_cMxL9 zsrZ%F=U`rkAJV=kTW~AtP`zlCE$Ra*<+T`7IQsThdbTsreb!+QswCId(hb8%gNTFI z}4vXXhbb&13RZV)hATf0s{XyLUGJ$fr?p`vg zNQLT2D}q_%VhWt`FHPhoHp161EPKWJ#eC_7Zk!=A406})2-G9b(sq+cA-RozgKbji zWRImaevBL{`5a5ItUwby8Gj*|E@9K8vSieIN5(krn339C-o1NW3q!g9EEZgE zznsKZ3@bXo@=2a#BOfnA_M^0S*hlLAMaSLMC|McJV1+<1~(Q_vNgPrc%t zJ?>LDL1*AeR-QoWZ!^uKv$qL*+u^XaQ@20V#Vl5Syt?ceU(!-!wL^+t((yiP)#=LU zxYm*aq_=k&=)2{IAT?rKGjd|`7w@OH8NyFEt#S})i!acbxEVNx>wHIuvj{`Gpu2UK*0r%ScadAfZ1vaf_ z&pMfaP1#}4Bi17YVg`i2|A|5N%HK-y9?%Em0+3T++71mjtc=_fu%-qetD^=^9-tfC zg_=Yjv_NC{n=L%6?@oR6v9|y}aNnVB7z|EpskD}G^vd{sG3~;uh1|CUoHKynF&V}> z{92IL38{uqLzpe=OjO>JAU7TqUo!hso>G0dsvR%f*FgtB#DhPwVDYOm-x{Jh7_^gV zI=9#`YAOaZE*h%P%@-jhZ$LXyoW<}v<&mm0#YTTNsUODawwpZK*~D2lzXkVvi62qa z=5M+c7ZO!U*`BLa3=?XHn-FcJkCp@@TZ^pUFK3{_N8%fyFdr7Pch4Hu{j1B{`$0Gp z*A%mn_}IIk3(+fQ!-2fPN4zbb^s=qG&K!qmeh(5Gpc}@0m7_s4L)Yuwsi?hy3tW$& zy8=Gk8wDvv=0wuCnb`HPC^ANTC~a6{L;UaxT?V%`uW+<@+Xflb7~;zwmf*pZ>+veh zqc|ZV^06R#i0r5T;1XG81dSDzBh8ppIw`D!Hy1w;;j?H}j>fZPL)GvI_a;F9qPlDH z2yuK1!`x8h<=|!$V9U)?P)5mZ#p0TXQ6CwsNx19bVQm6(`r-!}+tCa8-{L0ISn{rH z7il{u>_g6=M=NgAe*InBJ@yGvhaA%UKMRPb7Co_&4(X33YgbVuruUOIYKP$kk~ zAP0qnwX8I=)+WD@%DxC*UgAed>$WV3&Q3=7OloD8BubCs`d;$9OgeX%$DQYaC#l8~ zp72N=R9GR~T=Rr)Ku!eHH)9pi)z#kp;rVl~Bgd@W!&J}`Zk1)kX&pnZ94W=|oUQ8A z#V4a%o@H&fFd>4GPaZFw&OFiAM!@GsOcuS2xiq&n@Z95++TGeC6%2;5-Sw)Lt`j1M z`RhoO%^$}76BdV(9*aRiZVz#D0COZf`3Ml+n>;KidOlw%u|@=oWhG}Hv;}>}0jFfxj2vn68-@~o~;l7orpz}@WHGURc1=NkB*XyaDdb!fFykMhCjQDP$}9AiwV zWj6b20EtzTdd1e!8h7N!kL7S<8_43&q4ai#Q@rTf3PN~%l7f1u zZtk5d;(2aGY=|z{&#Llz-9w^$@%e-?QjqazpMxgyyL9b-n&i230m9p0$;QJB+`9KT z+Dx9?kM~}}hqsT$II3b!?K-w{qfkZ6_B1aC9}5jriK!Q8s>N(R z7^B$bU;7lT0Y0I~y4fsb2n^~|#-ulkwRigy3lBWgA=sby6yFQ=sH zfoZ{N+9p~6GH=NX`T3i#5az>!ILHq06t1`ld_5YBd_tRke8b#sS7cX z3S~t-&kpSW`cP84cHB`@>1G*JbBP#GYUvQiFjM;L0j`f8lYC7jH>vf6C`OHK>xL~$ z2e(962#(QJoo`yFm~+|EA*@!f+EI2%Z+0q5n4?Us&a&YyqP8F{JJ@6OI;CjOPDWK* zu@W`QQ|N3Hce8P<)beE@JUBX=DNk}XEQZpMy=fonTG_1a-gJVz=wNU=y+$Usn zQu^7C&)?C4);d6RdK3=RUCH|so73vI&ppteKBCwEOyFRZT`XkQ?Gi91hW^FUP=!1& zaTocHe|m9L1*nU4q$R~at~ID5Z|xgKSkfoSeuyUNJUO)mn~K{r&1L^Ia6@U~oX%C12Sdam32svC=H2!B#vNiw{rxg zzhsIA?3oW25GB6A z!CT3=W_v}tR;5dAe_`v5rsU5Wc#r!~j9pP*cG-QEs3PXLo2?2{JmHdOJ?Z<+q%5GhU|)b)luc)($*9CQCVv?PuzwvDQE?r zN7lp&V~=!S{ui3{cMr$%UfRd%7DDrqlJuZciXR7ZCV#f}GM~d!JlgAdHJH9XH>Go2#C zzLHBypWN1VZOMC7vVf;L^(Ppret;n$et!kte8OrA3D?kmz1`>gBoN(jX53aIK~_*A zU4PkraB5o8+(r~+bb3g4%EFIsbbC@l?&MXjpd#TKf}&^5as4$b_8ix)vv0dPb?a=W zFlL;+S@SbFg?o&~q(1qmhj+#ZXH)lDHaVN-(=U$VR z=Xv7-sN%_d?RYdbUaPqKZz_|S-{tLcRm3zj(M>bntX5@EnlFJ5DtA|B?S71Q60H%A z`hazbGnyrRcKwD?DbfX8DS0w~r*e-GKOk8bwY_FC{6p4oX!E!4vGuCnksq102r)yhfDou_U7Km#}RiU#wd`_V5ft`G+ z3v^D1NZSdcCG2iqxad7ytBEpP`uB8Pqi{H-!us&ztg>0(D_(YI0*!6# zjm%r!zwGpYxJI17v;FxGFiHg$MGRv0{2NSB{b-EiS-i@`;S8eUsco?Ps6}hxhCM!} zrVipw8pvPfyuzP@+LD!7r1{?f^!_x%pff-e+OoTwsgVHCn&rC&u%u%n(*_6Cr13+ z+0bxdQ`7N)tH9xtF|Igw;BiY(40RB#FssKO-ku7{ljYl) zoGJr5R&62o901Q-C|mzl@N?Z0g#M)Z3hD0pl>(#=+CfoUpz zS&!y|HLHk9|6h!qQd$m^>JQ;sYpe5 zW8Zm0>l`V0J5Dz(ebQq8?$*kstKS)ut=m6Dhy!LR z8)K8DBgrn9xlc6cg3CMB%$+5)zGf`{yA?Jh@*QwnDT$lpy_qQgjb;2Wp0=fu`AK;0 zVDP3O2G$LEG?DzS6h$#rMuAx8kM!*)i^nKU`(;w@H4V-Y_Lp)U5=y9K>sQ$Qy(+me zjGr|UE!9i3l9oWpp-9e4GcGk6NnRW1=oE*ID_!8yo0bLQIIobAZrgm{llaXXLQM5O zbC%b829W`{LP!x9yp8HQP`y~&0^1oEYq0{QErZKBm+QvI1p8%xCQy6cZtO}rY`!XqgYnU97P(UtLJ{T5+_U%oPEKt-hF zi5sXV1AcJLm6Kf_{6xj}1H`)ER_ER-^DBD|tVvSm?%q%(N$-Vf$VO?ZjCW@%tMlcd z0@$|OitDZ-atob2!zYkS+vdD#`S==_M>1Q$;P&{c*6A4q$Y3@JL91pPOK^$i<)kb( z1nut2nZWn6E7B3dqA2#sg~^p?d(ey6;9IBf$eBP`33&F$BLA$%9ve}5>MGrmukBam{V=NJkDt~ z=Fi?O>p(*94z2B#bO*^2x_h@uG!tsKvh_b|EYPXh( z+`l!ty~%ilKt*(D!LEwwM+Vo2P&~PT1ZXYtZq?MZ^yo*YR{eD(_hCQJhmW8Y+R4X) ztK3pUA|-=3Qk;@{)!&%``b;D(Z=5Bge9taQTaNN?CX!TN+K{7}GEAAl67or3dd0yQ zXrLcyhLUY`yky?A-RUORa~sUQt|bg?V$58IEq^96=nk52w0E;|&AAQf-YRE^ji8{G zE+pScAOCRYKw#f#;2??CC$xcmU#^-}(RXjY#_(d*ck^EzH=RAY5mB`ImiBh))GUwR z0~U)750bdntJ5>vUr!2d_(zbTPb+5`Y}sHOielwrwMrC|#e2o37P&Y4R#3vZWaC3Y z%>*)`f9Bojs`q^6R5I+~a{rK6mlkTx(i=QVXiY0;-DWt(ll&_j8VJ3MSt5f`F%c&h zcx{O?6qM$leoj#;upj|CyN?BL$oaTLd|?ulD=iqg{eihvFT29iPC=-3_A!Ro4_XCt zZR&2cty^^UTP0jKHU4-wx84_`MSD#J)#{p)IQc-=b)9$Ipe+Npwsg^4$~;Fl3x%lq z+alOGnogGgi-iXN#c8`iOuO@@+KUwm#qh#dITC~r-|D7Spvl zW4}0U3=HN*z%Ms?kY?-3;v%qod7g?tnnZxBor#2CI}5Lnq(G8Ek+(Az$Dt=_@)+b9 zP{z8m(C4U=f~)ixl!v0Nxg-vgd0wg0v>nC~`d7I4VC%jY|}H z!&<0Z=|^^gX@p>|Ocsa_f|>st!~?yZZ+KzLs>5ii^=ZW}S9adk=-kaDfSvcl%Ft&F z*51j@5$*WB@u;lR$bH)B!=|0J{O??5yktr1c-YL7mdqZ~H}*Y0ctr$&_Ky9bDzG+{ zY)(qCCWSNWk(x7#L%pdr9VIu0w%RDDVnh>HlR>M& z17|5%l@oyr=}^^$iaG5y;h`Qqk;Y*NQxh%c@t&oA{q@5M^ySaMCl{}LT+w4%9rUTA zdRPby`=e89Y6{7Rw&I{y`ZEp=k)|7CG^ZFgX(I2eI1hYh;omQ!Z&Q1qbq z)!rIm+I|!IZsKI9sMvPR8^RAi39|EJ`w9_aSWuB7d=KsH&rWDew_4!y^%x2EUY8S3 zSKCm@!(bVGww>gFQqUcocS2DpHPOD5nt=l%V$+eC=k0iC6T6ev)JicZnl`|-$7z=N@=!& zAj*cmp&21sTcN16scotHH9I&%b&Esi<)MiAryHfdb6CNm*}+`8dVKFor;AnO?0f|V zsPGCtKM(;oKY;g;yV?H)CNcgeFo~J<|A0ws^lblo`oCZjJ3ZU~-@fz@Oj_JPW2MHK z7bj==7lzu}n)gQpfu`@B?470AqR3;8pT|d>C&4Enfk6}sAk4*oir)74dGfOCx=C;P z_rQ3#?3&p&<@=~*EZOJf}RF)sKG0MfH*0YC)4zNLk}sl@-nP@uph-wc67#6aWt zbfGx>A#k~nA%0tT>PfrR-4LMx1>on2KFI)BO&MR`z(DjFJXc>}tkhdW>!9!|^`XcZ^&7I*{5 zJLUH*m_VNo)WLu$7&?dG=8r$j-ZSntJ}9~`uoix^UMkmkACd{UC_v5>1e&E0=x?>& zs_yW*55_IvyBpINkki}qKkg;a=MfAe%ikgG{(9Z;ssEZx`@p|W%Pbz;U)^p2{PZ0= z!T4yd?BjTcVE(PXR&u|55W#_zP#%HsmArgZPi!K5TmQB`vtB(F~L7&Gf>$ynU zkt0Jt*p2*TF zc2YrBLGXb=frp4ef%Mn_t0T*CKdyE}x~jK$3cGBP<9z?{r)#KMu_OR&;A()p&+GR! zJ{^58$Q~r@;H*Tzqim@_WW9S}EIejphD@csQ| zY3w(jjDvmrPZ#mPH+8ha%%;eyeDbY$+e0oQ(hAp`qbd&EOGOS03IPZb1~MoW+4T`~ zhxY%>0=wPm#-#UP=ijd}l5csG?bq>f%{jQ~+Xek}rPgMbtkVOG^niUslLI%3c!7TB z7=Mo({m5?h{FB##e)qhU{%vpl)aUSC_`yR34QhS;o+@}eKl7XKhQ($9s{LVM0sCR8 z=G5Z~C42Nyhk=8)_=T(oOZ(F<9NIxS2yXR)zOR4rnxgdIa1vbVZ_r=f(5@k$-g1CW zVE)}7yVA0HXHg!^YjU3Nyx!8hw;Lj5y=J?PodptdLMQ+MJie}{QiMDgf^QGN0{W_# z*9RGT_avZ?M~)Vt0_-XDDe*xeTpqFo=~AIiREBtL$bTfDHm^AFRX zlO{lbS8wy{@0`76g*_RVy(=_lDCX_XQTsG=mBKSA8J!<6;gAzL!c3>>^~_n8LAapD zJ)QWYKPb_TZz921KLN|4nWZmuj~ms%)l~}6q;b}-4>{y~(#Uw^ojADz1xGCLJFu3726$vImJ)u+Or8ISWNeH8odp4%2qf*3h@%i9y8KG?o{i!&eqie*Z*X<5**FZv3Ri0M)!y~-b4+~Df1L_di5 z+uw*zXd87^fr{ftveDPqo8A9CeK-=yT-@dRop)3<}`Y8S;Wj}VbMgWkRx|o zYh>Y_ZT>EF!)dnWFCQ^xT54;@Yl67vUdo|}NLRwyO#audEKTYN)ln9;;8l38-fTWQ zR9mB#X^7OADrvbEb0dZkO)bm_frqsrpw_+m~(m;qmesg43DN7#6%A9@LBflQs~cQ|B@TJ zoI?}#*<{*=R>|ju-M{pnxH%;&%`$sIKqji@n#bY&#`f>;!|uni)x~l`2Iv`Pp}r2L zn&zatSRw!1Q)}HAJR%JjX}q}S$m2F71P9NLKLG(GBLyd-v#vELwpz_gGY(LqN|8Ci z85O~-opsB64@ZqUS%n(icC{dUN=u{E0_YFkv(W7YVGkUx?1<5ee;u^`q#o`xz-v7{ zpF~tT_1{|8@g#4E9*#-zxMx*_6SkSI5v^h~ufrM8vuzWb?7i0=8&31i&o6a)>u>3* zbECYjDK#EB`v5fo+w>b^BFb-dy;>EkF@BcK#1412Es;d*CE0J5P$ROwlShnI`qJ1YI<(FI1BWB=XK{T_RiMl20Fao zjdrN!k}o}UabibL=WhNwAI1}&6t3E`?H^FZRibeYQk|r7khYku-y402Ken}vwq^hw zzOC*_d=z`9+%z=zlhn}*90ncPOq_4dW85(W)vfT-Aw4G;ObFNh9r+n(Ug4ey>E!!Rg}}%5GSSTzd4ZU z{Cl_}N!3xReyXY>qb1-G^5M@O?4G&E0)h-akVOa8My~unEUI zksUpSLn)ALwPgyRRE6?)YuQY40{0=;8ZGeU*}4~b<7n<_JG~4_Syg2$2W@g@f98>w zPy^$E*bKg8X1r9?S*`SNagVxb_1$Auqj`Ii7LwGCr5ij)qW#4kVEwf(u3mce%new+ zc;)IIf8lxgP1I+G(Ae_J%srGo=(@V3%{@VjwyxQ);(PApnQ$Z`9X>rqMqw0WgXuT@ z$bCm$XvipLCzTUoMp6huE~}Q!(HvA(2AC8@vq)-5z*x$CQvPpfj2F-9b%Qxmn7*2q zxqgcWvpU(Unq?j1Mzlx%kRCY*`^Uav=hxJFd5p5@CSDoqQcX2#~Web( zK!xP?0bDy{LItugHZg0L?6_}(Ab!gkj_7`4YnKjprPX)-gEXde43BY?Hbk+c{+gfe z!}C4cFE*<1XZvIB7kk&NTBsDShtMS&8li{!grjUGl2EF}7m<9DVb^Mlt#}R%mgTf* z>JICeCtAnU?zIr3ye4kM=@AFndX1~eDx>oK9lYkfwM?zz%HHkGr-^YcejC^Hz-Lb6 zw$2W>R$`l_@FJD#L*~7LLJOrOU8C_u+Fg;1iR8EbKuKOXdG4vk%FCw@{TN_sNDnRW z5X;M)iVXH^M>i@BC%N{*4?kYn8E}lZ$s}wQ=Z5>mI* zgI$e;{+#RyXC5F;-c(4L{K6a6w{;q~PpUG2$szZq(D@c`59W@TVtBw@_f+l5_@Yto=TE zr(>1^QDaY0lj}Jr+Vmk33nk52z`;!l*&;Q=)!lZ#M6c6kj!}zDvBjii_2gr9me*?= z85{Z(wK0r$R0u4sDP=F!^28jgh*l!3PwKdunjhi`^9DqHW24p#S);c<3b0K)Kb207 zwMl{O?Kcge67u}|QP}^?+|?{UYe04{zBRYR)BS!{{&pgBIFBwP4Mi z=c`?kRn(|YNUqK7ZEzE_Z^(>nkZhvl#bS5v^a)XaYiJ#)Y8_JKWA&l*2I{*hf$7NH-<fQliqnq|ttLcatRddxxKxvLc(kpNgv<_YVYLw#{t@1KMlj z?V+3FCl)^NYp4EdhfS?4n?SWfD4dtkaIsj|Utg>&G1raoQ+z>u-%2*t{;oV;C&*D# z=1$I5+FyBYoA%E<6r2O@;P#q{AQ)@Y+0&gx=?VR%TD2WZ^N2U zN8FPuFin9K%rEe|U2|l0T8{`^Xi!(N4e-#auZ!6F1UJJZ_a3?_EBFBt zPD+<5^M4HAI0=R#vg&FGqv4867=Eiwilf3sL-z!hPUVFFZNk*}<5DD~EZ&AN{M*$Z zxqyB>w1cayT2NWV;5ng^wx9fpJ=MB=3Dq0w=t=4T_;BOohy#y&#Env|G{da<%4rX% zuqLp%vdvdLN}7du79G``H9S|WHwgN}Wk|s;`Y64 zR7+IK&^cRqeAjRe<6WeLf7K(A&AYa}LaG;vKXlXxu|1mIy|v;mSR*=4CFtN~pw$3f zpGk)+{=xuopBE1u!l5$yzq;cY1Y6_iw}E+2lF#w%bW?YH-9Mw!#Ha`XRX!)k1@qj6 zA#yGg&$YU_e*$rD3)(z$wi4n-K2CcM0UgDAt^4GW)@`V{ZW>OQ5*7P5!TaH=ZK;3t z-g1RV-d(1e%#t1H5rSku;Bi}Gsoio_+s-+k+1{luiNl>T?uBQ31!IgXMVZSe0P*C@(Iy$2YE=_)%a{o;) z+6NN27?HlyC5zTH1^;-&+=a#dvgYl;lC*>sGq+yt_lr5}dkI_HrM+70U5w#d>wwHq z512CYiOOg^>xUEib#l-@qs3bZzsGqrCjRCb)pJ$DJMq0rB^-G;sH3OE^<-w2(X!I$ zhTiAr@hv~=lZNCEFAje)Q#-+ch0cg1XBW%bohgOoyvfuJ!@VKg$gHn+f6neW5?!;| zu;zJzd03ygPtz~9s7wb$$Z+2KC;n$rU29EDR;71U!oYZh){kuiUlfMW6P4O!gqo-f z@j;n8ysrIQ#$~ojnP+mL%Y-&nTfE%$mYjpcnRrG|b0q*InL0vtQb|Dg7U3rj_ioF> zk}+tKoxLn(>Q)t{zoD$siU)RTFe$m=SByS()8nmxSZoyx-Qgo(s$)*hAb*T7LMXbe z4dlYtz4Clxh^MZuNZjE_T?`lZI8)3FgXThcz%fMDD7jm4Vq~K`)U-4Vz2`?zZTgQ3 zRrDP^MesqXL zWJi=LRyX*cMSnN}eN{ok0~Ay}xM`V|;+&iv?rmK2 z#X9w0p|$e3vOpNQ&8hpd3e=8XZsOKi`X?BEqeSq&b(c zmy(LD;ZHA)B5PeUkmNb&i%)R~v$Ev29uYx;SKWxM-s~?AQ#2TB%!%(fz=vn;7+;u} zHT0NfH6ym3Gxn?1ASCtPIx9z6zircf1RZWPu(*)mMdDj;u}+uy)sSweNmQ7h*!Ij{ z0I8-{pF=fF8x-SF0D-)%K8tlpikyRe20^5WhCqz zQKPs~zAp~Bz?K84@h2f8v6hIl$P1+n|7F01k;sHfo~(=exnmU({EeQ!%p=OiTy{IJ z-`sb2UYGT^ku8tn#ua~oa8lYrGnQdY8zAR9I#d6jTEBG>CjPf`z zh4i->;FNHeo=Z=x<}+X3j&BkYP59e%;z@mk^TEmVWHi(l8}Tgu zB{3|Up+m2EiKQ?ZuPEk7)#YGR7sl(j-CeBYvosK{&rE>GHs@YNM)3Y@%NxC~9djC+ zD7EtQ*S$;ZvvufNvFCs_%!Jrl%nT9WPh32Yt&zwUU^y?Gv;)p9OsjVyyZ%BGOz|q? zmd>9_Ci7x8bQ8E{kwlVl^|(6Qu3Yp4R;g8x3BK(es}lL%`z&J4ATpBv*&NRX9V)y` z%HtGU-!1Oj-2sRD2X-}4`S2I%8T{OEHn&vh2x6VQi+j7py5M~BK_gj3*yBIzJEI!y z&pm}Be!1+)IlCC;q*~MU!rXcX+kn{3r;L4 z&|nG*vl=BQh-tL<_R22${M&H#b<05(`1Ysy_lI@K5XFk_IYmB8U?FKB63+6>ru#Xc zHIZSdqleBDHO|^u2a;6_m)HW1s2YYt$lGvU(Q=Y#=IHy(f~TPzt$Qv>AVaUzh1hg8 za-1jfRD!{P_(!n#*0!{!KI7>yjnxSg%B@-03@?>Dyo=56lduYVHH0z|XeP1dPl(mu zAE8b79NJYaYttCHSM4a{e8zaDei8*)pi&mn6(>yg8JscSU8)AI@ z_;tM#Cnfs`_@$ckbDdHuREF4fyD7uAEfkF)#wKe<>W6vO*X(|2&Xkae>*GxpNWof} z_wD-(gqf0f$!_&!T{Cpse~cj~oF+pV&tBb$kJYIu%p5e#dPe(1K}Q_Tdl@YrlBiuD zF<3Z9$4kkd{wO$}cXx%03}>)uC9DlY(N2?MB?zO=NJbq{4x73ll&xo$PA?aigyw)L z>i1_K_Dn41N)0K^{!$yxDY1JBHVGMcduGi3V&vBOxr1o)O*1Oqb3c{(8tl@D{^b2C z<;T@_T{$Zu9y4I6#OzqdVQai+(nkFg0#&I?Z~a2!Bf{1YgDL~Ju(P(4PC-iui)a|r zKhq<`StceUf~f^_P)FsFxXp^(DzP78ATIvuYh6bJUHtWxc+QZ&J@Izl#r8SbGW9hS zy7sP-P{EK`(J2bYz)I$>>)Vp24I|uN_&!*SBX)b_n@!omte0?YAAb=bKqS-Pft@Rt zz(wQv?m_ZoeO#6hQ~;@ZKQ~8}^*6o^MlbKPrv%%Z9qrMgt_fY0 zxPM8}jrr;*WtMLaE?M)q4`qWMOc52%UzveQ64a4cu7)2=*U?@Ik`Z+|0!`F0Q7n_S z+WL>#UR#CXY-SU>fQSA*3H>9m4%x)0eM7FZ^(n-OGU04<(fw}08g*i)?`~2RetaygOqsryw(=h$J!Y1hSomk#>U5cXOdGl!4@<>ay&Ox!+MG!?v%z zSAY0=l{uaJ0^Uh~HzH@}w0#jXM3e@cLEs0!{h{@Pap>VT4b~QH!L2-B%G;q8R`7WF zd*SYI2CDuEi}t>2&}1^W&v$ckQxaMc_TV!Iv{FJYr&NnJ#qj0kwT8-;LW7W#4AQKeQL9WrS8}g#i&pQ zuO1U*lKwFWBe*%KkYchA>0w0amgbP|2!gHLccVxW#JJ~5;IPIogZW}056nWt$boTA zh}cdD4}`&cch%#K=92M^%gb8q7ta zH5(&f78?uI@i35N+-3%aTMY@VW~TdWLS}Ki(N=J)rEh5?I;@f>mumBWqt`g9a9_X7BwBNtkFc0aa%j^%FJpgDY>%Cv=?qGLX) z^~3ro{8}^cZY2OLS{vy~v6{G2V?R1z5PiFH;>6UF>?Xwoujy{@VxU2Ny{0&TYbKmKIk#OcRj5n0eA$XgX$Oepk zEwK=Bu(ZU>EeSb`uGBRnlp}`=$pl#H@?HzCSdx*8(fYF@f-B-wbWEbSBE3dAUM0Mv zbrTpOlOtx1zBj-(X zvWt(A&5~392R_3fDOzYUTnoGHP@&x&~?cwklxoiHU`O@@d>c#Sj5bFAW*Av)Ze94a=n3Skn6=$ zZtjP^JeLx)#3?-FQkLs14C3qcO?i|um=~qN+nkzS^cP2Q5QB&AwF5Ys9W-wV&ilG& zj=vA$Aqr=~LT9Ix_F^Bb>Ekagh=#0SWu- za#=Ys*~lxeMcwC1#@3ci%NLIVp6%W^gdFMq2=N>rNv7>?0=i^`w%8%3)~xPg2!!EDW?e;X310hITu@}lB<8YM7Cu7(NG~uA_rPOxjNe` zRH{^~k<>lipvVTwEGHQDvECW5ptGcF2^;Js(v=&n1uL}fhNcUEv@ciArez>KlHKrX zl4Lbw3D)@5{RHM@l6Q)_SmsIE>%Dotzh{|u)WaRWO=hlPQe@sLx1{PK;3A6Uu?XQn zEz4!W3Kl3=DKKcKVq*4?@c$G=IsTS#=qos}q?TYJTBwmGey)F={}6=>M>~Xcwg>8y zAE=1F`!=^XroqgD`~van!$jV(efu|%J>9Gr$bbd-hrK$9^l|y?h6ziW-`^$)X;{-% z9~*n*)UDQDZxst}WSO12nLN}5l{8m!&q0UeXTP?|JG+hI7~1n3BrD_*`7nRv4fK## zQ$5yBaD_4l;w+x<3E_f91A9anR;q=we^;Y08@>tX( zq%~aOt>(2x(Q0Xd_SyKUsQ+4e!_Z`@7H!gWr1 zl+p+9A*K=MYS00bJB#Z) zO2oG>O2mqwQqtwn-wUTG?+i;vB8oUVJnZ=0q)ZbI?MAygpb)hx8q5Ms@YeD!)2Vrt znd|h~NAp~>@NWfle9%lnre8w;O+ZnVfeB@Fniv;srUN)k;bAR%fQ?3Q0r1H}tze9gUe71iDrvKz7Vdr4_|GPLsg-{CqP62_Q1=}CnFWo;s8api}RcSl!E}37M zUzbb`!9nsXzGBm;HXtg&1F_uvI^Ooa{>gqAv3R{RbfXh9biNb)1`q;*eLe@R)WdqJ zY!KL_-@3R^)q0l1P>PMB`Pfan^uFy}$N*$eK+upM;r{0*0La_Bt_NqYdLJNS2^UJk zAAyz&`ws)KQ%Bx~uvHE10zqt=*@*$Tz=H$GNlE*^xUlh0pk0D|EA;_1mW3dz7)?Z@ zm{9b-0r+}_FFgviQk?j45ca&hva+%|mZoevtrcC&;B37}{!W0?fUVwYTs_TRx^aND zrRlBiqMN-sAQ%?Dh3^+gE6)7FItnyDkQ@XAw4+c^>wr~XHDK`?0K)Re7Zw=$y+H`p0F!+6JVKoMJHxi ziiM40d!-NKr?HWX?VVx+BbU4Y@-Id6Jv0Mz2ql2O<+g=CtBd{ST_k|hfHk^E zAPzv_&7iMOfDgC?26*^kzj|BiokjtESighiu|K^K>_B^AML;g$>Ocy3?Yy=sd3phb z6CIjxscyCroTt_ehgb&g893C?)fQJaKh4oY1l1L^?oiafWMjAHS{z? zJ05;CmSUGn&0_=B3XrEjJO?L!PT^qf6@%UUtepwOV+Zh-KKr7)r?CE8Q_{bM-(!QW zgv|HzvnnU_%Rz99(1zUno7GRA>G8%ZNe{pEszx6P9`To2N4ti{LH^$;4M-qQztXZs zFpn=(Cf^veUt;-!0P^T>09Py3bWOrq=L0L7VtA62HG344!o}q12!Os`G$oC0Disn*~-#e z@lnO^h1(6tFa3d|dzjs8?bzV+Bk#ot55$)Pf5}M) zctRv1?lqTcUaovM|J3Ea;^$u5{Kx=-=Et{cY<#O+(B0~00opp+^XETtF_bdCb$+@* z`t<1NAzZzG!Nx;4dt$8H%hQP+j5YB3w>55}B$+MaQ3M)gd0k)Rh9y-oo)P{mHYYo< z3%OP^dKwJJ1UudsEMAOlY~~I*Eddj!EBusy0?F=u;EmW`^*uJ*S$r_WMV2b(e-ZO= z`j;HLPOT|On^X@7{{>~!@uX@ybJ%dBZicb@m6(OVSiFFLaCqO*%wRByo|Y0PWFiZ3 z5T-rFv<0&iIc!63fPZ&#k5i|_*Qq*n&=B11>7K$hn?vBHR5+(eriCRVC~{sfoywQV zEiRIrSh0N`JWNUFR4kX4JSwbwjy>J(c2YLFzoazRdr>GL@M7X&9hCdQ352JyiM1!l zr0~WQA=ap3$q~%=iYwPG8SSuJJ)@UwTGk-Kg*CoegA|DRxJ^<5uE*-))xMPOpQ4(X zVQxU(IA{PC2%+JPRnqB(nUV#HTq~a79}eqHlZ>_;G*1+KC5>85vH&1nq$X~+aBalE zN!bd)b9l%`eGw}EgQ1{DmQl0q4E-dG-JAAuI!YRV_=l^Z<)b-XV<~W&7ZJme5|Rju z*<^1^1sn1WQqk`n?9J6#*R@QXI~gSd%T$scm6)8FIGts2lYe4ym;nhc!Gl#KRCd2n zRpP}UPxN)bv20gW!90KF6@)hmFPG~4iWr`?a(m_C&3=Y)ZurSp7OU>xrEI#3~|5V($W;E+JI%(kdDO<|?flP6!cmEc#Q zGK6=^i3c~hVA74Tb9QAUwQ;Lp-Ob(M!EeA+NXR>itN~SJBLQ!r`pU?UYHY--SG8t; z54F*B5}-XX2FIQI);3tsgdcch((uf?Up_9PgTOD{%Zf%y+Nx3U6sbJ$p;yn)^46Zr(F^AH?*8SxaE6}@pC-jqsTErVjXu=D zVK|F33(|P5r_?vGTmpp94$!N=4#&=MZKca(4i)e_|6V_^oXUGy2o6``@_-E{Zoe_x zzkhs9T@$mXKCnr7VD_}4j8{t?~kc!XoXw27;k={FAxF1pGk0o!8&nY-}74~GuH0)2{;^9sZoj4H^M%GpZ*bWzI zooE=!F&nr~8YIT8mbNS2+3NzP!Gt=i5zh*Cz^~AuG0w_a*5525RiazvL-wwsQkR^O zukWwiI{%H9k?)&jc5j;ttogVj;3&s*^=4VkGx#Opz8n_J%n zl^dXAe6o%QRNpB{J$zlg?ywzfC5g))I6)d~BHXF0M0so6tHSu1U;}x0 zvjKLof*RS5pn6gXpexoH)$lzPQN+|+B&4+>P}-SgA*{jUI1`t@{H{#SVgM#q^$d3K znG2#CqE_&9?0-!i3ZwJCav1USLvTF#tao;@aXg3obgn(3cBHbre7}nWiz8>I(XU#n zieh1Yq|x0U4<`|0E!g|J!*l^Yf;rJ~xw3lfK;B+)=7IF~*6&Z0Lf)Z?;33>ijjx#*<_?RI}F$2`L=eCR&g)$F1{}giAI->C2xKYWk zzp{HZc<4+SXjqtF=T<4fWahn-3aE`01_<~}-9}(Tfkro32gU1%rCvn1Hk?+W?EXCJs>B-As zGj=k{J>)QUlKutC_#ktE=dP_08xSpJQ1nFbd`uBzMTE*%$8Zb-vmtSqKUqbjrlmCFz8i?dS_@p@)mb`+P`ae#clh6}JI7)sWzD zB(|e_%^ub(3YAOp7U%o~8#w20i{e|Tq-|GLC2Qj>SIi(CiGE*zpIZ(UeqEt&H=S}B z2J+9{(Px%XmEVQt{F zNBAIHU740Q*3+e>_3%Q7)Ep%Wi(H%@3>PMnLXOA^aD{dm6$+_tbGg{SUa^KR`i$@YcwfOyale>blYzlVa4$!nJbJI;wsu-c{X#cHF5 zG{I)ww3+Hb-^^|gBcCqZtn!t)GbEP1hzU0v4LET2}E@4usw6A z7^v6zNm*;aEKuQ@&az)0m*Xz_7sazO|LDF*S)~|dbuwx(m zb{Ko^dcw@q6ez~zLC=ZQT=hK0!}EzP(A@3yyUL2%vdv_@6el^KlKd>>Xb-IE?(%uu zQb16!H~i(t3tyGu?dJv@QC?t^f-RMcxLFILwqeAh{`7 zVKJSYL;Q8`eWF;Mo9Dj6I;oo&y*Q(76EnPPoc{!Rz#*sTd~m_*0jrZ?FN%FtCf1u_ zbb+NZA7E1j+k8k00ygolPTlP~v4E8WN{<&xfzp&f#wocstTqZLXM6DExmi+2fPlb!OuoPncQPnplggC?(aoc5>%%p_lHheKfJ(muFI8_7axZf5p8Gs>V4I%S<=C z#t8TZ-b+}D_Gp~ZmKvW*=8Z7T{0>=M zh6%1-r?f6u?Vtbcf5SmTA`ui-TI zXi{IwWV-J`mdar4c9a3ZgB^<&9J~8tlSUeaqQpjbFU-d&FHN?U@Yp@N{372c$* zF}F6O$yyuZw`fCo6%h#4N$hzTwM?jvzB_f?c|e+G z{Kz8?-DkEGBwxK!XV*TgQk+#V-`L|xr-+GH&|`2IRUm@IaH%${q|r4iW};*Nl9u=^ zg8sJz<`PIdv*veD6h;U0LMQo&iS)_`LJ5>@-|tt+N3eC%-i8D6rKN0e$nb0`Ycy1n znOjbC#Ia`UoDWKp1em1fVYgpXiZrGOcZ>-bbhhkrM2<6_nWtIR_-+Tt1LIejs4 ziS#qI5+Yu!G)W*+%IMEMhK_{h_N~UFf28A0$Yq7ItU9V^g&D*I2G`@MJs&$X8M6Ot(F5!cPm!!Q(l%k;#$dkzB<5`!`Qx%{wTqPN<+{ z=Qj|rT`f7L>3xnh7>tlm?3tw-TC|T7S$9_EEk>+upuKh(cl*{A*qo|s8)-|Umh<0M ztL7HuR<_u}HmeG}D!&EU_<|$IYMSe3$w> zuAs3Dq=XWx)`<0Q0!f~eQ@5m}$QV%HABWDe2N%riqih`xR?GMQ&}GwQl+CXJ6w_68 zDq!Ec@1ZdkTbMIOi~CQ8y{0R*?ijR{?Y~D;HGbI#9`VG@iI#Va=2Jg$wwl`U^8!Cu zeOJnf7|N{VG4TI;Oe|?P5mZ!-nnJCD2OsiAB)G6+vBxW(mDQ~XoXXd;`vu^0F37q}? zSR45u&CXh4BxI-7ryk7q(HUSVaeTWY{>lW89mq2WH3>3R8!_XD^v^cl->)ixYs!S1DJAw7{x;W}o^68J&I~+$s&n=uC^S&?|0= z%;?yUNS0n zG8Fwhb8$VCBR;BmPI9VL4Do$>oY+IRioOr);T6*6EMX1sxoGZ{1V{ROI1|$fmOf^a zk`4HB9~^yreV1Hm!t9&5H$L8m?cPbRv=uEO+q75fFhtNcah#2EeE51&XR(~Pq-E&oU%WjOG&h)Y$7yuMAX1EXf$yIQkXjS!eBBX#~nZwhx@_<>Dr@Sve ziN+}?)oz)W-KBCMFZnqai5cN9e=s1Oe1XJwsqGzp$F@oVQ!9m^TIdbC=4ayWn5nes zQi2lP5};CG@8peb!$*SKPb)@j`rfTkE{9YsC%)1u-#T!jo^v7{uKeXbx=Zx%yNl`_ z5^O3V|DaIyP$w;$UAJTWv_Dao=6KW43%(b*y*QDO2l0A^@a~aTfG>LlWddwKFe~qk z*6i1U0UvrK!c<|rzVH=#i&7NEIgXd_<83;sYs-=pp{viOwaEMYY%)br`D(D`L6uDF z5O(AA1yx4v$y|BunG{&RjR?$N9P08G1Q(9W=lX0^7vo{|0iI(`KcI~|{v*7dGaAT4 zP#z1rU#de`ay;c9iIqPk`u7_Ex<{0A}sX?~62M4^VJTu;y@YSz} ztaQl+RSazp$vyniD;x^vxor{7K!L-|M-#>E(6-CAuTA!%BdN<>zn_nllJJ4vi%4WW zM>fLL1<}>IFjr7OV;WMv>oS9fHH@9lrL*4FC-53G@B>^W(><=N_nmk`?4n1?0h+H; z&d8lu!>KdOie$V+4W8Z_ZWx;?y@|pnH{fR-RL3qHTDaGRw*ONS0GKj9`xy{Fjx4If;icJ z7e)ne8%Jx0LZ?W&w6lE`hJ|S6u46OGpps1?A( zx5NA$fTZ@`njfTiapCj8eZC;6ws$K^|DaUi{)2E~YOx=5rH?+uwHpRZ7uc5rNJ|QngsslxjgQAoOe68~mGHGLl ztRmO^GbE)eX%+c&>gOz$LfeLb^O6+$`;$}7G`Az$M5y{AyKBl7YGIZfNW7k`dU*|` z#p=-tP#;gKStidyyIA6QVLvQ1*#R9vgIp_dOAGq&z95b3;RafOVwsuCk2M)6^Rm`PuX4Syi*Sh@o&HZqcB zD6B!ao*k|+I0|XXqlQj&Zx(j_pG`xH95*w9l*j$4SLVeB+@s9T2!lfHNE#rQ;f~Lfkg1tTN6(6>$d9pxx;EP1Zj8yp> z%}lwIjke3E`s6>3(?gzDaCl{C#sm^YLoqX-x zA+iGh>-$HsA7qHO`*{Zpt}M1VpVH44|S<}GDYDN)JkOMtA%mO_2`CA zv-_jjIb6S=4VWSFYhH5Ehn&P0pddeqR;*3Z!V19pX+>E4TF`?b@TtH}{6hOLV zJyx^8qk5b(#4RuHkx@?-jM6fAtD*&po2T$F2$0sgcoiCmLuPdHBtYI5`#&pYgBbG% z4+7ktrWu9}t)abkaAueESvy8AN}A@0fmGMZ)?34JdEy+zwH{6mm@Cis&!8;bl|OJn z+jl4C!4NHG#Co`p*{GQz+hr59UeI|N1H}I2UuVwDsc+hJim6o@QRPI<2;sh>zp02g ztcs?dSm%RV5iLH@qDIcEt7T+)=a3P8Iqg!(y^hpy$**A`E8Sy5p68`suC3VUoUGec zz#GBIFutWaJEUZ0hMpOdE@dxcRsM+gs$w7_J!(2Q% zb*m5S@ACRC2H@R%wbNX3?NZ-_800*R{;3!hDE_O;sg=KMq(AN)?a>tHn~~^fisc#U zSVZ&vI~8_NJLd}h;PDaNu$}xJwGX$i6i-t&NjdnujpYQRtn6%B76rQ>8SmC+MnE|$ zepG-F2*Uk7a;4i&^KPN!Fm@d^nv^tRJb|-HUQBuMIM(#V~kqn2vSnp?pP2)vBhj$N3t+fzW3R+g6A-%OO6NPyQwk=nQ;%v;8eVfVUm&0 zX%F5Z3u!<4sZor#(dBqboaejnTqwdmf?M2hxG#;XULAX_M{}3x$Wj+a-c61lMT(i* zhFk{^ot2rpJ!u?2kCV4~L*n9f_TPjLiEJFGC^~KJU(PDtbt?_j;YlkYw3OZvi`Pl2 zVWTUS1}Wu|Y)95ItxPjSf`S#nJ-`W}4DNRu#S$l)X#EA&$grPzUb2zpm$97iF zRl1_87W@4sDn2^4r-9q+)eWsa0hrBY@l!uHYVbsc$el}RX+xL)?KA(xHei`XmE@FW zgo(V^e6{WnBy9`1ewkrQ&I}hiG@tC@EVQs3*Dp@nSznRPxKre$4S;;GfTuQyHd-D; zMd|P{Fc&#GEHxj?sid_O+q^=nL{uGIeyT>pCRMMTx{U5v;0UWZ8&}|9TbtyylEGtm(pZZsz%!^TwF|BEX%;42vk*B{W&MLycedE znESQomj5t#+Hxymt%ia>=^3KSP4a{|g{nEErc-m)M@&L%`xt~kuumi0ms`s1yEKi!@B*nlL zqm1QRJj^n9G>cwIvG34nQm5tMQ}>b6=h2yF8Amb3RZy0*LJ;*A+$|+0Z}*;n-Uaka zY{xms?35~OlCf^SciuXTxtGz=7)j-gT92}f?{Z|laQ!}xJANogrXl*fw}*+Fv<~o3u=dOO3Z^wEG0)_nJ2=@BMXze!iw%V-~D?Ve+-$C!RL@vK&3D-$>6@W(fbuV#EHQEH*5hod0dAVJ2eZ z;$r;o+y6`1VCVW@)c?3b$uI7%(19*gu_DI<7Kq7ypO!!FWPySb!~7tIiJupcFUCB} zX9Yn{p%&3Bk901Eqmn7XOrU>?I@)>vyzyeWkugo&)$qFVdFC^#*$vJcTa(s?h;UCvf&rcQjtak129yi+B-s0d{K$_IAgx#au*7oXmn&|9 zi>;sOBLER(GytgU>Z)G4asP%0xfLGFH}?lYI|=-a>>4bv4KT&RLJ4?y7lR=t$Hbe} z5fB_48-s!tF$lntJGmG%1Q3$VLg+{KlkoH)+xOQ6fP~7U{hc%ZP3`O70f+Jq#WBRW z@136u4FIth8vJ2SOFRUJ@K3OU&H|fuegqM{hJGY${2~m*+Phf?^#8u?oBEvjQh|>6 z%7G6VV5D-R+CYkMh2$jO{sADB@gbVUq=fV@-0usQ=b#OZM|uh++0KszAH10@0LY-D z0+Jc`cJJyL<%)kH!VQyb`^He+Rl)Bkv(4MH!NZ39KB!mjds7ngB+(Bx0w%pUHPxC& zBXRHD48lZ&{`$lLy*{Eh2oUvjCw5-?R)qes?8j&ZjtBsmm>L(K0{uY%2xgcT`K#vP z#P2qIL-c|volf-6f^mRoPXZqREyzs_&94liUd{pP|L`aX4)Jl*&#$Je&j^SO-Uq}& zn~`On^Do0N4xY_r+P~(C>-i&u=kqcG9xonl%6@@+3^18<^nK6!?bZbsMD&J+rkv(Q zeB&#rjQk^Y43~iXy>6gy}of`%4-0sZ!)`E;B7mf7p8{ODu-+C{MN?CAJJg!_#B zCN!XeJv#=b{hqJJjLr80gCBr6{Vvrc{&HUdfQWe(eEq5n3PSPD4|Jt4*TADi0GIe4 zNKlt4W&pK~9v;yCqB=&hy_>SI6=xm93KIG9Z28gnJO4Wp`4Ym3yqm8cT;mIo82bA4 zq!-5=3-W8qH1P*EU}+KcTnvJwTml6Y1l%9SH<;Ah4-T6MMA*na7!6=BO5~3^nsmO} z5(q${BHMs_hx}}2yFJ$~+ z-@n>Qckv~i=}I3fUUX1(p6ad(oXcT18&=^wj(mVxe=M(y-bIyZKgG8ew*gP88I>C} z-YiL-#K_BGH%hBMS_M$`KlniAvLb3{OUgdrI858*T0OMqZnnbTrSaG>cTc;}@@1op z5gi~Y-!)wFfA($+^IvD=UQc@NCeXL!)B#(yOIfoca@O_ID9bo1l5)tIq}ni~$ns&= z)x0t?`=@lnVKLK*1yo`Kxwz^^`i!6o03z9LUMlekn29_sdDMD3eOjf_YLb^iF@0-K zaylB=)2>-2v7W!4IHz%3HBV9P!zRW})7(M&D_1;+LP?CmuhAl+Dcr% z=o%^7j7l>!&1b9)~z@8g)^Sr@l}c<+UWFx4sC$P<(d{<84XX z2e}vdwkby3BK@C|B^Qq%dUhsjaBrZa)W7<}hmGh~|F5@hpNsZ|qjB5vLkDrFB$Cb0 z+uZCmsy@)eC)0v`j!d@Zm?KW38cXF5j>J;jf(2T|t>xNtLvlR2DD5lTs?FT;-sk17 zt1FT24+luUGmFBr#VuW{MDG$VG171Svqo5{gmT~vn3_~``-fJuJAUJ_fLDh54szWS z8qf=V5D3AbpinVQ!s+L1i*2s$jz>HqEDb7^E;+xLu3~VzWNb@NLsmrNQ{<4y1f{!a zk&RxMK*MWzYRH$AcY!~sh86=CSi$)Zr2!%JQbF&H2vhGC5SFv$p<{XNOT58QL^Hwk zH0-P!j8vXdJ#!nwgi?HO921_NI5D~tB5?|;HK(8L&(ZKA=Q1PN~B z{%cczLGCFcf-)ViQ4ATo5xEg%caWM$?(H5|{ub(3bU8K1La$O=4t=CEOuLaH5VGa8 zk&AqNt2CkKjqBQI4j79qKjC*8l9MmL5b)5-Szn5rz}~-dQIb?oVu-P$-alXOK=L@B z3w<%CqG2vl$&>`YKNJEY&`_uic@SxwNwijOkZkNr^;=Ysj-I;u;uJopG0ocL;?{)4 zn$VnaWlHlkPFsHr^jJ2YSOGk554C21W$;N{Z;wZ|I`Cay+ZSNOi#$sRC~aA3)XAzm zAqOoFd(?AP73d|Sa4V5TbQW_vrDyg9gLxxW_uxMKL>}eY&dqBW2R00!#V8>;ddYP3 z8G0R@;?sPFxAO{<1oEokCisT$Xd*-QEjSi%d>o-p?wZc*8y+n|Wjt-Yt5G$=qBJ$K z-9GUWF~;rZZWn8?W@*nO>ZBlV{%wG%lnNOXxFVgv9@mir&$y1X=%ZD?$I_lKumed; zN*DW8?i=|Fd|kbaI9={!C+BzP1SgZWOQ+^&fmiM>f8AUN3@kA^yzd2dQ^f=1b@fiM zuOeG$NP)@PZDq9H-GEQ%>!*_!Xf988!b+&hoZ+1D9<7tkN?im}55{8pWRZk@0+MI@ z&p+)vwPci?1c38RX>G3c|0feOV#v>{m4U!T{TUSlyuO3myUy&Pv;)EnhwaEc63&quIa znki#B$o=-oA%yZ9HL!1dB2OrnOCtn=M-VrYh);ca#kWyBp!5`FdjT7`q z%+(jk{WM;1F`nQMgc%h~xdapE{coeNRbS>3$1mR#Nz zx04fEZhD)?2_C)_p(8)V_(tSUeGg`OmEqv~QLh{%cByP09_@~z7nhV8(Y4f6OTbOG zxalICUC={nYV(s=kJ!aC>GQ8&v~^Bv>^C*S{t`9<#U;%sl0&{57Xi#oA{<}@W_i6) zD%ED2?YHE=lT?4FCqRIoBddjJH(iul`|waOlN5IO)XeJAdv(R%>{X&+n(#JKMHdw1 zrdaV!@Th>Xi|SCT;$FKK6izHK(Cu!!$df6dQEM4)DR=k^bOg*f#-B2e=mx{W@k@P2 z+t}iwngx=LN#ER&oy4M)-^TKbqV>7jGwW_DLv0Z1KA-cc)pOCz^o?t%C6%+7-Cm8$ zrxaIzxG*nna#$>CQe5%UWO*Rb;F8+K3DsDV@Pa;#?v7vAnJXsWW(Qu*4)!|yY<-5i zg-FQ;BFLYjX}Iwl?UvFLE+H;vG5#^9-Z{(PqqTu2PRXM?jVRACDLg?9 z|8-l?uzmJ~G&qiHGldUScQRnBJ2CH#QQCn2$X>*88L&QIF*|E%`tyidWjlKj5Y~gL z8-%S#*LI>haa7G1GGpYZYEi4w(_rsiO(L8>J^(aYpby2*q_m1Dq?w!8KxdmRmei1- zP%F)HCN3&c^euowh-q%Hy*-t^BU+92*HPJD&2^W&heWK3x9DbQ-EayiZX&rv)lz>< zy&0H(-&hXheCYDFeU*c%n!zWD{EL$3uxgD7#{|^cULPHF%c!_|f{)`W?RjT2W>}Wz zR)xMr3l^sE3sR*08PxO0@WQ}Man~AtZGtBLme7pOeMt2H=0muQgx`se&Dn=kW3ZYD zi<6Pu?LlV-936skl%?6k&2U1SR{51nJR37@A8TO{g>{2(w{z@l%b+BE~EMdKxo-yPF{;Bt% z9L!H`jt%pQ7SlNvxMTi4^Xj8nbbC;An7dBfZk_p%2 z-Cj0+OU2*GHGU%Tt{_)AH}<8K;L}?8GaR;2ZPl`JX}MZ5aEjr+QYHPy_iAJCr^F3R zt2de4nL`lj_UWepn*!QQYc>6Z5@n=DVVOcF!7Ae$=?$5I(c?b3pXe5^%je_IMPyA; z&vkoCB;7>BGjb9Mp!-x829c#X(agX{%ZCLYNkfOD`JY9gZf0~SyWVnH4UigzJ#8clBsuFv1JSe<ZuleB*ZX^e_sx z1af`Vp^^Lo%zV*6?MkajCk#RN2-#joGYyx;nF2Us06yc}%J~<>Fw|{yO5@3JrY<+q zbCw}2;AJy=4k+`IXI$;}L($b0te6>Dj((G*9*#eyrqC@iE}`fsk=GFY;?NiD3HW0O zi-jh_k;>--Dkm}_n!yLg@&wQDU^=|12wqnCO#iON?mBfEUS zLXH1uLc6)9$Nge^A*3U97Nnqz9p4QNVpFJsp#(%t*ZFg+Lf7{frdur~J-AmS><~KN zDvq5?y2{R@YUmju$EjcVu&?`v`wPptBPhXp5~BG=HJ1HPPo9_%liGxw&zi&$tQ2p} z@w2m1`{-IzogYaSqLmlss>-PICX+H0e{ z2%A?MmwG?(k{G>+zrWeeAjXoviW9aL7SX($e?qNu#=*M?E3;O(%iKxKTnkFfZ{MQg zilfb?8RL931VPcR|*_sV&q#Hr3k4}2#xBFp!JU4pCJiTH+q!)VRMw~5*y4D{n!WnfRr&6u42@&-qZ2zc-yqv#_iVea!D^SO_ zf0MlAx^n3qL%z^J2I$yVKmPR;EU49{j(HMbFWG6b5qULGGGm2cSn|fq*U;g9g zsh;>ZyH`fozIEM?=2QdyoIZIU+!fsh3+UH&CBd3;WZl8_%~oeaKK`SzW89)a8rc)6 zN_tf^`D5ODfh(0wx(8Mah3{*TuRJCGQ8;*p3C`kp{$sf}i7*a8XKd%h9rdm)?muP( zL&SBvg3y#4fhhKsU($l_ZuLV}67lI+uh4)Q?CV+MogMSj?7e^~j>di3MNN>x>(1^+ zvPskheD(^H}Lu+(J zpxaSEy(l?t={$v=#-k~Z;t4&IJ!qe?+|VVvf{@gY_?^vO znE5@ovPWkoOE9|3MZa;0aI&$NcZpq&U(8pY_dB<@Xq;BQ=a$Q{MjRm}(YJC@;w*es z$maW4aS5@!ppLeG39VAItd5C;GkY&QG@`|pn|6{(11~?5Q;>8N)MGRhso9#vX@GFP z=II%YthW1QlFLJmj^k~TKl5yX6EW}98DcJ^R^W5S0p4|Hzx%9}P8_>?W|N@I0Im_k zdAEidkuXgIJJ0&{CJ<}Mglv-8w1_s3=7qOEV40?G`pG@^te><1>Ca{XoHXJ1TlsI zEf`r?c&#Lvj0jIz7h8olj zq{gN1O~(h88{*JiaPLX@n-KYZN;&F6n>aJ2Jvh09+4iJ}EEQqVb}XdpR?YX3CFs4J z^Zh`KCuS;8L4$a@hy?IZBz0Nf@8vrv@UG*2n~3A~HYVEJj2=Q~Dj;!_Y3|S}P1$&3 zoWh{j(X}J)k;d51%s0Tf=jWL5I%K%^w)KAQogmH6R{lw1boeA!_4Dc?wc9I5^u5ry zNEFNThQ^!fH^U?O@g{D!YA**$>J@oXMKQx}fb^8Vh0&54( zM3uMua&f&1)%p_(o=^2NtqU0?J80bW@x~4w8u@9(BCsubI)?ye2kkl z{Ilw@nK77?Jfl#e;hSj&D_VA0d3 zKP|4>)S+xFA~-4!ulF*rwQP>CrVpbRMjAkFs=O!;l&O|jm7>^OU?j5z$>^mrr&Zv8 ztoHpINR~c#`&=gS=w3I@DPAyUQKoWoN2u4hlrF3f1eY0ulYgogVe_s|X1srk3aX$O z%n*!TX_Ok7-N-d%A{jPW75^eo-G}`f_-r(t+mY2$OK#q1*HgK3W~r+`fFy%yqoHh@ zJ(arGg12^itG%d}orvQU)lqtEXT5O^j#3f{&or}6zI%abYLZD<(?iO&KHgWsD35R8 zgtPqlpkUcQqTz!Le0*9H&GK@JeND8~=H^3p1s8r)=No%3=1{j{fU1X!&t)h)cVHkYUIx(F80=zGtNQMmR)^p{DNh@N{%` z;itX5)V9Xm6fAtwkNuqOE*z1hQ_O3^czw?>)YUZJr9vHVdDMGd{fDsm*3@ zra^i~nnJ$Df(usg>bex`OF`$w$#aQE7d7fC_Ne8^4MIe`!Her&z3E7N+@m$pb5Y9T zPa<-dV&vCA#|n;qxzzPxO%72|;bG-rx$vArsBm^iF$9`V?JIG9&6LBLEt+x(Rp(wa z>tHrV0Xw)+x<=C~aRmRMq0t?w1lT)@h=rCoglJ1E2DV8k;Mp%YH)Q-W`LUHHP4nziP@^7i(&kWWl?Lc|*n>JoXE1NpQ$bT^)oAMM{0N67eIZ~rE#@i;Gz79bO{tBg1gPN~kj z7EAG}%|I$@9(OQl;APVUI-B(E?ElFw`SEjgoSle3h5I`PW#L*IP?hgw^+_nzZpHkc z#5vCYfjGzhf2F$rUz}rRCi*`ImO<3Q+S$aBh(Xlaz}ZCD#K_Lr1eT8v*2&q?#J~pD zeIv#hLOJ>7nSPrprZ@-`WpH|)gm^oqdGB8Wei$BJ$c>boSckg88JgthHl1Xda~L%2 z#~A0yhu_Ig%e79^3dipIrP+|UTFSU(a$_|A6@ zV!T6e!Ja%cXg-L*<{%!^FF|5N052IDqL9~D5qMfK9nRH1%vWbu*MktA&PxIn?mxUI zz>RYQBOlHwpkPa1)n5+`jFmXHo$sX`%vrq45&s)s4fgczM!sri%2P@RB&#aBC z%7_MN;`%Kof}ei`F7!cM^-a75^}&k^NGJTbarA5QLk}eNr4-7SFD^m_--i)f161!L zGWw?$a`SKe+b{qG)IUiC@wDU9y~AV0j!hg#}}V{VBgva{sRCSPBeu2;PrlFvhRx60D~33mGmjG z0bW2UQS@^^V7_j*Z#P%}&?H2d)BP*#>)kg1CsI-rQncHT;>%5172^!#_81Hf?1cb2 z2t*%bT1Z(Mu=hU4yz%2@m;Lwmgo?nwT`tm>a}-yppUdU58bI4`W&q*Ej82A3w1p9{ z>L+Xqi2^CWgmnAew&Yj#v5WRqHTf-d_`MxpSQRvM!?=3$@{JtIIf&2mjlx*yB4Pxe zA27TIxZ710S|ePv?62Odjs3<~5fEY&jTczcAD)K7_zMN|Ij~P3X^)hi!j6Z~@=2P( z|8k(G>f}$VzaftKQfCK80SEq8hc&7v?==k^f+(8WCB_=%``%Im0TI#sywC8jhXw=+ z3h+q$#^Qp3h6C#!z!K6N;PIuw1{{hJ{Yggyn2PH8v!RIGUuX^xAp_=70^dTuAb$h$ zN%8j2?{QzoROQvsV2wIYnWUhV%&-sV0`lP~I4aYpILxyh7lUe(kOb1csCx zn>mc;AP<_)&N1}ZEW<3OjAonUX{PL)%l-Mfr?7Tj2#YYgd5;fUADixfH9o>)O%*(e zyad^;+IcvLV`o&QAuF1xH=k@mpZs*kPtB5(xs$#j$C3SlN4G)MX3(1IvUb(r@TfYmE5=f09d6+F;@1 zZmAN4QKTz!TtvzY6*c>A?A2{bF?O3Bd7iq3A0|}PGIu5! zwt2A@kkm*3n8Xa8-VDWlIRe(Bt;nRY($Xih#ge>jitOA9R;1CE`_~T=NJS_{SI;wi#fc2ogg_`xp(>yizFKrN zrcAfZvn6j{>+HbL>Z`<`%(-8z2<8u7m7ZomjG(u737JHwVk8-NYPP2#Gh@qOd@QJ% zA1v=3b@5Dk#U zgcm2q$arO@%x7QAJvFeaOGVLEXM(j?+H%zAFTiEEgOlH`WjXV-X|ozj_QN*39ZqB? zUK@9{1F#xNzALrrf#V{}qv#YtAB$OAlReA3ayi5j(iICe?KVjKsJpQ-H1%F_N>821 zGM5@SCR*FP^bE;p&{tzvU(jNz&X>$xrOgVJg-9`a-tsGUhZJ1v@ofIb5+NwdF7=88 zt_%#wORRc5tv!A6IGOC1*t;VRi}z0+J?{%ZWGQohfBp#gH+fFrMP<{04xNL_ufUGr z>RZIqiiz=fzpF=>u6W0yRxNtu-GG3fm_v}l&0e}|IH}cq$Sg|hMEd&%O^66A42s`} zEOr94)NtDtu;6`~r|l>11YTAoEkbgjLZi)*njPNEAFE zb$7l{jd4vR3}!++-fU(xT}^FeP>BV$r5DErVFe#zZuYZv`R=y!z{>}>#ab2$AYrKx z)j9-2rYxL~VR^734~86O=6LOU!%iYvsC@4}b-08NhzI!gGJd*1IOn>r1cyQW^F4QB ztn!5sNlAubyM7!aU!95wC}~dI8zhyc?q%4%NF4$S{?#2}Pz{pSEMIWE8F~4_xMFPA zE~@7@z5H9^pxPI7`skS)#)1)vMSNnmay`$Bt4Oo#fF9`amC+jryj36Ikrv84=A3p8 zvzx^W7g;nuJxjBOmUfAWu6aNTA^fg3JzLTtunO${^F?DpR@cXkN@A5rH%UO=pz;gX1I^cChd~%5~~2 z)reunM|E#ur6>!JVNG)2plTO0`UZdetGCyDgy|1-P{=tfdF2Qh5pGku=KHyH2}X= zq6mrv7D&dfk<_|@7s1&9G*rp@3Hh{j7Q6-?X6foGl?utvh{<58hP00WuND?sg0*B< zLE-1pONjU0zEsR>Jj*Kdq?8nk1Lok&9_JaU{_1G{An3oGX zGFkQ}rFR8PD$k>YD>jWWVfBtZgXO2{!S(R+XRC5s9BO>9sCU>S{rh*v8hqiGmtl6T z6}sc`^AI$F8n)$J?y`^y2<31ZSvMun@C+)qb+C47hE|rOqRZ+G2TYWt1QyIX`EHVO zP&g~QQGVyxOC-H#@Et1{>c#BK(2FIdWqA++IcI zsf~z|?sTC;kSf6*P{mbXNZZp~=O$Us`}i*hocvak?kE??cQ5K~+kN-92c6Up9y+DK zz+TFALv_rm82hB)^lXDZ_0NwX#Oq&DC1%?ojKqf_V`l+0?@1orr(PxX6Jx}K#wB2G^fQ*boyGx2TN{sR2-CbE&KcVEwk@keM__3cL9`R1=6rf!&jk&X7R+MK)_(7IUd9dej|_+9;c6GNdGPu$YB}aV31kU z2iQ-Zt={4y$U|A@LCY}w zwSJnwU!nS?+I#*i0mP_qsVQ^2b`jlj;7*$+jw#U9r~y72dU1WhW=U7(cz{`a&*&0T zu$YgwwSA{kr{?zer9G$8lw^xnnkcG#E?oJ91*~Yrvsi!Fmm$F)9nwYpET*+qkt2~) zq6y&Ne|pxMwTV-zg;0G6)4S@mJG1xQ6+%}aC{adBE?uIP4qzZw^6UK6C{bT@*qQss zOgU}QxTQdD|Gf}gW8$Xkr_9Z#S0oPBq&KBdvRYu-ynd20l-n&Og0~u2Y``l&j z9#goqViMz!GAm>b0V6Gbr{us=iBbB&?9sj;Jm(R@%LQXqn0A{i(oeVslis5%rUU31 zzPfn**VIT>hMLgG4qjdjdkSL~7Rkz_XO^_d0XbYZxyy(0de5zsh*$zh6$Q51_(0}p zmZS1?{Y(y-5gPCsDMY0&YHEWpMCpIZkchR>_tbh94w*IoXsN=MMbLu-S9lK-0cNaHp z@tHAQ%o9^gDHR!F65BTA#!F@!QpR_X$+M$uT(EC%!_G;s99@+yGc?~ z+hicXGZMU;;sc=zu5NU)+NT7UV!n-Yy&2XjNRp!uHe;Y)kD?o$PMdr`kTAs=3&8O)F$=|?9 zC5gRxzt3xsDhE||L^xXEMmZk5Y0O%C-O3QXmmGI$aIxM>S8}XMo($M3#L0d=L>`)^ z=s@aIm0N|Z_9pbLx`T;h%fBm07$Fx)nKW1FO;z&jwZEVdNA^g+WEWdagA(C)%(Kp@ zpIP+H@P)STdi2YXiBLl>#~>fhzY;g+3S|)-V^W$wlj)xkyi`nTywtAyD11cYIA0#p z@4~b#YV+&?&bnfBo3XzPUU{UnP(9z#V9+B#!PSz+HA4=kfS*3|7L`n9OSRvg93v4h z!Xod*HQ29n983}D31_YnyNvZ-%_60Peo|)~eLx(KSH`m2yK!AcuvrFS_83{^1or7~ z8zTOEJ?x|ZfIim6oT2rZU2sojDmi-SJ>R#~cXG6HTPrO4J3Wi>vPbtCKyk~mm|*j- zo^rl5sK$$=s8{sLQ74OwPD)iX&jWauKngGRYGOq_3&~FQI7J#Z<`%jx-TS!K7AAi8 zM}ir-SNW_&Rp($aW&e+_^4Rgl{bjyuT9;j^&jP{?3@sCI`-r@26)9?dDYd;ZER_F2 zfjmQPe;H-h;vIcF{MX1bxz5@1VZ^F3hOEGhL`ncZ$C0g@Nv)@hTbnhSTqGjltC(C{ z(3Yw*woKm2YQ5+;PuBHe?7qzpV2Aq``SuONB1;9xs62y33HC%5_(E#bXsR$G~k-U#W(-ziDM!KPz#`kGG& z*Ddu7Mp6~xPnUz}HaE`Kj3ABZo<6Rk!OP4^v7^$PLQXBLG&{6VUwJXxs$@pCNh{-A z05g)RvVP-)9;5vM{@W72QVJO5M-) z3tTdtdT^`rwA|W#fxXgYT<2zuOx3yts#5X#J%yaso<2QK?M2FPBaL?{42d`IUskLV z?9EXJ9{I$zwaw+Nh${96Y6VlxZk;a*!#F1-0v<9-)u_7a1#N*rGzKfcE0)Y-?ReeS8|+FKu0}m#L>B0c(uA~Z9)@n2Sf7>Bh3}OzC#vG0!djqHxOLdvtHDbcVb0ns z0~N}|rX1{~lD<}D)5TNwqsAtDA(H^214SL{XzW8-m550&-#MkF8MlhDsTF*WNA;#= z!j=G*eh;bu=g?+6+Abc#SLV{f%;FxOGTzdShtd3J)00m3U}XX0H951MkFcc%dspWl z$+lL0*Cq!N+t#%!{rH0<;tqI`H84eRz%iI=oI4X7%a#M8Uc%COt^K$mSnrfe; zi!X~UBEMY~;a%zXr?Gn}O)=T4ET>)U7#U2M_II3)olk__k%O+$FQ|!U7S2t}3z1sa z`T(;?7zBhPiry(Qmq415YelQ#o1?E+G)y))?rX3i)c|Kl@GV0lj6r#wYgBAS$+wBt zR6gfXug=~}<)={x^xd@coU#al6v%siDNculT<)tR<_7|>SUYEBdX^1~I}6yf>;ofQ zWol}+I%78SmP>7P3X%Jls+o_|aRiQwR=uOTHC}Q(Lx*ve%9Wtnm;Bn?EWQFP>Fs}< zT5MgE5q1QRZ6oDS`WYS@ZdQ?!Dy9p_6)osxS(o$J1kV$S#%+TAAH|tP2W3dlIz+G2 zl$&F?%=3JCu08jE#W20!nB$lGwr`Z|dxAqxyZkHa3BoXKx=@E41L>>O>HmWDuJ_8| z2ZC+oLI<9_*^LC_lsibNeuDpc5}}HOg|p-Kp2F)R_OGrno7$(NJZrR%JubGcTP&=f zz`Fe4?5x1o74jaL78Xt&qPCJxe7zee)B)X&i5dp9QypaK7^pS?GU1aiEyWTiqJzz3 zWQI)LQBsr_Qm%;l{p7C9b56cE@@-sNTDLWufagl1`U@By9jI<_mRfH~zv@gVTw0Kap!QHF&F$Y)KZPY@+9Qj2#{Yvhaqq7?NN@mcv43?M>`D1uev-=wQZ=84$VYUFG`P3}3h za~`GX@2<;jxFfnQnf}bo8dk9`-D2k5ud8wKWyDz^&pNAd?cW zvwV1e4w38SaVopCJQAct_H<%Mjun=4Bw{I!tRE{;<6XHQiYz&`x` zuwzW(m#AEAe|jPG7EEkvk>O115W@rcTVl%(=T(;rXft3;WxZ!tY?y;SFSE0ehu6;7 zXp9Ej!NnwqEmWMq{)+;-d36#5gm~?N91IvXm!>k_8f7rRPc*aHY zVqAGq4M-M7`+AF#jjhNThsX!oZ8c4t^untl?$g0PermJA;;snhhx<(d7n2Md)xl@qYcEV}GQlVCjN8;Hj77axWn8{MV}c9>R=E?1E?*Xe*BHO-jxPbH0?(jIpCkW^v2$$FG-}jq z+t##gb9&mgZQC}Uwr$(CZQFKF+g7HM%E?L9Ta|pf_fNR@+SgiMHh9!BpJuTRIq!d4 zeU|8NL}>odJcStNdpYJfV+K>9QBjHe*~ze$-wJUycr{ba?ey#R3l7qrzh#el=(GI1 zl!?bC6a*kw3#-TgEH&|JxOOkhCq$#BWT;wdbVM6x|`XI;)kr3A{qJR4$qWSX@WMJ;JmsO|wk zU5{3v|AD|UG5#k4$I8m|zXx&5guhw-Pm=n-6F7DjHunE-0_Os$oT#-(uMK5<5^2A0;UjGkVo15F2-}p_49VEbFuSO zll-zh%fjMiI?KYvjVtOVth{dyIYh?_LqQAyG6}j2f2}?a(ytGVgh`9Ax6dSUpp6XZ z2f}v(gNPI^Jo-uX=Y#+r-e-cRM6fgS69snR(eXD#;b*e&V8ZfX#H2)knEbK{8yN#- z%hMJAGY15=BvOc^4iw9|vHdI1*?C~U_3Z<73=tJ5VtjlY>cK6#Y zrwZfk?5d`vJT#5Q6BC^U?l{qO)1M*h!}J}%C8ejzuo z^Vs@t0#JiJJu^@=(C{ycExnyy5F&-%?0iPdjcL4ydyxWM|ChKLsJwkTAEX&b3b>$x zy@uibhgeLUMD)AHhoazQa8dgSg< zw}>ZUeZa+ijtdJ3j{HH8Nc*5pC|~G1ORIQynP?y2hcr-+ZepFFH~W$NV8k~>w+w!K z80W!22aGvk{69Z3pI+cdsGtM!jJR{a`(eVs-{CQ#$S>bjchjSUK7L4yx?YC-x3#By zdM)lA{qvM+yMQUci<X`DF$fwV z25i&0GcdmP{`vIo*S>v$#HgLzMFZjE{n=4N1s56wOsBUcu_8tE^ZNkncV!LTeLepg zL?p%Cf6yA|S3rV^9_$3VV}k&>$!GG@vq4V`)cfV&xfQaZIQpj2R z0XlH+TSO0a9<}>qCx<|D8GS*9AJqeTbsBU#{Pj@#sh@)hm-9(S;(ZUO1?a&*1tEe! zq~!_>q77tU3~0q#DrFXz&+)w$?9Lg)DT)7s#!+WOx-2c!-33 ziwdLPzOrbc(tnh#qRlv;b^J+<5$NaOqYR=>@HcfZDU#uHy)`e)hm(72( zzG(B$xVB7OUoUQxS&Mn+5ou z#~f`BKk<>4d1!elFG1x%zIa1Ut=u@G@5SpMe7|;nDI%juVV@_F?o?J$eyAjsDSH3A z)GdBq)Op(9cnN&Id*uy#b1OX>(1q3t#whi?`HB>FeHGmdG-{d_re{c8T_K}9ZpJMIL85Px0Uz;kgu4W7I#i_BqarYI#5a(^9QzTo{{Y%2!gm`_7d$O3Z8Fxt4mtIw^*=`2eGOtqFAwI_Cj?GO zRh_A|p*TtL66w*NFsPKHgq_etF+`@+vLuR7aWW6gd-*#|{torwtS1pqo$57>-}?-{ zJ`^R}Ubqno0X=XnmQEhCKC+?xWGU9wL-<=OSA}Ai?R7l&!3PN;14D?#x~a{9jYD9l z;hc$#xif_+18;(SNSnX1Y$hdGe+@W8=VnqZ_OHzO4X5Vv3 z9q;1rqK`b9eUZAwZgTjES;)0jP~^U!&gf^l<+b6!k7-+QI#1$v1I;p*+~Vy4?M_#W zlg_C$RVFDV2W{|O8Jq*&*XnEf`XAw=KOrPGUJ@b8s3q+2Ci3C2L+ec#91I~JyFYX8 znw&IKTBk$v>;$UVsC?}GT~~LD2@sxAr*YiQmT^P; zLfW1QPtMJ8>#Y#kZ-Tt+hEXKcIT=bu;AQ+5BTq)`m65S|WQ&4$eddRe$K6c(%qZqM z7)2G$ohYMgm!H>vj9si;IGDGO2!pyiEKh?s5$p_gbaJm!%ZQUi)c-#Ds`sC>Q0=T( zEo7bYnGx9Hn@_3YWd%ecoRV8r_weQKUuWWImrZ=-_vc;m*g0Y>5Ln}Z`=tMK3$>UP zFG6WG5Hi@K&Aursc`9dI1iPt)8(n-AYG3z(pRwT4N9JGW#DLm)9_U zN7ATr741+HbZ(Mm5%QQ)`AplSwi9zb41 zcw07inO-f!_Ks*}Rl(9_!OgysPm>Arc9PuSx`siS$!bFZYFptEO(Y`mkM)QYFdmo< z57FJ|jHAEyX9#Ns?S*c*<)ZESwP>nhInHfS$weq!Y+~shKpfwjt<`ql;D1Kc^oW@u zJ%v>=6jqD02!2{SQk=nsFO0OZtY@%8vD}tSohi_&XOQf%Lx`fg&S;lUj>viGt^RV% zLov8LR5Z)|=nk}zuDo>NSEOr*oichAW6)^3K_yCrKW4KSmSl5DPXuYwx8jsy@$Q>N z;`HQAJ#d6Mojv+BVou@?cJ+Wt;xk{zZ??Smiq|M>wj1x0eU8~zeo`ltT z7z!4M3V5R)MN~XL}L5g!Fqit$M&?RyWAZgzRCMsXTq) z(za`%QbQK#S^Oyozkc!9I;F0^M7MZZ^4$8=hk5xPXFqa7*_S0{0N!X2xb8$!#y{g z)XSnLW2BX!RsCDoPUt=DOp}d(h?4vp>V`74eKy##25qE4L5jRL+qU@>C5V#yyRD~? zhq~MSMBPKx*i&%~qm8p2@0cs$vSTVD#w#VO=#{CaJeuFEU0;A|5tHXPh6*+i!#wxd z#zCYWvUE+IOBWYz+5HlfbOxrjDYomGrKL%DmC*u6Jhwfcfnl>liL9`Z0{M@-Wm1`| zZtM;A=xKT`)Jf2B6lF38QQ0)kU4C@XlTed?%Re+~?wt>8pZ7+m z+LNX;?Ie4Q*Z91`yB~RbaWG{mwaFC;V$S7c9yL)p7LU`2Ag&L`z#*ZZl?exzjg(Tq zI9_ftTqHxrOy))PsEF2|a4mRXJIyU>8}L*vN7+u&!&&F=uTT6Bq98C(bNiu4ekIpp z-@oksjc?chEp~buM1Eje3{M(C^RV;{+6T4i%E>!pL$E{RFzzk06!HoC9&$g_ z7+B&Zn*3Pb*=gW`P-1&o)dIRhVqIAk7LAYy^mNplm47aZFx%`K$+xp8e6q3Yv{zk3 zHavt0Emh46H;Wd_np~hxsvc9T8UDS*rEx#vzRTR%VvZ!9`8AKZF)_5rk##|`#6uLcFoLV z>l4P#Z{X;VkOa|r%oE%Sw#?~sN7shL$h*Q;FD>)4r#?4o(uP890%z=crOhq{% z0yzp9A+1K^zm{}ft-L*{uO8G2nJ@gwBhC<>)f+SHI^XyktI}g$;sy!K4%L4pjVZ_% zSkW985~w5q;**xMW5L`UFAa*F2IY*6E}I;ym8-`U-a%&*1NKDo&AD*(_anbSfnm{T z=Iy2jNGrtdqvL~s(c&jN=HF;CIKQIh3&=)I55gqM_#xTgXMfFaH_KtK=4`{^wvu;m z+2?I#o}`-*Y*2p(zez6 z6m6|ie33E_Y_Y<|F?JyreBvvqY0`yviW=Wk-zm}N&OqmzcrcfqbzvYGS=kD(ET8{V z4c;-&K*138$`s(HS1i}&7tnaI$9+PLKK;iOrwR_Y@l<2 zoCtP;@MQT?s?ws{&Ij3>0u${3sbN{Wvl>J`G3PlRUcvH+ds0d^2NoYXE-{%Eu>K{~ z`zau8kN`>M6?A%MvDnkyHa@(5t7AMF0Al}!R<&^KK7@#InI2|Jzi~MRa7DrK_0Os|8kE7@K9mp3lN>Qs5AJi+ z4@}Jlthk`?3)rcNT_2Wo&Pn9DNSc5RP#;Lik_H1PV)NTi_9cxMLOyyJGl0qPc&fI1 zZ9=Kzl8Ul+Y*!1jH?}|D+W)~bzmgwE!Jj_7>2L$VDVqD*+?%}0uv$?`le6b*Xrz+( zGraL3vWc^>M>d#_oG1I!%#;y5{)^S%1sc>sc$9#xB zL$9{Kls(b4K1Q~NuIwHxZ5&m_EjD%8XU>XX8h-nwWT+4C9Zx zX_x}|gHDoDJNL;Bg=GEUms&rs)?9n9Mo5|`;+=!Fm`} zx)U0m**fJb6{Z7s*rNSu{a~;GhC0dnj)z`BD&ERbK2>{w191sbmcZYa`Y;X#UKd+D_AT)=8TJ23*a@{C`ZeJj%6%rP@ zzn0ATWZ4L|JE8uyX~~D5b}%#0ARM6DXO7dP5xPJF<_bz0`p+^IM)>5ACw!3*GR53j zRE>3{mm?DbTQ9HqK%bgcPVubqFpT)w>L{9)Xe zsR#VYvxt&ZzVRX-zX#}jkl(it=-_vq5vSm3ha{+=T+~!hZ@{?Kc|?RSzy`Gl~1W>l@5+YV3&t$%mcN3yzsahPZ%vDag$Y?E1fb#db|T19Q!qCg3j zf|=HwV8L`hv=mz!7G?JyXz1KE6$!8sfI$Eq9L`>=00zoqoEmdzIIUNnif0n*;Q>_4DyM zy%a$3iXz#X%@*YQAj4oZc7}c!e=G6O)N__vxsZA(x~zwAeOF6D{LX^cW?w!e#Fbgh z{JL^pW1DYi4s5R3!ZqBym}l+H^uiID7sY!^5d07oz2l3W zBSg!6-O?BkR3+k(a()7sbfVZ0xKqA=k7Ox^B>H5IG#_7fT>bH^B0;P@N6jfMJ@1fQ&X&L>pisB)i7o9fR48d z1L$5kHl1fnIk)117WgnBR-Ws-)XH1yi*p%va^%%JbpSg{P(eBU7>QNwHEbdTS_%zp zT&+tCN19u=^=nn(?qPW|*>3VB>_nL)cv1Q%- zLF=>>LPd3F^sq5lx|;F;?dG5P?`C+HTGi83HICqQ5qLXZSwLRwYR?NBChSw@BwimrYwD&_| zBo`h=IR%VvB?pXr1NlX?zu>XU3WZJdVI|t@0IxymAJ{g_3T;>K3G`e(8|^fiFlU;B4I#;7wbZr;^`;o|U=;NY?;)-Q# z%`VBtkHGwIOt#SPE%E;8;#R2MD$yhSTzTc)S4J?g%^r6;TrUT@)kAX(QU9X0p{Atx z+LMw#Lbk{Ri-HDjO9cHG385F-8smYFAz%#?};xAeFfZa`+c9r2hiZP=7VrMtELhnrDYz;hj z+v37+sWEuPH_s}xZtNcf;T>%Hyrf8`DFLB|P4%(DYn4aeB9)*|IAU)Xd^O+l3BO%F zSP!mmIk)+_SZ65;$oE2Ri=7?z~0Va#tF{ zazPtONk$Yb8Ao!(p%_8VVVKq%G&Y%H4Z~d}U_{(11SKU`6J2;WCcHg)4A4s7Ql7Ic zQbGR8U-ur8{ncJA(PSFe{#5f;t$c2PD@GCLz#NI)&;2U#jo!v`N$dH_F}o<8AB6&D!Y$BeI8-XPo-@bCyE zC^idbh|u37rzz9w>2Z>)!M_A8VZAOA5~HbmtPJrdPB8_as$Bj>;2#`p(h%~bV>ax{ou zEbi=5p`cxe*j+RN8%jwoCcjOpoyUO6C#$sa87f&a=G(S>Am(=@T^)S2FK>Fv4Zx8y z^IN_0DvU(Yv9Od(0jeyLM3*$8dlYJ0``LD?+8-)!V_zyQ$WI?~HIr=yIL^6$NO`U7 z_>bnc)*jA-9pVvg-y?It2gB%CG>Wy;7mOfVi7OMKvb6ihl(sF)QOo_@G>3^|ZDe`VI2&Mso8~+KKGXF2xB*6L$j8 z1kSo8Zt#elDqRlZ--vfGC0&RfbV^|2k6y`}!B}-Tv{tneJjw zmvCI!@XGC;(fGJ^OizO@7mSmYry~WSAtk4!MwDk~ZA<|Ti;#qhjEG2lxX&1@v;V8d z$WaT97VS@jeE&nkj|UHK;E)CZ6&cAQObq0yYwwo^#xJd@D=n(4j7CULP5t6Vh(d=r z2jnqG2qa|ShmQh09QRN`qVP|H5J`j4I=u@3{?rHdOUufN+PiV~tAIp<2Mt655<*%* zKlk56h6@0liqpqLyLhQZ`HZMhr~fL`A;<&;ym*1HzyB-;5XPO4+fFCAMD3J543dx#G(W0#{?7c zifVmJ!H;yix(+lHH2ke}U3;k)tRJ>JPRNLP<_|*jsSowbj|C0^9McL5%E+fa00;@> zo(2hQl+fXg&<+U>!Epfm^BNayPLU1V&mQC_Ar!dKfRa`e6EyHAf%3i*?mCGL8Ofz6 z6cWvUIPT|M4m2br;GYqj;{Mch8(Ew{xK9t(3=`zwQwnSdmJCF=kGngs0~-*$M|cll z{6&dDNJdRTM@I(Z=LwS6qpudPcRc+iKet=7#(-H$NC^}y44maaoF~9&MtL2|4Fq~0 z0#awrU@qVHL;l@O{0kM7UtgcL5BeNLDDFoI4^k-mr^+EUHslS&TEt-o6*TPo{qr=J zXGRx^6y*9v?)Byao$2@D65Cwwm)ITP4;xz%10lb-HUc3j1sN<7YGM+^*w`3Qz_-o_ z7}!T8{5-(X1$jo?Z!6c z{$$?+oL+0Ge;5*f+=MiB?O*LOe%OBibA*VPTQ{{pSr*-OZNQAe2P6N6i}@*Yd_q=G z!F^ra-dN8Guqs##Ny;_C9K_q!pQi$gZ zn|_nHUMo4{F;p9Iq)dz||$Vf23qVIw{-S%pJBtLtGK**_ju~=wd zc7kYx2f#w^2H)XBz`FLdaKRUU?ch?Q26Pxv0=%$%Rs23fLwzl+~$JAM?w zo&^gXGw>%5iP zfomYtaxCTCD>wuz(n1!bc~eB908qx=PfyN6tJhDBbL-04xU@N@Hwha#@;iO&`&Pdw zA;HEEn5h#nnuQxP%_n4!&83XJSk~_cMcSlOhcuro_f5D=r$udH_kbzCMW>S|B7CYc zwtGa7jHZVh{qUMv3S$aIHcPzHFF?c?pbhmMC@gL2r_6k%S{$$f^?JHIR#r2~9pY+t zbx3s31xCHM^}^H6#b%Pl#iodNc&Z(${Yi-+ZdWzfg3e z=|#`;(MJ01^xWC{3R#MS1LLUMr9ZP|f^-t$*_(5dN8TTz;VEPWBmW)U}n z#|jzBQW9ww(>-27-I?JW@nNAbxPK$Ot)bK6x^Uk}v)<8})f>oyIcpx1?4CGw*|+dp zlD4bmK2o=~IiCB*b|H8v{WBikNevV!yRMVB#*&5V^}@R7{osxlp|=*dY$c8L_NLDq z5D=cGDb|FD`34S!sh6onB@p>8;s5#9S$`X_TkwbIB`>K=4e_<@7}s~!09WUItnNu( ze66N_>Q|G1j(tq(+tkzi$Ts#E-fH;#Qv`a`2+tn8zq*32Y&n}e4@GIDh=R#d3>(`s z;~Z(@=^r%ZT$7WmHUsZ+`G~U%*!h_7xE`~*FqzowVidNqrVa+K;N5b=uQ40TUr<=Y zjk7-NH4RtmQ!C-WJ_N9D-X7g~eG0{S*YP??T>UyQ$RS+`5C{9M!U{}V5ym^|5x4{Rpjo8!Xz@m$QAHR71;d>=J06|+U2jE z>-TB7L@TMTcUeg*Us!7Y*LB7UI((OA`b;G}?r)f^P;07=Sxw?#-SWU;f3rl{GUU^X z#gTX9vt)-hUMtVea5w&_zcVg%N(x?qt!dMb$NjJc!FrU;GFj|q4gN|90esSU*^r4%uv&Y1RQjidIH8M98W1?vD8fM8{V9-m)= zG0ib+ZG$|~P}9gR?V-jdqv^KW3EVhB^PCI6ONSEQ?@<4)tmV?6eOl8Fn<{IOCbhEU z!!CMUK)YPRxim*J5m#XL6HKnT;Ry}Wk?N747r$yhC1Y{Ak=~F(NzP*Ji7{jLJvQ|u;J(FK=fPKMF_EozR)QBaLZVq~oFQzRS zzf4$^x8`kx!>#H7kt7bNc0+6`qWmO&S=jgXC;SS1EX;v zwM?iuEg*9zN?Wq{yL-x#Bgw0CCasG7Po4Q)i80tGY3=+unmi1$%@sNs;E%hK6;Bl8 zhPvoBke+dcsqu=poZ)e*lPL`b-_i~(MLE=7O8&Q^{rc79#cZ7GM;i$ptw_o)Ho3uW zrxa>Nz;d}i(x!}u<|7y>>N~#Jk&X9J4tN!bmJi0l2IY3?{VU?;vn+>)oXPXka%a3( ziokH_iDVI}>~`!kl4o<>T{eQNF|YZL9SLffwIh0z`%=Ks`Zn$f>3FPmy6&BJ_2gJI z6{oLZtJ{4-Wjj(IiX%l|(;508tP8q(zI3Qbl(liZ$UwFFAzqZ&^T4NLGoR6nPj4cH zfCy?4jPJ&rtcF{)KAGK6|6v#Vj$RR}LJmyyZ~rtg9`2Vlr3*#l4i0*q>v3BqJcP|z z@VCAi?rkqOx5DDsVNQ2YnJ@KJ$M~l_%ArlqXJTc`UAwKCM}1pf`%c(&a)Z;A_9+AU zr`z@Tx-ilHz3l~s$AK2Tk4pB~P^gm=+b%rlY#s_bFzl#h&Bn*yIF|oP?da<#7Vw_0 z+MT~Bd1z2ERI8i5p7;EBHr_M$Ch%w~83}_kuulh5hp)&}j7#4c9wq5m28x~AVx5n* z&)@Bg3;uXg`h>ACJAO znS?RMT_8v|oj;d-<0DLIqoGP;5z)JI4=7{&INpU6UYbbqgT*N2_UA}8q-~iGM`aBK z6>4iovH;kOJdUPU09E+6TSx4%GIqI)tcD)NF5RlrnX~=q>L~6~;_ezVVu&08w~y!J z--mYC$!Q3Y-8pG&e523Lx)}0qIji*s5TtA>SLk@@2uCWO;3axb8B5nGx_690FHD+> z{nQF8PeBAlI6;Ap%G~LZtO; z^C~Xa7nAG zFw3bYjv0z*kvQt3w>+qsuo8tDSHB1H$RLj(R^lo>C!gLWvB*U$|m8tjLRi}~f=$HvcK zw8I3Mv$rQ%`)n?K_TScv^(V5sxSjd+ovwv9nx_K4VX!E*Xdx$Yie5J`qje=L$?dj{ zGth)%WGH19XXE3}MS=0yg!9rCal=!+9LDx3qOHfY!hb*~qjtOtCwfMsd~j#(KLZ#r z!||xL3wAh)<7NjX*3!w_9OQu-|G;7np%pL+UULBE`oqzT~J z-UGG{1h2C?45a8%a@YU0iP2U&aVjk~-j8L0+jE+s3pv|P zX|_{=OPGwvEaNNgDuc5ZUFV3A&2k41;$>pPw%>#j&j+B4;-H)$21#q+<}$Qg({k6O z@ia4fu_70^k+F)gn&mrM8vv^M=3H>|D0u57+k%PqH8c&w%Ga`+p8jecQ=)=dB2=(yiJtCUYmf8rSQ;R zRxh!7a49@pOU72|d{m^COf@&Rs>cmIz{Q1JRo*?H71O!u7~$j%!%Wi!Ip~&Vtlsew zlb#OF2cT~B@oeQk_+!MILYV}6u>Lgl`ElUb7_QXu5z*Q=Jm?MMeVI2gCMq)45IEeb z7N}}HFi9wCb2TkFtj+q3ETZ3I>9xkwd93SH=K3_XbSpaWSF_zU8IkGKF+Wm^%je(p zO?1)3k3z2X8%?82<%}<4M@-NidvVwG7xzSM3+>2kqe0Nz=A2Wp7ArPnqPiXH-2AjX zMz&5@MTv7+futIvwSiM~w}Dd?Uemdk3wJcSN|C^iGJ}w6s^3^a(CF9V2`Mi)yocNJ zojc-U61M}ZQ6`4V+xs#&7aZ73lHITeZ)YC&m1=0qmueHFRrAgW_gPzU*X9ncd3mW} z`%ns3ww^+gTs2;4kC=+MT-+Auk@4aQw)}mG{8k>c{kfO#phKVjRR$H{8!HxPxfK`` zc{i}L`DG9WFB%^La@5{Q$~`mZ4_{v=D}H5;WS5J#0!Iet!Kw(1waS1alw=d3Su_qR zgb~wR!9h(Zky`(x>{H}@KTpmu)@eXULBmD9!d+A|sG8t&GR4!oqw7D5A;2$ou}06C zy>oFY65qf(dF0dwVkjGJ0}m?^Fs2H)y(4a(Mxut!t6LZ4Eidn2mijA3kgYZKnGG3# z>#zTaAXdcixx7kQvSJmiCw_A+o3{Ma#yE{js-Fpp9F=lE|}H7(Xk>S8JS55(&*@m`y(VAn`G?5Tn&VU z5w5_mdxdeHuMDSNeuq!tUY8s#i2VF3My%CCVshzsM?@NV3EXw?EETG2W#2_53oj}Y zc8aXEn>%@#7{7oNj#+|67!QM^6`p?o6PQ#J10X>sh%WtONJlJ=Vq z0BCnz3#F$-G--qMsan_7}J}|I{0gm9{L+Qb7Epa0DG3Ms_@$g{XwZV7{WrB|%vm#-%+UyI{YzLxN#DobL~^gpeqwW9h3 zsW2vVW>09N^~0l;m6MEu;I5N#cdw<#Fh-ra(DZrXqY^LoL3|yf(MV~XXuJwn(8H;D zN*vi9U5T8a=^bsUXS}VfWh>(8NX_ED+(Oy3Qo2uiogRn+U-7w)fB};2g6$ok!>`D-;Z>sXJ`OQyj_K`Ca3 zRYqjG^Ag=!^ zp(^WR3Q7zSy=;;fj`+NVe^+A)b6IRi5rAHIt_0i{Er z?Kj|cYjVNpr;@wMiLD|}&vUuON->1Myw#qy%R9XE%AV*G&9ye`!pqDQdOhbRjSdfC z#EUEkF7)pkCKs4=aXtyBk-O?SuK7(7StE)d5`|3^Py7UQ^*34!xoSDHUHzN*1d=3g zD!sbtTYq@GYKo-322M;A`{~jfk3tDiH;-se`Nr~U2RexTVyC@*T+M*79-|ujUMda+ zuW`1sB&Bu{BB)$sf+bgSWwQL4yw1lRD{n#SgH9v6#(#ZM+2o7bG>IZ$DA}AdOuvwQ zfO#TO)OF*nig(l&eMv&KBk^qy(Xm~UaB_fHz)Ceo+Avg#r~K0O@})6INI0m#K*N(f zX<#KaW}c3CC%A7I?lndj-Lt6Oq!U(Wo*#lQKaK&Qt*V)G^Q$6nMPQXqb+%OPRzYR( zw$@^;VL!2JnUtZ$`sx$~Dm$Ku-Un4Ie;~nbrzjG6)!10Ym2-eF@^PXvuxp${GG;~ z!%$f+6$SY80a2h4iRCrVbPqhJc1yU%lleIz%}nHSWJhS}s?7!CQeW}15srRTw+mIY z9vxWIYa|~BArN1Tc8IZYeLfyWUy93$xU*aa+yQ(@KZnvJ0`Ifl-Y2{7PBV^m8ikU$ zDu_?mF6wz@_aH#zIGw4q1+E3{qk*7!sZ661r<2>3dTzYm+PJ0q3DEWWr!r-`mn@}3 z$Dct)er)e-TtJUZFcGbkcAZ{mteWeMM_(cbi4c{peGb|6O~7W60IzR#TV7vXM2jdI zk0`P6W64n@Fhj=t=E3Ln*&YBk4@J+;8jBF3@ULEHot$jEYjT zH^*PUcleEJIO@TvA^voCSLQ78;+s422OnIacTXz+zWsM!6t!s1EH;G>#QRO%_bl9S z#l`YaR%$7_joyP9L7T|t8mKnG@GQ6fWY=f=-Q?m;fzgAPj*oYupV_qfc({l7j1G4hS{wPsV3cw{GN)HM~TKY0Pux7o5sGoMGewP7m!nW8$3V zp|InOGicXdDG9KL=ZZjck-`U2uw`QQ#sEXL7$!s7cJ_4Io0n(p+MqJz_TGwtA=znW zu)?`pvJca{gR?kjTP-Rt;;g1OyNozElVXDIi01bu_D{2VL4y~kOM!y8;?BOfiLXNb z%j#m$QuwP+G6mUl#md!O4(Ku5h@z+0e4k9!AN9X@dX=taZP>MO#=NCxfN}i{^ie!|R2|WeW~_!y8wcuSyb~ zw^X<|94T{^$FjM)|LU;?O&o4bBxORUYA4yQzx)obJ=&z;JP9#DlJ>R&$wxU|r$iX_?rrsw}Nt+hV;S{kZ4*;Gj2v zS253K!_XJv?jVMT?QAIIK`+G0uIvBO={ya|5B$|3K5F$mhn(ci$#y-a@A=-eXdvG- zX1eiLrNnl${siyDe=vwk!fkw<;i|q=O}1^1$I628X)iZ*x$57Z4FVzogot8AgFlrx zB=3ejeQc{-2`iEC5>@QDQqV(}%S#Nn`@V>gUNI-T@5>+d+$vLoL@h5Ix;ck}%O*>N zJBlfH0B)Or72VqqY)5;VhOW(}U#1N=LngCU@CU0BvlHdx3c8J2b-M6ot{Y$I%i?Ea zs&6zE(NPTt1N|MVhhieu{)u<+)Ge2INwH8h-`Sb3wTp+HW@ zL)F&X`O3#&SBS5~y-Dgws~5dWka06EY;6lx;^&NLN|l3jSAklH!c;myzq-O%9}A0) zn3IwOW(vfchlpWq+%uVfo;-`bRT4;OVaiT-imb;(zt|6!lwBW?aXZ>tB~z=#5;+}* zG6qU*G^Kt*wUz?=!n?=|Aui&y*nhfvpIAeySmUN@2F6s<>=N_RIb4in_E#n0`4>S6 z&E(QdP*Z)7NvDZm%0cOtxlb7V4tv{H+pguWN;;2)CAN>~+KS6j)Sjx%jPgrbsf35F zD)JY{Dlakjh9VN>%3NYbz44xl)3jD^II1uX1vCbowiKxyh=fI*BsklN?rn1>on#JG#{st zDY^vYZYXr3nIovovFU8{j9~C7+F`=VofGt`fS94{R!=k@_}u9#EZu<4a2p1$^*f7fdfu^$ZQ z&J>A|u6}JCIl5Z;w;5GP(QNevg~#tfDLHS-nB$A})|7pWHz6>KO3M3zSiWs@5a z1j|M8-%5^!&RNK&GqoKNWjO1#qx+kN*RfG_%FLdCGm;sy5Un%7N%A<}EMq$xO*T8# zqvqMsOI*kSdmOU5mGWr&2Vs+et z4b^z>m^$j5`CyYS;s*FcDZS&!v^uxSiAOP8d|@l;N{6Q7r|M$MeBq?x^_}FBg#=4h zz7`c&BJ^(74^eB!pn9sq74gc|Q+zXouY9u~*_bARI6Sr-QrXls(-=Y2jwdXDFN*9> z^@$w}PukKY7MaD)$fPyu{xgd=o^U?tlYbzKULHTyMHjUH8dHvy;#@6Vz6nNc4SjPu z*UO{O?nz^RF5#5k6;39{Ti({k@^KC^{!{DQq{}`?FRB(keBIoM$yc^meHF5$2Dgs= z(KWdLO&n=T6_<|r!)1X6e_|PxYm5)DHL!Al#nX!N_ztP+Svr?3&J|pslk8%m=hd>$ zseW#G4_WErnK4SWAnLwCC=|2DTf@FZFH-L*w0qivAvA4RMku{+1%W+2Rf8U5NOA4MrZ|MI#>0SvO=j&5uRn_q4BZ&?GS_ngqs0pXDWD6L(5 zptO_CFR;^^kF1mXSsqmwGp>OWEnqLIN~BUELGGV87}J3KK{Lp^*t zf_=}k0|9Vw?=IELS{1;XL3l|CxXL*u^Gt(P)j6Uy?Acw6?YYzZH>$78vwOxEt8gCk(A^; zsB^+xKFq%4ES^G5w)&ZF2jE05xQ6l&0tu<&&D0=uXryPV$g=%jUQM|9PtP?`{a96N z6-~`Xp0Tm*O>!&pH*tICI2G%XZ&c@QKcJrgFX{h;;936zf@f!D|39;3W;SNF|2qD6 z1kcR&hv|PY`2V*#*t)|g&UU(iZmZ?WccaB-v&E*SrTu??Y**TJs$F=!?3m@^yo~&M zkW(dgJSxjVS7{{2if;?-uB=Ec#6rbGft6ANDu!O}O$Kt&B2l8@qA~O92&@k5 zOb#dWTixE)ncE(Y-dT^%{mvysXJPTHEXL~FnplA&EXXS(BVz#0ONvti6;E5w~27HKVmlLC$D;oe16*B{g8Q|p+eMt<>_yHJGLz? z_oA+*K$6IiTw?5MEM|ULf#vCqJp60@D`!1AdT~GMNpQ+hilrM_+TxCDN$?{VF&dLP< zr}-r*}$fy8X_N9A*~%G~%V7yq3h>E{{E z@9Zb)I7&Oanj4ri>hZ@CWdy+Ull=G{n_5>Fc*?+Os_F`a2a7}E7oHdm-Zwn*_XE(+ z=HTS|yV327{px4we)q0-b9`!QaSF`TXt_U#Vu-Vvt!hB7%De|9%hY#8KH4-H+TEt) zMHO=0a&2L0?=SYL06N7kC<1_fF3s-dJa$P4wq79%YioST8BQT+hk8Z}TB0~u?`lS` zIN&7&>I;X_#hMG%qi%D|Yc*;*no#82Vx?*;Qq!W8nb#P)1at6y2H3u6`}L`q!V8+3 z2PR4S%I;4iXa;tX$K>1qj*)-s7ku39=N?a+7PB?z8s|7j2hv@uWR4a-7a`k0R4uP~`& zcZUzeFUvG%_rwQjAKA3^57Sgcen#$v_9^jIavppCFxPSZ7f=FE>X{YrWAOcjRa zcrYI(cClktEtRl{+lh|;@KmHfVMqTD06##$zatM1k~%_UyO1a@uK}m?rZA6@+xA63 z@R380Ku;sMgO|?gJeOQh>$P?L^WZ^=%V=e>}M5AvB zGleAIV>1vJi#bFpU@d+1o+qWRX`E>uHyGlFP`o&7``?1s^sFo z9!J+)nGdHO7HzqRUq1=t@w?6)e|syKyvqDfS4<@DXLJ*#qA(dzg}KZp?G?2)cm&;} z_j|bhOd*TxG162C{_h|Cn6-9;G`%jMw%b$v%*T2t2CY`_`v8-tPSk}GkzF-4)>AO&Gprv1<@%K)jxB;3e=#vywFypZ< z_nkkSX{gxvh|Y`GQGX9&l}SIoT?pq;f6m<4ECtrEdSBDBi@5AcX+|DBbZa*^LFAh3 z{g#rT_%gFxiuWXH!)UL1$%J6seam_r#_UwFOHN=VOqFu3)49~|&b-CC`jnFVj9C@P&eT+7$p#B~_?RK^ioM zdt>)Dr1I|Rm6x}?xL~hcZhk$V-8@aJb#ZqgaG1mSAn^&;PYtE}ezuT}&OFd}1~7@Z z*llj_V|l2d-)g`1F}+x^|FtWF|5e9xwNeIowizsJhhc5}x@MG(%O!|V9hIS`YTE)i z{M$Msb_^=e=?e(zVDZ)SSvFW7pLj?tkuo>vITMMuxd!Z)YzwD#-mbbcCLhW3jNurZ z$6MGENO$@=!HzLaQ^)3;$dFsyDFhiHkIu6+Ory_!;i+$n0>}$=_fjFWm!mo?)Alob z|FdM$=^j!`mur7+?S9&RRXA~!E+{TVr=x_Zf5KDna?R19(mFO!YCt=DoY%F=?LN~B z_v7Vt&s3T8cq%-M3Tb$e;oN2g`LvF3EzoK^)IV$Fv5;y^I-M<3?u75aO|jJV;>0^> z)|OT#e7J+hMHa7=X`SK|twm9xXflX*)?jW~Txy|QK*nln(MB6_HDIUc?*m#>hcx*{ zf-I|~^VTO7uKdtfOo_05G0Ztqz+_oTLw0x9%YhC51Z#;-6F-y_4SP=6$c4Dd8}BS0 zmXOIxPW?w{_zdoiP;U8Bmwa-D+*sEp)Fr;ae!jv(^zAtqf-E`s1UQO(b2p!E)V4KU zdcp}I=K{k@6zDf_H)Ox0mCUcax7e^7BEpc?9R!O!3mY;gwgsYNKZfY0RZu*q2+XeiMSUG{CEE$LI*8w=053}m6HoBD z8JH?3p2KZ5w*qvA4RvLONDrFo<+%N95XQyOaZrYVm(O$Z)&$0ug#K3@avHY`f^BmGKhZZJ5)1elhz& zS&^=-KP|Roi5PH8pjOUW6gZbmY>I3Z31yoIQC6}RQ&f#(<1Xi>=wqfHWt z_;W+A$U4$dlxdTdpser4&r6<*5QUQQwyKE5&Rq{2A`TMv!`^=+_TnI>wvk6qbx09q zPQ9L4qMi&l&u#GZm340d+n!OMbAJee-dzku=Rez;Q6Ex0BMRc}7Zn040bhOsP4EQV zGo;Kx8F5d5Fu&%BP%@~qh2U#Wv$?q=x_hD64zs`u5d-?}TK5?Uo1?Nl+HfDFW_ON( zHa%Qr<*#ecB^~M9aGqZm{;cu`%_^=(nbBwUC*iDh$HG&#fYP`h;{|^nuLqdtCC5;oDlnPYJ4piWs5W2Pl;)L&h$m zpEFFHM(FD!&X?&0Lh1&!@=$+|Pg>GMMX7CBe)SLrN61XL#w9>||Be~=AnGv8ACSxG zA~x|UNN*fdRtTILI!^lAJ>?II&dTNn3Y;_P;ON!0vUE!S;L)4NEuV!WALso5Hp~mI zkJXUQ-O0d(bY`eE6Vtx7+Xt2l3OXS!$LQ9t)rfUhY{+g&^@f7pjE0U-?r31ne|8j4 zuJLu8DMy?r0(qK)k>DBmT?ZJ)%-q+y5|{4KPOFJU#MW<4Xo{852>AYXhG*=eA5%9 zUqJeoX-|n?^dn zJdB|mCWgYrcT{=eWwAp?ZbzOSuyOfvIfVZQ<#sylr52VzH`=N@Ul2I$pC-JG`YH2hye1EIg; za!uCLI-yxh;ZcqVM$lj`=tSxgd}G7!SZa}OE&%R1m9eWV#0C4+SnqCJ(@1P#K*1ljtX5CgGKxKcMD_AgDp{#_L-*r^nw8X#e zCC+(r%l||_mK@&s-f^89OyL)BxtWz2?5*#y$4$?*6){CZ8%X%gaGc~lV5^|fBxU&l z$-r=yDaj#mvr9{wbH5hIDGH_RLKU;xJH_GD@x9RYV)5?WQP}q~T|kMdg9#EKHuPDx zyXRUqFnSVT7~YfBeH{Qs@*f1%$PuxNjR>AbC9Dz@9Km7OgEY112EMrj52SXti%Xas zWZz0ZLGU4mDEzgG2~pC`y`elR#XQ~7%%&yWOAk1$VOMueje%kDBn$Vn_$6pGR#H7( zy3Q!Luse{x?%8yCR%fh0NxJ|xU|6w8m5moKQt*w%PgyBn@tx8xszS)JuMBRAbBSh-EZVcYzMn2 z2dZK%^__5(k`verFF&-4Tu4m;>2nL}F)~Dum;C|-6bYeKwnuGy`H}^-Meub%FTsTJ z_R@wVuO%}=qTtn?u9YD$ZIVc}&2swEd#d2QWAltzF00^pgeaxYRa0tXmn;CKNNaI8@b#8k>RVx`1vgH_pj}5 z;YKn3OkUWdWZE_|{r#u}?Ha8IP>r4oMy|D>*v7~^ zw-w~&F#L3w_NM4Xa_i#-9oD0Bn@4m4>9aG(s~G_B*80RqLybIB_DOT_NBd98{ib3Q ztSxEq==8axhK0i0GvRRYzISjPVH>=ghP6Uzd){urqV0hNY`ugV;nmFB?@ox##X9fF zMfmXU0Xw+716jftHqpIdXStN7C;oo+Tc2uMhcHL3sA!o`-MeBCefsnu@-colFKzj5 zd0a)Z8hhILDLBld`Ed(%t8!^`X2eq4)BN#Zn^6r}I7k)G(^wLRyQduP$saMEG@dWZ z9Y!(}(96kR6&Bp|ad+8=jjh9&>p{fh_2+7MZN)}KEv~k+Q77em?+E?^<+@**Z<55$ zgVLNQAzRHdKf?`EIzMp6@I25KF@4DC8?Rb-m9e89_P9Qdk#-cIoPh`Lb^B z3o|%Io1^hh;1p*R`e)Nmr)(`@84qGl);M4%&S3MDBs(V27+!H$Zg4!5r|F>cMnJ8q zZ-WbANH=fR=%-jtS;7IUPj5;)8m4)j122gmb~R=0ZW@*`LzH(;d`fOu>3xJei%5f8 zW$SV9$xB)s>N{E7fR72giUaITYLLkxrC0baR=6y#ib2yyhMbH_u+*m(>;@eul`xF^;s~Vw+5w|e8V%}l*yb40=D__vOou-i{-qy;& zN>eq2j@(i93S6r#tc&78KLycof&f064He&t)EtWsLeU`HtEQ^a&Y}UZ7FCjI|KV4cywjb#&P)ClT{Bdj{TMvPOHJLasAUU6&lpy0 z_pKyPw0jqUJZiHPdFM?;>l>m*hJ>GZ8esNiF)SJ=c@y`u-Ll8c^l%aIhrYt28_ycW z+Sa{G%a@?GQmxqx240y!g~H8=X8C!G&?^igK1?2c1!Q^^QoCgpCjb+8NUjzytRq?Q zSkkSZU)=f(w7FR82_~%DVT2N%0QxLJnH0!`K{H<<(|3_YKhGzPQc7@DX{d#>r`VNZ zelMuS5e<+>OPDxB$mgt5NPp4VV!UlQ`&TUu#__b|FsP{s!y!qa@WLvg^Ovrj5wjB^ zUKP)^u{;kLWfR<;Tk&?Q_!G46Qw3%jx(Q3k6>5pvJi4m~rsk;~sO4JsC*rL`-0>0gKJ>d+8MFL_-=$(qMvtR~rV%be zlkz1vN2_GoejZTEV)|Xo<1>W0&cALV4({0{7Jryg(ZYmB?*=v}&}MTWyLx@-6P>Q- zDX==HK4tfA zGnGFTRl{-iV89#mto#%S33$2S#DKN1ZMTp@6n-N6Q>Zs+mohCdOz))!7D4N}>C5kp z=pUL0CsWtOV;I$Vc8a3JgE^~3$!GJj^OWIE%Uj>?S$cVWjIc_2ia3Dx((2qoarFgw z%7=4LIFnnSY_>wksUVZtzlX2;9u83=o(#2f`W?Gauh``0irg&OCJ$?XUnC0me^2e& zW|Z)wtu{_LwVV=a?6}IpPKY&((~jM-D%!g=A13@oo7*L2spy@^yJThSj|59v{z%jjMpuq}y?w_wsV;X7nC1@Fp$tRb-o0r_eNswOvC+gx zuM=V~dDadlwJ|xmtqd(+1I=y3NE4hcAjQzkz*M{ow{o8ayqPCt;k_WaWVIMT*64Y*K~eDRp~oQU z>2eEF6zD{Bt6o|2ji@@KxuFARLU^k@)u_4)8FA9`Ko{w+RX=(kchwK1wnu<|Z+9ZZ zHT7qbKa)*95#=gb)hVfCr;jR-X7rbdr0ZnvZc!JWJ<{g`iJMbyDy5wV!UY&nD=fO$ zmTM92@34~z(Bzr$KPto`RfGJ<_}hUrRKh?c0n;yd_#5v z<#_RST}3%dZ_Ts^hq(^@&(5Pj0f-vL&LohGt~t`;#!nKQ`KN|(czC@1OGz{j<&*ZZ zNnQ;4L3@`+ceaIrgI)}K- zzduE@Im&Bw|A3}hN`>$!#`=4V4+#}~DCh2zQRA5!rmgDbam7c=h7NE)(=$WGuK|%_y_A#HA1#RuT#Xijeyr6mT`Z9TVN>lMHcvK8Wi>5v z$E?XJnn7Ie)g0ncmUBT@*Yu~lXm9+M_7dTY@WktvPhhe#zzT;~-tac{wi%+L3iH3Z zfH-B2Kgfi;Di$fyhNCgQU(OQr-OE`%BOcI0KzLOfAY*Ij|2Q(lTrp9KrdSu%%&m;1`#_Q0^Q&OoOa5Jwtzx2W`>Mn*Hmb z%NFkbu)E7F#+|H_n`ET}Ul!)??aS$rc+6o0plg!pNIKrD5&Sa<9Bq`2Hxno-Zq$@{ zSZKT92bI^W5hxK<+_N{`6b)?hgY>CiP-}_Vb#BEvwOtA{;66*sLBA1MmuCBboTDgISr=A4QECI9Oj$w8hx+v%XODo!H#X z-5Jhuwno}e@mKClZ%dQ=hDYv=RQIQ@<*pGrN<6_qeG^fHh6lMy=Taom(?ZHi%7lZ& zxd{Uu*>{EtRDt53yJ+lo&ID{KjyJ}jW}2zbY{U%`X53CkSJ)L!;mNKX2E64qos z931O2R%nQ+c4R<|#4C}qV&4~qAm{T+-!>n>+TyXOcEWxU%ao>+wP0!|J)VJi>34;w z1}n}TSb7F6fz9m~ljrISg%NL&d;d-K4;Uv073}(D-61~wjA^Ag;G&?Xdh+Dc@D2F-I) z*CO?!Y+#&NAeR-+LK<#*IP<%GCXV~+)2`bE)Pnj1?sQ6m7#aoc^2FvWd0fztCB!$h z7O)8w&Svd(uQdnriACQD>o>Q<9D%xvFG^+f_`tETKvnPjGm;5ZLLDvn$OoM?bZhx% zuwBDl-IIM17T7h7XSF9MOoTl<5sk_w+7i}ZSa3-v8B#tlD4OqTRlfvSEr5h({bFo&g8se8Ol$twuOl_@T1*J?as zKmV@pb*yE9Y}Z}&Ulj^8W1jvtwIFF&<%w`tt$qLWB5UKg&$gMeGoA>|Uo^l&W-{2? zCy?P=Jg%Ztf4lRn{7*thnX{XOfdDK5&>pz3{h+UH0tNLYimHtfP5;jY2eo_b^zjrg za9Rfqfe_#BxYG6!lP2r{rb(!*bUC&anRe42n8QP@(XaUsa7-vKYQ;zbd;MfyzbVwZ z3+WCPj9{=p*$7nk=jENA6aA18Owvb`i*x!#dXX=U7>hS;cW%}9s31y{eq16qpMt>& zepi+bA(k&)Q}d+|3;jh0itDze_ML>~?9Z`0b6W9RrsH2SR&sBhmF*lR<=2kl0Y~$0 z$<05XP`3 zy}OUkW}4NnI`kLUUnc1!9$wgLA#r!Ri$um|B7pbk(hgxWY%rv*yoreoi{UDkScyr) z#@<4HC+{xrT5L**&&6H3E!>-vioLXI7=vt2)>m*z(nVU26{V^NC1CcLZ&d35H`e1) z=A`hRJu0PElwLhn|ZyG&WUR&$1a9x1bD&77v7|W9$=>nf(t;l}sEB3&n?GrR#|I!tAbXR7wkU^u`-Vfv%UF>}?DCoVPHweO@^Q3qcc+RPa_Q z>~-o5N_d^bKH;fC&cPH6zB7}TNb)1?6Vk1Loyb?@azh=6)n5(FAyu9y%KT0-n~yl@W*`Dobf z)uxnHCTPG_mxUBCe!bsc+?w+?&0Ku@bE zE8Uxu)z4?xo7jQsniaQDeuj2(dK&@>xq%{jEWh#U=~tw#q{&T-mKo!pfAaNE`{%1615FV3t+3k|~W0bY45 zinV%Mu8RGWJ65H$f6nguLgJFBvZ;gXW9)5xpLeUl9N0c)PBdnJOezzZ)U5L9x-*&v zC1oJ-3c>*D4@PEmW8A0#zgnIo0k54uf&*zal4?>|Wh*a*yGbUWz9Sc;w7%-hQVMuE zpH}3+{K68*&DE9#AX%$pT5$)38Xm6QL%=adp4dff69^RH>o>m2gI?2WaG66|_}!8^ zC(nxSTqL;&?a%&LWN8Y$aG1h0PWRuUxSHE7IgCN zqeT@4RlElqvnaYO84+NSQzUKOw$L@8BQA|0U*vqB1@lAY!lzh*xV@qU8;lrT^o@7w z9I7~K5}Ww{?Jrtara-U{}l4+^Z2@;8C1gkYyn#Ei&G;J_+VQScjs(W6*b zp-kkBD>x^=T81l0VSsV5qK+nZJI%^_=zAigxt&q=t|)<{GA8Q$TM3}*!&QHQiduiT zNUCP9X01igLfwG>9huFv83%B1K_uN@F{faY#n<;@Rh%201D}X#*?`MJ2;;s+!H2su zK;@5ZP=|2tkU)zBBW1Uj3B=ZI(6n#{b;C_3oT~O;e88g_@W(u=u9;3Gg-qFJUiK`Q zBs?AT!4gbKUGR#>NmQtwJ425{fXRTP_uM$Gs>!$^rK~Q1jXBFo0@}lGm2!sWI2Z~N zxi`L}*DLULI+I%DkI}Y@Y%t-gq42z3Tl+X^AT6{D!lG#r%EXFN8b1&BeX6#Y^Iz#Z zla_3DNoc4tpSytlv*{(6e_r89N#1fLIwGL&CUCYQp&l9aQzJYG`#K@GaajwibIdztUM7B`wjZv!t572mXn{x8kQ#C53hF^I$eUjae8W zSA(^83H@^i24t*X^i&@V2}QLS<;Ottfyl%3f8Q{8+!f3;?r?*z+@8Wk6Rz?AQTa4h zVxsiavuFd9h!2RNt{cC6GRui!fICh{@=NX8e_urG&wgu4rdg*obE z7Al{QW@rJsXiPluy;frSqelwu7)U2P{%62Gt%&H?w7+S_%(%Y{5oBkkxi!!L{j6~4 zB=vp>OSV1;;3ICMg6vv@Cd@BB(~jolKb|78(5G->cYzc&+}m2LC!w~ij`IAcJgFFmVXWe{ne++h3ANc z=VQN#=+~YQK0^p(EJp6pw5|{iq62&TrOonpwWiSkD-=9QXs*ZhRy_#wW=Hnn7t5&| zv$lguE=aPELH4?_HZx^Pp78GuOx|BFd=|rz>P;xP_(34GOvHH2%fN`OOS~&?8B}DK zJH}f!1JgYSe>^`UiHKN9rK)*xG!#%w>}91_&ndclA;b#8OID@^^u3Kjo2bTL!q&8N z;&|4hEKpt()l}d<)12j9^~!ie{h&&kH7f6YVB>k!79e%(HW2WG{q(1-8XYMl)m*hM z5nxLRCsimv^%8FaVK~f0+*qb}-=PEilx8ZXO*r>+$jd|LRHS424Cm z64QXMl>ICLRZ`;jQb2Tgw%kY=y2V>mDpcBIP%@_-Jwp^;_ozQhQH%(DRX*04IA^kH zqkB%Ca*rAL8v$fTR|&RlbHezsJ8VrD8CFpHu!u@+!;G=!O-{t=9~|cGNq&MY$JL6* z5a+Cp)BCxu@{jGNRs3Cm)QQi!Aw!H-;&AR&<+UZDrMsHae|QoK>)gt&w` z&%bpa9vTiszw3;64!O`~5BHCWJ6iStD@N9GGU1xoB7lTQ4(zM-yTR;Y4}pJ+Q~-{!;vSEj4R zW?y&BX>+aX9rO^-o&PJ-f;3FY_>+bCH@0g|s?-1TlMpE+0X^QGaQp?(GLUCT%tix0 z(B!>zhPBpF)Dx`3K% zSpP6*!j_jy_T-oRtUqEo3Pl4k^QcI}i$h0FDfXOHPvV!%@vlq zSMAM?WoVXnY*f;0kn)8Tv-RC6|DGMpN2!1Ztn;11(DbbL$uFGkE z0m{X-`=~f$w+YfYj*gwJl#;eqb6#=)(ew6s2wQD1!pb_LMONaDxa9*%Z4;3#s3$O` zs>Ke64Dve~e0?$jr;22FG%+9wO+X_Q#BYVeyiC2tt*e!jmzbs%I`<85KX>dz8X2=M zg6c1e=jg?5j;DOm?De<|oIp}yU{Sd}BFneO2Z;|mu8q#Md_<&JJMx&~jR>w-?V0tkdpeYKAT%2$bV*2yJLJ^ijy|=lSE7q{!SGgUbktg)`GPsp2(74 zFmlhPdu(NF2Pw`AT=3OZeUVA}+BG!Ld~%!I2^=VOVu`-hnn(`_!U;19>+XfJ*GNI64|)8&yq+%7D|r z%|?V*M)fi&5{g_pT!td6&LGPo;1se)<=Um+Xr9}a(yc{nzmQ27%-^<>ZRbUuy~$S> zbI{^e#Sc8p4FrAD=+29IPs@A60s9cJp>_VL5+4^2?hbkjlZloa825f4iDZ_-l>r%G z-___Or1F^e;==x##EqwV?@^evGd;u}j0Yih2^2f{P+e|pa!2*} zV{%}|O!pImZWMT|JaXrV!i{okMKWV#>h!ku##81^tVby0v;tn|nq0?35fahyoN>(K z(+gDS{mU-Up(c@r*WV=D2X*}v1!Snpu6~NJEGA80{;)_g(Wr0{F_f@LtQAAEZUgjdPaw>lpDl zJS3TLi^W@3x4^cUg4#Kku$3nY0sbmi(eMlKdCf3S)ILSXMMeteqCbWLMv5-;)RPSK z;rs@7HssV({cHN+`>me{h8zd-CHjvq{|@G8LdptN;9oEoW+}q>!aOHl9fUH>gbiUX zGwH+QdN#SxX`)$;R-5lQ?Ppt!JRBWc%3W^u%_Q4Qm{A?prLqxT^kFnz1PVUzvc_*O#_Q0zo}Xuj{{eW zRS4t*QuT=w2FTC@kIfStSZ-?l_NABrY{ zh%m+{gA}8X#EtRU#f^Jn)gJ}ZnRYutJWfgtNpGmrN0eXqnitetFYCS0;hof|2#4uU z;SpO;#29xAwkQFOIo`lv7pMGvrukr>W)xL4sAmX>?x~M@9W#5YXn5N2OFEj>Y+6xr z>ip(Wn1TEuI7~H4JYVURf5W@~IA^I3($njh1Lw|M&Apo%DJVrgL8qg17rh$*_tSrU zcwlSy+AWzD%$FLFj2{#Zrrvvw`L+{HisKa{P_a@C`c5&`Xw&C zOb!NlsB%Yw)-r8XvNCFi(A!sSR;PCT1S)j83oGXXc9uL|B*1EmxFB_n=OdfKTHtl!FrQ{`52)f=3B{AM23{pkxZJ-S$yp zE@a)QHt;KtmCI#Bm1^d;)?f>fuD6>0%OnU6NNXa6S89wu_iGwcs; z9UV&$c6Oc8CT0klT#%|rhr_=IfyO?*U>0Zy4m|zlBGm+M&2di^ER_LvZ-n9Iu7nZi zcfO7F5{SdlVFkBcmPslqIZNu=6LSY~wC9Nl>P|ickrbPo)Jz?5^FvA0`--tOt^@|dpLn$jMN}xWNOiSOe!^qJXrZ{!aFoT zG6z(S0Mlg0QdQ|$EmH&=OQ*LCgRp0iaMKG@F+&ic_l+yL@A75&XOkaxlvg>Bk$-CW z#3jpcXFUjE%Dj7-7cX^}5@^{Xyj&fYfa|#&%Y)!595uJJafU6l4?RUN;~(6)`Te%E zo&hpbkG+0uzRh;KZh*Ji3&W^?a%e2Tnvf-TbRs0bc*TgTi!|sZ!w4Mz$Ty$DybhFO z2)OCc<*shPJGMBAm1rC?RBZsmF^ zG!YLW~XX7yj-hY1vJ35Ewpo)vL0kIv&_M`-k^EfVa z&z=dpbe6ny*sgEMAt&|8*4EfLHq6&sgm4DsI)R)dz%PPbcsZ}1Bt;u+D4vMrXOd;n zn1ONQ2_pQJSC^giIZ?saHEWgB`B}SuC8TZLGWs>^cobr`EB&W&P_uQ3c@Uhy9a>~; zZ7b~BnEpQAmX|p3acHuAz3tc}>T^^TMkz7F5<cFcM640kv@CBp6?F zPu%71_BSe@S_OBJ{5~;VQ>ZdD7SoQU?9HG)oVKJYJ>Sv8*Q14M5lAZm0sI~#6jMfzy{jv+#eH^mCD2Ym4nYQ=GBb|fHc z44YCvbHH-_@opiiMsGb8H3JY}3YApg7vKCX1hVuY(fRRC!m|4PySLzH@d%VAzP{C& zW)DBTw>6lw)IqwQ>TJwOsqdSDHhDCEyJJtL*0@&veJgQL6X{p&!;MC`w2PRdj$@Ap zwPbSlY~Vb@)Ca!shDXDQGtBQ;fxqF?Pu>bzNM?HqVsrVi#AzFBDj{X++NG#^7}6Tp zLh0DQ{m~7~$`T}F3l2WGAr^t|&$ql&_^zRv@*d1dta?HIwwNuECOyGw`L}WlEKk`D z20@YJuT-w%AAw=-i;j7apkD?>Dz43yACddf)9h8!wo~$AxCyQ3V$HdNcTM+Q3@S4F zX`iJ5!3BuU7KV1EmE9}Bnq>}0P58<8|FNU!w-CB}1$D5P{aR{n8*}5Qw<}k?f1ksx z%+7z#NyL(+>Ck$oK=f)v-V<)LC5oOBX1Dgl56d6vv&oarS$OEr<(BgD8{s&xOcZhN zK1YD|{DYxZ+3+z#wF`@}*dD-9v-6idep$6%N)H1;HjS@-l)LBf{VeXcBF}n9!J%rDc7-~&nc#|prXT+f=w}>IYFE=KaYW~!KS~&P z;dS|y@Ue2jvoo)l%D}mT-h(aeRSD!|`9U3;34j%1@s;ks3lt!2fJZ!)!@d5(V%_B(l~D=Fg z5DLiJkz9&jtMGV>=!uaDz6mSZ@6tZ?daM zykBLZZ~r_Z>N!di_V!1%e2Yo$jy?%<$U49dNI%~LKWjE**?prirC3IQ1INK9$0`o2 zq^f-WhoR!?;BvS|2Z|5XRnLgpAZ7xro8^H|)~p~H2dPIEZ`yRpjV-jz-}Z~I_g%Sn zRXcJ^4YkpH9?>aD?^?sbn4?kSdFy3j)RRIV`viCS@N6YOgUdAz&55QRt{ltZ;09F=TvAT!c=@Bp0Sn6@7o1YmLk(M!XbLz zw9VMR0*+5G`8{rB;$=M6Q3NPtuOBt5Y@fhH+NNb;warh_-Xw7O2KyKEOl(Z@G013c z*md|bxwD|;cV>D?jq&y@NCsnvDLQyUgFKG9TuF7D4Iw1um@W}HK5Zb5xZ$L@2#WDn z?G1?oC7NNGoyl?kz%vBax#f_t$vpT2s7RxpkUg{8dsu_v$ZJ)L^ZyqeB;wn9-x#=C zQ1CNWlOqz9vi^c5!yyGLA5Om(Icih!P9~LjUTx>al6p7}Hm*hTqHX*WS9h$e-||X0aDEu{}IiU&-b3)2Crqv(m7`i>)`r#5v$=@T`*0m zTb_&*DS@=e$jD=jWR;Vj$>a0L=ZtC-&2ep!ZsR9lxPf|^$B>Qh_j&>d#zRfnd21Zo zAtlu}anQeqogA8(TUT;)X~h4KXdLIe!fu^?X%NCBk3(5x@#U(ZS1IS2H^!8Kra_?2 zHa!&Dv}i;QN11$O+Tf&zf&J-wFF8(B%Cw1Lz092Sdq08J5M3Gc@_`3pqg#4kjOB!X ze>^t1Ou7s~r}!vJj(`8mA%5TO!^4DiPy#YpV1Qas4l8Zx1qad=1d%E47#?k+<8rbG z+c+@re=_Q0cXhnMvc!f&PHEkn1HT}3$gXnd`%C#}juYwuK}_}jO~!NPR&3u!5&`?> zf=aYU+4G&hSQ+vCji6t#Nry<~P@jEcncp+0;SduLEIf3hIApX*y5>W>$m)q4)D{75*~|IA zryZ5Nig8)>=T~ZLQ$J>1^d22}9!=E!H5A7Qr0AcOxW8V#iZ#b79F@NaB|dx8nmJNi z)>5nf-H&qoA(lqD5J{zvVYLSLzyFSe?r_AVf4f2aO-3Iqel<+?cXH;&bhB4jdPyVw5>g7WVHt6FokN@8Fy zz-@dt|Lr!pTW}W6@PhFF9h@0&o-3W<_n}v}T%4}XU;=kaKx&4k{*HC%gZ*09;uZqp zC-Qp`KHfR23wKUZT>e0idcPQLO^a^*2*xWvdgC(_E><$Nd=;C&sJvA!O?%jG6TR5+I=Ow8_vBc5EB8V#Ekj*S=)KGu9|DW0uibw6f4}E$dyP@wYQ*q zb?gjJwHZ5LsS4%E>;X>gQpRd0>!UQegc;ZH?XWA+H1thiP9dvZfZhBiz0jhIe?}ht zvf%R(ZU~TeKn3fQ8rd3&vyFq)Z$}4W_d-Dhv7nMCgDrX-*bZ+J0Qd?pq%^A`j0hJ? z*>#od+ii}&g{4Q38YRAZz6pqZX)~=!rwF4iRaygmBQ!v@ciA381`+>-2m>RbV^=Oy zvBTEhe^HhHPDf#|5$mGyXa4J&1=`sWM54cNRUpn=vF(=w)ZSDSC2`Cf0v06Qw;;}D zI~dG(3o>bcmGLcUXjZ)NUZq4pJCI2#ASHZ|mzpT^uK}W5GboT&;#IwbSp7w!0fZcw;#`56R|e+U%OBogj{=)G&*qx0v$1`9+E@{O?p;$0Q~A4{FGn*xWLX|7{8Fx z^rD2Z{thF8-JA|b7>yuKjSg#=)XWGFo%&qC&P=v%Mc5G}C)#Qk8?20iTYNr<1XB6V zt{a?N&eEecyggTTpi_yvpQv$|yc%Ag#6`kU1t)U-xnCcGcnEK#SO0R!%Q{Vy+Zn{~ z+f$CIg)TNt*h>YXYPSS0&QiM+{~jI75v6%2RjWmnMCDMb@H9Nye-eY+cU&B=vWJVk zXrYbhehtws9|Vl_SFk|+ZnHxe0+qb7cw>KbAvT*^_}1)bF9VkL2Aqfv|I+CYl|?q| z$A2!ZF7~;BD+G6HDXL*}IYiY*2&-kKId^DdMs~Y$MO7a|#QKktABdSy#RuRmcop;7 zqijc_e~ZYMiHtK%iG2GtfmRNe>c4r5bwI8K$U6sC*sfNgs_I)$%@Jj!5Qi?sn2meH z5acLqFvN|Od`@*J5+13XovS#_@O^&#Qc8lUMjtb$`=uTSU(z@VTw8Xh_osDbE)(@w zS2RTWf3UO`I>LL8m^4)As{U2Y--yjLEDj&1bQczewhvyF>TpbZw-)LjyYqfOw?ddYUA8psSoz` zc*)|?O`~!@oLXr5QWm{UzPcl9Md~pkJcz;8B$7b$-;#@CJW*wCCoP3pC!OgWGn}1*g3o$jLFnzus?3-S?R7-JyUiRcCE7dS(o&dYzI4Mk=bJLf zOs+X1$sI0hwG{eu&7xaFc=4jRHia&0$mPNVO=tyg#8W0ri9*Ox zQ%OCH0dD`?Rc1U7uW(1HF(Jfo@nY>)V4 z6!^{;;@)FutGg96dm4?1!d6*0JSTHvXVie}=j>$N$H>)Rp*`M%E|lKQX&}aa&;Fh8 zx3<^5XQoKgZVMr;qNZDjCTfzTx^AENw#Nl!jBXGB?i%d^)EaT~O_SZTI~aKRk`jl* z3~BLM9gyKJH-G{MjgM(^anCn@S?=GGf7eePAx8Z^`XiO74nBGUb4l0d{H+majYD|f zx3;Hawa}&MWS3$eT%QB~3^)Rz{L$#ZHG_DMcX?Xcik1{ApDm7sq|@v!i(1cz6l;4N zI-FtJ1l-wFO&ciaTS1h6twsT0>_r2?C9Z`(_O;6|>t1PkLjWnfG$&HZu-h(VQc)o zBA^J(KfF~pHp}BMsfIfY0*D8ocaEIz7QfrL#@eb#tAalZ+HWUZgp&pE)bug4+7dRB zEb-Gk?b+tD`IKWP?!FAORy20mTMEZyLmA|Pkwr~7yz*LJNLlDFkuE`Bf68uwm8VE) z6G1aH-JP`gMethcc#fiieucUE2@m1vCBOu|h@D-XNVUplJORqL95glz?5t&{D2PMw zVpXp=cF#I5)h~2zItO0%_N;YXpJ&eA)0R&BOxAn(W=k`8jVy5dL39s)6$iMWnXDmX zr$1VBBMX@D)w8(`bT$G6WagoP70(&?$-q;5M(<sSI_n9x?G9Jctg(hYOfA*DBdbyjmcBj&w#5i)e+>- z)`~k;PBB3XFf^D^yAIEdSAGg_#v@RJVi8a)gu*!3Bk<QAj%s?N(@)@eMf23fuzZcMqVCRklRp`3waB3+X%5(SiFX6_qi#yRJ+D z0L9fwpEZaX&B^thSR$w*%RsW_;6DF0ok&JQQD-T5rF6^k`Vp`)*TZ>tA3ifzs(Zx; z)e;1_p8o>8DQx@n%(c6{7Hg*>GaU{5 z7N=Q(Wxn%Oo7{%bj{B6FFUU67e1m5i^m*vnpp8a^R8^>3!zd*{s*^|aols&OO zy>qk$z(ztp;F`r*rr1W0sE#6;3yndhu2E+I=ny3JPeQXh^XU9r(MdVEwH|61LkjQ*7a0TQi#a3gXh;M+c=UnFWFw$t}pu8I%X^4WdUkMV~z zrsoojT|uBCr)bjaF-3m_~VH{HtjBBEkjid zZGgl3jFj*{14087xmJ2$kkW^%TUqwbbQ-ou%CCy_{T(0hd3uUh>}fV1kfCNDu*)Lt zn{{&wI!SSY8z@dvy;)1r62h#C*<8$Nq5Uj>;+}0@X5}$<DW?XOEmVD|?sL~o)u$906oz73iIK`%0=I-X zgxo9w@O-3g8M~ZXGc<6Ic~*>Q^G+3nhf|-U5cj#RiVtE6?(R_o$`xYG8Bd6hh1Hja zQ0~z@Fb=#9FAYFY=X_&{?0@m=<4cdM;I2{U%t6n!(ZH`R`^T9(w+5i!*F*nExG0Tq z^JYEjy7g%qYynuRvwf#H&Iwpnb8>c|?=rcTD}?yMN33?1Vj+-l1SSsYr-G{|AS@~9 zl7ulP?6UoVah+p!4{j1a>};xPJ)lYX)rljC7;&X(o7P<`OTgh=cJbawf)Z68^PrO( zp3EEgYh@-Qc*Ard3VDyhYaYX&6hF8)MF6^QTB)Jy87XSm5n%Jp%__=!Z>Q(=_k+Sp zrh>HK<4zAXNMBi?oUF^CIK#lpGZrPPXAZS`+$B--v^80iDEXa-$QEQeNAwLoX;p1tZk%EUrO()okEFUtsgs&(w4=4m^9+kGP?_iAUvvNgG^Xc$3Z zQ_YaQ?qVJPYa1(QS*3Dp1Y&dP{3eXd!HSENKoZ5)AzDW@u~q^PS9;COBPs1d*P5yu?u zL_G3UG%j49YS?YDZxR!3&aY-?W7r3SI5A~gLKUwHJmq4z1ULB2YQq?06yDM{YN;7! zVDwaQV6OxH-=>x0p&^s%PpR8WxX9>8+_=d`cK!A;lh1F4F7nNzib)QpN+Xo_uM@A( z4QXbQ82)VkU;IzQy>}oRinAhLOZkN+MDLf!aFiUsU$g7w=yyV}E1Ew}xal2e?}5d^ z>|?U-v$aJiPdsBDBa}GdNK8WAtPKHiL67Ep!0}7W+$*O)ZfH-b+%!eJ9_LE%qcjvA z<=ns@j2#z+lX|N;Oj#zz>k$ubx~vS`9~@;jHXl`7IFcc!&})UWBJqbX|CSAYtRdyu z$oV)8*C<$13j7Tkd}UK$W30weM=bGR_QJVrR@}zsZ_Gli5%`z-dRjluc|6;ZiIB&U z(v2q>-Ja_NPGfP0i829pJ3{dIMYSZlE1AwjQu$8Lt`O7?4sLvJM~)PxF46H$FBe zT>kELJHv_z^yuS<9iZTci2BT+=P7{&#=BCcZ9XOGl*9Q)E<3bRlmA}pFu#K8zr^== zp_D=#EBbY36Rg)n!5;*z<-@pcgwb^RUmT0s^T2r)!}AsHZ3z-YmbR=U+Quy^gAk9& z)~)5O*scI@U0?(3roboC3R-K)w7X?}cZJf#@j>0Fa%~UJkKs_tINS1a%@o<*ET>)MW0So3TZ2%rz znxGuZKUR)$NmeJ{aFybv+tj@(Ab{29b#)mmn%VQia z;#vC;pLLc=5>KKF^@jlL=gf+d>Or9sf#vRb`$PqTY)VxXBxeKdbru0*hUwnQJW9$u ztT=3R+d>^md-nbH>4d?4>bpnRNy68I7!*vRl$KK_YFfaP#3I39efVzURNjpiMS9(yRS4JJuh(#S)YygKPR$h%HRYi~#X%koln zRwld>s0Iu$MXFS6gXRv~1d~~eZOyxD8KjE{e5ET zoL)WshsESK5TL^B&x|mjpaL1W4S|={1CiP0yKY_0yd9~0D??N=>L}7Rys@L{UnZ%X zuG*CLISpA->MM~nH0fp`yja6$c~Y!XrKDVaFEijywF#=%1FH&2-`xRtpAJmF@aF@X z2rl9Zl!hhb4KTd6Af}Lk`WCM^{eR3eUW>W5T}NCjGN(MjVpA4~uFVS+TH*>yw4Fq?~o6w*{hGLH z6;kZtM6X+oXISMg^7=gEm;Nr_Nk^Mbo(cCbKpRPIe+~1byrruN-rGu z&uFQ(r1kWWA@9L_q@tj5+#{aUW0bDQH1AbRbU;3UlF}jRCVOFFO+0z>AO-~NkL8?| zP`)1SfR?qw+(uhkwi0l`@Tsv7527x)*A57{eolsz<_Cp>RX?W7h z=$O+c1q%Z|*PHL2A0$9&=L-8Q%o?f~;}J0CD&e`)Rqj=ZA#IropSz&h6uzxDybD`{ z_l0?>)#PB8Z!oQ+tD0@aEFOt*mQuaP!8(H?xOd|+m4k>MG1P>0#Ch|{!AxKSIEc;L z#-W1WKhS$wvgikzLrhJ)^xvc(Mgq<~k{TM^nYTA!TT)HeB5dPg`%;#z^Qir; z4D2^J+NmNrk6^hGcU;!_*wKe#Fmm%C+@UcA!-)Z?s1kk(6oA{2cb{nHebZMA_$9js zGhMswc-XWZUnc+FJug%BocRN%s zA50Rhj%$4^aUP!6jNPNI@ItdW_WGx=bVjMy>$17{M$lBEL=?f$D8J;I2`=Efcv+|# zNa>eCA_LF|1=G^bW@k%U4E0TkqSnMIz1C54YiVdv3Njage(Qpt%~#^k)Mv}8jP;h! zGIwUu)O_Fi`N43lb7|1gp*aU0B%^ZOfj9>FUCnJRl!a&As0<2Pau%SkZx(h0m}#>*47-zs02i zCpleB*fxnH8SZ=<6O(;Wysv2>SYJSF+-g}1%mXCbOJ^);913!&M| z&716?LRr^&sG8%u`Q-2PS@!T|K|!C;3A9FQLB*+&e;vY}^u4=VtnjP%&sT=yDX=FO zQIvs27V0XlcKi;3)j0DB)+fvb`HWTD5((kJsy>2b-#S7AWpSjB4zs?uzd_YdlUbvl znWj&=fpM{%k4>?y%rm0bgnDO))PXZCe45r?Sdc;^TR= z)$GSD8Lh>k{NdOoibDRYBpP{m+5BX7lfcLZSLVQEOu{B#n$}4hj5<1T@l3Vf2ZC&b z5G3JeM$r{V>)(UcA3I)}H}<_s;gVvAMY2n#e%YWx&Fa9kWlwh7J4|U()2Rr6h;)D< zs}<4oe*?i5D+lEM7}KzrepYOW2%oMgGT{;|w}Yhw|7^neBKuZa#|GLI7>AdMaGr@D zaM_ET%WkR?6Rvj9=n(17IcOrtK9ulKxkbP5V*bEV^hz*$z?g;2Y3u4%03forF?mb9 z{TaC_(uQPkLwshD+!yOx?{k|Ego6CSM-VM#Bh0 z^Y&TZ2EUgZSvP!BT3hAfzS9`0_O*X^<;B?dn?8g zwwIP}>5qobx~K*}N2Kch31Mqh+Mbtv7sfUqz$%>j)5~SYsUtd!3Q6J&Ct7vxi~OS* zS$ScRW`cu7@Zi@9qQdy;DV{~dcX$V59PTDUkf(UpTl@6PfV(M-qK;a` zPHv6`{fYHVva6Y(dR5s-m#`N0!D1oKe-vu)0w2C3}fR!{XjrPAq4OV(M}*jh$|qo z^?v5nMdsuC!PH*w7o42!rVU7g@3hd3^__W);UDq_&Z!YkUc${btG)J+I1paGY{*hs z_qgu%>9^Teckuw|#XtL+!QuCWSJ6{Jzg{(mC|PMNvX~0}JmF-?KxPQ6AKBf}RI&wF z%A%V0UiHk!qT=VT;h;*yr!70x^iO&~ zo`O67rITcwD(%lRhDyAQxd`4n_VSu?qu{3Ecz(mW>RK`uMq8OIPyytl1+%k-_sNFh za~wpEmNx1ZeoJ4%doXTH6k;s5!6FglwNrFN?8sxSMegbNN1U}V(T3-q49{4Y^(`MG z6!*od3_m&dcL7Fy2*M3jzl2{YJRo3`YP4e0;<-wU>unuB8n&NX+Sdaj>PLdginH$~ zTNYWw@5zcj19G#f=u`ZW*7EjGLCA;O&jCTzt2)8v-`V=w^0O8oy+oYWt-zPn11QOO9)4Lr)KDmb(&ga%l)p(Tb0*99l3GAlI8J}f&@JG}pTxTov*SfMWJJiOr8J5ol=s? zZ4iZ>C8K$;!YKg+9^xZbTYWLxwhGxKsmoM%5#)pF?(`yEgLJ*urcV|4c@V z&a17NTv@E@paYJ!hO|DEIx>XUtkrgas6PxlV}J|h$sI?{Cq4zh_=n`5vpLaV>+lY` zEi4H6gChj%QxtdM!9wYZfrO1e&adVZ2Q}n7SiroO$)nuR4%sih( zRm&3Td)&P;+69|OSlF<#qd-DBXX*U6fRasa_xnWxh1cbH}A{C zcv2hdqcfq6e3yO$vJ%OLPvuH#S$U6x-$!avJT5b^cCvi8hsVBH*sR-CsB^Ln*1-8C zhWxBBdMzoGKEiw9@{vAnStp$?P8!>qhVqsxJTwCnoe46kcU}G)y!V9V64Q;bV@chc z?LPiDLImda=vB0tQ_C(q-s+dj4SF|53~bx}-ZzLDTLvIFq^u30zs%panTM>TkSQwc zI0>`xhUQ>0RD)G|UT0NEx>zBY(C>7z=!&JZiNd*OeCMc1lbc-?>4l9wmzuSdIPfzK zSlbt~$ZvHL&=xT`w*LCZ6b7lWOcJlAt`~9=3K<F81m5(e`#HiRgOn;){TW6=UzX!D*IHxiKN!4wnhqL0SMZu|EU; zU#R=Y&}AFEllIXu?F1Kq7l+}*YQU0;IFWD(W7h?yuK@edlFBwT%l{2jVf{Zr6()KX zmjCuu{s*YS#LCEl|DV_Y161)ejHA_FF!?DT0Ah`-yg7#e-v6slJd&P;>^I@ zmdxPHU;+lM89m*WRJzlMRrIO_40sH!PiFeG|w? zL>XlG=vWD$VBm>z06>Tf$uDY%Z}M6ztNlkH6BEn*tC9=TZ}L}-HRRV2<2&}5Pn|6G zSIvn&DhdEe$`H*jzP!B{2l~6$DY1#E5v=Z;%70EbmQBNYXF7e4Wos z6$^_)NK+9YxURc8urjh7iGO8hXlWc4-^kVw2>#iQp_z$+<(+P0Ze?NQ@i+2!7hD2u z(Dw=c{tgSLIg`@@}>#W9=W` z{&O4f%lvrj@MK`1P#|cr^vm?;S2l73V>452BON$N`$v9hZv4m>=vS5sUE{|zpra0%G0MZIO||9>^>mV;vysYU&C=)0(l;}@4qQ4vnjFfCfy)9?nq@@b_`l5hUtozm{&T^(5YLRoaL zIekad+GtWA3hDdMG7AhP3&@qdtDT={=ev?;JQS61&`q&zvHTo;0DN0Ht5xBE(y@0V z8*X^upQh4{MbBcTX~^-Pno8=_KTQR+!aU`wD^i1E)IrC{egr)*;=eSNpnsYQm%XI6 zLlSlMzps$c#Xn6Ya;^Z2=%+RCpQaM9=iR2MVC5ZIFu@;sXjeTDVo9Zs6G!lj^1yq& z;U#+5Dkn_v=;>+7KWpIu>m8MjiPSLFzp=_a_jtO{6C$jTlI_Ncg&T;=vb&8a0yK2t zK+;U?;UBtx&88hq6EL23tn{HP-q3|yQ6dY7!wj?~-xrrjXe4Sb}B z%M#6w&qnlw>Ns91wnTS$AcJz%30bs;iG~$8w~%(b!qFjWC-{m=qU@oYk#W#s?^>px zul(N}XTDU|qPy#8-F_?_mAMI^>sjA=6CL3!tU)xAx-lvGHI~#aG)gYm>Ue&n^{ffF zYcERJUhiStQzneTV9kPZ(Q4M1wht`~CHm5c0mGrlHj9Fr;0!K3w-$-jYj(5aG-%0e zGTn!C-P65>eTBz-I13Am>cWn0;WRV^NsxiSuGo7eegZX!e2`QCOWFj|B6$jbgJ2}_ z?sCgbga6B`wSeQOv+PwxoUH2WK|<(N=2`PIhYJBoERPtx!fS>>@p@058X6_B72ZQF zAvS(^VKpK{PQ@|uwHRpz%CQ~sYdA%pb?dUo^dS_BQz08Q*sGUvzlv|TZmp%&rTW2f z8c{!Ee{9pdp_hp~qc9@sa9@LyEow4@3&BCf8{WVqhB9Q*P4q3*mF3=Lo@&T_L0}$|r|sv&%P!7~4=8_SzmEQD z&9G?5uP^VdKO zBLPi7Luv4sRM4F*8W&QV;u)_VY-G8m8dD}rEpG^OvKm^->J`cX*%qACV_{c`w*tPt z(Pf3QNUU^M1J-S2<+%0)m&(EV_%?9=6I7O;Cop)$i!uj$-(Jl4tcz8}QQw;|TJbk( zMtQ1@S%Qqtf=7Wwlzo}p0FMS??IT|6rIHX{8fFqwKyTmzuQx5RUuQ4m6PQ#E1~QQK z1a}+ei>~^}|NRQYuHP z0(40enuQ?Wrr)0X1o8Yel!fOlm zqK$4ucV5fq`{90Z&toCN+m%?{yU3`cmYnv!(C)aMz1Y2rJ|mD`>5=trL^X=Rpw3mV z<=PhRd=8lAfPbkZLiCCbOJQmd?C-Obvb0c8I%7n?M6}C@Y3tD3`~=j{GdgDR^bt-2 zbpm^*3;03glSFZCr%LOB({(g!lqT3Nq~arl8CA`7&*|w(eD?<((q_*?6~_d()KorC zl+I8woMk4B&Ry}oEnBCSONXxE0R`5SJaQdAt;suKU+V+UvXuPI7E@q@U@B^8(v z(byq0?tR%luB04U`j|lMU|+nAK(qsck{wKd8_3vKlglBuoTGn{HM#?uE}^wX+eKzJ zD<&^OYF!U;2LhKV#7V)!yBzV#SoUk5lY3hC{rtHt4VIVxdzkfWe)u+g9yv^OqShBr zb}UW)yJguc=F^;rZhMLI)HM=xx7ui_0hXbko%{uX()Jy0>)l<%Di`V%hpQHSTmbaT z&ZM5TnrQj{w@=vLfOnxkSvo_0BLDix*u=S8<52Xt$?^Ix)#U?*#i|-6f0q$XY#?fu z&J8w!gro0tkK4_x@%i~a@Q|+HyT6qyJNRbrk4UZrN*J|$g^LPNqQON{=e_#jbsR$l z%#yyKEqK5ljN#DT*&BvXG;BM#2cfZP1y65f_s6N<8u%-tb0o^MU$HdxDPyGi(ezEp z4WEb5gy~%O#9%6j&1%L^OwQxBu`Wl_qW2ftw`~Bb8E2brSkvg#$6yaEPxiM0|FWVX z`3oDLh1{56RrQkdk$w3#qQV45e0Ba9&ug2o)~EvkZ&C&Qhz_R6@iR)9-?j_gY0BK& zDjW%=au!1{38m^Lz#bcmFj7Ln0>`3TVXXVU7f*0PB5Lr}Zgo7;cP-hlWCmh9ySVVpAzY7jjIGa6KOZ~exk{p5MdaF1- z^gKeR2DLTl9BFtN0?~Yw7nUCRE*R}A3l7pYBRO_}W9f@tD1?d8j(pPj&H&wv znNM0|ayX00jRc?MZxVkE7MEy?tu#+6bxi{Ns<7{rx2VlU^-KF?8AywPUIU9B*Z7|K zK|0%I(bNvNTiPqMMPHQAtOV>@xK&_iDcU4+a^X*@U*^@Eh-LV2LoqCYiaVGFppfPb z-~BMw=PE%+wlBZfPejbeN0OWq0vVBKhHYbDt1XCwm9a-yGjw&IJ}n|=P8P3!e*C4_ zE>{T%;iasCRZt&q5vtElcQ|s-sWeiu9E{she@-E1r*keKu;M_%I8du}O~7G~Qe?*I z+2Zoqd^N+~_2!JA_9t*M@&16EO0DU1)2Th84 zyDf8kFtb<@3-b<1llD~;G7#>m{p11?WjTEDbB@VHxC%MGMk7rrCWn)`C9~P25Fhl` zZMZiEorIgpGEk0@s;l>pj8`g_y1LcLN|k!y*Ow-TD5c$bccoZ}wq`DB!8a$f%G>ag znjp*Yc#A6H6)rPOk$wbpr zo&$RpXoeD0;dWJH`78pad;PCye4K0Nl)H3-%>EtvR)uINN84(2eT6Vj9 zY^mff0SC_yT(`@{-?NSlj^}T%Kb8n-lykWhj*zAeVh2ud#L8?&IM3anQ)VeQ!=*tf zm>C2v-E-34AB}Es3f`gFa!T-pgjBOtxh7B})s5vPqTVR^J(z^g&&+iVLEAF>1*a(~fJk+Jz}jCLhD5TAS(H)9@YcW>dU zLnHPI+bkl7bi?+2jtY}k#EI$Wzw+klghXO zsl*|tMFluEy~o-dv;ImTWs?E*&P?Hi7Y8*T;3EjYy=s^hcev3OqgZ!R=G8O@tU5f}{5V;eK_B`%PitsdYx9k>{zSoYOx1LcL> zwk(bbGu#yp9Gv5xN&6oxq43SK$T;!NVN8AAjV{Itj^j6QGg5zKOHOR2FMUJTr+tww z>U|VS%Am0#tiYd56Nk_YK>p#S)5pf&&x>bVPe+4^*+uY%HFr&02KC#4$WV-+KzTOU zRk=NEj{~3Q!ntUE9wb(?A9v4C|CTpXLHffyvJ2RLFq%6mFUJi)9Cw|ynutW=b# z)=R)(97IhXK}Wf1R#*o_`?@GKjS5ox(oju6q11hy0E~5#xZdMuuC)LQ!y;xPh@Zb}$W7o%My(x6w-+(>xYThj>g5tSsm!nt5MLk9yKK)qc2vzxDujt^#VOK3O#dL#t}#i+D( zFuQ{xpC=L(S{4-N28O+~GY*BrSH*cZZ)*l)j+`gb3$=+?3d&%Bu4z|LGd2hKTyaDK zg>58x0=Kkl_?h94spK=68OM}uF=-osB*k)ODVr-HZynXIbBCEdG35^!)i4-0Xe0YH zbPzLy@ZWp2Aas+J1aw1N*4SRhzc$);nz8Tr^kMCYbb{3k^#%pC{97hIlQ zHyjYBHLjO3Zb(wSbzumAEJ0AZAnb+oaaJ)|qJQ;P$t)@pbi)(8Th$P9^+~;A32Leb z!%4JtPNYcGdIDnSo+)#w-EXqkX~i#{>Kqg1-c)|9w2A*E1iLH&>#{ZZdRt4qnTHiT z0IbK(gTJrZSCm3Dt9)(HSsD^CAQf?J{?SB&1909hbd8Y!$azDe)jcA0J4K9d?Q0KC z`%8o>Z76r*?+_+SsU|~7N3h?2qm#Fwh!FqKe2V^&GVWOc#k*AGpcJ4YQ*gK*YI$`D z`tqcN-`u1KtSS-!H&faZ1oBl6LAQ#txb3@Q97A z(u}mM9F8DX7s0igz zC_AlK$|14tYAbainV{dfg@azUL@>K{Uy>vG4=@J^4pLA7Iq6a2-fMX$z^PJPH$TN9 zFIf!V=q$-M9M?dsx69@_?E#2yrvr@<)xs=*in;7sHl~06gN2(xaJZ-!Ua3G2@8B$; z`DY}3Z9z>4sxM={MU_yb$DY8rT3lYFw=xd@IGDnA?&cys7JTFpQe!pm;Z|ND2=aDX zxHv+Zg|IzE$D>wV8+1w6^v9jbQ5DQd@+3pEmKBypQRN=``$mUp<^rn;a?N zq@KfJ$;Rb{Nq=T!5^Z@UC=nML?WY`s@C>^Sw`UYB9ix*uA8N17r@=^Xrd~>ycfyTJ ztXpGmZT}p^(rU4fLCZ{Z)F z2hWAQ?QS0%g|0K%yL(xfooK?@*(8xJWE~SoaS#K}Z&465{ZfzOI|8aVS!)xh)X-0}4d#apDCETPZPDgeI7JIA_^B+4%?l)JXagPOOBwL!E=*q+B^K%+lYC^%*~`@lg!r7aRG(yw>T3RD>}UG2#!MTueAB%sH4c?F~C% z=_Sbo8{SZj_==tH6cx0Y79;C*Gip8?*{C!ma)!Je(M4;%ctIvZl2w?c-}yA|37JZQFnMRY#QTB9 zP})*CpuZ<+8(Hn=p5gpzbd7{sR@vsheEf$d60fZX7`~6j2bsCRV(Sx7@XM$$PVFmg z_rU5;Bdg54L*fxIlVM8wmRjjuz|F@ab9cGUVJRSMkr*qg4;jk88Kr72P5yqKg{esf z7r7Hvz7p2SJ&wb4^biwoCPJ0x*+EK&{3#v*aOv16Q0W-pPNTkoedWhOB-9LXUA~et zz%ML!b!`hc=((8s6Ed}%2KOZul9lq>qte;s=tIu1D%^MBGAAGSfONBU3%$%+Z^y=)=P9QLq&_l*3^$0* zw!*|LKELfKwGN2(XJ-`;Iket{CMhcAKx8_nJ0VUD@O5P5-|i&@ z1T+^yrbZvmO)Y|qA@%EeH64{cOWdY+Z*@V?*UaxTpFilp;OaA}AXw=R0(r$VRHU$Uh6A zdb1cIxn3(>eCYUm{PAWnS_oh==*Ne4UgpjGF1?1FI6W|xuIOi;VJ+Em${Ouahx7jC z+5RN=r4E@uDWSa~TKk&E8;1@z3=GVS7wq?SLEdBhd}T!9^biW_V8;|Uu~i9TYPW^s zQF%IEw9z#KMHijxk(eic6_Bm1qGnQBNS3K!k}&H@1_fG)hw=t`%0LwSfQ1Ufj%=Gs zkC3LWw!v=uo3(nJ*zacM>4=`loo5>WI5Wz>9c;&IWs3og9_U}3461^W<(LI5=wO@N z^)?^lb+Gv^Pw;PR84fu*q0N#|04*a;T-Zn-t2LvZnbKgzuL(4Pu)2l=*$APN1PB!9 zi-G84l)AbhbH=`VrY^``ehv$tQ|eGUj@Jj&n(J@c$U#v_&$nqHq@#j|ngs%~IeK3% zW(yf?aEd4A@Px!Z$aXhb3Dg}CixGFw1?I_c$wv&50CX(eJdS7jL#DPBj5dAHjc>S5 zbUEYz$Q^2nysdh(=eTRMVB}?V zl>k5!7rMemlsB7SW{T4hX4){3d>)&ijfx*mD*Yhj_ey&b>xVHGa>BWDRoyLeXKGbe zf#c9=4Dx`61rLX7!V&LPRf=7np41(q0atPA)H}h@WCgG=v5S;ot(2u+LjL8$3v>pF zz6p^3@eYJ&(!>}5iI^HHZ7s$z9gs)W!iXsl{~<&h@%VeyafJ^vA8g7iZ;}GM@a<&Olyo znHN947bOpFqavRxz6;cnBp7I_{jB0e%`Pvy%O$iRPieK%8(4c`LYSNkekzS8y|{r^ z;y22r-T=LEZ3)w7k*)qA&`7KuDvxp1%kn4U3Cl1de?YJ<_6@pr;bWJ@ZYaVQ;-$EW z=y&)2>mE5=GQMY*qS0VW92&T}3$%-E!^rT*LKw|(s;r@@FuJ%b{5>Lv1&FJ|c{-o9 z^nNoSolmiu9l?m^l}(<0%c1o(4OG;inA^#sI@QR#eC!x`C~Pn$%(O`~IeFP(B$072Z1Q&CAginhmZH_> ztc@ZcX$e3yqt;UZ4YXOTqbO)d4%6`Yt!og=3e*QQ5cDf~lVyTg?ms)Ppu5HOCB;#i zvlqprnaYK^b_=o7lgv9lV6(0hk^8H{=P;ewSrX2~aBrv2#x_H7!)~g?pNZkY@nP$- zGu;|&y%clnoZn5GS>l8pbGlt^w(46?;UdV}iW^X`gww+>*VZ}L=5$zph|o`xq%gCaZ6pS zZe~c}(Vbz;>!N_Pxw}XYqqDL{1D{WeEp8SyS%iQw-L{EuKjq#SI+T@3;kF<-?BI=MpMb5wufz?hXsL1c`RCld zF3q{nzzs##g0ZDvC>3YSoM0_=ICj#(qT{iQ@uV%q#Ev7Ny&;ht4OsLX)Ww#{r9p3>vTM{Id;8gHbqWOs)}bg=W{)EP&|aZEv)xP2B7pCu zag%()YHJvD{Jy)ml$h#?0b|ft@s?qLwnB$9jsoW!49>4#g7+BNmT&@)u0Jm@_MlyH z!M$4l!Pq_a2o`l&0503MjV{}^ZC4k&Y}>YN+qP}nwx=dDAKzr=H{6`$?0wgHR+fRD zpRT&zwAyu&Yw;)}hF0F5HI^q-8yEWQ>18F!fRqUA{wgNYCqH1N^lY^9TM8VMA3QMP zT3%!)*ew??`^lIo5flp4MK|3cF@2y+R#xMb~&s;P6X}smz6bA?t@0!6B%3-2g(t>h3(t3BO-Sk`Xmza&x`7nwpZWIefRJ+ zbgJVTK%FlM%I5W2KVf-$3vVSOu>I)xtgQXr=L@fxtMrfFm2i_lX3!!d8qcF(dMyx0 zy6k+BE6fOC2oneUIbz9ODL5B9q(di!Wq{(9;w)ijD=j$1);?fPaq#m1O@V>Qy;TIF zt`qp=u3bz4&Q^Xd>|pV-dQtcH;}0C^WMmk&Mi3hzmZ+Vsb=D=#Q|H(J#uPTDINrI~ z8^uQ6N)N8ANTftkDdfjE+MvYIro|0*J4Kx62XYZqE64075%geKCNdlzSoBz=7(RE^ z9v*ifj$uJ}YgHz5$swZgKf0+I$t(V-+afJ(=2t!fHb=|A|}no^hy z{`>85mTIcZubHmt0?HK8Z9(P!KJsR4v3U{OKCn=;*Sh*Vg&{~qgPfqPyHS^`$myp_ zSENTq|CA=Z@zgr(+JY5Z++Cwg9Eh_i>!x12b)%9!vXm3-^;4v$m-0T)_)E~QW$1(H zkU13f36WBOEyC?r{KS%aOR|0;8OLd%{8<($t~zP+W6xYY+SRGV0)iI#3Tyv?;#LI^ zKt|f$AfXR3eXs<`KcKOu6mK9!^V1U9D~rl<)@=4@67)6ImT)}06WOxt<>dL(o>xbt zfN2#t{$%I03KsB$wYgt18VSerM$Zy{d0xI6veE3Uz%cG+Z)eJ(`Db!lq~JQIs<&@o zDuPu)U~R&KwdPMVdkdt_ZN%+G)Jx0|oU~}Hn6$&m#^4k_ys{d;CBz^1QV$Acr2neMNaK2oCgd)m6{lJ zXH|{#ku$fiaNsU+mpT~k1+K&H$2vK&aqgjVazVyl4N1IwLUB!gjcfH-?|SqMso|$$?EvOnQY;pAkY`uY$5uw=>u*A%GTUiDP$|= zj#r95txSS~Hqlp<-dgWPi>RfjBO|SO2LfzLTb6$mOda&@bB?jeMeEPT9)T?R^0hOS zZtci8?IFh~5$?H8$Ft1`WdcVIXGDJ%KgtFnl8bfQqX@P>yqapX>IdZ7UttWp`F;!k zC~uxvt0XOO|1QX;uW&1c7|9vy6F6@|<3ZQMd9EbEgN8a1`}>JnV^1tr1I)^^f4T}c zBd=;n=zU@$ix(KK8EmtF$@Mc^XNLb-X8eDS>8>qbD<0ke8z#_DGWr7nV^UgCrU7riq^ zE|nH8%^h=o=zuQ-xcyx|qUdI3&>9sj5h19(|7G|C zTd{=Y1YdMj93L~~5S^_Xc;wRS9tVi$J)*M{<;U`tWh43VSMl^*YJk$Z83&$EE9j0h z5jlM}j>}(>AHXBJ^V%F5MY*_rb86=n-!>L={-*I^ljvdzXQt7=&VG4C<#eAcz76Z+ zg_Q&@{+Bse#({*O!f~?Lf@|ky9GLB? zm54S$j8j*^u(p_=+&Q)h;FtwBBW)pOQtzGe%THl)uT#TmN?~mUpbr*MXR8H`kNNYD zHfk!4R&krJMZL@G<+0pvkTYL=*QsjFlMzMe);7K#89e0|vgJ_FWvuaPk}p*FDG38P z^w+}0Q1R!qol_al_#D+*A>~0Ro+?`04-OuZh4@psTu;qAOm*^Y94Wj|&q-gz<`WD< z09hJB>@Qv`62mc@ngWYvlG>Lmj)>!LA}_Kx#x4B%1jcO)@Q0rW&rnaxOg^ z7u3}~eyRAstU|R>=hXcTUbB$wUmRO!bemJ6_^4JxT=a6V-E0X|PME<`@T5}h(TcJg zf3r7BQ}#605W!iiwn z6`Qk+v0kFIRR)r#$ek6zT%| z?_MNPEGJL0hqfc#4Tg%V%F&08KJ0W;LIT=;!6I`K193~0YYivoI!rlCby9*mPW357 zLtxRG8D4%Y^_lp`@zH)p*+)WLsfJi(&Pg2RrUQ~wBeFI%K^b4GOzw9VwS(5op&w6L zZnxPy|8MJgTXrK|h`s~UY4lBSbf3Dnc@6ejlnsbTqO-vum|<$nV}#Wl{_Hsad|XeT z$zJk7TYyrqOh$&lwPhUsnjHn`%qNvE6Ql6EK1HY1Q)koj5z|SUvM|TaR0Lu$ako{s zMWl>JjK7YX$fNn8DlN|)_8u8_E{61h<5c<1r^I5v@MrQ6$?aDkB3|{Xg)%;!U*jxGYeKL1_qz; zEMR=B$s@pj`Gbg1_LmdwjKibe>gp3)SMfezlZ55=8%J!?F(Rl^B!@1fPY4&21pH9B z!%TFF=&1iLuDx@y+i>pTN2 zk$y0cAJYfS%NgX4dTXMCPZzEOn++cL-ed~f?CGjuXY;|A_CMxNv zgMwrit6ZY;*TcK*V!I{u3P_4maH=np#ja=t(EvW0^AL1JVR8@`nD}0h#}D-WO>L~7 zpJ)aa7v*&f54Px$>I#|2lRv(O9UiYG_yJhL4?;h#c;cns07`*t`{xN_EJ|JF5+4^y zd0^9Ve$U->mL=8Cgjd={f|eyrf_|@Zknj}QfLBF=b}3(V<#-kxwwuPfz;ENN`pazM z))-i-)!%zB&DLUflj!Z~BH=sVag&fD{ZF3QnMcJ!sLs0r-&AFcVG36pua?}>2**i4 zL`a*;=h5kfnQuvA?p;Ue-D=GruD1~RexRspKVQLGW?GHeb?pLzC|2$TGF2|DWLouv zU69JrO|44xg>3!FzbJG!Z%Lo9J77|$)i@EHpEzZN+Ldc9P+lvQIZVkkN_6`JCod$8 zjmM~91a!Vf1E|0M(Js#a-a1$YxN^IrxO$${AS_Gn zgG~jrH7=GDw*N{l$3|pX=08;^x8={q*}G=X>Ktg&`(WpB$Rh`T2|BxReg zAdDfikbOA_t&Z3ryMs1jd;Xh3am#4YiL9LQAyXpdsXDSe4zRDpHMXFnwjs@zhX`cu z$J9i>c@*YlPp#ly2Wg2IM|T}TiyM3rW0O8XQGQCh!2E1qju*mr21MQE|F_1 zjmQ9vrpz}-kKQS+)qtX%1;mv-gmzPi%KSEH|B1x{632=r=g?suYW9jt4AA-~m#WKbkl2f7!W5hVyubRZ9$2`eF%wbL4hS#}Px zRHfAouE*JZ7%V0NR1Day8mgLk2{e6`4mW4~9Y&QRW$08fS z;BY%}GD1^}~ug8M;u4SI;J3*LTd98f@ad zH)au=F-L1P!$G~23ye->e4TAHR)@Ho(t}lU2h@i4@f;;a2(6*eV8=>-C1|g5-1ka) z2+_IUc%v0mUR$0yBim_PqGwBjhsBOCjjg)3_~2ou=19`j%+jte?+XH&~stpEtRoJ zC`AAYgx3qb6cC3NoJ*G|4pdgCgqDV46-SDwU6L{bQ63jOaE8hMIk^6loTf8r{p^Ju z?m3cLAeOB^e83bFTkrL32Yt@fQP*wlBV)ZQX)$o?{F139TythJ(_c!x0AB9qV#8cO z%1Z0~484Hf`l-$|lyaup^dJX&^fqmRsHQ_;zkE$e9nGDU-1aj0NhQ|egF6H+98+@Puy}w8APW2m&c8~MNNL~|( z+;b+lMMN{uLz#o#ykULbW>)+((yt}uO2rH9jqFraO)HB~1jfO>&Ker1Vm@^-o%rZ9_Vy2IOkc29-S*(Qle?o1cSw;M5NWR2ZQoObw`$zdYl0$$C>dX@NB za~_{SPcZ~-$7Li>AAUj+6FFKGO6q0t(av!f zH_~5Vs{)F=1m*H;OMxKyH{UVB7pW$kHpcwC)D_P#QK{)SL|++J_-K&Vi)?wt`Mb1e z3`73X1GS>6r-&Q4p$ib}wK{G45$2`nsu4(rD;-3P-=sk$X01uLYn0#XbCgRgUg07& zH;-9y*Xa^OjTLqG`m4`4-8qXqqd6SR+&ol;-Bc4R;Tlaf_ePEe4?_~;DEXj7h~WZ@kT?*rsJ!pMsIRsK(3uhNtU-3-@a1sqPT`S?cUaNruZIc;-Ef_ zod6@E-d)#%k#}M$eLG%Zd$yVyqS9k7Vi4dBjyk9#cs@?;1R~6SyC5$_y<2jX;(~lJ zbw0e#EUIXkov+9lK?6}Vcp0O@9SW`ZqNX@VX<^FiRWH-i4sDTvDF0WLJgY zY8!3{3I>8j$qmq8Q@!)(zVD=wwQj>4cxyvb8`%b|b|`(-{iCaF8;B8ve^EA0Tl)6F zm+c`>5w_)6S0wUb!gUw!oPI5TA3qe8{U?v1Y#e-3b+DWrp29pExg(nQXqUIn{0Q>8 zoahdnNien-cwx4!L_xsBVaAO3SFJNQrA18?O^uS**t!eT-Z(^!C;Xc#ZyK+!&FD;G zp+vMx3%$n+-yomgJshdZIix?)vB%_)k!tt+>0^oj>h7$)bZeOEvR~I>%GIP8#4a-E zsu)Y3s5)_k(kh!ZBMySnD~+=pnRoBm5vDcb#O&DF*b|0WUrOTq;&6A8s_vdgf~dICbgjGiI`WgeYJreqgwPjW@x!-9lb zGj0gloNo;+A7>LL)%|bBGn-5oUR2nh(DQ1)4|xoU{(5Fq(AX==QlNw zD6`I~@-FpBw$TqocYa&1=%TclW5$HGt5AN^JZ0RtX@3>HRSwB*lzSjZ3BQJHPlr%5 zh`g!fMNF?e!yfHcJy7hbxIG*Z4iHbk%Q;=1POce9JQH}D2lsB$w8rS(<{Y$jCPq2$ zhgzw?L*kdR8R#aZ2Orf(5zn^EIw@6x>t>l2EhWUUze4&B_B0=UwC|3_K(Le_V<1rc*a50`G0;r$k@r%IKGfv$Ai(@-edy1WAkLR#l!j3DLsxE?a1 zc5SOV(rJzE2?i3%#6_K6nDfW3ZGR>k$g|ZKb0q!tGQ&tQ0_8E7tjrjJktY$WHsfr3 z-Zil9%wInxZaPpSoc+B06#m*%5?X5*y5>Lyah^FXKnk`0rkcuPM0S}W70B6JPBs}_ zf0Q;%WrfLI^BTPj4TfXp+s_?oR9vBY$M2Dsz)DdZic!kBHXj`wYDttp#xSItba9R9gWkXf+46Q(91)aSHwzOWN;lx zGdRMb^pV(^C$K4Gh!Yt}`HNLgs8KUtaD3^*9W1^hk76arsMYrv2x7DuL!;}FP|Z#4 zygnVo80LfqIqASS6Tqol*U~i=o{f$nI@3T{=uk&NlpB0zzyihxG}dE;qQexr<*Ce` z8o>1X&MtMM+tZb5W|-otu}6d6v;joypTRM;et$C{)#o#H2g>;HNU4ABKV=46A9k2b zb9-!1rKdg)ETfgKyD2s4KFh|NgzOMdDx2LqX9%=1ha1`l6^9-;6AS%Gd~C*OJ;O8w z?}O&{iIpxQid1EsbPywt?OsIr#-0SKC71WN*F+{$UTr4CZw!11-CB_4-A&h`sw207 z1Q%t_pN-YG3EzGJ|4nAt;xOu_#`A?9AEl^qr2Lt&$(&$KX=DJipXHi3ramAG;p6Li|qt=Noc?jo#LNq4dPW>kFR(V3}5 zaIL`MNl)%^m;{${s+G_uKF8I|FqX9y(WkTC1lfi^MX*J8wi+vbXhy}+A zLUX`9S~4RcoW>h(32|P;#*C`b&Q}t1P?ykU9R6~M=sITm?IV~IOM>6~BGI}%oSsGeXrbGgs1ul`V@;uR3oog7< zliJ0O%5>c6XN-TMCt-Q^Jp}$94nO&KkPK@%Kap_a5si|1U)YfV*4rl17;gAR>@(m; z^Dqi-o@~SAMEwK%j-nl*0HCK(=^bKORyrHLH^bcF_q_b~mbaXnR}8e^^R!`bC_}wG zQ|j_%SGQxVYZNp#q;!ZjWl=bx_cY)W&*kw1_oLnaFW#z=-1i%`FVkMkzPWGxa`W1O zzoNt4(%)zhoy_-e7Zsm895ftQJ5O~+Q9d1?VTf{jhACKlKqp~s>t%yg6hSZ&+$vI! z_Dl?Oc+0>df%{@C_?NGhNjePgs5W9o;kh zkLJV_$&RM00=Wsme116fDA61&H>FJ!XYD>^*HRnb3-QycGf*Gg#Yko6fl?nnPEJlAF__{a;(on@5!HA?U7~-hbmf$vE;YBA1`@myy2g zHTo)t@jPC8Z!_VuZ|X_+uZt#Ftu8{0tCV7e1#9flaZN0Lk_3ekXjGhOKYHnk^$!Pn zEdv+Em@QXaWk)Q?u$mEn5D9XyV zS_Ihli-+J4o=teJfz+AqPcVE+jX(!MTyBm*wd)Si)nvR3RBhA-2vAS>8Xj%z)@+h* z$a?srLy1xuNpQiAb6=H8%>!3^eC-PW<7D7p6BQ0! zCt}upug1Fe$*5b}O>hvi;l#Z%sgL?l{;42Z2maSB9t0X&Xr@;NqS7E#!MwKWSm%0# zrc(a#4e^=Yuc)uD4)GitYyLzD1M-c%S`1e|(5ZQ2<9PM33e1eQK23pW0KOl~ZC`$oq`rjoK`U9n z1m#dXq5Y30rBCGTP$F`uBzN258P2 z*n%V5OWDXp3!|~exO^TcaSfz}Fw^WlurDjz#@02F$~pX?aS$BEE=!j{EF%A*ykrdI za(It^uimSu3&$L%ksi>lv|8Y5A&hqT>>e9;MCDIL{Q5dPH2evt4OTPHh3C z*`8|q$d$_L^BCb6X7vH|ul^-#OK307a?*x3Ri5}r?hHmUjZe3wDRFr*UkmlaU}nJ- zgKHyapFQFp$zQERQrOdxh`dS%L`yV{5%@FgiCH3{qh+KBi$G>#pS#r)|Mv&WBGA{vIq78;uZ&>=MH8Mn1KC}XF_kHMN+Yc z%ny{vaVL%VsvL(1nNfo6#{iU0pE7IwX-p)c^4M!olf6ReH`gI zG?J^v1Lz&QumzYOa$|I6wTu|nLAxCLF z@2YVV6JGutzrq$dF5X6+GU)A6fcB~!ttn^4jzrE3W{Te8Jtz!{*!#B+zP zl~*ttiYK3i_;e2W;E!nnQd?NhYMU^_C}8T2tCRFi%=y?OR#U0vwf}TFfZSt|D!ekV z5T!a>nRv{rlS~ieF()T>ZHoTJDZ4P1-5$>03a~=mNXI|mID-s~=9+y(lM#fco5Z!4 zmp@>2bOGVJ0W>H-bh%Cl8OHkrY3cC#EM#9?a_(*dm5XIQKGHjA-rm_FbZ_hlZS9bL z)tup^%QCtlT%`cDm!Slz*f8T-i~vqc7N_FRyfP9`r^dEC8Ad0A2qV&KudejcXm-PDG-j|4Hb ziX7_#-u~l56KWMCCrE^OlwoFFcZfc1MXL|+k~FQ~D@nwGj4pO1 zu5uGnI^&c!#ZDvP>-;;;cF^A-ciE&VG|PJcGn)Zy9^Iv+-Uhl82OykjTnicUlm)fX zNME$Ad3MJl4z7iKhO^m0>c(%Lf~vb5oArda0bL4_&*F2b_bo7k&W;X6rFR=eVDz*9 zG)4xKu7q3EG({HHOJ_6e@PQkht++o%wYE7& za}hpkCbwq{Es*V3WIaZ+v+%g_;nP!=(+MX%Jv#Km5Xuq4$WaRq!Qh$B(#Y+uxJv6~ zK^<4<)4XXNRqlsGMb@gNot|^GjMLD|EA`CRV1JR6xXV+D_p++W-+QV{WQRznekR$< zxy^kS_siAteS5;VJ_t6$mWqGTQ1+#m!W+uIXeV5-E@>khXP;MxA}g(e{$m4qHbd|M zJxbqS`-ud^`6okE$n+jJN#9miqD~2XN$SLeaPxCJ>ot8A?tlH^h{Spf!+m~xu6#IU zpR{e5x*fpGJHJ^r7zFu*#|7JXiqvGDe5cn+0Yu;H*X}6yuM{N%L6$z9n>e84uJZsx zrEuWp@>NN?^)tg%%JEZI{0(zC?im^;U4I*3u#}~(vg#ww5omfE;JzoQ(AU*>z7Xk! zNf^IFZtcuEU!4LA7_Q?B%R1oMCYsrp9aS-7sS>M?1T1P~rbLI$un^_Z-t~Prax84F zAVN)?jK@8+l=fJoEv7aI)~TTLmG1fXQ8PvS26=S6Sh%hlAng`X2%X7CM=h+{dUJVN z#nbEtj^uq79O7^=KS3aaPNF5HUwUj%%6r$hQr?X<8h?WGs}qw$J2f-MZ9D$&BX-dE zG2XG{uKvHw?Al+$#4m7}x5G`g#H2>H@L_1X-a5NvPfR2GgYZceb}W4nB7G=^)J6b( zWdIUU4d@o#!lJDcVyPbcKdWS@`1!>a)GGGI2Y+Srh$2^r?qPb0Vl9VVxYrYCVEJ2n za%i+Pcl>06vC^%ajH@Mkp7LPOA2O~biVsRHjguiXX}q4OC^rUe`M2(f6RcVH$NixS zE&BvOMDt86sayZ?JB+u|EsY*D?|a2a-M~>h*^4Q!az#t_e__-GRDRlHn8zPzjQ<=_ z2J4$vmlf?oMo5( zHof#XgxOJOyha_bHQ1)O+`ww!r3h3t^fW*bs_jjovj0XIdV4)biQA8@PlvW;pn1v- zbteU&cjKkU)qt%=2;Eho`UxI{Ywx(qL}PFljfU8#@&i82MxZ_*K%;T3%Zz{Q*OA`7 z`f>gGo0oGZ=A2bYLH_VTW4e8c-5(mh82Dn1rzR#Ip7z2J3Hm&CEi|1!2fJq6e*##y zwD;&_(oB7wi7L!*kvc5i;c`j=3px*EEo{dY0>@;mShNZXS zOSUU{QL2|4u_*&?)@d|kax^47%$#-S=FrZxCWR9KMk7#Y4q1TGTna1(`)7i`o%Wl^ z(!5pKG<1Cj7tkM#?QA;fCU!;#nL&{L-*@Vi>U?yD!d0B2{fBIeV_cu7k-4)Bm6Q?1 z{Bi~Fw=$2vrA3l*9+tz7?)S$Gi&&k2z#TvK~EZ3gHYra^a*Xxl_P;vY8D zt`$?@Kl)jpGCO?{V)kHS;N*}j?wa6WYo6WE$q29Ki)HR82?clCH}w@9SjK4ucHtFe zH=I~F+rO1YOrH#EF{d|rxy~IjrBHl^UKub~1O^0Wz*W`-1jt2&2U(#mI5cZibHdLQ zG=GQrw2?~py+$lJ?Vp%~!DAPgR;)jHSW-og<1RKozjtg4Z9jYKZ=GchyhD(D zxKS{g5N71f8dkYClPNT0te$;RUD7+d=|xdl2V9PuX{Gn09py6t3oYcm#Z-aB_VErc}n-qlu9z~l^jt%%H06~i=5$Gf8LAUJuS&E9YWP+;0wFB9y{JAh*)W(q>RgRXjU;DdlF}j*-VEhx^xw=z)}3sAa@ev34zHagFUSY+IZWgCFmZN`%@I(U zJTZ+@Z357Hk|AyplacL4ku) z^S3B4YmY2;Hh#3B4ZPd!wICxhM~XSNvQ}1yc2M9}L&k!pK?Bij@zk;w;+YW2hghBE#Lb76epRG8pbaMcuvYL_V zC1;}XV&0n%a$3gNObQ%q5Q8|3@#^}9)|I0GiRi&xxGlpUTMIe9qm2zT>w6eiH{Th0 zR%Gme;M1w5(0v-wb-zt?O-2RSnLYN&7>) zqWS@P=|l>)0(3E4yVF>o)6kxlPCWFo4?;S)in($gx}ck~VuwP^=ma}RBuH)s(N=BA zj9bJJX6V-OkH}e?B($*ci1W8Cyb)w&mmAGt9#uw{P}`jD8y z?ATde=^l6#k)dBU+vj*kYdP`REqEFOib|-3V1Ok#D|go|m80KK(b3lhGV7}yJD{%! z#N8Bsb;LZQCLn=t3HPL^-l6~H3{Rl{=oXo{M3+-?aqi~G-r z$=9Jd$OUgT@o4jcPwntgRSBk}fL455J1`N3`KP5hPpA(7hyjb8V65y(I_~71v!AZP zceRG>_mxp!)zckEEO1+R*9|6`h|VGN6vSI)|x`e!4>npv&a{+ z{H|Fm?SNk^Ffx7Y$v5T_?A)A0Fepd=S&2a;wwtaH44cD)Zduqkb9p994r-de6qOo&h6TM zPv+|sM(a&(LgTvz1kN|xwkS&IMz$qppbR%I1hSe5lMGDCe)~a;!;c)IPK&bUPG*^Y z7^z8_kYjRL&Tm3md9tiM?#E0J=6lmxW@yh|Wjpa!PQTT7vECeH@!NR zYI_e6>l}!zPyZ%Gh@fZ+XeNn;-($mPWG)Yc&$-I;JCjMpkWC^P;HuzMNiCzoP@hOI zeKtD!_zSkyoTm5pc;_rP$yDdTHwAm;BR-ISha1S_qst;Tr@!sW`uZE70G1}yh;)*V zY&h}RGm#D_UZl~Jmo{0Bll58w%0(Bhx^MfA?pIymqj}nXOJ|slLX8^YYEH75JeSRMn~s=B!sHMz$;LDF(M1)y?oFu~5REAQ&ytUPlbRVr5T}N9ADG4_(`@p(U zxc4N6c|J6vfglv*#4jNe|8Vs}KQ~@Kv%wwl2W9h5rByNWVU-DCMFc|9$B)J?w7A&42P?XKp4n8 z^CIa;IJA}Mfhv`L@kTwIsk$c9IcfYj3=K~k2iU{w3LGHlV7P+M7{3*Mz=?tJ0vMy!lp8-3O;nr-BTi*>*#id?`Z58f6l)Cr9E^r%G z=p^2(ZYy#TTx~;Bw}Os2KgTl;M}arRs6a0SNRCxPW6bQ|t*s-r4!T&xB(LfH6_PW{ z&UTX#j$AN>opWW{J|Lwc-ZXwRlqPggws5~bmP)(Sc4bn63iBAxj8F^~_~rFb&Wez} z--3DGh2ZM6hA?Deh{Od2Z(f@T{;`@ChRbWhr6#E z9M(f^N}?5&3fz6!zWC`o6|%K4GQ|5Ms8$J|!N9D8mlW^vNA7jHB!*$M%=5WIOeI|7 z>i$~3bV5HdSM?<)!~-^KBz%p{1K!o&AbZ43wW7K7bX0BcQFbaQ|Dak5ckLl96 z@a|yuxvM$HC~&#r1#N(f#l|YaS^)Oh_CX3HSjoRoXaa-%E8^O!^`YmxjfbFkGAKkk!MCBV^(smMQH z@9`%?>>;~XiwI^*lwM%l%!Z(hv!O1|kHDw#)FAICG_A@Q)LN5!>34e`1gx)D-RNrneeY>3EJ~`Vu z`0v~SJ(FfA_!2ot{m-CS2AC}(tKNbaz5FeYrISkEm6kd(ayML{ip6aVrO#`CNZAR0 zE~S!D6_3g8S5hn=3&0A<1v2A3bfb#Bdme*!y6v_4Q@15Yf<%jU{Lvhr9#!0WWQvJX z?1#{5iCsoHUqW|@p5-O|bss~wcvkEJM!-MOs))4nc-6L>!- zy$ic`LsVuOllP=oCZV+;BVK`qIC?bZZiBUpp&}z$dcFBUwFTWQzXOxSVy5Q0xOac^Vz_QOUxOdJ z8E^BT1^{%q4X4jx!<${3-`VYX1pauJK39yR4h>eX49kYp>~7`&KX*BCNv_t4t+!et zX)x4L`RhJ$p1DJB0e~rTa7n*^GiebrGe&x? zk_u1Ah=@sB4D}Xl?DcT)xJ%Onn|wV=m6B#iZ0Xs+|AtgjxFNl=A_MW4dyb6(GXZaJ zTX2isyk0l4(AMJjl1Xf2uBEk~^H4P=_Ovj`7kP^yW80~?f42B9&%ZL%Cg%hgkUuuG z{)=9>-mdcghyR0>SMjl^NUy0{;3h%}LcOR*`u(L_#|Ao;t9&cqJ`}Eu1%3r zZsR`O$Z<|=EYF)f=w%Ww)5&ONMuPiskkijHiR!kALx`mFAGF}6azPtc3|j4lctUqS zP7()WolP)>9Bj5)boFVCCLdfD7J7bC47b{N9Fy6zrPp^&j; zax>Xpzbn?xC;PG*_o9&#G?eHAda~e=Rs> zn9USN%*~!)BCO32Y6w~eT~Ye zaFZZETPq^vDEW|`9!PiYA~QWtj_4R@S0DLYydFZmMz!;Tmr^k`7MzZs9-%6}7xJ9? zCQ^Ke3l_f?J7U&M-?W#nggE!~crlvsbQfI?Gqu;PZawoh2ZqD519_N|3=u_|iocBF zYz_-8RpE_*^hp)g1^IJ=nNP}X7y8MG53=;(-1peDs@Sj~@DlH_P+SwMd^UmMgq3PEC-A?dHGNgDK4i9XD~YZU zsSqw%iIOoyYT!WT-`Y?$XS4g$m>A0z@&GggkmS4Ydcxj$9^{VI8*Gt(+?oG!(7hXC zma}^dus&#Tdy!yhgmvUU#b^LAe&-yZy^K=?r^4M_hw`qX>p5{v1<-)3T!&>9E4&4? zYa1H`8_QuIb!Zo7e^)FA+kGi90;9EI!J_VM0zj<0c4Ux#%-QMBs&b}|2wRUXWkk?x zhX#_3`vz2Y4IHZBzZ;CnRg|`Yf^$6ET345wNfPcBOE=CVIX!hIg{mm2zajppS$r2mHL$6qeC3^5{)&snx1X0emHBBDQ% zA3~7P2dRw%TPVRUq}$!~0(@o#RTzXjV>Yoc0U%$QY)&F1t)q!{*@O6k#o~xqG&LS+ zwP03CRH1+=_td8^CEzpO>Y?%GmrH)21L}zh&Ur-XLL;FE622hMrG`w!{f-9Q5`u%k z=QQEn7pskf!po(3o@fkMxtYY1_WJxR;FPu0wSWY3bSb2cGZZt)tMj2OtF@0ukOmih z4by!V4^9Gyim_q~!>ua2%S+Av{L!j0mM5FHtVgM-%hR%N3wq*=c3Oc}1=e9GrLI64 z&_R|Zo))Q245mx9E`&!~V6{x?ljH0;Ol^O%YT*LW_AdAdbI~|3Oe)Xho&l#4a zW4r$Z7ZH*W8bqY656T5IB2`&*nhJ}u7AqQS7!e;KtahjiOlok@)w^krZVdol6}3pE zYGu+6S_rwMDsA!y^)$7d*#kM~+CNpg)oq_=i9AHR&HE*pR+z5Q*}rBco!$I~k@M}l ze=a(l6}b;q+1!@Uoc!1k`V@|w)OSOA6FcT|&nNNI)fgx-H<7yl_&*`$?Ee>H&cMdP z%JH8Na|U(>X14z?V&0D?MB=wC$U&8 ztKHQjAoNy;*A?cbmP4b%qtlada|tGEB*o;UpmU2%eaVQBYT4!;m>cTQ79E%k!AmhP zflwl?039EFeFz+9g#iGuwb(qEkd?#$$^h4X33C%E9w8=bCJ*2GsG_KbG(Sq;g|)S` zm9@UG_3f~X_Z%WnVq)KdGQ{51$$1C@0^$lXGFl)4)Hqe3Pz(+1wF?a(Ywyzq}^A(3B?>l3}GZ>29e>R!GV3o|3@vu7WyZ>GtfjX4U) ziHPtBrB55!?<}->)>;PU239}{_V0qy?5@3^U%`ChJnidm$bSpwT%frhJ>7}f1zl;> z`~k`DdQyTPH4l1H7eD#0Z`Rs8rKe|@0Ln0qlK`BitfBzeJP9kmg1KKpS65uq!LMNc zH~CjE*Ci(=RwD*JZ8E_Ij^=+zJlcw+&x2*C7oz;oMCsyT*nUZV*rs${L`a z^bncUMpw_o7t+Oo+r>J6YOyCe;ola*S&)y7JoXX)#hm$Ey+;}sS4Jy=4n(lI4m#Ow=|63$r3@Cv2@5mET@#pHO(0| zm#pu&H2Q;VCDnS&pj*rl89ds8je#Ba#Zn<_h={qcB+f9g&^+;Ml584{hWEt{CYtWy zek0GQXL2|+my$GNFk(T+Ai-><;^x@+UjQ>e%)eCK6<7bmV>QD`rC$ZsX8ZAh9g4fT6!zs^%c4*`{mnQ z=nv`s4;Vx>eb$p=cW?y`|5zEEn}8%-5PSe~gyAgB|ru2b~W3^IZ-4V1T@c>@7 z?3FV_W4IQ+9>(-E8Ite1wO8`=dC4A)3;i_$uHdKrU;*Vunxu})`w~C{J1S>L zD=TV&735YL(wN?2`;hq*)r3K2^Vfxw5OMLTgbKAIAc|K#L#(xrQc}Rj{+{EOD3& z-NBB@wv4s2RM=qo0eMt2DbiY}ORT5*c57B!)>txjb6x(DX?u+^{f zmlvni2Vt?Um34^fl!lzp9z@>&hK&?+B~_lSv%09yVAg`5bvek^#57HV?v~tCf#}YT z^EpTQsC|HSW{6zg=8J0dXY@eh%zPSI>T??b964MZSKr}HJ~Bv>3L4xu;nWcC>*t%T z2utE-UM3593gfJ335H;ARcbR~qagak4HnOSZzns&G==x^Ul!msaB>GK2`4yK2xIc2 zJMJ;i)8N_XvT~49bC`uVnWQcqtAgLMV)L$plRzJJl5pesh8Kjum|dIAa*meSyi^Fi z{3Y8w82^k%SLWNCt6{LB5vT!ThMY`hSP>u1a={|Sh;?4oW-ZVmJq`}!xKc8Y3Az~> zLj#tgFM`idF>+-eZr>A{i)h0YGx~vn>f8(jipU*dir(W1+S8&mx->P%Qp%c4E$TL7 zzUfS3ZV!Y-=%ba{#>Z-QomODp$vZ8Fz8iD~v3rmYA*^P^`AqW?z(xOVRRZTx!*RJ( z0&%(?AUIf0x`!>@73lNr6K--6E{p;p41}W=TEqz!u>BhCrSaywj|+~3r-q+e=X5_P zbqmq)Fx~1?7TAv~gFtJ>m){JrLG!VX?o?t7MlG*Yx2cUckPhvKKoVC7Fr7S5?>mN= z{_W(vo_uP5aI;Q40!u5w7mmf)MK&%PVXDEK?$SM1R4XkuURXLHHd|ZCkVjSvTR;XH zlj!|o2W2om+j;qCoaw2Jh~WhZ$wXYCA=hBHZkTxxUWTPgm?O(CUy8Wc4av+k;O7UT z)@wbD4fZdk&w57v)?5Du7&m(5mL zv0gXXLZ@Fnz#5VU2a#tq*N~?(CwR#SlY5q8OZ6yLb9rQcDUN(%&gJPovjuI3xr5j| z%~m^h|`i98w~5JG@0s#V-(6tL(_4)H)Hy!(JKB?Hb79i?$TS{Lclmw@dvTnZy_ zh{u7s69d(&bF^l78h)eyV}*wt8W$7$ z3(&~s_f6VWw6C${rp_U%DIJm5tXB3ceUmcwWA6ib-!nkE@e5`kU`*bu>oanIZxK8n zfp;cNHQB;C9wB$RLr<_e)EZ+EAkkz39_`v;HvN!TAN&_#{>sBy^TwL@6aSWsNS`0~ z3SF=-tmJO4=7g9(NWf~l&S^i_PyW~#F=@oyd|Q(M^gv7NY9}sBP|pY>vPRh?lliuY zySgN6uVuGa^pe0I$-;jk^+Q8LCZ`#V_C;Az;uzxTD>dRfM3BtF|J->!BzhF2DTSfb z?%=kulQZVphPPcAhTIY|X^GG)#0lt`w*Jgj^8l=E{Rpy86LREB_x4)WmUPP}wUp3^ zz;|uKcM?vcsINT3U_kK{*qOk*`Fo%UHXF$k#v`_{k72q;N#PZ73-w`^ZVna_WyVA7 zTZ4HwzuKe9;LSsBoAg@NZ!|}CiB8R#gU0{+y9m6Rl^-WfTyv`qkAqp112Z*7UGht+VxZcOJsDu+8P4S$40nkgO_z6 zCck91vnkL}#0Pp-7{}p@n0}J>S>9ozaAGt|)rBS5Af0w4tD7YbmT3Pj5suY(p8$#9 zGjReBdAXkkI_4gB8DuKJ5;gRl-N}k>x8ARx2;R`;(0dQuqyAX3BojZ4uXCpum6fPn z%rzmb5_CHtvm0jVc!3MJN2}p89yI_QMi;|mWLxE_t5B*2>EFRugKV?bJx*LK%cqBx zmzDd1IZJ7imQ)rzPD>vEePg6cHnNa~>sPE#kZ1l;fa&cSU z_ZvA7RXJFqUM8)XfGyS)EH?@jViYi#nQ_1A6MKjwYrBEt>BVX0%`h;8En2AK&CKkg zM^vzb8@w~-naR?DZ$ii8$*<|?8dg%`z2H;x)xXkV@*5y}LI6~&p{)UlBJIsRb>TNQ z`7#5#o)e-iDIZ1Fl~(VM5}qU5#bda(paGd9x`rhLl2yHC=MvVAHG|CT{+?NcKw)_bevS{168FPWEp+%-gp$6NH zt1Z-WG8g*!2jV_atfAUc?4z6Lirs;X`n7$C$(eVPx(ZF{9!k}etXDUMlZ}wk%6qmy z7R~cBg_k$b-HYH8cPqNKI^%vQOKGy~>J5RYsrC+4@)=ku)^fu5>$7se4m|y>!LSoL zc8u{DX8E?{CPfyC6RVgn&e~PZ-(|`uFLxIHd0$d~$5{$iY2e;W$t{yy-L3*gHajs! zT2L#Q}2-iz}_^jQa2F(}*&{A1DPO7n^-q0}sz$s??t zOS=}p*Ca+q4zk(yn+w3I3Nve#@%XFmrXo3H;+jHP??ULBlY@zyA5a*-g?z<8QLma- z*##%ENm+rLd*G@w?Ht%eceG(W1}xo>5LL$xH0Kn5D?6x0Vxqx*RxKh?V+Z0?k1!m_ zc#psky)#;@|Lp#>oNJ8BH^)BC1+tgOfY~(3IJ#-zK?1+D#5Y(B=7Sg2o;Kg7`(eL!*23Mb!at6hhpKTfxBb+J6$Y2)FmG;l%P^ zrsu36dX*o3!~}!Kw|Zk$>5w4KO>0-I1D`!A8=*7otv81Q@-&=0Gt51 zvr4ROVIpD0^+mCrBXo)lQ`PQGJ3fm8e^^}YP}|)5NTqlw{Dg6c?Tfv}x_<#T8vLbO zM*xx(tmQMLckra+kTEo+vhjQlW(5fW4U^1BJFm0*iWoz{LtW&v0@P%812HNXMMXJb z_nuq$>Q3o67W>AEf{jI3;|G;3H>{riNshstps7FcPSSqZ1fhdqZ`(WeJ` zJC)1ZP#q{d_tPE&?XkjmKWrcnrLgS$v{VDVcx5aq)h`rIRt`J)u4X;M=!ZB6##X{i zT($H{pVSp-C!uNv67EB?IBK+BOx?ejq7I@?U6Cu#mdJ}+)lMFYAd;SCK%eP^lU_N; z;?H@*{ZP>}q?laToH;kM7D^da!vlO$LHfHo#`Tu%#Rl=YGR+@C@8$3*Wk2`#!HZu% zmSB%Y{-L^GCvXZL8RzQ?wWPTt@1o8RL(&NIh84IGB`6T;SI&-sc7uACgd5Vo7yUAdzz;{HxY7f8?zRPVK(+x@Cp$%tlxJdq zvh%BC_{g9f$y86zAZ_BV>U_NNMrXVa7rPvrYLaJ|jr6dBIb-?aJvnB74_4?Fi7saS z6z6BUWgtc>h8eBJFdk60kWT}_o|}o$9)H}j$F~?6_3he12F7cUV&xs&ZXmMzgW9BP zB7CP!09W5&Q$uV7nHq&jG;354uf3_u+q924;ZiDoW&Jqi zLi$V*GeNtYpSKcNJMRc|+o{0s@Jea=J~B4Wc~&(mu@tn#c^ z{8Bov?(%Qug&eL_vd#p@o8;@)Uu7nBem*=25~hJ42|A{-B)L);3EE}^#1R&u@3m#L*|dl7G)_ka3y=z zA$qC%3JDGoCDIqu__yD-mno?LID0gW8I)cFlwQH$#KcCB2tM7EL@=Lg0c%=VqDYeY zG)RJ8Tp9({$EH--h6~XZ5Ls^vuzIT4@P2Z@K?=ng+#{4|j2wJy+7ilsA`=_vVe6j+ zPKii_l<)#_yv9x6iL{dr;#Z>A0^3N40`fle8_+G_)KPT4{q5LjJr+0y8jI2j>;sZU zcf$obizoA1`smrIzZBv!UJYpH^dx!UydVjzI|qM>{Q-`Nr+9flkjU~k)7Ema*EeV~sOmv(F6%q-ANyec`R8VwfE?wON2IW#= zT#0UmPhCk}&Q!C~Yy1a|*&qa$dL#6^?LYg>8jaWY z<9C8vAnCu^yN#>63pk=^=>Vcl2$~@!ZAGaH-PTl2w&VRYgZsipjh8~k?^-LUxHuM8 zEoAfX!PxQ4g{JBPdG!Fd4rVmP;NfQ*P%yu!R=Rb!8wKa3yl(U=Fa0q;>>-hjM+x(4 zkMJ%5x{e&}tzn6MrB}!*3PC4?!C%H}c(~Ca42L4MoLK10{z47TI8nG7CEQ)WD&gOzZpkaUEHG8-l42 z`fuXs?h6Q3dEw@>^}yDcq+Be$fTElp<*bZ=(O>LmzFX7s1yW!OMI$kmqx5dLY!1r# z!=NFz1O30bG!Ker!jFU_PD!ujNgS2XS_;^5agV>5!V#$ZUWL;i^@%Kk$^#(}7Au6y zvgwW-OQ_aQYQ^dXY5!RF91m%bL7uhL7IVw~fC>S**T~ zvJrY}CH#x#*$Lj92?UNvZ$qul?(l$)%*ENq7rqpKQS%&Yv%aCeXgcU*U}K= zm#xEtXX#fcqVczT4|f6DIL;y7^~pm-XBFdIAqmY4Vw^3^Ap~s#N@OH-PWz;lT)4Ai zr!NJVitXZWQKp*3xVNaF2{p>w9!KFiPdR$1Lok^La+NP%`ZzQU~FwSu#2*TM>!;Ivba-arjTO;ZUQReC2l>-P;ptoHzCC0DI zw%lY{s&nT_5v`T*Z7MROv`>60CU3btgO)mY%r~L19Bqt{6+3i2Pt|bBm3apslgv%5l&^;eu+A0edc~UZJW1YrVvV(Tvab&EQ3> z1}seR2oixa#c8K;MBs$W8uhA4LBCt67y_nsly^m`_lbxDkJC(+a!FDm`Fi-@Az6)x zQ>BV`_7#c*3dOx;_SKv~b@5KYc2+XqPDkq`g+~lj1G!XjXQbevQ0MvH4SR4;V;0d$ z?cT;svT^al;Sa`->~&T|#LdqUHcVZrFZ!cao2H_J(EMI$%&%|L-{Fp-YPj4aSzHSY z!G67o3K8RlNd*cpwh@6@eWXzA4$!|4$>jc0A~j#g&duI`qf*W_IN-MzUaIZrc_z!- z`1}omV@V3kixOOBXolFT5x`uBx5$Qt5mtXeVv=Cgu5KMk25bu#}jP5nx&4b39_P0j80;bWCzfS9=LqGFpLUQ4Q5^W;b(@Qo;) zit#GEWBr5X07au_$}9W0>?DI_4D0N!j%U5X;%P@*x%mmw(q~!oS0{Ex)Q(8i&$v^l z8l~TSrD}E$vkP46CB~kiD-D^5(aRAtra|>-Nr}M-#|=*_Fd%O>DIsYnyn)88E3>>< zC6B5*vNV+;7v#Zm`%&qK=xMizun8reY8V;sAZa%2_(e1fNVG0aP@0%>x#ff$81;Z9 zy^JDfj9LXcLQEhmiQ_K6Z|1=txYp-x3avFu2e}bRFaBG;BPaK2_P5@?{OSJdOo5c~ zrT4nA#{3d#i`%fpTM~!$&{ZbD;d9DTzj{4wk^bGPzSTXBl+9f<_1sx)%nOpd4#eFp znpSC}j}3X&LYo=sEs_&(j<=aOA8)*Hn5Q9me!APYta!t#Rm+WW`iEl7=csVP(z*I{ zZ@9BE`VB4Ii6CD75818opRE#z$N}Z#e5v+OWvyRC8=dLcU+(23Q|XloMG3La?|4`# zP@PP&dlOeuSMY5`uHc|v@ko3_pQ_(4i-wC16Up`8oAlT&lW!PbB0A|STF48J%)U;U z%K1z4zdz*0FG7H5OZ`u% z08g2%KjZ5IkJAA*-Klp&>n^hcKUfpu(h#l_Glq3JW>!}ZU;NwAOzq>)5$frYo-}ch z?*x5j4c5eNh8f^1k5-AkFQq71D`E8W2fZTU&-;$z*fb#4Yiu8lSd59wO3Ry*6mZ>gh z5GS)KLl%KK76o|w#+3{6bD6hRa`?mv}7D6}T4UDqRinW)|- zh*I9`)Yr6}gZCb%JMy$LNG}r@t;dC2MQBa$H7Nw+J2Zxf-f!6(KiZ06Us$57tb4If za3oH%33R5q0!1xZ6yhI8ATK#y4c#@twyO`p>1In4wZ8!%GkWfYV9_1$6&_lnCh*P5 z?&H)m-TiUZi^?WDj#Wq_LbIdKI8EBFPq?pF~52DKIJ6d=Vhc~#{0kh2?1q=ebP|s4ao*Ou-gt^C=8@z{%z?2)~T1BH@NJuGPsr06Em?EG0qcR zYj#c{8z*8NQrY+613W$?`g?-Y z=JL3`RJdnj9BN4dnAdZK=R@nGaS{e=7;Z?T}{m*GHm zH<_nf>CMS-TpSk!MM7gwAewlDeNwdz^gwv*WW;Pb9~9FDx$5jRvsx8Gx)S;NGwCP> zQ$nZ{#7`$ZPwqpEa1Ei&Lj!iB=!H_tFv9RDP(k^+Fm)Lg_8P&hBj^Mq{0xfjJyq5~ z7dE}T40@VKQwLUu7=2`=E(uL5Y<##XcpsHFN}UmYyV$$z$LQoSzLi})0G2ubj>0p8 z$HIA%ISBmn2Z9zCXYKRM%|McyrDMpwVYp`WmQrx)t5dA0sOlwZn+as=J8`P6jBW3O zSBpcQ;SY19ph%%VF09|%3>YEV!b)>f^TZV5)rrC@a|Mp4UGGZISlGwSlF|FJsL-Uf2 z#_Zq68wm{x1g&sh^T6vCb<7w{GViRS4J$qOauwg~tA*{xTR#hU;Mds7#Yg$G%V4O7 zGDTh>2$}FPo3>w4jXLb$m;Pugl4r6)j7+XdOi@#Va`3%&M7@TPg4RxpH999llnZ>Y zD>`WUf|3fOyTfxaSrYHIyrKU2;X0JM1R*W^XGoFdXPAM1F1|~l=ILX5J8k~3C-UVq zTd?OZm0u~`4bI@KM#|h0YYuiPu7iGSj`RPj3B1?-%+z@ zW{G#xLs-uwPCd%Xf2$JI2JN}UG5XnlezOKYzus$DpXkECM#IbWVvzn8>W>KLX|P~D zw(&dYsNFBK*Ch<0CjEYA`9)S_7#VBGR%-3mgXNfyRJNKv=Hmo^H4(uBMvf5zS7WzU z%gxeoJ%wYlFOIf(&m-|&8E&@WsVQ(t8wwM#w^3^%yJ!3guVWz0phJX|H6rKIqXQsE$a z7-g@u#nH;ML{>Ub=n zbRvwU3}n47%^zn<(9{|Ac|JOsBAQ>jX|+gM`Em!Zks5Q6^v%gk7AOz0Fu1AH?&rJvgI zxja+Ux=zfTxy!|Kowk6zG-D7DdTQLGu?Dl_NZmb336ok7 zDH0h(gGd?8fYxBO!s7ox!uDaCk&W@BlaZXP4iER`l~PspLYFhGj{DVzY{Nu_zlxnA zjiJ4$WncsG^V8z71GrTIwqaW5S#^n^@HNpA7 zty=5{O2*VJ{;qPxf}Aae!_=+0j~C!344cFp`@U66%_T>_1RnG+m|JA)vR@{1qr?R` zHXkY}?bgC{B}-ixWi5po9D$y5gtwfN@r1zgIUjY^;=C#JNsO7DLKd;Zo)|TlX!p{} zIgvJZd)H*sWASjA_*0{c&J9WtI+3clvLE`q)wANhHzW)qo*Ys1ZA?xbOAp4t@rn$g zI?9#90YOJ{N+<#R?X7hPLl?jwlXx-8%S%~yeZ-o-#X|`q{iqE3_ zuoltd8;aa1z@yMR=!xy5Oc$qSGaS(0ojFPKNrG_^?WRBs@N!WFPF50S3%kB6^{7ol zaVgs9qM+T)%yRQa*LrEc5C6V<5ip%dRX^?=%cW%{Q>0v(_@jk>Lm14|3H5GR%YCG4 zPhRdGfuo?+|AAlqenbW=eMZt5HMedK!xup zs_^S(JEc$zjX5rTYwPzp^IPZ8W{pT2zZ|rpav~mjQiZhuB|9uzXIp%}3uw{c>oOhOa$;oxfDPq>P^=~ z)P^Q6(k(=|_*pzP+}7@n77Dlr72C;!DH|GPi}s4=RAC#@)qL!+Z$9O<<7`>?JoZAu z-xYcb|LOKjqBU21&_OH^$v}jGhzaR&M~q&E3rO%dV@>3(47?7nut900KA1}#xc72~ z<|6K8<^#@h7obvdXdxd2C6P3f)`H6o=IspOFCt?44Tz9{^LlPDFv-Wy^mHwTW_F&|3=*mI~}XoFwUCTQ-{ z6vD;)11=6KJ%X~NnOf$kU2QI}SbLOxLoIuJa*!O9&;~i_a0>Ln`u{2U<)Q0#mg4Rh zFVRCqxg*%kVC8cll6xFpr4DUSj^r*mW}>l+AbeGH;uZ#-zVgxJcc(5rCJ3bdwwGV? z*^JzN`Mz~~ugAKzfI@1Am3#2*6BxzRc|KR%?vfJ}k2WLv16!t#vVQ^4K8Zt(t&`AF zVfv)+lfJ)GN9?wyr6r*OVXm0~kjP#=+{pYf$oNP%Dp?x6wf1@wLdp+;he%y44kp9vKRaqwfOxh5K#$*buX?L!%XlA6C@QIVwVWc zUg8GSNsL88*;6WBP~Sp9KB-ltcbkwd+Vf(honx!ZCSzyZ)9>=~zb z1*J@l|At_EQg@gV;qj%&;O_IAG3kx+n9S z3@^!hu)>a6-1faJ3$2C%U5<|r(*Ocb*YSy_sRT;!{O?Ayz)p-FYsMpeE*o=GS5^c} zP}Nc#<*v_P2>mL~QUZPJW~?8tkzL9u0H11wxA;A6dsV$Wh9zW0rMnY<3+0I&UjQoE z8<7ucmN%q)fNDb)YS|ec#(67NL0@X$m&Wp>%`I5P%OahQJ*f{u*kp)`2CQmTY>{ZC zb=$Ji?2U3;k+j;4TfNOVzzhXVJUGc-L`Z3Fm$tGOx+d-0#?i)Kj)J{!2ykuEH&*twWgU!tV19uWWzS7W{^~F+tFk7J^dZq;cw~uWP3QCJm@+ZE(6Mhp|;{mDlMg^ z4-HfR%IzUiAz_qODF@dRFpaDhu>51?P^X$2AFj~3Pa&Z?BD9TGl3XqHAkf?^P{Ml} zWELoJ+!hA@wZU?$iM+W`OOQr`BGTHuoB&WOFOI51p3i3yvXhlNk=)&-E|iQU`Bc^x zYU@57~INbM@^>Ke#J z7|WCXv5>R@=9UvOVACxLxFXK#4e!H-{1glt$A``axar=ml?c%jMHJDe-hsVAi1Hpe+ zlnKMEIxK&G9Xjrf5jTzZ3f8|j_apUFd@CljKZZEIFL+uC)WhaR2?K8MH8^Ua3V|wK zz?Z$PQNchcmzl`l|Lm-Kh}%nf;J&fVLJK;ckDe;rH(Nz+v$K*QyBf`jr#=`ZFO)4d z?Ph{H<}McEy6#Q-!R||Ii4qe8Zfph#y1Nxb-f#+>59pA}-VVx(PD!i1AHQZi9}y&qT{o~u_unSnU?n>agMbvj>n09$ zI+4>1tX;B7hAXSaKkZ*Og~e&XfqCI*e`Ykjon<-CJ#T!+9RRwhFV^^6h2Oi9%4`?f zKg-(rR_Fc>km}EoF5rZL|k%~kJkcS4bfMeteGDqSQXmT%{_~DP- z5|ky3e;+JKq!HaAWHBx=CNd^?$xBM+9IGF*B|D|E0ooN^80SjrpPF~KLUaTXeZTNb zNJJ^ewj5LhfKBid%gS1rPhV|nStfLIO8M__f7aVHW_@H81sMThNb*#?efD3LNy`%` zTtPHFPv-^CD2@zXGrp&@_vsCRaA7#QRoH2!ag+?2OH6wayFLEm1y2cC&#tU(balw6 zxqvD1{yq`hMojOvT*(+9P%5RC{$#~#l-DbXW* zMSepr(4mKZ;(Gr*bY&Q@(p`PY^LH{&PSt)-g*Zzl9qbG@&Grb&WCH${lfDC^B+Z93 zrx-hRPR3fy^0n?HANU3T4(PYFOv^VlK4q@Y10HHGM?)>TbR#k7f#+JrO7XVI8up)K z=b}MFv}-{Xyy%f$7i^2PFXzW+!gUrNsj5NbE`FoFTutk<_RrDwW0a9WYSZ}Iy$Oeu zxdNxO5sCJDwqsC(Wwz;;T?=~0Y58Ts}G;kr3 z*bTWsSulzTC_dvS%gDW={cFAg;`Xja81DMbOjONx=tNT#NX>-ndN2D6Bm4R=QB#cq zyy`I4Uvh50%LwFgOI9cFETU+%s?eWu{Bx2PHdQOtziCrVf`HwD&l8uAFm zoKr38MIn+a6vVqVI$Ej1aorzg>>X1j4R%sA}ecMccR7ir{%@Iwe z?d1^y%_qt$52ou}XPTF;Rw+AD^sD5b`1LJ*$Ps3kv|H3Q&U_8-9os7dZ?(d?z&0o>!c2Tg#<*BBt^s%gKB-OSEcSDPLZP&GRft? z{MBuC%p3-9CSjXt7O_-?Qg^ol5z|qQKeeu?dk{X8#?F>_c!!2F=xF)%!!`Bi#B{_? z9X)Jz&`*zL>V{@Bc;`i@mb{gA(BHHH57s*=PWcKGS8T*dq&*Rm7uymP3F~WK>;QZU zUNCg|Pu8j;@XDrdy0WwajRo2pxv&C(9dq;Xn-SCqc43XR85^1A_r0Cf;UTuh#-@b? z(O|S7i?rAkv$ib<>54pa(}O*UmHzrFjm=cLG>_)%V8SqkQ?G(~8% zMl}sB&)ZB!0)k%F8|fMQ$&bA%evd{JJlo>mz-z5hW>>35nYJ=`Ysm{72v8#80v zlsz^pRCmae*NY2PglP9Age)u@&_>LKA1KG@s z{&Q#TdF&l#yp;u^jQMicmsW<2Q`dcmr$msp?MUuox(N#wj;2KxBTizxPwA(|v;xbe zH(>w5YHf`Cp11dE?5Bsv!$*5L*#iZBjiMe^r3%YZlan;5u@*o_eutA01?Nlr8I z!4H46Qqkltu6ow~A}gVq+jRdH192!rF?=`SBbAph`HkLLBhn$P%$wBJzeoI^O?d1>EHR`J+5Uv!77gN5BUMggNQVQ}WlW`VV1*^< zQV#-=8OBJ~gsoT}1h#rg0mrkpjI)=pJDVbltV|t(TTMw_bP<*m*sMdUjD)p`iyL}Y z^##Xc(P8$frQOvnX8NPy`)Vu{5PneH%?PFS8oIM4wzIw95(tl~;g#ut`)L-)&|nC&VKQz?`1Z!1?Hi zZ4PeBYV8b@rK5iJ#fS*{DQLY`Sbf);#*~oPjc&ZBexe=%=J!#X!dd1)AAd^mUES&W z<&O&1$mnidlWcD9Y^bX2$k_6#E02~~)JKP+n z5Aee_&p+M7@e0<{3eriF_^zfc`=K>ex0=W(m?bcRxGC5mu)vEC8MZT?eLE__QriLD zNyHyr+^S2QF*!vzQO}Ul1ur+^wr5dm{YvecayAKEOA7Uz& z^^KX;r>>AgmRSnsEkLoUZsw`};ff`wVZa&(+iy{dTzB)NT&nuI+5|+(G^Z(ZRAb-- ziBz;$d~EKTlmq%lPNCn{V+uSWy?i~NdZt% zpQnx3OkNqq@TlwC_)Tvd+g;k1=U&9Df!y0Be1_6QZ1u#MHd4j9>wcbtxgqAhL4DRj zb2U1Rz1fr^QfxYb$2r93M7Ao3a|Pq5CKkqw>LlF;#qgkNRyF5r7#~!Y0fbbexHIVf z^Q*#k6?mG_p&r`*Pq;zqG)$KTD$G)0NLTl&_KRTIiV1bjlhCb))xzX2Kwyf;r*!4R zM`uJ1;_8&@ecvl)VotwL+CVYQh)pz1uCAV-zYAo0W0@md3ytd$t+XN`%#?!Bki|q- z4RfFR%&0c_jJ^M>0k0R%3@Fw8ehiw83OEgYhtfbm9KgkSp_(Ql#Q@){1O*so;tu%e zVmhiErMvLWlE@-)eIUOTGQh^ZYUqQcNs}}9*t9b-OyRzP z);3BWBPiGx3=#i)^=%v;g7Md9Jxd8S(|HSRE0i&)l z!JE>WNUp6S{c$mVoadyFC-=YY1dp5dPI983ps{f8eV`6R^doeR@*lDD)H{=(DW$Q| zd%8|y#3c(w&7^|VmaDy>Y_`{n5#?rX)Qw?|NmrW7v7;xrjlq+^6sSxQDW3q?l z9Bw@3_M5NV?t4f_N<0FRe^B!&U7C4)q$qATgXC+~Tui9lB}(Pz0=B3n@$=V>yCYs! zx!cI=w(`;8t~7HLb{z z(yp)*X@16KiZaWnCgzn7YV+u~-~H~cynAXJyzUd!mGT8@;3nRKA`-Z`$geC@M{`U5 zWW}J_V5Eu_c5{l+Db^!q=_$V`eOS|$=WW>KyvU!YhHpThughm(F4Xgs^|2lugt1`A98jCvN8;xAW7nq~0<lAsm;z@(mZ zTvS9HV$Z92btfFpzLV)8{SHnyZjx+MC|z#^{@6ZGJKX8K*=b?_ywJ!rx}y$9vjR^E@3p@sIt59P0dhF;H#0uj)6GNPm94 z%-!6*iD=kI)B?rau|foty{K)Iaf*j$;+l?BPK=2w*$ zm)E{5BG-nira70)JUjBm{g@9(O)X2^X|@z$03vfuk3A@0-(n2lfBQ^GMGMxR}@ z&C7wMb?Pg}Ke1J`^M2086HY9iL!C0;mtSAeTM z7Zl0xPe^!*;a4W8elt<}Lg^kG-c~R2%0CdKN#o z^Xx7GWG7X}l8KK^S`utx@5txKlb_1T0`;D|fm)bYhH|h^$PVpIqALX)d{I|2kO!^F zhM6#810Cd(7!=@cei`#o7exvUX_FtZOA_C2h7b}`f2pSx=iB<<5+9&D2qVOb3NS>Y zy|?4<4}wk5q?$@%H62Turc+a-5>$i0)6ttu+uYn_gd-t@H8$v>lKtzw|*^c#u* zrL{$qi{UxLp3=nb5UeEyIaLac#;}mQ`dQlRqlBlLGVd%AT<#%;z~8uIxo@`v!p($( z!2NSD+v{^I%t#;-=|I|h1D4n~uL4Tz@Vf`U1HSok*P3s;!3}fWU0+=i9ote{Ji`JW z_SctF4E0W6xE=^rvsZ+Fp&|d-YTA&ExS_-NMR7?I>-dfAb%X@FM@L|b1J9g0%su+Y z`El2qMI#<5J|G8Mb*!Gty+^b1Og_6J*DnAoScr00@fRekYjXQ!jb>roWn-9;x|3`&ITw zxVlTQPYZcK$Jkp~JU{9;2Rw*-z=7x5q%Ddk5|8pvMBm;v9_(uWS?-6i4YN+qP}nuIkq_)4M-ndXW(~ce%=|INy<2^0oW3=J=I3A)O}Ycrf3p`-kQUEbRki zQwoQCaCJvjGYMjA9unLTFf>seM7Ia#rhNlq3@#cbfmW_op~# zX}9~-vlHl$IRdfx{UwgWN(tBy8KO>9t;K21h8V>~scT%(CZ|Fy=T)~#p$?CRlole3 zG%}{tiu&OaTIJs5Qu4Vs_0}kdL}>COC&gBPRD&Bh^CSsX&Is=!dWeANjbZJvlM*@#{CqaT zTtx!;p&pPlnC^Xh7PXl)v_j}GXXMZX#cUp8C?pHEXeUL%n-f{OtU92&A;`67oNDMo zp{fQF59bnYJ5dS{l&_bKp?94LFqSsC30qY~s9O=MT4q0qm=TbI+X}b_RSTj5-L?rF zf0E>vWi(2!|894R?qJb3f*-k>WuNZ`_sgm$i&>KaJ@}U=RuR#XWZ+T}97aX~Oh~d%3Cw zO!|}b*@yg-6Y^V$UvDp@;DDn=a}d(K^+;_A4WOir*O`p-Nv4ujcAMDP+|p$~3Yw9E z&1zJ6)#uO1G#gy^Ru_|qwnt!I+cTb5ImyQ4*wi4kY%ZQHUq_UJ*jk+%M_23FX2ABJ z0#h!N*Di|0NKYpI;~|h0Kn_Du9WTY3C`*kldGBPjnvkvs@mI(^Oqv}BZE>CW>9-WM zIuv|r6&w9RFv#Q7Gii8v3?8eQ#WOeb@|_txdqixNp7bV6*~jhm?x+n3mlXYdW&s^n z+j3dabKpqvE;N$>{>*0m%;Wis;fRVBfFC5?Nfkq2p^)h>K{z`v^<*sPEA+8$%YyF> z{}Cc9IEg*38ULGonZpM2GT%DARb#d{AlyDzzq7aMrveS)FQG=R#B|#kOy~9*#C3WZ zd&u2kIg^uL1H#AiLE-_h19jqteOw6^jOY#pZv=Mlki0i*(f#D+-GF6`c`d;xT=6n* z=HvfB>o76=e`y_NW+wLkNb4|jGIIPcX&swZBYV;-Bw8FRLvHRC=J}zKp%W19wR#&Z z_~I$dd{?;Zgr^W@%my_R;tzB@WYdq2USNWR&-`VQWH}nL(>b03W+2p2L^)n z4GhHyNKjtr8=iqQG$S%QGwp+#rvU&`k+}k>vH@U2LsJ8h3M{S6Yy%pb-hkvWmVCP* z@Fw$Kq6IRWHGMn=X(7BVLWHUcd2i&Bx10gyW(`%#WffDlyVm66iY zL*~UNsR4^;tfg^aXab^SM^_1q_~jB9A!CanYxY@_RO;k}qF*E@J`AB{%*&ZH^eZp@Ht&LslEiwXR{g`QB z{>(Ccocaz3n05Y^{16_!!Se%5 z^J6Ul`H_|U({-w=j$o^009XoIR$OOf$>0DuwerFPVFiX(pdb+3oS5nXGXQ=g*_yyK z+JAo!e&K~S#_#ZXgKVaL6ylEg3F8Vu#->5aARIr$9F>GCeTzQav2~`YT2tQ`7#JSC*!%x%9X@hoWOihupk@=TLwrFr%4tFqz5~$4FkEOHo4ZSe3&nK0##*_Z{)jt8gFDnE>PQY%6b`8Gjho46sC|7;zs7NcCd zI?#Eo!00tE3@AJe2hp{|6-!eHobWPB)Qv`R(TWs6XHxnJ7JOXa-4Q@e{wq*nIw`cVL}Z_J2jF-Pw5CJBs@O&{q~Suk(n6#+iJ|awY0U z;rdoZAAc9SAr27^_q8Y^rnQNz+_sz~*DB1{zelXy&nnAzAKLFzziZCLg*caXuqWYF zP6-K-e-^^-xG+x?JwUPWVXj+$AZ30^jc1Q&4{oiN|Dvq+gd;SxI6TonGKc4MYtp9c zC&;|sX<=u@?FGh+IRQbSI~gCMZ|t|%&Vj`zG*6uk!mYf=x}ImMdj#57A*Ha}I7(X& zO;VcTy4CW0@RxjajF~t{^{a!Yg>Y6|R{5;OFb9_zn?nkU|Vh*yC40>oS(Yo7;ZP4bAHqNWSv8(?#j_A@Q&%2N%BysMUiyQJz z?$gp`*$F}k1uVmBXq<^C-iCRMh{I+M%TI8MA*xqp7O8?n5iH#x8%0lyqT8Sm4QhL+ z3xRHZ>~pBGJ)p_9$rUTd8mUO?UL1hG8A55LhMp0IbySVQ`u8pVc~cZI5#1ZavTITN zB^*wcp#s8XaX-8z!??N%pvz*b0>6*gy`UM&scg1+oyQF#iCdWv95{N$4Bf06cBP{K z1W6hl?h&V)#&iJ(8;rRQ4}ojL!z=yW=W5{45=l9Ma!B7fqF16;N>#eFDz-7ef&qfr zzdRwVYhnby{2WpGRn3WesrWf3vA9WKly48X1~W%nOLHD!`ZK-Gphyn^)3wYEaS4t} zpLyB(@1os(J@kfDGxNvptrrm+OpfMU_lQ7ZESLnH8voJ +{NS?aSVa>-LKdCBnn zj`iFou2kC>Bx7IrQ_y2iEsu}+h6qY}c@PUa>RkE z>5T_^YSnf1i;`?we@{2apTaApL!!sg9afI$C|m+V6T*4||k}Q0M|s3+b^Q!xB3B+3P5*u?_TC zI_}~~-<|@^vA`ZXk^@A2dK@k-Q)R+0b!rrAAcv5XJm;PVXNy=FQX7h)0BSSuQ8>`P1jtSdn5wFW|Q3F<)kFa#g?2o!h@peXf3LB zRQ5Y??DifGpx$n69I%)L`yJj-+1|+=t=bP}{^iwuL6f1La@`zmQGX z>@3Y?=jP*EM)QYkh*<8^#@$&E)yEA@w6J5HASkGf#{Ilr@7cZW?4(sN;H8JRAxPeua_P|8vD-831Kr~2i6{E2P$rIB5%(d|W zE90R2?{K%cAineb7Zn?xnM;hdOcmcnRh%S$bp#S(^^M=_UEg?dqDo{y`@fx2txItl zK|$q#md8JUlbdqaqD+vaWP)uo!6es)QRaTp{=hD|H&}hhf0(7v^?N$W247$rg;VdR z(9*L9aF&%=4W))N0Wlu681Z1yLd+Z;rU7(QS||dm7{&4}l(bBCnH3)@l08Hamn*MR z8!khSp$+)ur)}224Ep!I>3M_65hmDK$>N;nnMi<*gm@n*6>AwaIvf-Ed%oxTOuJMrRT)aL|Szh{*dK|Kw;Dv`Q za>+>ruHmkDZ>M|63hGiTydWHL@dH!f`C z)yqNjkV1A=`&k)7G{T#^Ze=O(>FZ}!+f~igCe)}6SEqYL-PyH`A1@^CdeS%uya?P% zVESZ(d?o$%CaA!olayMo8%b6+OAiMzQ@5)4Q6mAoMc?Z#XDf4S(Q$Rr&>kza1;dBW zg-gD7!LdIzF+@ayH2eNad-`YT)haEmCPKT}mfR`BNW`XFn?sLO?f$Aa;Z)>3Ed&evbNiVdY%!26CY$?|LKAQ}bt#%~tK)l+e;?o9 z&QMeP+*4y_(y3ma3=sMaOGzCo^ux#e$hG0vnL*{6=81cd&m}lbzn%6LKHgR5GdlR~=6^;Byc5U~NK>f;7 z+(jC51If*v=Y0CL8Q_XJvNG)gMN_PX<`IgDz(S|;v@R`*URJ4xDgDkpmL;XF4|pw} z;tur=R#lWPc_`caHX%Ki%z${J9a-7lCU;#CLC+8t9H$Taq#zqvwV=^cG@@~cij1Bc zN|$8gT%vfjUAdEHk(T!^Fxs-$iZ{zyv-r)032&VGv-$384|<&Zt{SE@l}ApamD6mq zSzhCx*XWr%aH2%eqp-|Qif8cvh*rRu5;*M~RTi)X2Spa0rg*c2`eyp1n=0c0%DKIi zkP-sJuN%TH@t+#0)Y$N-8byjA3}fUJ&Rs(%@%&byLX&eV2HqA)&{vwVVV zE8S`?VPj%?MZK3=)>AdSX^FT|u}EF&^H_|d;aUmjNii8kAR<~?_zhrn7?c*ZUbb(M za!!bnG!PZBjxAViBw?R})}e=(Wl#4`EGIJoUV-pJkHt5&mtUynEsPsi5!`gUq8DUd zha3gP_XU50IvQFHTyykGL=2}RWrdLGK$9QM|4kL%6-)rS+t=Q%>{z-w08{FRSE zheWYJmZ)-wCFHxgwWKVx1GTB8Beu<^E46IjdqEJ@1e0tlUEoT0#ZPzotKY}5F%_7~ zdvU(F(Hb&I(B0X=qBy4edYtz9e`Rv8x9(qu^4jy;RxFOC9YtUmCtc|O1^~wqp#C9@ zsHAo{VpLa0DY)t==6<=-s|K%vyzgs0EM`ZxW|^;W{B1isoZtkbW6O*xK+r_+Qz|hu zb*k+&uAmI!*e+>rs$D@_4Q@|2D)7{QE`Q!5Www>>i`>4ZEcCRlym_wUB4a2tAwnIr z<9p}f!$-O`M5zkrvjC>#BP8ZWjSNii5rQ2nRezMCnxgpS%@$V7sWbq=S>A!3IlT}9 zIGSWz<+5Ce0`!OOjSzP00@t*ziCE!eQSM3M5v*36K~Snyt%MhW!17?7t4c+4^tU@6 zUVwa3DAqV~Vc%QGq(q_J+N2HDzC*!jcCN^jyyPOIEm0ruh~{(8sNH7ib`Kr*&3!b-2F#9maLpYNX8K8WPa4 z^eYRMXHs*0Edq~?rA&Pi{^Esw4yi^q1a@*Vq~RI)Z^_YP`R$-ry}}+)ZP%~LeO!6q z7v*Wjt&5@mY%FGgFH`31EsFs;hc{QuJb0~}0HQRyK}3CVP891f5)6IZ-CWijNg1dQ zW^#}rj^%lTlX|PQ<#PTDCEo9;fJ%eVuyv6d@@gaMen`8qmNQ8?5kPeU5i+6x)9K9t zde>i@UZ=490a$03r&ZQRNSUZq4|iI|yUP8!IS+n1Ad2g{e@`t2$BKY$yR?Y|>^r~A zeA=s?G0gCQPYXS2g~vNZG;@Cxj3y}^mH@iW_|?GUkvS7EXJLieMVxX`x1vW4)(eU; zzi*0-(L46nc#kXg;Do{m&+95tBymXdp(rT9LpJ6L*iqcK%35q%w7ry+X2^LQ=C6N% z?4vs3BL1(WXC>I!@A+QCq_}oAD<|n~mqNjBeP9QKtR17leL%oZsvFbU3&Ttu*YS)J zl0Rwa9CrHT`fxmBcFxiArhJOvkXp=GAxi(WDmbXp z6UOO;N7cXh;gyRJAO~=RZO9J-?ATnvz)TX}(P%q@LGHc| zaqgq*rn42gyJN{IegDVQK_ghYT4Zhwo+_!g-A_JpLoW>G{E6kTDN;nVcF8?Br3DG zTg}%?*_H>=CkJcaK!Jl+&^EAYYG$jZc9Ea8A_c7|!3p1hu+@MHJ;;*4@SXH^kga`C zk2tE5PfYHBHfi${1cKO29a?&Ag?%&xWmyW7SYsiyDXH^wkw?C~egpUV2Id5ZftD&1 zy~0*@W7Bya_^E(_=MscmcGMr|Jo7+Ey9s(LL!c0O{Xh!7@8 z=SD@;M*z3oH-if>j*;8+#8*0a(P^jOL0m0*T>+&AgMC&PtF|)G#9A;auJ+$4P-Da9Vx!jAgK)FwDI%)I})$ZH>Pb z$G(9kem$H;|LV_Epgp>>gQaWUAcjmkW9l+Pb%)p!-N=z*aLExnhn9`NX(?EKQbetO zrDnI#5XkZsJ+5*|N8Tv3!0(lMnHB|&Ow7pO@698LX@CM?9oh>H{rkK3uewU;j)+Qj z(yv0=^jy(bOYXUNpb9d6Xx_Mdx<*Q3Bi&96R5N?vf$jXB`>5jX_HDE#ArZ^!GHO?` za6kc<-wGHeNhKHPPe3$Xaeo70{|u3iVJd)4qWMp~oB(mx8B(s$tym)(11XUAq|)fL z=LC)5j=VXYSSy&ar~}x6f!4@2(6fUi7HbW9Edo^D-Zq?=J_M-{nRXD=r!}0$?w2k6 zrE*UZ|4a#no$Yc^69ZJHI8MkJ- z)|V-&vD_InB;N)$l>WX32B@AEgFwn2acrtx6G{6ns+4=cghq|akTeZ?Q*zjOl3pn$ zcj^Hv(^)La>v(uw#pY)8eJRPgbiu<}EQ94+ex1Q)?X1{Y#kwSdua<}}GAfvX@Uft7 zmOC8CW}4oYNP6kP2!)r#-Z(dU@8_5vf;d3@T27m*!x=YlV(ZqZITd?jEF$$=wJXXM&ZU2Vx~n-Rf*m0*$}UGyX=YaP{`%Po_#_lGm^h>HB&lsEk)8 z@x*>=;~PnMLs;ln)HKj?D>hLyd4!9(dcs> zNrkb`+CxwTGTfL}2t&Um0p+*foIjm@FZupCm*4x0(9r@>Od5y1#*_LhV)myyb7s74 z{6s*8^o~?#Q^Q6eC8b$kNW!N$!&>Iw)4}*}sN09kS-wz#8kCEkRk!Kvg=gj1!zkeqsT2r2Yq^{}|*#mUV zLYr~gvvW)C$|}{Atmm39#NJkeXxw}Q&<2zs06C>CjS>kb=z-*oJkduA6I!fwChtz0 zwhiLOTc%{adrco3t}LCc_EDxiaS)w*qO?5B-RZRvYWZkJxR!|MhH&-^e5oabv`)aO z3jsnga?hq|cF3cn#(qD8p^&+^T|d=LLA45Kj3lU`c~6b3w$EyW;@dL8rpUAsPZ_6V z(s4F|H{{AeE)xygmLh^tawEiP(lM+cVY@()OYmEejYr-gH9&M)%@0Qp7C($pZPcrr zTH8?QnaD;L|9!S@@9@pm%G6E6l^67u{PR+dcrxZXgzo6_klELCI4GN`w@0Ie*)~E+ zK9nS$D%dUf2ohM!vD6_KQ2`8xLdDqEnn+2G-)P;IM~W4a&rU1zQWYaBoCRRqEQ

gTe;W#)Ce;0 zS<&5lpiZN-mhitkm-2VSnLZqvR(EK6=~~t@4>wfPa(ux92nO9446_YOokhW~N|I-q z;#b0}yVf#bGOa2vG6nn5tBDBa&{l3o`kEvA#_(gZlQ->75iC+dfPtv2WWs+aAL0gq zPpC8_nrY1wRLIF`Hte&62Qh6`nL;vDleH7pxq|XhamTMJ%XT2hnJ<(b3PQqqPKu*; zL&~O7bc%j0k;WELI}%xL;+mf0+z z)C&(g>dMuN4xysQ-@Q8P7!3HSb0@n_FNbKHE>ORhV-fObr6hV@+n`!z z#@6HX6h$jaPj$ZIENN@H=gSkVWzR23rF|X~Yb$)^T&EUn2uaMHO^jYJ5}^Dyn1zFO z{!Z=miB%3GC!mYH(=T!O%-^$1dl6glp5-2 zO2~~s2Nx8#hkRQjX87R}!Sz?o)cB-0Pzu3SKRa-n2va{*2bGjoVuU`q{Gq5+$Pjca z3{F?Q^z;svW-ft*efssJbJ((QO2i{Sog>NKs?i-sTn~KV;;|-5Ug*c5cW;{WJA8Qc zQ4}&Ooi8%8+Ogoz$e7Aa_Az73b}7Ozhpw>u%3x(1f!9Bk7QnV&G2A-~dNvwpecuqL zOHz~b@lAEi_mm?QC4(q31N{lyWb~fw=S0f#rKD1l$i+6Ft<m=JYlE2gf z<0Mj8xy$Ryv0PX+6#HU5z8$SkPi-oLMdJ2hRux%-=jmW}B4SjAQv`SNxO^bZs!>Vs zL?__IY55ckye-LFw;FcI2nQxjyyH3OR-d?CBX` z_G^chcK^WD+ze49w{6usMEnU}*;1K{rlx|oWD-!edNa^9U*(|&^%cH2{fkfqV`$0J zl7MAXEL$ner?H@petxb8;|1SAwW~sSlZjsssY<+ zQYTF&XJzSWh$63oj7-c9L^q4<{^aLfa)YNs!A&xz_jLN8CJ$?Y`QsQtw*Mp|2|ZPP zFU%lfXJ0!pa`Gd9BR%lV!c{jbODB$VOmyC_J{#eo0dOS82*J5}b>mdy-^EVh@2~qK zNlV`+oqhnka0EC!f)wcmXhST>o)+v?n&t-01$HsWsWrthp6_|+uX?u{oFn}KhHJ7! zZaI1naoiDj5@Wtdv$lYV*`&eD_8HrEG<5K18Hsgm2bz9NWL}O%A18qF ze)~HSB#~CaNt{**27!2e9}u?B#H^_CIssYbiL;jV4)?;`%pS{6=of3hob_?a}x_K)%AQ9AJ5auD;}1+yKZo<*D+tBW&r*MK$F| zqV?(kD8Bd=IiKG2(%}Nt`Iu&|osAm;1T(79NC`cDOggRB?;UQ9qVJcfjGtY8yPxU+ zX*4apY?Y+`ikpI&q^I1z=dgg{mmL=bY1h(qN#Z}JZ&eamW5c$(Je0x-2N&3Zhl0dh zl&5A7S%@HCE*Q$Ob@~hLK)4E9*m3@Lt5QRG(EE7to1Yofu>>9J0u1a?i&u*?#_X&y zQ^D6N`W6jqe#8HDsb*XumUFgA60PWkhX^C$+WLugFj7Z-S$1d1 z4MyQWLPKsDiRwPE`cPXmSG%@Ilo2jRCN0hP0>n^PLIH(0I0N0DekQsA&$Px?30q|a zFhZ>ADc94dAJyT$o&`4MKi%Cy%788LT-t0)NNbuuO^O4+3gIW8&<=)3?>A>F)i>D z%$#t|8X&t#Xk|xJPR_SqeK^TVbXVT*v6lkv3j_i~+QpE-KDu>7P@LbJ+_4!PCtfNGvbTT@1yQ zo;aMZRE%9ci~!Tl>brD%f8)5dkCp_StODQ(>pLKDJ}nl7iULwDn#I^Tj%q2fKow(F zA`)_+OiMyH%bs4Mb+Vh!hU-a@%yD76=oasVL<||r z3@VX-A2#Iux4l6_Cux75jM`DSY=7KW_ZmglF=>Sj*r->zA4AR%OYWf`4m+DQf*(!| z6zy#AZipo}KGe;i{waW!S~%Qq6{|!NM%Q1L3PX^r-7_BUT% z-qHDhbux=114zPRU2M>?n%kX{OF7b!M8LfLDMx8lVUd&I8;t85PS?%b&gw!|~JNRDhGOKYrcV zhnWm`&*Ckay+)*QMY>4+@Oej?9CO1K1LMkKqKE{-!}r4O;4~1Sw8q~XyB?_p=t*s( zmTPgL)h)JYAG0kbvOlq(;^#Q0kBf~a8qSHL-N5s?bKf+RaI1q2hTNB*Rv-M0-IIzk zPV*j2gM2}JP7boO|FbY=-rreX2UFm0b=LrF4$Pr4(W1Iq30~qMfUfnr9B?s-brNxq zKiy=D7$JhErHx|DOKjrGbwh88Wjkz-^a5L-o z1~kmB8A6?rId-Ls&8knvHOrkMM3U&osJRPRlU3frWjvs!622zKCl%z440#=%ZJBbv zPIkWQZ#OpDq*mWi;G2SrF4agG>!@sQ)7g}G*k}yu+rw&DLm4q^wI0E6*mzaj6)r*? zX+lcQVb35xI-08VaChAuA6pmyycH+uBo?=JkbWaH&1~bwvWR65|Hk!=Ta`(VQ?ZHN zCFECf6hayBjuZOqEVZVn;qR@DCJ&KsZ_TU$8Z30yA1~jBq`)?(6Qt z$u|Jy4)~+dJH>{bmTk)Y7lZU;zD&FOZ{Yb*@Zs790lsiw@=IZgJLMWh zj{zXGWuk`tM)q9;*E)W2&THGUElZ=T;K?2klI9jv=q%@iZKEaw5IRsDiyZ}+m}!xnccIO*@1$Y6=@^?Y{?m;IpY=VGfDZ#D zUM^0Z!ZY2ygmwZEoIy{Vlk2-LYG+U0=ll*`H}xmLYnpYXqp&+4`>lH1fooyMr>O&y zNg$k2SJ;uws!H3(!1i!RtlzP+u~CLZ>{0avZskcl#_ov+zqZANKFq}WF;JVgTN_(x zQ^4>A$d`s}!asF9B|b6NdQNA(*<<17jw)A1u`$z5*ylBu`?f+sN}IfqFl zQ4IC@Ye@wipva4~9_J)Y&4$`iEpTedtD8_xOT%D@oG+jVn^XQFT@ouB8)_m&CKB^9EQ=7~BFf@rOkDk)~HV43#?~ckQ8ZS12+|?3U`}!Z!;MPUVSxlEn#y zhttXh{Q_AjT{1w0BQeKTPOpdK#eNFbqi#Xb9HNM`#Gx&ov_^x;CdpIS>aAc3NTf!QhVxdq zE6IF{&*6}M6{zMpx`mj}2t44i8f&6agoeKWx85Z<9Bt;s+`Iffo0aeqbKb@fD^?&jbAXyk1Sgwt#J} zP0#3bOm*!H@aFdQV>+w46lCDIvb^3u2I1MfTAI7W zl8#+mfTMkS%sjI@Qv(eTXeSlJcs)of4J2+Bv}Xq{nIar@9L?U+rzuXAYj*JA0`ADQ z#dr}ry>g(mU0ofG;@HczPSD4@>E;1G3)y@@|lz0 zurc`&@H?G6z2iKiOFp!6F@4h%hM6nXjW9mFxe{E-cmSHftuO1`1tPsLlL0=V3vhBl z@R70!+gx-TZ+=M^}R$I?QC4JrBPjnp{A(psWuj}*O!5p z6TkMPCYh(TBs7Hg0jTSaPwh59Mo3%atr1B{@;(SaEvMZ7H?!e|;fImIsQm)Fmgh|u&lJ?Pum#QE*} zquiq)uNih;*}-T&s( zg!CVQb?2c6OfcG!Ch#!@&eIhK+!5m27gu>303`$vi$ZvFZO_5o;YVNPxhJg3V!Wij z(+FPru+RP^JUt;v=bUbf%Gckv0(+7#>4uP^<6RJV0piO&)zL@=@!XrMw*s}C>DW4o zb)z^Tmm26Bk+hhgyjr$pRKY>==`l{F6~AGdGKJiSASiaFm{Zn1ki5&OMbyLqa<^`+ z3L&+~JuSzO!eUhJ+g_$`HNTk6x`2sg-)t>f=Rh{Nh&uDZ^~gs$_<|B@!2<6m{q;53 zC=EUGvRv$~iAJ_Esr=Ixkz6n?+hC9NY0S%#|(uAr@r+O`GVv~BdG;!@H{Kb^^?y0n{mRCc+UVod+gj_r-w{R z6ks6OfQyUz62xh>+%kS+#6%hXZR%L%VW|bW^rYzD4Q^y3UR1taC4*A9h4~|gynX=6 z1k5zXI*Cfd#=EI`)J)FgUJb(YGY`cEg1%U@H3^O$C$uOf;;u1QzA(dw+H_-F&rI9E z(<@g3Pn8hoV{!<)_8!&&r|8m?5I&4HNg9TCdzv!=$zbUDAYUbypB-~h2|CSUZi$LnSho$=w0D;O&x$ad!R0$jk?j#RhL9;y~6 zpjD^199B#WYOpN6R87t4mS60eiw9v;W9Fw#)g4<6c1r^Fa83Q7;Ei$pP!8k5X8{6n zJU)Jn^rEmlq=8_b(YFtd2B7Jk_xiq8MKzxid~2g@@?X0o^>bVzGrc$r6-@>yBf-pa zH>0O#M1&(8cg2Qck!M@}k*gxsPeD|F(TqkEPuezYNIvVFd9q2zi+q{J(rVhVim;au zDi{G9jqnWmHxSN*r(Z%MgTgK9)Z^rN>Bl}cBvRS0MtJ$*ZQz3|&zS~VS=aYI(=iuo z7;!Wmi?y zw`w7wEg|;n@`Y4r9&>F&!{`Y~J4N#}gK&#^{aiultIzFnyM4UF*NLUP!o+sZMfOQ# zHNs}f{WWv(Y4Lt6bE({_;oouP9-09gO%Rx59dB5pX_BQRB4~}*?d;2tvqZqZ5G;DJ z8>)yzMPyFp3Uu-Yi%Kmi(N(;_^X4T}okT;X1MEd>QiG1CH2*5A7NMb)831nWxHoAF z-l|nBKdJYkz}77W&qM-fNq>Aup?cFGX`|^E>ff=l;WA$C)sMilh0?DP>VQyUf||wh ztOWv>blvXphA__h|IXB5m8JI4+8+HL0hUhXMeSUyTjqa~g?VL@%xEr)g@0%B`Fk+_85+Z+TfHe`e?@df60fT( zPd&{~WbT;oS73|2}~dlNDFd+eOZ9Guh59PBcjNt{i_H@X?=*9Jh9Z4D!%xCA58 zx+C{@X>w1Z5C?|aI0)@@@WbT&tA^1*J-$u=reElgg?>s8V#gKg{48Md4{6*93oJOo zGJmpT#Zg4rJV%#&@nldsFUD#5M-?S|swY$^BKoLuN=!_21t;(Rp==0O3h_*Naitt5 zdSxuc`l+)e2AVvtn`Mqqy)2eN&KE_$uO9qxzckX9z8pnD+2(mJZy<9!OPQ#sB0`S) z^R(B)qLdv{WwRVdnABH=ZUb)TDFn#&>7w|CnIAd8-yV|)+`3~h587;%?!>CaKIkj`sHUJxK}=C4GChkB zuDb4H$<827ajJ0DMvNgJm`(WVke_QmxXMAa-3`i)h?4DSl4?k4V**;rh;Nc>VOJ7h zmggEWF6ao)wH;iOh&LEBoV8MCi?$aN3m#DqYeD54VPOunVw?gB<{vr8HF?W?_6dJh zK>y=QXjH!ZpHgj1|1s6Z_&+f=CIUuI4o24hd1WSG_@5yG69Y2~+y64vX5DGzOgFtk zhqE~%={Wi?$2Jr3f1j2_)PJ!y^4-T9?;YSVr0K?e}BXf z6as6r+kJBb(;JvPhJvqDq&!m_eQN`weF*u+#ule$1}5;kwvG;{Hm>$L&W^kJZ{#9t zLm+!LcEB`E^-O@EV^kK>;~_wl1IG#g2V^Z|F<>jdfXMvjU_^nDfw7^L@gO99%TtKD zA2(oqV>2u3d;YYnvmemDmF1!NcYOVl7*{p`4Fyy|Mt4qBzcPmI2!_7C6$}F6d%3pi zM&wog9kM?$Y`@H0SbmSbBvygH;vv8BKSnOjzpWzRgJTd3Eewue7#V3AYXft?@OB9; zC9VK1zLn8BSHG)I@C2p4cYqW>`*BG6)`lOkt&z>mS^m+GenM+ABRj+ELx==cX4VJh z(DDt9jCJ37^uXBARycFDnsX~CW0^#Q?;{K}bF>c7JC zy-ycpzcZ0l;q}3h)4hi>Kl_KdQCOSnnx0>|bibG*y+PQNOpHtb=IQAe08v*_Spc$VXt}=uR!0YC=7yJF^aH<`lfNy$D&k~hH)MYp ztR`LmZ1ty<)8-%d6a+V-?kzPgepDp$VUi^upKL->BF>Z0+5d0>QYu z(Yuk{W`@HU%Iw9Ell>xuT+$tOp&_fKy{}kzQ=jxMhhFLgmK$thjQekkY;l&>)`C*W z%QP6DWUY#GCOr^EGXKoeU!H-BZNzBl{B1%lT_P15pZf@5UN5crlfep4*~WI{yR8Kb zISIWH+(|h6W1}mNr|*kV;%@gc4O7`;WWISBO}5Cau&PR01p15scr_c|J|N$JoI*sT z`_RnR+Qiedlfq}2QTr7ZDx>`CQ9%{m+&sK0T48qPV3K{3b{sE*&QGTC`vE%sLY+P`Tez?E8&jwy{DlCi)5_1!V6or= z`B9i$UveFbu;oaVa8KCmS;hYz7msr}^zEvO=Eun217q6z&r=bD*@^VWzC5=nZB$VQ zdtV@vw&WtsO5F*NH&0HWuxP)9Q{WcUQ0(_YnlI=nQ#=!9sb|gTs9U~U)iF;Tr80AZ zX1x4IlNT{uwk?h{G(1TeLq*#WhWFNhy_4kmdYV|-pb}FUSlpRg452ym@@QGZy$nLy~y3O=nL{<@{ejh;-X?xN|-1hEA%Hs8gfTY&!-;uXn3 zV?ljjqc-kCKuKWJ!faadEzibhKidK2;)cV9U`8*fqn3wsSi&s!06$9M_fv=1fj@`g z-08)wy5h-EU9#2?3VC1$V)=Ko7(HHWDX}|0G^tu+mP!0*{o8&&a9{3iDyMspk5VKV z@2Q199+P080W%RBW`)DHo;M%&}&6O$3;NGi26qT1YiTB1W!hsiR_=JQk~K069xf-jjGZn>@pK z?P=gR(&}30X}Sl^q668u4<)Ip5Y2P&Nk?d3sprj>0VKy?`-`fJh4UupUq221va8b8 zKG;h}U#>#Oeu<~f!nGBo~fBN^RJ_ineW^I%p!Tlt?wwSEEr1x-M*zy9Mw z`!z0ukTI7FbQI~HURh^oC9(cr29RUoDB9Bc1>Gui;jFHYr^PMc2C z58X?XqwN!s9Scd2a*4Ck7m|!Jn%F}V?1U05G>-CFWX49BN0is;pn9q>oCFn2iM%1f zGc^uWP|yG;0Sk~%V)^}HKuD3fG*8mv$oSLvSa2#6ztBRdrw3h%Y*(IKxdFeC-J4`I z;6zsC?RS$QTIMrAbYR$yQ=w3B6;15+OrH2~!-x{7jW+P@HBHgB^8G1etRSEQx2j8@ z)x*#%wFF9CrodK@j{K=&)`2hxx{|yK4dWmLrl)h=hP@3C^&BRzL5?hy%-n_mOAuOQ zk?3ALa~*3Q57_L1#IDh;bH!)dw$wGGg@HT`R$@)($Q81c>zJ`~o@Jnjb7RNGp>X01 zF7Fx3y1v?!HUG$;OvQ_lY^XfWDCJ~2VsqnHNqNPzY+_}Kpm1@&gU_JmKZJQH{lU0(qAdBe zrcV__#Z@jCGnl2P<85m?gWaZW9O3deSI)<-ff{426-3BzCIe{Q%ROtx8j{8ze*1TVkG9{NKmzl|tuoAq zk(w$;)1%|sj}T3vbo>qkQ#SfN;-;#SDpg)@(Fmy4Z&B<0dtGq`)z)KdaLw~X#sQVu zzA>BahKY;ttQHJ>6qB5hbjwnM8jl%5EwhU*nV#VRk}_lEcQyHI89!&%$g|)B@SV zh^e2sGz92pG~xDGGP#OJIo&0Zbt$iTNvmkS^jQds%_QY_tsM40^x9M_4}>J0DJ}=t zTCTcgw_Ci0?C}oR{UL3Vfl5z`&sWvRUZOi4t<&guqAJ_3%DPQQ^wzxQL=`Ea#$ow~I$fDY;|GYjHkLBb}6P{vL%u~L6+4|jM zHrM!%D0eFNm-!Y0sS!;3J+FnZG05+BL4d>t1ht`teMyFOqbvYycJcm=J@piS{tIsj z@#{%~Gx7Ov-NRvV%1sC7+fuyx+L!+=kL7jIDM}86{p@ylrJba=F+pqe_g8%lSasI# zw_}&dXCbInqux=CXOnA0G)8k~@j#)sKBuKIB!WwbLPmo^UL`!oR>4xc*UP1FwY3Na zhj9U`k#p4jhTO_f-tY*1#y+*Xp3O=G?h~=1I-WR?GkNS;n5~oTvo!O<30sdd-Z7i4 zws7I#C~8L}{*-8d&+8YG&De!N%SU_ruO_mNgomq?%Y^Q9CHQ$`@l;veGvez5Dtp@3 z=gro=>O@m}EK#FdF>j?S6ftn`8c7yZ-Da3w$vaV0JC-Ads674qT0z$9~909uz)vq)aU0(|1KWYj!v2YZta& z)@BVO@US|(4|ofT%`md;88rW?cL(6bYhi^h&$-fx$x!ddKKd_1(!4R~q3HfKt6O&@ z`0rFw=)T{u!Zkv_ba+jdW_r0K>1k%?n0RM_(N7H$e72uv1|c7gEfg2O>V6N_M=>7{ zCO!r^!!9QR2URqhxQe9@-faiBTMOyu${iXvyP(?n8pRf2qeJ=~+F>|mU&g_=?1 zda5N-$A6k}>~H{$$+#+H+AtQVr-!^**M;vGERS0I&TqK`n+?#PypfKi!QpgjoY0)O zLqUg>KWamlh1=j0M0B{MxgZarX3XO@D=$5ftvLrZ?ApD~W^_;g0-5ZcGOfZ#_hnpV zEZor`f}#1)!nQLPvqK_+c4s>ft^>i9W-yvTwq}w{C-G+%76le^6-4x2@=}Q~6&7Ss zu1;z*Zu7(JuEip~`V9C=K+4&_La|hDI6B-4N-6#pR^}U$SU|4$kHg343_PkX$@-Fy zZ^AiW@-XJ7TE|4foiPHw^iHm$!Wv>XrDF2QjLKx=^)Cbi)c(9z3|(R86mAdy><*cU+YK9X6fKJ#I}`H0ltpq8!U==~F-X)Afjb%p? zhu7cI;(#~-WkEb-wEj~&UDQmtC{$Utc zr&kBPE@k*$n#sqBTk@^pmE;F?t@~+V(RSx)e0#B%9WRaDh?nxY4VU*k8Mir-jL?pV zgRi7~7+EG@i&Cyr_!uf_lT>Svtfr*EA$3(W8dzU_D^_sFd)8{=^#SjDjjZz`cBm;c zgL+Rl!7n=X2kV%c^5wvgrbM6a-AZ6cH|T6P`#`b-5<6Go-w|cY3qRC_X~-a*K1&#$ z>-grO68+PjnPA@$^6BnujFDWxFw^Y0tPO3I8u zXux<`4qe1G|E)7y;u9O|()#6#FVUG6rEs6pnEVIJSS3=ypLy))(Af)2qh@WeE4#9) zq1d1LCWUP&_11uS#!f}@XZNE*5FDm`)KO@aZsJ|azZ|B^T$>G&f4pZ zwD_WBLuvoCvDxO}cp#`>I(;2t>b2{8BlEG@JR&#dhr1aFq&1-UI%dvo2W@BqN2bk& zh|8v(Cp*GoRBdJy_*y45&(R^J0k=zn6_3NslEPY*4=3Q9o#g7W-k^R#ltx*0=$V~o zdBARo4&2yqwmxM^*k(tOy=wM{3p6?s##4VH`|10#6xcOl zy>P*}hqPoj4QW#039evuJJqsio7+CDeW#FCIT7NE!!~mRTY8|fQK5abZHt~bQ3@?q zthqad($UV5U_|T+Sg@2$!DCv}Hf!k3TqqO!NW4;x_^%Q$E9$BxlUJZR3V zj$Zv8=x{g|5F2+^PpnkmsTy0T>>8Aqlrh)ow4dLf_Uh{NLOr9+0Cv6DCM7oL{te$t zl`}})j?JjRSC%n`La*C&J+~GkZSd4Zi6w#)`o4gOw^|ofeNCL3uuUd@We_LjySNzBz6Nv? zm*O{s+m2}5OIm~%9VmwOY}R6-(PnQbNymkUa*TAJ%JYMY6)eXB$I8_smx}{^*27W~$}1^c3s*YnX&-2yPJ({E<+sciO^sA~u4{ zB20=OBylGg{Zu+2Zz_W^JK8` zWnU{|~B<&jRtfj5Q4^xNz))sInpq6%8v@e{T9 z#=;7JvxY<8eW|ZEG<`0g&qtkaHrA<*JaD${Q*C%Da(W{w+9R!}Izv88501?;?*)y* zsIb-b;{4ijjk}}#3TYfD6dTLk*-hJyDn3&21+^G?WLP4z$G(rAYQf{l4?^Khh>t=6o$jw{>352MDO&6aIf?@PUH!7 zcNE4A^s@=DR_xWk|LDtkDGlkJUR&8oN~@2h3l6b)V@o_fR$&GI-Nqtib^wLFcCrIh zFIN4+;COu!d7Ri)jtyk{3#VykO);@6C#mmxVv5xhXa`k#;Ny!fo;h&^pe&3Q9`h#nY^k#6Qc;~wQRLnpvWuBhL}Q8kDBy( zy#=#nKtU_gW^K^E!&9pFWgEA3!Z&?1XkYH>Ub3?pMlS5ur_3dX@x2cz&7W@W=(;O7mJgL2>$ zm-PP1WtZ7~=!FsSLd*hOm)Dg%WGZ@Dj+uH~_XGaR>>E`}Y}of4Ez;!Co*`Bo<{7)L{&ldtcy#Z-RJdh|=4OFm%+Jk5pxD%1yIRnLs1yTmjIX+x( zqr}Z6>ZbK7R+q?{vGfW}%;G0}qUSO-MtE)Pu&Q747yLU$9VDPrHC1 zWGe)CBI6Aq#^CT1IvGCgiihh~VQ;LY+_hdK;G-7WjhmjENgFc=W>>>@NrcD@a(TKz z`o7u$?=ytc!Pcbyza>8s)4$eoj|HT%=sCmQc!pc6HA_wrB(yLJ8TS0ssCsQhc>1L|nx^K6`q80BFlA`a=o=uGEtF-W-okoz z1I;$* z5{}Px)R7?`SGu{MY;I5k9nao4iv8p)&H({SL@55k3sM&Hf4yx4u=Lum=EBfM9&tl3 z=N4Y=Pbh-zIkSt}Rl=P;WCksUu=veLgINWgUH;UoDYx4B$i}M~9oSREFJF=cuX;h) zXNlY*FRpq3q|}s638^q53)ia|*rlo($%l=g

g(D~FVX@JF3Pc>7s`@>KYnbWRP`|ujl?&KQ<^?=ELJ0%5ET$6!cu>1LTlOAoEWfGy_22si(zpEU^ zg?hDL(Q|(%gjDVzwiI{Gt-Sm6DL~#~*-4FY>4+!Kcr2H999BOaVJowWX4ys#a4Y10 z&gX`o-h~t13VNi% z?%2&EHiPgRZ?cK-MN&S8VxI%yembWU2zt1hlm(zT_(pL*;QaSPz`%zvDQ-i)V}>Z^ zSCi9`D9|Ky@Qc-6@|+*jnW@^tNF&mI3{SzNg|GTfmQE=hS)}b%Ig-x%D*^I7gC!zn51^ zQptUzA*Yd7qy&^XzuKh{DJzSS{02X0|##)>QGs6sSznUzjU7Ui)XJ9hH?g zsTHoyM)gQC#Axo`iQ(c{pB$QZJpkwVyk^9`p2av~#rMq%q9LHfS(!h81U75fS7Hya zC^SMfSD@P~RizVDmO)1bl6|hKtqb{(9`>rx4C~LZz0cxt7Y=124s65#!y~5>U)<){ z^ddv&M3d>g?*kK3)vMo)bTNcJxF=1`tsEc=j2_}!TuH{{VAJw64B0&FUFDeBH4baw z&7gc(;$!LVNx)kdjj*~~`kF1OfO^Vd18T79Lh}=yNlz`tW?}$aS8kZ48^c=gM{R}$ z9!n>7Cm}BS zq`#<5rIYDp@nam#g?tC0GA6azYJB9{ONNpjsG8s?axZ){X^&JnRuCcOo zYf4MUF;*B|u{U+BH}1^NZ?5HF*aE4JBF5H0V4taOgSVZ5ktYK_BgK>!+un0e8Tzs~ z3;UJEVeG7l{;A@oeQ1zS7kHt9l#NM9JneXIg+HAIDQOT@fux`3Gu|P>Q0E(A7EGBA zXKeYS+O631VXahCmY{fs8s67axvRpfQ(3PyH?z(D8qu^cG|q72GnU1B*2U|jVs}ji zrTV5!)~3^9a|UR>k_@NltRU`1C7PzD*W{s4tksqPUznssv$=t z1{)-1XW?wlFlC|0u8#Kn>`+yrKCJm=IC&;O#ri%-bJph0n)piZB%zo0cP;YH%!2OY zC6t_PxgVN+E#oioR^L8OHm);bwheDQ()Qmw=dUPQl|KAG7zu&|Ri~*EJQQ38EjN=r z*`~B_RT>8UEKu;oAvvxzx(!8xmD!V2->~lRD%Hrgz!iWUkjZHgxV%O30~~!MPm4mz z)C-JuJ&n8gC-& zR64DAtPEwz*ur(8`6uz;q}n(amgtiB?%W(H?wzg|0(ZlLT_t=T*pk_-#W}t7O$Z}D zAK}SO;2q59wcFhOX9EI~LnFd!>)V^Sv5l|q;JM_6w||_|(r%~~*EVrU4M_B~d9fIEq@u5trfhz*P#VY3V0PXHApz+%YU+lKt^Ruc&U5KtH< z+Vu8Hz?L$OB}G~Zw{QrzIpyQba#+Y#}>|4 za)HE;!Wv^Ly0&ur7rO+x)j>_8U>;3-7k#hAyk0JoeL+l$YldtWZkf|sOAYHwW~ep8 zq_8Eic?ioi>;^gGal2c+X4AgEFJn2TC#hegDRztGx7c*y{q(Q!)RhdBwXGS2+Z#AS z3DF?(qFAPKFr)lFT2ygBh2VVI;W5)xJP3=F6@|P zYzj;qrB!Bi>>Up$xO@J^Zbj#3mQ}{*QwP|bTYK)H$`r`YnFY)D;%QwFM~+;hq2Yu4 z6`KovZkN!VD`e2Vho9OZdz$p0<@`WX=l1W0 z{K(OvSVs<&^!|Z!8td|v(C1Hs*0F0t2XrnN{(6eH{u?sEBH7RN$`7j z;m-t&Jlk%%qnwMkyM3#{0{BR-nnH23L5B)8es^Q>ghQsmd^e+%50tgKwu>-}o%AN% z$cF;d80v~4_x11`VM%jknROOwv>qDUo&@-nc(uBV33#nepp6JMMxTvc(Gi?R+zHd6 zVPIhOH8~VpgIg`2h9{;{JP7g_|7BoUPX9TJi^U{DVn4m$AU%=1M&nhne#t--V?t^`I0k)8$AaE`Z2t~kX^Rh&s9vBD{QhNi2^0=aHb&CnWX2PD-sTfLI5OXJYPKPX^JQ$@UecTN_=pysIa zug1g7jXvmSxV|foU&K`$&u^>q1MfF7{~B!D#soi$V<11WV~`pu*|#U#6J2sCR$H6? zz__$mSAO?*+yQii4*I%JPHb$IlIs)Hc`7ttK4Cs&J1xGUYaaLxu1&YrfE&=WcjFuB z3JI``GcX*lP$4w2B+~)!AJeA>MT{WOC6zEVf3zjig-JZiAkw<9D9RVeV=RK!|M#S5 z87sAnAM%;3^Mv_|7Exj0KJD-`=Ek|uGBb!Sr-{Fp+gd>{*88+or4KJTO!daiVKKa8 z<#=J;C+2V$9%kqGb`R#cCW~KPz+-GU`!Am04AzR|AqZg9PJz`-`H9J4EH>?+{#n99 z&g1l0TFr;oJ?UeDr~idJ(Cs-@l%h8(^we;AflbwvCp6jXLvz_A5*y+v2;KR{>9%Wc zOb36Arf;8tPYlY~o4i0g86()ORK^2ja=X@1&abyt>opw(0^zR&{K_5j9R}^L@|Z{b zbe4;syY6$YcQ#aT6%T$jv9!B#!lo{N#jNhe8;=-D-X6MteBLpn@V}5kqcWScT~%ip zv&So4l0*3I{kAF-Pt%b6tK2qcBr{liodXs${X^GC3|P&(R!u-*^o)g#!>tt__bkn$ z{JrB1tKe3!eU6IDB#8P32{+X#(tJ47L(?D-j4e<@leYhxQ(#|md$TD2Gn?q(ath_h zFLfG9CwMq9{0oc<&sr;X?6$qhhmqsObU>njBAkxL3k~hNCz_^h{JAkrxl@8aNJE_N z@OeSJ!N^pSINjb#_kF*U?!mgV5sT!Fsrbo!^%TfB#kic*bwwp)Q|8yK-Xj>jifU*a zei$NEx}!%bGo?Y|2+%Gq$#Xi498I-qaqnI2?~5E2(7){3cdw^2fu+H}ZnvX}#(tp@ z!k|2nNlLipop?G&QSg1(G+6@VVI>|a33YWb(!KU3gQ|LL5knLYsVFSI_OT#X4_{o% z{PY^;HHN4BhSLmnHj@X7+H!O~$^`Za)SG_=E>@vGn%^U8T*w-5eP)?@1&}8%r#3vV zlZ>jZVZk_zG-B^ouuGceS@Xw<|GYc;wBsE;I-s+oA!e6)t$WPr_$y@!pWXWj;uW6H z-#B?%VDG_nED{=Bd$0HAeV{f`ICSF{j0O}|)2LixwwcKiu`jVicM;6Zlx#Aopbg>j zXuJCDi+nbr;R{wukbID= zApx}p0^_3Ayp!@>WzeJ1SBUGNkQ=p8M!(!`Xc8}G;g6Q0kBME5dnq4)i$21b^T%Wg zBKA2;{<^Uz3~`8Tm2-U!28{040pC4a?5#C^y>h5&G2R)R>js)PK)fm_uyVXzn2Tm> zkdstciaAdil;kCugU=;P1)Pl=K=6f6FwP`r1|TaS7Tk?5X45~ZGX<5cHG%a>3m@^R zKfvv^9||Bs)dDN>`eU3J2GLqlL^sY|kXUA}b&Z8x*)CG*Pi~wRo=&_yPx-LN`>U|U z8}yY%5zM)xM4;*D1|{8~;1A=t`IQv!r0+@3xGE#A8XS~y;LFnHNLiO* z2=sXKjB>W@2{Akwut66wWA}-<9Nuvm z)GGMn`SM16YiN?NqiTk9)E_B9K8(?0$0z2reD~R5q;5%ywE7KQ$Q!2!{rl$ zgvLSWET<>Ug<%U|Q*r>uzsppHXVh&cnW;2=1i{`xl}Cd63gss#%HoN;(4TyxV)zmU zjBT2_v(R9v5vefiCWDWa8~$+li2k^$Kz6DaR=jqX1sUW3c+q1UKGS$%c29DvKYJ1p zkECME+IBWKW#R&AllNno=a!ne-|QNIm~Aa4u%cE7Fe=WOoW-S`@@imn&&@ENfjbyi z^Y%8NZx~`G9`$%?(!rW?tdpquW0B`Li`)+l6y6us4aR1TZK}Kzr!HQ|q=cNgm?4<75JMBgEzEnq z*URpOJ^l`7I0e={G@EEID1ph@GG~6=?Vx)ekw7|!c~!CU6LIRTKBKZTr-CPhExsTy z454WGZ4YL6qWyIbjhi9e*MevC#g~rl)NFtPy^zhpA@xYIoZ%=d-otHFhsVBPgqjrB z!f-8Ho@{3i$MkV#V6hNOCQuS1p1%8r*50y+?S>@vMrC`F7|AvO%0OD)6^kfKT5xsB z6+xZK{06RoD%b14k@GGufeSnOk_1JxOZ_h4+YEn{X!Li~o4SFCJ+C^yDVp;Wl<9;U z^h5MD_15;P&&WgiC7yFy*n!m^9<~5|>dNUDN`U+_6$-OUKsCZlHE>M%yroj3cjNsJ zPvWZD_#+R?;ZD#xBT>&eIsF*pam*yGk{>g7pR`&5tI z)cXmW{;r>Z8Bl(%$Uv)`+Ud;NAh6)t6p!&*in0>TG^=ltqbi=8jj}r!H|{ zm7hfR){+}G2PPOlQu+xf&$8m=cO0*_vIU63d#l6bZd4oz24diCIc|>cQStw6E~z(zzPh+ z@MH*oGiNk#j*STo@A!t<1M{wvolg1p&XtN1Mv`@>1vo4rZ!?G#MHQxiDG?(T%hPvb=dt+J`g|8mceg@_GQ{2*7IsJttsvss$kqu>?3 zAp(bQi77PrVzCc&lxZ%Zl3p3^77+cOn?x+>s`%h;1L=aC&{Hv;9QXebY`dAdHWxdo8AQOnM{`Ytk~Tux~7A{fj5) z6T#*Yj5(GyqCEQ&ZW6fYlch0)aA^Zv4Ol|#3OVXN>|~d)%jdxzVcv=E;~OaT73)Y z7H4OmZB0fm(j4a7!fsehnfUx2Veu!ZN2+_hXXrBaH<0)(q@i5Qb&_Sx`+9-((vs1= z^ypv1R5?)Zd2Sn$GzTZ~*+#y>)90xUUSz1m8B7TSo-`e1nhXt=Q8b+_daObNAZU&T zy|1iLQ5Y95DZ_@TBszN+x)2t9T zy4Zlf3jb%x5xNHs>(wk{#d>~5+Kdz`2fj?AXy)aB(z}IS1Jx!LGNUVrsavf;wh|{E zmw|8IM!*uvh`zR;4MW8tR+iL>{>y*Zg0EoSCCAf(Rg#KWVRrLEXDIP0WyIUi`v#q zk_PHGKFm)8g(e;W{Sy%`d$+NISDOndXrvDB-J3?8n540`-Sc@o=(xy#W#HbO<*qve z9MVpO*weLYM~0DawFcf3b8&4ruBC1QizX<7R%6D~2N%sHN6@C7c9Pujy-krmULlyP zh=O&xCO=RN>ktu16Unct_D8kA#via0AiU|@!YVUyUaXJzfh`e#A`WBqYjr@Ry;Rdt ztvte57d*9&4pO%r8+2D5m)f;P6o-M=Qjy2M$S%PiH;MQlW_L>b5FVBeV4C1p<)+vFwCyiGq%ZUdbxO7m8lkMAoBoxHlAE~IX6g{YOYb0 zY(n*t?i>QnlH@uOjQ>xxa_7UE5c3D5W1xe;m1%q|X|zCm#csCh9)1Ezx1zY=KJMI? zdO?fqKHbW&lH|28aYC2^!X$0b^cOS60g*KIRy~){{vFj~+(o&dgv7v2%vE$#XjaRP z!7KbO$Lp`GlZpB0P!8a=BW*galQ+?mWewqWgr)T!7W^3`%InrGeloMVgax^7Z;yyH zd-o=JYH}h>k85rbHH9Ba6_9W<3#of1t~~xlo;STXkRgvuL*--R!LxqyEa-oKFZ#qv ztJrR?CaBC&7twoaYx^A6p58os?4hCmdSPg3ElRtkT;P4Qkhb(B%@hA>~;@dgQMDhw(4((jH;B2RUMwKR0EvP^*6oFMb-Z=DFbUMzlyQ zalP6XV_i0x*`hxeP&7&ubVRg!#6k+Z$+IO+ou450jc%L|7n2J}+C(c8Zu^vG^>Lqu z)M+gW=&H2%vs0)^6T_sEL~&n6_AfaRbBN9qLQ1cC;EM;&KIwjQ={OKi0WeuDF9jc$ zsP>hIKAJ+%afHuyuQHOWvqGgLpFVXlVuk?8#1o~D3^!%#i9+t#=H(TDo_eYy1k)Rr`-on$ z4sJW+KMi21TJ=f65H>h^Q{rkouUxOJ3%XsiuBR{D=v`arP!8kwl}eg0nf$$VRPrZ4 zzNuT&LWtsVh2V&D!5II3Y6cgO&aqBnR3Pu;@h$>SS4>{L4AyvJOEkW74RUs{%(17p zl-^#nSN06kd;H}(vt>I~2YJG~|F@H7PNsVU;W*_TIl90zmkC#7P}vbFn59xeY)1EC z!XOyu>Cm*Q)8rh!A;kTmlgYYue7-*umwN_MS)+Ezse3M~REvX@-D7YyIxr{IG3jQx8=9dZ|)O!hj-HgrZ z!zr$~SvFeB0>APq>KLkA{IwgYGOkSGAEqQEyyagFh*;a`wDi$r^bt4;+NGFbY7%`P z{b+*e?(PeA$G@GeZYmN>fS7^VH1Dj<-`&K55!PGma#wWlKvCP7*b-d(7{WPvi1kR< zd5J9FaA?^2_XrVBSSv@2a5B#P#L=cvSdr=QP)ToCC~dZ%35>)CkrN+LQ5wveI@in@ z@{wnrx%&K!3mkIV?#K5CxJ-MXAaipcS86spFApRm_tRF1@{ zp+3*Oty>gzCIfUB2(7}LBkAWM(uAK-Jh6;Xt68D;&B@H73QIGOe==u|T0E11U?lr2 zHy)L*N6GVfs?h$K>;38Ry-h-L>loTXP~B=Lyejzt3Lv^G{=Ug5ZZlvU65Mx#YGE^i z2Ph-M1ibv{U{QR#F1x#_@5%o2>2@wsQ+L?GOxR+-fG-U5c|*aU+EDx~%r&x-AeeN5 z=lFxCtR?C%sUt)v-aT)?%$(lC=8X10BUCqPtjyu365O#0L)n*9p$LWF+}9YJ%P=c^ z*ny?sWWH#Y5s2!*w#LX=9XOqY*XY|NcbgbEP0K)pkmOv8#E%>?caxQ+O|9ykYca~c z;fKThqm>?^bh7yeVsiE2e*$Viz!Xk46r~uAxerZQ-PQH)!kK;Ps0Z-Nxv#}Cq0mAI z?(nTdJp5b;Sherx8mgtmOxkM{43Ofyxh&<+c0ceR>HyJ0a9zRgy(Pekzx?VOx)0kw z`M*;P9Cq(|58@p-rC~3^~HI2 zh^r+xcXX;6^tHd&kCL6Dps1N%0mt0ppm-f3^T!Z4geHU_DDX0B;tk^llpyS2D}*J( z0!JjkXb~?!qUHyAUr8x_zmF6eOPfi+JpjdVTi84P+ZM zOqMg#q(;MNumLCZabDS_W3KVIOhN!)0(NZBVnP9U;ncPcbVJ9lh`k3>5-A5G{XU?RVo+Sh=w7YQ% zromx`J1T_7gbeT@+}Sy|Xs~cL2^*2E>Hzb`XjA#f#w~X2JbZeBbuStgcU<& zxBN$537Q?>_gf@H2NOMiMPu2M3f95rb=eR7qYU=>cN5QFj;#-T5q2$ace;m&w(OW# zU~pbUwwq9Im4ZSzVMEYRaY$B-8*NugLY-4;MI{CMk4{V;f12U_s5aF8q>CUk9ur9R zv{R>Et6P9Sm9)^&8v;w3N>F40N)+*Tw8afEhuX@C_f4pe$xTdpt%P#X}wM46tL_Z(|Q?gocl zni?du)<*)JFg7oSH*EENT`$rcY$R$L3l^XU8<31Vw^3ry39Z4Swjq71~{gUx+joVQ1g`CSWtd_*r)atlx!_dXq73z_R9hD;*#``&*gS5hYpt4=sW z^0%Ded&LO7CVOd{?+%6PXf2NbB2HBC5DB1jIo?CGlUA1TPPW>{zUV7sz=d+Ty3w68 zR3bPTw{zmiQ&MQQ%|IN9sKpwOyoh8&ddG(@eR?jh@O+ftH}wMMcD)A++f|m>F$tVG zo17bDbEMmVvySji;)eJ~Hw}0})uPKLCJ>*il-sAnstAbrA`MDV=er`p@D9?!XLkD* zAT_b$Sn-Amv}WS7$exJpMI^2GP&MUj`~}FN?NVfZr+SWAJxt_G^s`e2na&{2Hf{!0 zDXVmWS9BSXbhqK9J+9=erR18kC*}PF{D@F_Ob({=FqD-i=W^28gT|I$+yfEmJ-1TP zATzDWR!IPh%2v?fxVJ3#>9c?(TzGNVf7LF?v}BhdXw?wcVXc z#Rnd^qrs$Nk*Mk^80ff_g3HbR1A+|vG3Siv#kW?Pd;Eog8|E^*L0OI~z}%*w{=Q8l z4qcBVTLDz+#f^qYyUp134rij~n5OW^f%&qVG;L%3XM`8j$bgAxf zXXGF-{%y%qW=VJ(u8K3FB^H{0ps}`U`~M5M4o2}&m)D2jN{iHpQvx44uE}YY@H+!Egp3+dbyu+`#bXIhACfbx#8N^Y z$bYvpwNz$qwirirG3b$-pIT6`ZiiI?Z5`9EdFCPAI4Ng1yQ~hZ8A*tx(MgNne@^Do zVU;d%a*zM!c3Zv~YDeh-ty2t(Fn1Gz(kwL}@E%qzuU2V!f@4-BwlUoiwow6VAh>7r z_TsGzpE-LGr-d@ll&3C-EWN(wvVKuz#^wwMurW)c_;;u^FN49x`jMm=Cb~B4dahh#2Lk}d{Cgiwyoxa0kE8dHy zHTbUnC$eQ!1Jit-r~E!utQ2}UOYYp_0#`HXHzU#HPSNyB0yYL!}Z(-T!hO zy0z-?sJSAHEN~iRz0ku?;h?Cfu7d>d0lTer;FIXQ+%QFITz)YG_6HRKpugNHQse-% zV?EqVFZVFa=nP7`8P{%m`62fXDC?;9gkalKDA-RTWO>CM1h8;%Faib^mqFcp+YHI zTssVf9E!=dzdNUhk+Q)-)Ssq*Ed>>iU_!_-%D(%{*#?xHc8C7)!@IfjxwZOIj+t$4 zva*R3VnGvWgMA}DRu6^tfI_OxtmO;=ZhOc+faY0X(BE+GUD(<6fdDkx>yL|ibhYZ6 z`Abt+m1t1gKGkqg9fH;s(J0KfL>}{D`*l_~zK6^gr%s@)O}O2yyTxET^lE%VK;DRq zS30fXzjiK4=cJVqVs^1lOdgj^zOj6nO40|4YX~ObB|Rhsyh^iD63T6S_jhm2G)afO z&;d2aod2c9x01~mktBF``Rh-J ze+j9yZ}9`65`@be8~57w87wRL{uFMuyJ`d7pkEDeMnp)?ejf-y;|kVG{G|)r?r3?l zXy`AUrpE;VW2G|y3PJWpu#s(^tBuIK?qWvF%`0kn6b2t-t_hG5z(ee^f)CBPolRYS zo+EAPipTGU5&+(3*2elG-Nq%+jO=zvFlK>V_v`^cgmd^;DAEpIdyXc7Yee%BGBr0h zogSi4v!Z1BZ#i%vz0<`QzWXK4fQwbV3)AnyY`p#@c1^q8X)ea8 z)~C^!q%r~^eLc&n4|%!eB_m9J=l@%mqk^$&a79ap08rLN z#OYY7mhmJPBg%F4(ef25y><4O7%w?!txZ_J)x_lxN}tiPW!~s|^h^NuZ$Q|^{W@=9 z#V2&mJ=!opUV6x%$vjDM+?;l(t?yiurok=qLKxhYN`!mYD0t&V0kz40uqFFERn%rV z;UpXPPoel{sY2d1Vs=R{GjQ&UtpC$Ysa{f|C^W-?-% zM#|K?d+=+NQeiIy@jR!3kd5>1%z(}zSl*1?W0NRQkeK1IZQHhO-LY-kwr$(CjXSn& z+g5Hi6>V)*^6C7BKHc@aZ!_yy!$V*4z|-StWeL-GL;{cY$|!SQ(F6z?fX8A2Z*sQ) zbnP|Wen}zlhaqk4FYXlG)`rqfQIU`Xe`jgVM1s0eleR=HkxvxG;+w}JsJ8^5JIPN} z{G%=)abucwRmk;+dvSI+A+Nw<3T4E0V;+Y6Oen53$DxWs^k=a2i{wnJ4`c)iIN~r% zgKl0B`KGsm(lJP=Hr@9*9d~?Yk(v$!YL(>TKK1YiY0GrLA1Vk@mZ>@*k~|~Z`*lQ= zT1bN_l0dSDu>jhQS0)ss#iJsH7Ow6ypVT-`ED8KdQ<1Z?dP})Cy8d82A@H!MNrDDM zlZwnt4j*DDLfinbF-)xHVAZPrZg=cJRdFh~jX!`G^Wpf%VrzZfF2}7`8h16elUQgh zc415Sh<2`{moorYICgftJD}KV?9Ku;+x?i9l0N58Ty3WQ^1nDQe!^Pe$brS@Zth}t z$Kf5#ZK;hy@rYrz8U_z*wB=!b8<9G3`4<_4RZEJanNP5tnpP7t5bKxRuANn%CGzznV1(7keq-(#$6*_>js4pFt+12R#Oc4SetB&WVMOY%yi`e zDu|3W=e0_7)e8a37qQAOq{<}URVqx90$u5u=-qX+$=ke_zN_EyC3|a6JUT8MI5Ysr znS2fisI%HYR+MgtN5vFOkWH(7mhVlol)CO;osWpmk22?b5{MVTqg=^D)oh;b%Mv1ZtFv ztacBR5<~4VJNB5`zkr0JBWqtE>cMkkaO@%GSNigAE^b~0q;;0LSqD#XwYUP)cC6kQ z7MaZQFFes~5^CU;J=6svKfbzHEv;R)pCm49-8W3k^hj4^khnyr-O7EKBsK-JiDcTk zf?STb$D2GDuRVL43*YeuFb<+Pj*n50Fcd)M+0vAJ@!`%9b*$!R7P4E>aP-(3>0w%E zgKzPYeUntn7Ly{g9%0dx+IEAC+K`L2(w)Yz*ojGnDs5PiR6G_`mDKn?P=HHbl=Z*m z@N|{_m6C+Wq5DOz=A)S)NTh1dU*|n6dR?Af2l#u!{V1*m%5M%x9@e8$V1jVoQro)1 zg28jKnx4Nuvw818aQ5_ZV8A?@?cz8Wu&{pNm4{t{&JlGRqV~Y54DyMhaWxUYxnOBJ znYg0A{uoSoz63VH=m|{I&RQKNJ zB7{Z@m}@~K4j;?uQX6r7rrgdCQ~HnVx0&RitPcOOo`24yg(5785I5!NP%Q}s$cIz{ z{7db6K%B8h37~9x>7pf}-^qdA^vT-M-a&)1PrQJ!y?~(^ zFHNH=1kso76}#Dpmd8gObq-sO&ejoU+@@ks=|w!TT}fNMclBU z1L@PFG?i^AQ(W4nE!0uP-qW-B1bKRt?>n)=w3ARzpU3(Hwrv_2Ziy9+HZo^VFDOK? zScBR@(PfYj2bZXLy+@j)>XALe%@ifBqb>qtAo63Ej!u2vTZJF`E4xoxYnj#w1%E2j z7QfZT0*^T@Oat%K%4m=cPOZ3J7C~E}g)jKIcXA+wxhvUYwa|L_EYBb;RlO7&-e;Kd z-jtwfn@)@o@G~kt@zH}J#w;cW=_I09Gj8}ImRY}79+8wS-{jQvI^i>e2Be0B#S9N; z!!%V{=TMBXGv*D`h*QG3gDO;cS9nPi29E7lXeW|!tBM^FBC_>2RxY(SPrMWDOxDH` z7%87A8mt7IRYbT*s5~5f|6$}hCShJMbc$=U3JI1+N~8^j@k5-x|LbIx-3q$*NYoL# zq@{(Bun}Fk7lzYOhJ#I|qMz~K*4_uF|FT0T;r(z=O!f8!2$zR)tv8}>pEBmZ;T-R4y&R~G?*`;pMN?Oar0-J$Z6HGqs2ssvZJYGr@!}y&xU+?@F zXSbnx4x@+yp@50;dDs{7NkO~T$w6e=mR4CSMZm9?h0f@X#zN>;)y#LQnfsfAz^l>4 ze$^8AF;vXX?I~()=ulUz#WM3zTMvIfX_Co(p_#^*^{{46N4^qzh z-+TEzJC)PnQnlmRYhA6=^Kzl{{S-#_KfJ$}|Ly%nP);z^GyjM8S0MSHyg$o--XH1z z_Wm;ellSL_kZ<`vy}y?K()&{?HvYf7zav%>svKl|YMZ{osI|5_gB{O0IZRvN(A$N(YrIWav^O%cQbBQtA%=h5=b&5ZOv z^^yZ(LRv2H1sNU~vn<^|_guJDgBevljOk(%t;8B^Qrf5a`7fG_<>KHRjYkN7`{ zj0~;!4IlG7ll-3E%*11^t!sFHW)pv#?{7iRSxr!iSwkv**#UlKqc*VCF}2n*0h6lV*Q~SI36u=l`y}?*{%ZPWpZO!6!yUbVVROZ8YW}y49O# zN}Gq&na^93ay(x(_d-205#LQHzs8^?4(E3??Chhy^f0;hV$##=uf}8ipq22?Y7c9C{a3!u8nz-0 z@8e)3z~>M{47h4!Up9A?O>Ha2 z%NwVs#_fT#D}lPktl+yxXNx+$)Xsi?h{sGf0IA`OOW}<0M*GB~I`pud@XyhPTt_!TQZXtdT{_mZqJPxh;V_i=w|A|?c22zNuC&BA z%#{0?3Q;Nd7!kY9x-w!=cplRZk7fzgwPnk!8&G#`ncP1bGO$*>U#so+dOwPBR6;ls zSU0SBdD{(@m|3EqB2f`XT?8eD-eMd&fRN?!d2A?yd`eQXex73#E6%P;EHO>;RIuzLhh} z4&c=X;8V4%`ybNAna!KXlg~A6 z3)~Z3Rp^#9ujhger5p4ebCQ(!`13}-SPL1sl|bsp$)sh)|?^1UvHs*Px zNe2OyzBMNj%l07(u8ST#s?^Psz9m)`=1rz(^V#Lq*X|X315Ys7e2OFiRI+0wtw9Ce zOmNGfqp&o39{1bguv2SMJUx+s!+lPT= zbD3-8L0g6S<_wj@@6fJM9#&>P97(E)UNH6EEy@5Jo%8Qgrqrwn{kXb<{Okjh+1;Y& z5Ga?7ul4Yp75TNZ90-^BAjdQV&)wS<4O3M0a>w#sYP8U}6So2Ob0{9a`&AQ6@>1BJ z5X5?0k`gO4G)NnZryih#6W^P2ym<53WxmBlCcN+B+@Rb)6OpgIW1U7$0n${lps3E2TT1^t!T*U3e+HHDW@_s2Z@QuvCjp=1vtEa zSo{d>C4gH?e7K`>a*{k_od~_8$qN7FaK#OEuou;@+dQP&a6pdqc^>w%hNoY-L2U(R z!{fblry809&ls@28)< za|yXaLCcO5HoQG0lajDZx3;Vxm5P>;Lz^*lq!Yht-d@>><7vklE+d-w5NI+0>kMJa z+`nL!Pp|yRK=2V&h41;3MfeCB4%u90gHbRZS(0nf;dBT;WC9SjZ390;){4D<&`y0% zEJ{}e+7}KP#gf`JG2k3zZPnAgRaInB_wY`E2c?q|>qZO?5~qwPlL0&1j0!YZ%+6T1 z-o;gQP@D`(Zm`RKA~Zw1<{TujONd>4U2}!btCx@W8lQ{$#DZIx?;8=Mbv4|9KSa&_ zMj6|`r_1N`c!KiK$$ni&wEm|v`Jrex<2$_qYWar7D&wsaVOF`KmOzz}JJHg=dh)x$ zsRoF_D1diOkB}hHFCRS;05oLIW$l6JiK_AA1}`fNI|v1K#Nyfs&IQV>+gM8$N5Dr8 zhvC>8)|y|8*zq=8G>QwpDfe;DVnF4!L;M&^mgb?#%J{K?--&D}jY92>>Ln7aX5lM8rTyCmk6t9|685##KD~WQz=+b-Lm?n_QJcckMk&PdCZefsGHIn`QA+Kvm#Oiq z%!1H+{G^d8rgKm`P&Og7zc1p@hj@!QCj4uRC*Ojd-`{90TVFjBo0afa@D=x5JD2#m z;b_E}?9jd11b9@l8H9uPb`nqFu`6d6D|rJQr=51L;=(c+azdyAi|c?4SppeS-*bRc zm8wKqJ^Ap}QK+{c9E)6NmfJNJ_cE>caRqSQz<`Hj$B?39OzF7VQupZNN}{0sjw3i} zrd7S!^6g&hsdUSsU~jLcuKbnj{6%0aI-qXE!xc}d0;34ukotrh%}{=^Y+8pfzq|owgM^0`U3}H3AT(* zdwyU0P*Y|!vgL&? zfTzy3ZG$}m$=gs@7@eBWaH>m|1ceG|mC-8sU^Gz68ODaYRuP;C&&=h;`M^-IvyK#- ze&Z_>*2C|(aS|!xZ>_oo+tkfG%(#j^eW+n-09ex~e1b#L3RU{0YI<`QSD2Ox#xYKX zpZ@D1$`7p%- zX|W=a+se;=KGf^bK>MT7D9_=CZgM?Cfi;p+gj9Oe@HgR zpHf?RK8vklEI=y+Hz-+>Pj3Pz_UY3*@)nyggo-43*@?$%#jTrQq4B1oVS=QlII?6p zbB;XEO7`ZSOpiOrEdsD3PZ#iS+U6&JoO#V4P@=>A@gar6+cBX=>8{;f8i*nfe188a z;`5gL;7GyvrfX1F?s4rqPpK>;h16+4O8!~0s)pWdR$pdH^bV^I1f7Z0&qL?j4U`6J+oEVOZ)LfF7VNdJ+7IVrnd~_YZyE%>P5BGvZh@YHIP#}+vpMP}hM|-`+ z5P*DLo|qq((44_nXMj?pE){y5-c^lYSDUuahD8!x!WKd{fJ$aJ4`3nuN@&5E*FgBw z&4KcQjZTiV{i<~S{B-Jh$X7-h*)W|;qc2o1VW=**4xM*aXw)(HJziR}~I zR%M(Q06FkK-~foTXIl2ACaXvYKb)zJ6F*2>drTu?kooGW7G2iWE1f_K*Px!`tpE0g zLI66lCm|ccro#u45NO($xIM)(%(hK}Dg6q@f7uuqQd+$z2qvC7F^bO6gi7w3iAB_s zR3q(BF&gy0g1|7R*vN?YEl%~HGydrz`7EV_)m@uENrzi{=30tRx@bIQqH#)wb{3mR z3V{mw*9KE+t3|q<5?ytyamHW5i3&mZ!8kkzcNahlz7hVK8z4}UX$85(lDYF zS{+#;1$|xJsK&i*^o}7tF3Iav2_u?q9RFTbLJ}f6>^GZL3P~cU;A!4T#V)qyh$T=Dd}Cju(eB~-C;4^H6yu9G?O9@L`edm zln@%pi&8$;HASmWoBrJz4o^wU@*0iFW&5{#^~K@ym0xDhOuM%hYc9udq@y)TqB)zj zRkBIHcQE5Fz{dsE(3YCWH;`n&X9Zv8Nd?``+;ce?a+cxxh>&k5AEZM;3N62m2@@Cf zMBWwT!0lMGPk0agY4`a~BG3hpev!gWmuK%9hx3u*G3JGD zXNa38jClO1@2Xp`FK1}i*Aqu9X(XJa_mSTMtxLCRS;V3~Qz@O%GDyAl2o<>O zocq7shF)YzA}qlQlRviZBP!#CQH13#1XL zif^T>vw0EgE-)r>Gle24(nEMT_uke56tzU~s~&&)uzr0)bs5qqBJ1KfYo;b#Pop9* zM@kee$YzE*VsPI}uHseW*55e^0%yrSeVMb|+4)~Z+lsv#t9t@FbzKyUQ)PJ?!k8k0 ztXUtpYMY}&LWN6_4Wd?o>gCVK?@U+A2d&wxz#u5HGO0XbR8TLxN1tQk~IzS5L0IKO~U%XOlc^~J`Q^{hVA&=0eW`r ztPWQfaRt+{(nvi7reN&I!agD(BbLpxZ~YCSom7qqj>#0$Bm0oC#aAQcxN@DIw>ee# zw@JSo{@SQ;GLZqo$_;g*q?6PyEN+`3cnc8XQ!1x*W*a$497_Z;{L!@|^41eqh07lt zLM|p8e$&p}M>DGkgLyj6_7l_zeP*B(NteKBJjX2bw*5DsySc}s;}le>{X+33P}IU$ zfevMzA=g5GdH=qvD-bA{6Sf{zsaF)GXn`bSJU(0D-wM=quPMU^1^(gZNF%TtY}8*a zl!Y~qCzn*%K1O=KR$OaN9I|!a!}o>Dv4XUMid&J}fEbB-qGQKLw^+Oef>0Xcjinl< zZ^5}w94c_(B77XQSb4U9_Ksa~vLApDAm|AK7EJ&3+Mf1Ia^L%3lWbU z$&`pv4XZn5ac;SY2ovZ_4@go!^&}%`-H_`vZFh;LWFmS0igQK^T|yzshOs=S6NZ;& zNL2v00UzD`ES9@o9TiCpaUDE0FI_(3Y>nz5q=osxiw`e@U+bV!LL>rRJ%4jg==It) zL4ay8hX@+yJSK+LdYE%QzM+80!^EYG1uo*w^;S>U+dJXz(N@Xe$rmO>NB-n?MWZb! zt7r^(#cr=!DwV2M?zUD~RdzwLeVcWTHE?j%v+Q+(7m$*&-k2jpuW90XbR=GGb(JNS z02l@7rrhRK0!0P!yG)=%NYhVrk1fx~rFlS?TvyeV46m2ZFPw}Sw$bHy^)#CIdY9I^ zK(<2T|DAA>N+EGAM~`?b)x76KmOpfHPGb@|mdSm><d?;e`P zp{eJE9jBwj(-4NnfL^TyiGinAv4^2=vy)!1di^0$_FSpgB`_PdSJKAsgqYzg^uzN= z{aBeAasiAev1fZuYp9mEx_(hSyL*abx-1s@*nDR1*g{@qJZfoiCSt<_f+5fSJQk@n zTa3<6ic#I<6F! z;w%r~?D-@AG;F`cU%hCnK~43Jx4Ip!gH_ zIin_CCnLRR1Ek=B9+&q|R0t6U78hecJGCBlWY;Q?P?pPD29v$i2;!5pAe0Qv(r}!x zF88Po!q?y0u)bZ5-RUgxbDmH4?#SpC4Xn||!=jv!H+_?^m)oSp;2jt3Br+z&k&{*< z^!#FQh79gHDKcY7Q%aShxk~EP~e?6HP>XyPFChv)*^xmgW==iG6f=I}K9;{1OG0q;~u8R%JKfgt)?F=lZ$$5+Q zoAAw>@Z+uxMlfBgG=cPTechLpTx&YA7&q2DTqk})a|s;mDyCMwiUkul$E$umD>F5Z z-@19ms}RcHqAyN0Zq8A8<^#u#;dI+{A*@u*5seK**&X#f>jPkuMvhSlYw=Y_dDlrH zFrbfx4IyPOT$Je2-Hh4ftGeDqqbg*QW!GhvvdmUkeB%`OoXx16;$)ul8;?AAxxbB6 ztG~?HnW42>ry;~%C?Sl=!?0ZT4ZqG-cB{~3fN2=Bo+Unev#&h@V>zK zo#1;I+Smw1(Y6YA31Ft{7n{%9GG zU{=lGb-jAatxm6Wmg(<1u(*6`ANXA|QB4{LtQs|>LGaEaQ(FaEtN+;_8b*cfWd8FQ z9YEHrbwACcRz7g6c+yjsK4r9>OuqixBB*pNqNR{E#9o6<$5+Ow-GPF4;K5B$HWeb= zapTrxAn=1oaJj;{>$OHeyWj}HCVc2lZa?tVAk{{#XpmUlh#1mgxNKr)UHH*)W_ zwk$Ckd-r?|c7o?oFALhJ8qIv?<|V?3ya*wm%PGBKGyd#F_rf{J7^lFxqzPk2H=o|- zr5q|$bt(XbmgL`9`kBS>WL3rJS)mk@|xasndEZeqo|&w zdFBgH{dvIwl!ZGEu+3L|5sZBEJVLN91KQB@AjS`Yio%t-GVw8;)+2b0?~Ho`*ZcAP zoGuVHuhw2Qu(bfM#HriRaI99eqJaGvO(VZKg>|R2iCWvkQZ~k*W2wG+8|u%Vr$S&Y zaO0?ijZ`%)JLRxl;*T`C+8m>zrnySDBF-@A!}3@5Gtf2P*}(Bk3lb~cJ>D5ZBJ=nt zDjn10_;G}V(07kMlC*}|OWrqtT3p{4(uimQH&OxVIsTSS!lZ)5Se(hSh-oChhzk~_ zHGFLrwRbDckQxA7zdi&4LrM4AEtW$!b&f=q#!vRAWkaBO%v)n7~xx z-4r1jroPGr&T)uDe1`BNb~_5&ti@w&dfz(#u}{qa*16JD^;}>-{+x3bkj03%En;X_ zD2IQxBotRBd_($tiIr@rrEA$iAb*0I2AVo{o7uXEh>Po~qE08U2+0KKY&xyjC6#;G za_|lME<-DfU&hl&FL%i_l808BbyQV>OiY7n%A=D}k~-0G(P~Pox*@ z$#*8naKh^3B3na>^GFLfg$p2g*84!KX#?nyb#0_;ChxJ--`ZZ_xQZ4b z(O0lWrQx61nMEz+WB`J4i#cppyjDqO)xnrD3xsdX8kt`}6&lvTq`qI!=WJoG(s~ zvnZB>G`qpLhqG(+Z`qe|kuY42*w1Z<3P@Qo_VnyAfYC!~++mNXiYiLu>zfcD{8Sy! zZc7Vz?sitAT+7OsgG2@Tjssl}8N!v%AQLyL>CK-bDr%=q{GS^wB zvR43lgjfOe;WDW+*g4VhX}4nfF*$5wg$_wJ%kGB-41GFm2Ft_Yum2MAz zWes`qz|p|XxG37gUJeG_b6BswaKFEhOujew(C0P76e>r>Z?S@6SZW7Dkgjh_Qtx{plcuOxonvd6zA^vcQ8 zJfZIiJ?UY+$Z2-p#w7dloOKdPE1>dXE5pRs8S=U(ZLSj4=$pT_p+Q)|# zIU4|SIbizfpOrmUL|klMrbkr+GD%9WIW(FTmhizMtQb0dz%MEWzB0f`cpI`8`BJ_aCoaeW8gu~%`WM6`WpAM{FMla+p?!b2>do6KR zGNMn}dd{@$YLCI<$A4T(Yt6pGm6&29@%m&{X63^Ox$lhRtwMu<6FQNR2WlcTxgG<`{E%Ah%%*is zAJu;7vHs7nemasQF@z~%L{TN}I2f2%tkrbAfzbso^Vyh?1XEnn8v293%K4NDbR*4v z)6nkZq2}$VmY}0&?*zuq7w)7a`m*nP`m~B%*?Z*)Vz7a$~*GM{yf(*YR>5H z?FE9K{W(SUu(umb5AY32i*pZFojcB_3cKSoiunuuO@b!kEdlP9vN^ZCT8>Y|Ve?uX z{$p}+appQD1MyaJuzYtB+p$*KQ_gU%dZfa}G^b$OZcXilR;~3%Pps1;b(RoisvO(7 zfd-|#`B+GE$qra%Fu0?Uw)o&z;j?!46~8vQ*vtUd2a;0W1vM;Xf@K$CN8wGvBPxN7 zB>D)nr&xq(hkJ!XMQ~)r#vuzh;*k;W5lFLBG#d{tPq+3^vxs-8vc~chq;r=o_CQU? z*(lc(Yp~PVWj~MLj&_GGd4XLN^L;bQY-(k==o;}5l3YM_evBP6Z~De#gdu(^-4-*1 z{!Bc1Scdnv{W4O)ORw^w|1cIv zZxAx*KsHnBme}v#>1NkuI~(%Ui!38nlk=H<3POQ>re0IQKTrM6ok?$|LGaEF?F%zy z{hwI2?|-AGW^ZMjrzP-F2?p@TPTw&Q#a;;)i%{{knV`8+d^IivCUoN}*Xt~^oN%Y@ z48q%EAG_glPIgZc&->f!hn-y~-9#l37apUi=|6$CNl`N!#ikf&oLzFANV%o` zfov3EryQ86ueL~A!iLqI6fnOB0$lgLC#a?wh&9GKn@B&KpApkY3L7cB{;Jyv@h{11 zy{z~&UsPV72KEu{H5C_W2|OZhAoUTkP7YvUuQ*#Y+Ox5Zrs62*|Lwchqb z0?y`gD-56Oir-b%keSZULN?(O-d}qB`OWWAB2qPrvr4rduXljwx5or=Ygkql9XQX$ zMj*tBfPqm*wv2AeZ(BF!{tBR|w``T%cV(X>xw&SV+ql|a`Q&QRDPGFk;-KZqarer7 zFo@Gb8en=g&G_A8nNkqK(01>tPXzW@ZW?Wk3(QWU6;ELx`#Qc!shb#Da69E9 zzs=;dsq(65$jNC=q~pbjxcp%M)uuM5cO_?pN4z=m)x}JBs{TZWor1PPm;I=tbTM3y zn@Bt4&1%@rM-9H%Ljqv(o<*4cF%Q6@k>U|O(r)Ct@`k;Yw(4r(^XSf1cRHObNE0=^ zvE_mbY!N?A)X2;$@C`IQYc-=r=Mi+~tVlk0J{B-fw#$>4DJr11w+y zKwZI?!s#w;wvB3V@ILNXDuwT>=7EgKf2YPUO@Zvs4})>2(>wILg4MQKUTCM7gM5_F zSuA!uXFcS`)#w~u7edbHyj!jsKhL@Xr}PRS^3tdJZykwROto<=t;@!>M!u%G*;?gAGDj<8%bv~ATfE!@Oyj8$6c65xQw7RE zi9XC)sGuPy9tA)j%V?!Fa(miAr8_$;u-^{HrAg=Rsw>Dnaf|@N3k*}KM6=tbMz)~; zLa!^V-0L>;0z^^Uz>kzGk_Dzo_wOy!bxh}(6g)c%FdJ;V!Z#_>fdN&FJ_lQJ``Fz+ zw4zf<(EDi_Fo;J}W%puCFaU1tE7!?gB|r_lm8+;WNZtgAWX;#WU^6D9P|Ghl*BF%y zJuKLbO*2XM)gahZ*EAEoCoQ>m>{R84=1)&^H7dXMFLKw0PDT1CPtlM206p-FriPM{ zp?z>Zb#>6Y(1d?=bO+@Z=$R7rlJBL!5iSl}VA-Ov8$YZzg#~4B0;s(D;E3y+fS;KityEh>{8Jvk!}Z(_9jFqDagOE~hG7%4X}ApEzUmT4CsmVdl~c)N zNe`iemV7~0(!#%(E`T)97P!n&8Na-mkhz)%D!xb)5tD5)3_`^;g^RHn{MQh-+%z5# z;Cx}oVM?B63rrfO*(6+wAY4QeT#w}s8VS2%@NqP+CVlOq_7;J})}}`BA@Pp|BFf#b zzkRwbroT0OSl74NkYi%lxgtT$4XDDkA%nM=%MTW!WS#q@fOR@u= zygUE+In<|Rx{~*Y<5b}OEa@Vc61a4JoiQ`5w-e^j|zs#Q?Ef%=Pp`imt;rSI3xBhe?iNmCua5S^(`bN;7B z1>ZN&b3G!=ptF1O8^F*c|EeEZ>GKd`)mYAFlWJH>4J5{Z6*G99xOe(YJva{=6kj*` z%^G8)nX3belOZ96V^{xc)oiSxPCck?P%8A^+2i~PlChAGJ>u<@$B-vmtS2aO=`mSebW?8cD8S)>5RWA#Lr#O~h`t|FysejUu~M(XQjJE< zC|wTP5PZwNOsK$wJT@cVW~;4V$_*>bn_g*Al=)y?w}zTBara$+)%AU!z!0JiY=*S> z(pu0?d6c~)wqDj}HG4x6h?;&Y^^1%812bz6;Pd6g=iq#M=4A=U>Q{1pbnUf=^B64V zaZ~)Y!J9`B9nuZzvFu}pMF$a!33%8ghDiw2)F-S)MuCu7eH^4D=IjO;tK5pke_rx7 zc26Xiz+C%^YZGrzc)7D*k;Bdw%dgm~tGT_`FDcZg1lKvbW*ylf$f52Y&v}==0zsqu zXtcAuI{Y@@h4CQ&)+B4wbG9r#>;ZMyjvqYOz>i~#w}E&>@of`J6^-6G#FUYz9Z6cB zjAGORgIMc_NdeNYo52yqeSE9tM%VE+7ECV!MRD}IJL8!_%9kD*U&S>@{_uM z4-Ks#s9Oxa=#{1u89&vZoPui>MV>Z>5^3&>G`ZG3{&PWe@;W6{M2WeTl{J}~;La?}MQ{w`JIF7l-P zBUyFQ$Y2kG+do(D!-kuag-%9Rk--&EXI*2A}Uoh2+ zgr?N#Awes?5-gyLWWKSbsy!6S)kWPY1uuXx3+^YiRrYec&{i&Sh;vO;bNiVO&<6J7Ros4}J^5*(Zf$6v&X!95S*>IT3S~F)f9;?;$L~`GR{)avLE> zFmnYmR!3YNruR89>-+Brjv}ah%t1h$47)2VsM&c!))y8THntaoU8hZ54qB_klPI54 zZuh*tZR9GOw9l1bjT2VGX)02ETie4legBkvs(NokFp~hyl|+Nz#0hKTsORSHtG}>(pRo7re>{H*#cf+tJ?Hoi1 z1N&b|H4An21(Cg0ud=oex`)@;S(>c=T`^ZCQKFrc2m&f9{I%63!Bn+`kSKMDOQ#+j#wbV06D#Fv zk(f>lx|i76q^oD_-n{apFw}dA3GN32Ub!E(Pgp1_TrUASAK0h(tyJ-0!Pf2<4huCA zILrm4YR-y|nU0lq$|1YC%&BLyvZZ^=w=R+984hmozu~c#a=kP39UvSnwBc4}+~%P0>(O34_c13!zS_BOxR&tN%OT&y=5lL=x- z-N=!<^_uq8>9%EAOFePWoOki5}RW&@d9g5x2CJ4-JLu1?(&E?v1M)T}Hn3$%O? z@Y>S%+Lap%i3zx%7=XFS5$sugr@bI88^Jqlz zd=|lHI-R6nx?5kxXTdr_W9Lj!vk0bo&O5We3w53r>}ben(_>SftTlg1`uCy9y4uJd7~gH7dp@R3aZ7o*Qb z`e{-$j|iVsMu+X~f+;H`%+gu1@YV<;IulS)bHJVA2`-#O3@<>;iC`ty=ku`jsJ z;m&kg;tvJB=$7cN7r?dNbQ21qlI{32@ZLWFXJp>sKJ(enSs*#U z7U+X9XI+AJzOcW(K?g$ee7Wy$reEju-d~MU6=(bAeP9>wa(S+1XX0Z_69*?;bU>I| zyP~PEHh-59R%A%pu+SDL)xp&WZA=lKDEgU>BS_kIRwP*_Sc-(0($#v!V}hB6!Klin zEj3Svx=j*NxMiZvJ@SwXST0aLt!j#HgA?Z@a!3Mes5n1z=Cb$ffEU^mB(v+B?21c~ z_(xDOVBm3+-cK`Pd#yvOmz`ed4AKk^(G|Q84!i2tmVMM|rB0^nDwkxig&G^G3Z)AeS+nxnSm{9k)WJ9>0>`oXXZYqNjtSReCMA()*(#6Acc(!_T27fH`S}9u(SBiHJH*M2$bAFm< z`#crOSkAro>sDl(<5&9Fgbe`WK^aCsOP?Mz zCGx7j?OY=_T4oqD4&rTqKarqMS#E~b&^rwV4F$gNhM$JfrqH?4)mC-{nOy-&U(mIJ zDF|itL_;=^-8VO^{dKcBPALBSpc2khliyu4$RR_cd|}?jot=Cn0 z^w9J^L}tw=VzXY35D>SmmAuofFJeivW%#v2+$hp^F|j;hC^)=tDIPcVMdx0Onx&4-tKVV9ynH8m&V`8%Rsq za)RQMMI^s{78Z-ZH}#f&2cLqs#7%Npnls1bTv?AV48eZ7h!|oi5Rx}cjB^$D2Xg~D z=M1x&S1>|dcZS5{a*8I*XS4UdYmujA=2sx6tj^$hz80vc58hnFZgVZyqTgRZO zBRr((w0cu<4a?u^%2B4P&rS!?H!!erk%CQT{UZ_hxzsP17qOTbs#T% zGbrmt6*Q{yE(-oXo_ZV?xGO`}9s>_adAMrk{Gx>*s$@lw1?v!pzUAG??()9swF4SD z<7YtLAll5L=@YXb_sg!EE<=V|!blyW20Wp4ZXL`lJ*!SRmt!nCdb^E=`w`EXAlC>F z=%M9}bF#NgdvtdcPH)CdagrVY6W0V9B>*GzQ<89`nza)tInv{X(}K2wN+ML~7eod8 z)()F96v=%LZT55$vP+W8p^tx>2?=)zISx)er;sd6uAAp|%C;;WzPIo|Fdm?kuWE^V z7&FeHrZs;D0qgKZqS!x!s6nS2LammG%zgtR(x-?uqbk)qe(7SN?H{RYopuH+1S|~d z7X}E$W2&F|@_DF**qVO4YWEF!EwF5Lk7>Ut60X0ppC7Fl;!1-I%7@U{k?W!YO!M z&?>pq)<=%T8F0n>9G)HeegxXMU#@;)0SB78W~H5y)=o}lmbnPfpBG}=;om5~?%3HB zXA&la1u}{&-dL7U6)rFvmzxR1QZWMBM@cRwY^1R<=gfq3tp;t8#VPn55xt24-tO(m zd73_~7H}}PxH`j##$}*0C^RKPR3jH}9g}-vx zV4rGMklTbA?KkR&++@f)ODi){ArZ0Pgx_RLvhyNJA9?EXowZ_jN z1)~e&s-_a(?j3^F{X4RKTrgzh9q+)|b#&D(qG6vBZ#|}COesLbQc?8tgC^zQw2-%wC4DbX8%=ZBgpANx=<=f z44}5bhBQgUQ@$k}xR8d%b6dFkYNUr(RVxoq>7@n7yfDMI7h z28jJbs*G*9*9-_v=t~BzUyjs-iBehYH(PoY%b=WaT2cM=)vR})UzzC{M3fgc|At^mp_<=(7B2rL0g z!8j=IRZyJ#YGfdX%gD;F(oqgtoG+d3GLAVbnp_(Cp4MM^^;{=^Nq+Eiz^|=@;HF>WkZ-Nmc zfU_6!R{nWYI_`Ch4=@`5NwI+ShpxL`CkJ-lG)SnK)ZZ{-`;aUe?9R0s zKYf@RxcfVXi29TGIpGEZW|%ff&KUvq^*s^d%btht-q?M_zS%yQn|yInS`d z=jeZ@@9wAgl862HzylbpNL%7)!bDyLH1r>vWq1~ThQlaMZ*!mmjFE0WOoJb0yr}u> z#E~Q8jkD66#@TIaM$vLVn6h=hf7WL*%?!9aXBV4#(=hKEZV>c5_mM^W6TZ*npi5wnc6JXp2PqB;PW zJ+ky+R|?uJtA0f@kg}5>A-0+GDFcPl zNSilhGEFeIE!(OKyX`VU6F@5Auog8}9yL5C{)HKIG!hE{ToSmhq+yv+X9zF5fyG`? z)BiU3z2UZ&&ZmeC%8Xm?=NVj&SMLBQWqFbwnN-}Y7j3j{=c$j{9-&L;Dc7Y^sSl$u z0YE$5&iJ1FCS<+7Eork4&`mB$SHJ0O-a-(G5Z8Mw_0)r`z3sITEGrkkEQ{}Ro@2!n z1d3>thkwVpT&Fk)@X&`f8i@J~y2Xom@`}g+!?AvhbvK@*wtSo%YpHKspnQ2|gNF^; z!^zUw&-;bj_%Z3Ey+Cy+G`4O2XWkmg1%ig(OVl;iR*E?8(s($AN zrewV|p_Tl+FrvXqTs0@V+W4ta-g+VXH5A16Hnxxq(Yodt@JH@TSyTZkD}j<)8^H0L zb+1wt>Ejzz8@{0O&p~)!#E~f9FD$+`pkt*`5OsnFiz%E}0F^Xfag7f_mFj8ZS}Eu8y^ z$kkqlo2BuZp;q)Cn98(h=uR^>2RW2O{`*qCK8i+N^D9)b!;6 z0YA4_G+j1rfAYYkIsgQKDu&#r3#}l=@Nof0rF5WF?5!+kbP( zGSfyKZL|8wWJ42W^wNep!F?%(T!|t&!?U-NjTr83OhgcC6UzR2Jh#t0G2)R|aqm6L ze8>f{k1zv|Qx+@12bf7knf7DVm?9s3A6ss~Lrb zbdiUMRTv-lvN1AZ0Vo-R>>@dbw8Ov1OSApY?QhpIn7L|)AGZViwwZCOYS~Qnl4oA_JTsHrG1gOv?_gYv>{b|B zZ+A=SF`q)27vtzgi$0Z}66>AZkWG7oZXEV)g)BZfZ&Zlu$z~h3X6E;A?d z;S>_>;8rZvj5T9*DXYn^^=QaN7`LDah77}R|n#U zCiJ7Kz&wn2xp3^Bbn$|#RYl!fYcZfA0eYZXR@RWcaj-I=I6=X)cRES+f2Tiq6{RC$ z041eiT4c6#E;Ppl=#UaVDjN0F<|N@>93b?%VWAKbU}bTDPEO{b*d?X)MIcPifJw** zM0@(8&5#I8>9;D4i$*ub<)pYG97qx{f3OSy?&$ z6RM4gje&#pe?YaFZm-Z{Z@S*BnS$eNwm6OcKdmi0CNYLn_1}_gxAB$tljk|-!}1%W z$|Kq;rrC5EGcizjYiCAec@c1Ipl@Jo3RoUNEyd`>)D(=Ksi9v%{x3UVv^MqiwQ#hy zKQ{nO9tA(>8Gyb4XdNR{W1j+m@D&bsHuW@(Hoy`o^DisVl1-E}jSWpUz{Lyei){)i zDgZAV8=C-|nVKlsYHrjoaXCN$02&m2-_!!wA9w}%rG$i30C}mgNKW0GD?{2g$#W$J~(FXy4#E=phh!H%c-06yqRZe_eGVLToYNHW8)Zj1L zT1X$@SL0i0)2%86BAODf);-Kz7GjRS$`Gj;LQ%56S4wZT=D z#i6O=P&YuQVeuKI{PorpvHODa!FjABE9j!H3T22;0V1_Y6xu^K^#o1-PUkJ;jZ-$8 zUg7O)`c-u#u0(KjOhX0?w2(%wQp4xpdX_pu!)=V;<{qXv=_oa|wN)YMrT5vQ^P)fm zQV;~|R(LL7ZIPk8;Mev{4Pg*%3M}L;apBkD4zV!|rLlqA-8QWhBp@KV#dmc9js|^D zdU(E+ZW^KtR2H$2dysRr_GRS12BD8%))UJ_G1CFTs|SbRh2M+)v{PGbqXDO!@!NN8 z^>!ExX2tBxVd0bvlr#6EB==di%O+44_O(I1o8rPiKoF-J+E{sYrYES9B}U00$_D^> zj|r@w{1WZkjcQ)gg?O(tBzrX_xDXiEZaeU^wt~VlRp`x9-*JM@_XZ=XntGsa^KT-3 z7kUxc$bd0xohNj1-|-)kE1_hmeU^yjAzRdo=i?GT)6e(&e)@UTe`?Jg>(W5H2R4`h zAq1E@sp&kt{OAf2yb?V#FNZ~lwwYq8(=`OnZ(%||^kn2z%aXjay^ArLb9K6UgHtup zNT~{Y1?MX@jiaZ;S;FtUJG8{4wnv^GH>Dq)5fuvtT-@K2yB%s__lhrq3FJ0V?`>yD z+R7GSNIt2RTDl^aRmbBcBH$6*us)k4sxdK}$W)%gyMY$*kl~vpnDB%<2<3FyT9Kzw zu??{v>OmWPl73V|Asw{3<-?x0x78zLMU*Ng2A^(U$hnDA5!McYTLD^`X{>0=;5~NM zKmySaeQOEybR@K`G)<-{=8VaJgbcgWtl+a9Ap99gk6h*!SpJ(BE(OAOPaMiIr#W{Z z4ZrIH8;9oIMSy#QG%Kf4-JYOqs;QLo0z@QAU4Krg6vbNMn8VeYDKsNRHuEc-g=XDF zZIwJI``tgGex*?w_ca*xN5dhZ=Biw3tC;G_8>#rfPvuk+@kLE%sE`9#YW7c;r+@(j zel>B27adW!z_jT$?rf}C!@PA_B$+dK>#fVu+UESVEbj-?)l%J$AzkcAvErGKgo~Bl zJ#sZdQ3kq^5w?#)z=WXON$``q&aOHXx8VKo^qlrMJtkqnZ*hA+YMwlgn19q(Lvb+i zU~3ux8_$$L8#R~u9ZGn{i>4)`9-kSN00b+)O1phen_R86yjf0R-F@n$Qw(ICul^Iu z5?$Y5*Z~(65w%(~kz(HTyei}Fn*@0G2U-J} zS(sh~-VYuk;ShX8c4SHSaz$Xs15=2PF2qu+PsNES5(NvWmYUNX=i~z0bC+uDK z&iwM7y74XPI^$|Tbr6hvz<)g|OmbRH4et7Jb4 zh=H}#_Gx?m^2n3g%3cT;S-5SXdE(N|s1OFdK)iCY3>}JN z)xulmsM^&gPJMsn@u=o16hi|DRuMr&DuVg>-|h?kGt=rW@RwZJmZIyubYhRV=#c3% zE9IFFSH1_rw7uIq8L3$1XUWtT0K6c869*X-dFJ-AreV?mIcz~DXmm7b)F@Z(<6>bY z`Ey-nEkXz<6EcwC$z2sMvrlv;AZOM zAxY-BR8FEykEtvuzPobr2-wuyFeMGBQWB_Lm8adH&5TbyAIS?*DZmf|Ja-lCuW#?M zm!+6A5;els6ZPsMx9Dmc7)IOP#gauie(7(AC`u5Oy2lz-mQtoKd&}7r;=!gp^>MuT zwI$rC49n%)ppY8fhf9S{L5k3A|B&1OHxK8F8J|8)RB)Q=Fs+Dt358MWPwg6b_}-Fs zQm18oq^ggdP8#L|v?)gyt3CeNTU2zbHTPTvKFpQ={YhqAEKzzC%3sQ@GDXjsVPeKn z<&KE@VGW8(SpcyD;~wTrRRJx+e!+&2jdNOZI3Un#PlbA#hJUPhOAv+}OL~ncwS^a? zqJ9hdm9S-}UspX6a5RBooQD|7|ANUxCef?WAlYtZYrTZ86FeL9NNJ|TlnlIkInNOY zC~KeMWslfVCNr$4HU_ zGiiS*UU4i;oBB9RWI1u|TrnJ;^7ypvS*NsF>ecB6kcn)7cb2%{ux0c?lO<=SfchqN z%G1@-vfgW<*~V5&CpcVE-c|5%b{+;f870S@m)mH6VhU97k72KosrFQ&lzp4R;RLV&~J|@eg>+ol_}LYk8Ay z0`6_PjEAS%sh@TBhdZ&crr)2Qt?AOv40Yv&w*)0mG#G4fMpaX|HFbBKA!DQ*F45rAzX(WYx;5*l zXg_rt_J(K4eKyRF_nKqlAjbPwt|j2IMjH}uS`;2T1)Un|G`KQ#Hop)>MDI2C1LXvG zP^{wkxV0~69z7%SPm6b7(om$V2C%Eba7^xI^Viok!CHX-Rei`G`;j@NdGUVOvo9nL z!<#@(rGxsia{}d2o*DC1vyQS5EhFiosJtFCk3o2M@fhRmSe&aIy7%n#rOiqIbg|=0 zbce?h_hdtI?{C14BSsyc*y?ghMqdY?&`5m?K`y{yUN8wkIU&I{NJFZakcdfD<>Tm- zPCb$_^c@j8FfPL+hO!kKh{Ncr;=?@R@>;b=K9S15w^AFS73&gzwwuWTV3bS4*mg!^>{;rEh+ z-Gglw@Rq~H{v}asRBBuxv@EtE{)(7#_W{xSF23G*ujfU=iie^=_FBx$0!+lbtzbBJ z;-RDRDdeo%4lNHeyFXb(o8D6U+PB_Z_6{-Ys2otN1R&N(1_r(8h|)w^PTx$xtN z=H;iNKH?XsLsd=;W|nL-QG!+dI;5&`xN>W1wJZd$96dj9b-JJdqNjO`>Gis*G{(H( zRP|hyHjfC2SsZ-Z@rb;W|4XKs?C39Ri~hr+`0Lp`l~H)AmvAaVRH?wus)Xc~GLf~% z#1LO#tHnM-Lk@KmuJR|Hv#QAcIrb`B!A8B}T#4PQV}Nx`q8tWNnMO!FvAuS~7dcmg zhuvND$N^>}k|7o2(@h>Ij6da-=qi_+8`|WlZEE=x50rCJFSG%EQw~QWIG|`lhY{3S zmhJ&WbWwZ&?ZI9i+C0jH_+}9Ip~69;nFLNaZ}fv}CA1cCC(qK>5Gy$kI(Z-hZ=Vv${Nj4Mvt zJ^XHcFkv>9rl!pclQABDs;HKdXznic1r3xxsXWVmHxQh?D7GY&M-DZoF#R%yP4O7P z>E4i#KnqGu-+sWuaOkBl)Nk2}-8u^OF(ll9*f5J0DH3!&)Ogj*OiWX#@yXAKI6FFY zl&0^uOfq4bUtf_SyvWUt9hG<-*2h70ezqbFsZQ|dvJGK_EDL+0dY?ZM(C-Zt!PBz> zVHk1fakIblhh05t#Z4Cj_Z-od*DNTk^GwC)>EHi<;LX zGP5Wm5K!5|BXX;-EPRjtUo4vuVNsG${7*UR&Qxppty}7Jo$HamV+s(-4rI5t#L{rQ zh9dIB4%C-AdjDVXm96jHGweYjhLa#c7B-pZ)&1i0(I9JS*J_ob^etZ1%%jP=B{HCk z6xsV5rvmOjGc3jnQ`74gNaLU=kUsZvWtEG{ZTWp8Kxeu`nqhj@_hIDfB*C+j4G_KJ z95z$oL;mD4Dhps2Ju^59SJ@yfJ=LZNIRK2abR>eF&`*Dik*Ihvm?}1+qLqIx0VNyB z>0;{sA-7&fmJ1pI{^l*1GlskBChD4DM=r;C*oSpRhx_M{u}Y;p*hDe|`~!F^t`kJA z73pbg=cQ;fR2O+cHh&#dLf`Kq+8d4oWzlQ);Mn2(c7Ta8#>8ii>3?~;8HwhX*G~TgSRGa1d`^JsgC{j+zB`W5Gi;&=9*MoEJR;#mqd#Vc;btwURMf_EKK8tiP0fnzQr30H3o8GG*a!eBI{~qQbo?6%_t~)>us8k_D1j9(XQ@ zRL{#sS;0*1U_~aCyXTd;_qed8A3EyhVrXi_3|r^;u)$GhMofNP+AmSn3I9TJd(x%V zf?h$fMQA!bm&6;t(wsoE;xX8{AOjBmYl`Ai8!j>A7FaRuwdKIQZA-A#aJuQ!c$3}Q zNlLPsc6m5)tL^?~D9OAjw4Wy;1&DPP=jh~Eg$3RTO!n5e# z3-^)Gc9GTNama`aS;%{6RoJhLty2&{D1wq!^qO|zg2SEfwy$fEtMKTex<9 zRt`4K1qLBUaw&L+;yC4{3_B-Sn!J+HA^7IdH*t*iUb!p+BC9|7<~hl_yM!8NxB@T+ z?TxhcXLpjg7Yg!Sw^(6qeT3a}4Wo2{1+e>8B4+H!J7a<-G@I+Wep{p_9e7|UiTu77 zO1l?d<$>NkGSwwg7^<1}0jO^-(nmPH1-dZfT7;jfymMCovy&+F)zgIq$cA+o_xt^= zP-$sg7ZCabjbl9}&p#wD4Pq?|hHl?2)3RVn7u=OQtVUMNl-qmn>{Ml?cFdX7J>i|S zpluet?r9^M;|`eA%BQHTXsUpAVUFO-aj%miy`emzL4!~o*w&%%1RJ2DCvLAY!dP^R zEhnnyEXEt)iHTOPK){v10OaS$C6*c)8xyGLq~GQJ!twIbARf$+Hd1KE z+(lt)MnGRJ2Ucs#knfxL8{0V0FC7Ad9qXXVfQ9u*u=h*neY*#j1s*$c#eU<2;#Bz; z_@YvWD0&PqUcpb|Z*NEn;07$~sbx3ICcySX#=Zz5G5 z_Z5Wh|BYm7fo>%t!D6YyeLg_U!NpF}6%~_h0Dl)WyLgn3I2^NT#md zeMCOoB&eP{_ybvXoyZpv+kjem;V=+m@YF=H*_z?>NH<1_F`avMFRF0h_(D=83aK>@ zC_0V#RVBl0)NoY)9J|8iNAyhP7+yNMW;>8!kkNoOX{eU<`|hG|&EJws*&+bU30WHU z^NQ1$HZ!u(3|QRQNqKA)bh&jIh85c4=`N{QB2{3hb#6Ny3_h2NN-x*(V$lf@Sz>L8 zZXIAkQ2!BGbmP$_#=}Gw<(VA1*J~2lXOfN`#xs|=^geB+E(Z60=J~=gh0VcW(VTaGhv>6dV4!`$h;rG%2#ps`LH#e%Q*+!F7IeX0ffw%0}iDVJc9Z6NbGws=^pExf1El~Nx zTMr#}%*AKIB}(_=yFUp*nlan$PQNOgGiyv=I|o{ZW{K*olR}E!?($IDVJ6c}*Wa3s$-4;9cK;~K5mc?F_6n>*VJ_I@!>R-9X$UTJbBKXNK zMO;De5tVL6qC1NwwpUS&7M}Pu)PX9B58bzkqc-tD5C-#{;@@zL z=x{Ll*k*zl{4qM3yw8Jj&tS};zU#ce^ZuiV=;z<0=PjBVG-{Wt#)ium4rUGV@le0y z^{@D`q;NjCQ}xL)p1IMZETztQk%OrP>bsl1Zj?;4?TJgk>SwBxKyt?Ml8CcOIj`DM zfV_N|<~wfDVWfxAQR=lk83H5OyHjJDWcBP4p6;+@XT@cU&$4;J541t5gP{N5`_$(S zN@=Z)>!=gc)F%^9>`~W05}R;T{zkN^Id`Qh*1jr)?k=kkeDSjqhFpeNFR4PRPAo%-W)}=;7}ri*b98c z8Q~i!&iN#Tvc8?zYMwnpOeIHKt_~d*ENdUqlT;9ia|YRqB4Sn^Zbws81L3HboCcFa z>qg(xEr5qVrI-UV&Z}F1j4O7ZhDhi4?X&!I0?YLWJ!QSD^xtszA!HxgeG9`&0JB`O zJCdmjGJV;ZXh-Lm>@; zN{qfDI1aJFXQSjDC=J+OkYmHo`6p9d1pV=@FI%AUYR4;SQTwc);H#GJM|<s3e~N}?!L1DJ~yv<_aY568McaF;0x{@#iEr@djz{0oK!Bs(H)6l ztpqPc@b*DfeNs7}_we(`BU6FLOxEg*b5$6~^7|i;&(7F2(r+Pl_yM$eXaaO&NxSnK zhV!`H|82}aX&mXt;U`D)A?cs}^NE8=(J=0Py(s8OQ4(v%L9e@VTlCPUKa>~`izynA zk$+T;_V)-JBEO)Q!aoYi20#s7QvvetB~EUG58?1U!;$Zy*{i4wV3Qw=r|$ExBxxqW zd30C6#?~dh6X;#ryG>jZX-9UXD0UPO9Q=vbO?Zl_5|0NqpZY^PeBtNX zO^V%{Il2rQ*P5z67%eSXH8B@(+mbBDo2%M@Gl;Et7lpRAp~V+JN`{d9hwWbv@_g-6 zFPlKL=ot#7ojgv`$hkt*Fw#QHtD;%a^fFjlTQDL)$J14br4`v5nHOdflOb>P=m5OW z$;cz3wfZS&@7I7^r+c$-WQ9!_n(fcN-CGS$dgL4lOJHRyhpMRr=gA0p*9{JQj0~J6!4y*c_1bKq+~AI# zVL**|u&|ldbsDLzZCN~KG&1?#DeflgFr3LMtc>TrOrwTSX~}5heu6iyKAXORd7K_V zVofZT9L)HsN*DP)TaO30w8fHTpyHe}*>0rqj-H;DBY`|EW|XE&;nT@JUqd2Z z9&4WyEP^6BKpe5&HT*E#CwY&bC$=l%IX(0Y@4_As*tUJKx?Vdv<1k65m8&|zPR!7v zHeekih2)eMF&cv5QRttp1HL))n|xs05*$H^c-x#&TlvSnAEX?Lwgrb#EZov9oj$1)h?$2{`I6K@YIBgNN(hTr!Vai zWC=jmbop^*3=Y&q=IvF8Wp=8MoF}s}LsJJUP6%rS4&5awZ{Eo1%nHvRx$yVf@2-fk$DC9 zIF`DSkI_$dKt-X|?5vbPn&eHOc+u6&N;*ZJShBJtLlq2`r$Ig;c)xvF4%KG0)vIDr zX5mHffK9%gb5?PVr;5q!6SuZIj;Yt#T_BU)5%{6`|6q!Pea}MUSND!+%YB0ugXTMM zPKysy8Jik8O*5@{-=wI!`w%lQm|Gq-5TlS1p@`mKd&zi-J9BD4Ns%|hj4wc8GPw+_ z2x=fw!GyiuNV4Yq0fmTwVX$P|ym&J^S36#l7`q}7<6!t>skkOK?TvuMEGGbKYqp@U zSu-bSZD#KhNP_|U=`ueMdBKE~)T2k9$T zJ=IL>dE1aJB)OhSz8odw$AVmP>S_UUK7q2Yzrw|2qsiq`?4$g_p5*m)iF5%Pa0dx0 zSyQ4Z><1@iV4;!8^l}9?5=J%)0%Ct`%YY;)=1Lq`L`@1aEN$#7$AeStkU#q{7qaa; zTw?O1en`lIevjP-#Kgh$!(d5WabZ2FF3daA!V+fvXoq&m{n1Vd0(Nmd>5!Mm6x$Y~ z$w)~Gj+4A`;XCqO#cbw4Zr8C!-wyo)V$F#TcMifQJq4A|caY=}^7i8r*A#BeUb&ie zubVt zY0@`8q~HJ^Yp&Hi)=rlo$h`-7-{KNbvKp&M$G};O0Or+fawX_pAuEjw;RIY=PCvMT zP!*zsUIGLuf}{4>9CcPRuOa~b z$JKxeIV?iYDE%xVsKZ1?atkgYtXbBA_qfc37Lwlc>0cW1_ciQY9f8Ix-hK7OCUZ~e zM^i1%;&G1wG6kVX#L!2`)nifhkXZEcFL;vYTK|#{o;GDIh2Xo*b9W0GiFCXpGND0M zk<~fo>_JOVh#Nlh`1M;d8s%BXiQinfOj|)t9?3Oz20rIed9R~y-XZqoA2{H=WlKs- zKv2gP7z7a@-W-n(a4yIdeft##zxj8jF#N4%@-jm5#ZsbJ=ZLfy1BycQ&0?);iiJ{(!>$&hRVtFuvx==Ce=BPe}j%zHDBM{uYX9DdSY9&?f9QvRd zr$wqdp@}tYy8}-Hi-)SPw;jh1>tlj=Ju>-*aptH)bjg5D+snron}~|rx%fK`L)o;- zB~LIR#SE}3Zl%P;xyUQis?I+f;ioPHt{1@2jXA?~#H#Fmn?MPmw6mUdGPHfWuVY4* zh7I7m@7MT^a9(p^%ln{JOe=>R2O>c?xY4A%EW>S*)@6DM1RY9pVYPPtQmhpsvw+E5$ih zbk?QN6vmiODQX>}lhUCHK6T5eRF94|zufssteO*!*6MGT55U5HLwrmC)B|Dr3$qeJ zTthw`2L~x{#2TouxS~=lobMx19KAL0I7FEe(^|IYZ-+|IOXUdeT97~0WQBeUOJeDp zZv*|^#H&x$EYLI#(cewJuC|m2Z44@7R+x~v0ycAx(@_hJIe<^aeVn9n3bMoIc?hX> z-aj(^j9->?^(`^X3$9%EkdTT_hlA@z=Hu%jL^dD87uhZp-4HAQBO=guEqYzc>%0HL zeq+~J(TZs=H@9KfD9dgEndPd>Alpj|AilHPT9vl zRHMOfsELwT_IGpU9ej_RH85Rxr#@6tzTWqkIjOGR(mJN(Mp{9#@M!mn(B|Cmlb1k5 z!%6UF-BtQE_B$Sk?kcVgQ4rip%6vwP5~7X&S&Ij&MgE~=TjSY&d;_t=SZv34VbSWV z$eWw{DyfidA7gVxclp|wNxW>|$Nmv>D2$`7pkCm8(~gNylVr}La(`@87_48rBo1|98fCJaBt zHVc6$6W-E092hsflQ+_ac3FuVW@KmltQfJ?<8mDqBgTjK;oKE5P4?3uzfx@LUK)b< zG`#QD&P}Z_PmQJNj&U@@5*sZ=j|$nt$@bDN4rOBlKcU}me$Hh#gn;#PK`qb|f)D7- zYcQ+aym_YxU2=!NGlWEobze{bRK*ut-*n6qH*E+A|9Fw~pNj*}nX9lZxzo~6Yh?-T znXcKyN3T(xJH*u}f;+oc0?Krc|VSxLYX0GeGLKTq7U$sBx{L_tZQAo(#!Pquz##z@*+r{y!6fihG zg|)_r@AiQvzy6Yz2Bn(jbeTKDJjU^L+sbTUR!is?(LA1DA#t?;2c0cqNOlz>U_CX)E&&CFusw%+&_DZoh&Z|4cWbUh5n@lxrW({EQ z;C+()y9Ep#9jvIz#)$Nj79eo)?%XGXR_+N_Qii(~g*2*3#~e+cRqat;2#ziKy9JHo zMyr$siqSGtEgJ42({Gc|i1I>K;+LGaW(UV;WmIC8_2UtiJZ^k=ZaO!s{&>nevLENux2_WEj{yj)G#Qdrd!U$>cKS0JenBEuXR76)w>f!M^&7j zqcTMjn)2=)XVy8Ip0kZ6`(yVchx18Yn-Y8rOd_SaUvDTp?aFVbF=7S9I0CYQEq>MA zSF-{-arBDQxhf^Q!92^|lLGo{v~vZuPs?B)jxB$uHb}-Jl4?`<6rxAhekfcVQ_fj* z4&r@rWj}|^htKP57i}_a z$@}FvJ+L=fU&@ywA%-RMW}mqATJd`aqfx3{?=+m($t(BQjdB6#Z61 zBjpk%8#!h6B8KTvVj|pM+1KIjPB0}aN$A|dll@{&d+xOmALg(f zRd{H9`UqSQ&>kKxC68N!gcycaA%k1JXr~ahFO3N~T#mWJx$U#TUp;HbGo1$(np0OvPF}O@L(T{U;kT%wofIvPQ)RI#+2$mUt;`HW#_uBk3S}>c+n~*e zc5BKszNNMbXf6s-104cz8ngd>01NwcNPeYDv4i<^IMNX7bo&YESE^}xyc%^*%FU&0 zQSi?_CT{a1IVNspOI1t$;pQy(M{@^>zMqX|pMut(%Zd_)LMy+sNx~z)Fv9^J-veGg zcHRaR``78YtwIK`KWreq&5wX%@_ztFK)An~1Wo&erL@p89NeOq?u#0_`MP@AIv{-* z3mp8jeUxBM5@#?SugiA}ERJW3n>toenM#flp)NE_QfT^QF5RrJ3C{pSz4+SYRNH5Y z?QnB^P%+@IF7+RQPzl5LsUbJcskLJu5Cs$&wR6#~GG;AFgCQ@IDq6iQaQCu|j!%3? z4wAd{MR|I7IQ5qajlLNalQt%i%!p&^^pgM#Vb|6bXL+E@DBlt8bY}sl*M^l4q-nS` zL?A1sGLq;=>2q#@7u*YPdSheI`tIco;0gjbFg6Xy;o~cA@ThHi#ENaY!#|!5yH>rU znWTdi<5DTH)wf3nNX#&1`ud{gKz-raqE9d^>R?dsONMsIlck)FK$es2HvBNy{^KPn zq%dZh_I|m~t7SvgmsCB1!3dcqA!&#zqp0AK92-vmHogy&eX5~f*F0W*e) zdMa#1RIVpKOUl_KnQzn&T-?UZJo9Y0N~3~^l1vip%R5PM0{w?F>0$-V#4{G;-jmoy zG`TMpMfjS2hSi^mCtri*!q0>cX@DQ$pfSvspE??M=6_PWTzjFuS7p8>@FihC{*G;JQ$c6j#UPR`8Rq;Z+*Pb#TDi===Z5YzO1= zsHKbLd=7Eh^Maz7YZT!j`++JtmbIIp8str-*NEuLb?n zeX6V>A-S}nSPYE{jGn4_Nw;72lQOP9fia2#2sa9=4*A|={`J#|1)|Le173q!PWSO= zQ5cA-y}J^^tQ15<)I?ut(#_BkeWbV3E^Xx*Y(v#C$`<%_yF2R61zgy<1Bj4s;BdaL zSoWT^PZ2U9kv68d&c2gsXEr`X(i?ED=bk@4Ik)O z_3{kyMZZSDa3qG=Rka3%?7;8)Efw0AjtPF~pHG$z$u5Z)_ zJ$SiF5FWE;ymArmKA4M$Rsvnft8Bxer7iBNTV7QQE*WiiWXQs&bo-~qUwP7k#qE%o z%rF+gzpDWR_x8DhM)NJd8eTC~1YNG|MyXT|8TC0lKkQX(P$mV0w_+9}`bwMbt;R-~ zhK1kib37=O;3M%pH!3U`as_T^L1*$WLDsvr_w`f5czq3w`_`lPg^-~UVl6GG9VmQS zd`;NHhLw;x8b8CTzN2AVxj#>K2ug)S=0WP5UWK8;U>t{wMHP6?Fu$f?+1s${BT5`e zf3p&W6b>azy8DN680Q;&-We!oU3yVBSZNrrT;#?$5~<*-xg?v?THrw@9&N%v!tX5S zhbsceh>dBzliGI!LP@o49kK1e^lG>vuIadg#%q_u6g(GhMCeq-(4#$ry&O}lO}Gb$ zMQAP83AXyc#}?l4{Do1Tdw!7`#UyI3kPR4GB~UCxtFw1!LOMKbP#F#Ja-x!;ip`lw z?_8_EfY=}#RWEc;#62D6A`e{P!wTy!2*Y6RRl!njd=Dv-rtwTzkpitUr@e{G`7)-O zRtfuj+wP1itsWM3XHVsJDb*)}Z59{1+d?2=CX>!UfAW&HdR`}bwae8rn5w>5q(ZQH zmhRPeeyb&Qw6zk6F8-b9% z{9>~AE9bCB0Vwt1OFj;@jqcEqhTUhsGG{&OLoIW?YWb?b?eR0Gk-r246+PQ#R+L76 zgVAL~_5G-&k_mQ52B}(uI2eN#%UnuvQA+L)&Df9>EqNtYU$#dJo_X60i3p^xdi?&z z!NhpDYV-{lX|3Djv|_Y6Ss$JT)4Ays@23(ZKEPFW2aFldPN}Rl=(8w5@?F$(sNkeVUA$)( z#9BE=?2Ait&+^bI8x_;#9&(0EdXq#HB|pAE&r~qq=bhCW$=^x9bNt(4Zu<@y5uW1wEXGigg4htO{ zQHeq&B`ojH?$$Mt^lWW(Rj__>mmbd)@^b|ziGEd?PSsgLI^pIF7{p1AQ}Ik-*hpg9 z4HxEz`c>&TSXW?psk9eg&Y=lwam;yn5?C*ef~CG+vh!RG?A;V>^eDfo$jJ3Fu8^tZNQA+ z`?j*ly03pKw?PkOVt~w7`f69q${l*>9%Sy<=huS}iGLaG$(y@pc86QCoS6Z|>KIo9$=nKOL&Ssa0wf)4?Bwa~_2;NPR+ zQuR&>ZZ)?@I3>>g>5gnL_h?91eamKe`L9#^HzAZ&%ZA%aW z7Xlm(Ls*gld=D}OAF^nFERv9Zn0kPD+&>oy-R5zSlN@L1!q?)Slqc%_4!WQD25cH6 zjK!W`(U_yp$0YBbOrov#=A=6t^p0TapEJzr%l3hd(oL`h+6z+BOs!;$VoPovF|XMg zWA-xUXJ~5O+3Kys_RO%K8{F&mgJJVM&9HXv-x8p}_I`jGb16zdhdr{Kb-1_Ii8{~HxNoL}y24P^D+$s+IQ z@vl_}0lZ}M-?8QWD2J1sB*lbeVsK-5!ryN$>Ivz<@}@^e+W=^N?+Q<7ygzbfNSH~B z`==5*`ZDIorPHZ&8aK#CDh?|nNPCv?a>3eVIJ%hpswBIM$3XTb+{Z;-=Vmjc`i^k0 zx$;X_%gCrbye)t83?IdXj+RK%y@%=<19X}lxNlyj8pCrsZeqy*S_ zYo3fK+RWBtyj)?EqzV&4bZnMv_9^~U(7F`SVqvb8FcGx=coQNG7q4(zuMav$sQU3@ zRJ4$ZR-Q*^u131}1Mi(mCefy=JXQA4zig;F;$0jQ-Z0S! zgDOmVW2o7#n{d&gs1CKYiEk8iEzRv;mU``_zi6@8p+kMp0KM#Ep4D<45<7#JDWBQQ zBP@KVDgyNo*D&Ct1E?$+@L4~XhiDVk@{y{}Knjax*Lq^cS^%VXO6lr>InAtEqCv)~ zuUZzhB38||l^@^YWHj#t{1TQo5*FU?^pybFNV}ogl*=4H55Bqg(ZK~AHblzbJ>)V` z+fs;>`pbaTY*~BP!a9J6)KwB~D)pS6C_!npyr*fhk77`jGg{SE-3eH#v=mC=@aAW3$o(cZ+_K?+ZXE0#RNvGDUAmta zN{{mrSwk279Be2^H*XQ(?-sf`{oO)X^|}oaUBa@vU@De1d!mM zDZGe}wtLi<`~vLLKSzt331xDr;{a*0dka40CA(_Fa=ZKLkXobB4R+ZjE~56;dkpFo z1nBt1@UzSvhy-9_7Qnw(6O&2ij~KWWa2@zKR2n&?@Spbi&lmR%JHJG7hYD}5 zdH&{z%yNoU$}l>-560T^l!gc3BBN_h_U|gJIzhMa7d`N~9MN?Yi*ueDtr}G+E!jPl zQEeax4R^xSIE+q2_^zrF!eF-Bh6osWc~4^=lXe)eGPL$>rRlmaO=V1iM+>;9r=Vr@Fa*_HIddYn}M zH-7x=Gy1vy&49GMYXDl=)FzW4>u&Mo_d$%-;JIHq^1WTRxC4iv;oMhiBgXI*xhYBx zL6SYO&0^Zu1h?ifInq`kR-K3bGb?0V2Q7P z(~(D;0b4co?Ff7y8-nQi+4ewtUd4YBM@hOe9e<%?`H=*UZJ2qmGe&H1g`yM-ie#qB zdm@&3gjap?qdP?{C2Jtn5&mjPixStryC>G(2V?C2?vzT_x?%j(Z0TV1NIgm0jeCI+IkTQ75CcEM*9W0`~Nd2nG&up z@8Q*A95$+FlLhkh|GGmNX+lzo{~}UR&C*#U*v$YU;q<{#eT)7kT=Qg}!5l*{A|edW zAzR1W1KE2d5|gV*iWU5@<*9E!@KZMsdBN(%Vd)PzFf2i$YouNJ$g~7_+w9sa-gTT} z`48!bcwb^Oe!GfhojX~EwGR`sD?}MDnba9%PN>|dyVBC*{c(no{@$1ZhUvkP*U~}L zP44G7;f(%WoU(Q~)n=)ISaX;MA9JVF3GDUQeGAP3>TDg+OP|)tg%x;~S3{!(JY2up zaFMBK>EjHwmxFf@G(qD^O{BN-pQ~n|x#8nZe;O_LwaU<~<|GPgorr7?GW&%Zh0WlX zoqM+^i882dMcS{*^TlUnA)dfr$Oit4=vjUNlRDs|8a2+O2PoTk{;W(ZQHhO z+qP~0W81cE+qUi5bM{tk)!lbUQk_ovlWFG&R@vzrX4ia!V<&X#Ea*L#O56nX38qsM zPIA+}G0c`(-lt}E#IP#3p&DnGdDBOHzY%SZA@I#p0U)z{1Nnt64 zczM26qImC)o1sxpVWUzxjeteBUgzO+TIF$sE#EHEzUzV&)51|7h_ z8CmvG{=Yg^6Z)9kZH0iY@i_=1?lK(werO`!XEyV^)*nPT=^XVLj~?N+eM#n*mdr!sno=+#um}+xbJp{jNiQjPd8i^1aKn$YADYHxquBod51 zYDm9*gviq`>4>-SE^Z`E1ZlQ>y$La2-tCcpI;__eem-i%Qr$M@$@*b{qDOO^eU}th%E3Jv03GJ^jmPm|8-pC8|zkdQjNa0A;@J#DG zmvdihTpOiaw-1E}C{{)NE2=aq`;R9h1-zHE!C9;u85W|y#hc$@#r5tJfME|fTBo2g z&n0)~vDz8b)0w+J;yAnf;JW*GOaEXG!m31g?e{HxY(lP&>9{G=EpwQU#>QOGYCj5U-m zpCA6CDhGMPeqd&~rmiU%k5pfzfRv`0g@acuOT=dB94>(ONNt7+sLIuY-QEIi+Geon z9*F6SQ1QAx*-(>b?S$(RuQEjPMP*tOclttjZBUAN@5l`0^MLohhtZTg%Rj{+b)T>! zt~rPam=n>%pN@u$^+yklpSe|hGY@?tbB$#QM0x(e8FIBnw5L)hz%amh=jo01_Oi@{ z;3&3tn{hEfENmS13*4#B0iwlY$*B|#Q|D-_BdQVLFpF-KEzS^|icj%D_VXGId9bN@ zV`qjHe~qX>H`c^VDjE_Ye*k`9*2<8r_X`GleWue%A=;ubH_$9csF$3=kpxL9(qEV@RSHc2`Tg-ou2m zko%`eoDj|wd>%n?HiK@g4Tw+>sq6Hj@-w~QJoQTKhx?y^t95Tvnz(ok(-8uLndz zJ5sLZg?zjImare$-fzyU`U_d}oIUBql&3*aM0e94zM{#bHN7~C=*_da07z|4V&!yE z&3r-BU3}bXXR$$daw>NQ8ZyVGq7AO+P`UV03CDw`6jQBUIsPq|M06XW8lDz$4(KSlLm|e(nMSQ=Jt0x>QhFW%=`Esx<^zYwBw(_^7D(=4Oo+jAVp*WtAzgeM{8@f z2o>^$0gQ~@+Y{2$5h(3diU?0$mtKw*?g)aN3$mTBsROMDy0&rhoz$S^`0}5vU1_dq zOF2uhd;${Fgn9F6#r5!>cphrd5Ii^8b`n-(%M?E>DgmHE*UkA5X4I(y4Xk;BvI`ib zZ(O^lgil+d1MytU7G3aVEJ zY5l^}EB()}|6Gd-vI;sujyvrCY8wN;vGgMA9eFI;Q)F}0@ikI(1@T6<$-IFqMTkek&Uj+*7u-cm)4qZ zm|ZoVwrUrWVz(@)T9;)0>wYKd;{#wTFgPPhG3ellsML!0j#Nq<+t6{g&;l=XEvHjnw==oK^t&0CMfVEQ0 zpu$qUFzrL)&!ySV+AtEzUm@SE$k4dQ1h8l^D%IC`8j#nlwU9eV%pV)#Uv;AH z=+ujpKNu^U-@Zn#rWF~_bz^(9@3Vd>R#t(2sk|B-Q^vZl1Fr3tg4XRme`)T$HA{sq z7*v581R5Ri2w+&%Q1g7@6xP>G49#1B;# z@$defwcYfY&;WN(4neij9_by*7dFYnMi2e%rgPE0yJqqr(BMsDN|Ozi!&@%CXr2}s z@0evzr-FUmEhEC}qkLEuv*F^N5}}BAM3lh|qZF`~J6<-{=!}hR+=lz_@5zVp=&`Ld z(qnHS1YN-e+wGw(*7B2XqyrK+MZe3{+T`FoXqC|crMQo(lubHK0X#=^ir2DTCVe7M zecM%`rY8}qe zH|pYv;?4lLpaYfVeDRlt0^4~$@adw~SD$2oldPByOuJ5apt~+Lw*+^}uE-QeiJgEV zT)_pzU19_#^KBs>JqM2J^Jlj7oTeOA-D+5Zagt_K&VSdN%&CSx6Ick=XFY+YveLfu_Hyr`EC8yBhCW<*X>71(b%;CmgzbSZ?0SR>6ODrIZf(J7D^EGh7#Fl*|B7D4A3bHTBSr}f0tfTI5O*$4z$^eT}lIhJ;LSjTc|0tAgWrXQ(Ze$)=P2kBc!Q_4!Gh|e z*BsdBzM9S}vT`ox{8YIpKbskcUdIokb;+^O9RT!_s71KeAZ9avpY-`oaQi1I#M^-Y z^`uku9GNfBXNp|N0!bKxok=9rik%18ff1Y@P2aV{MI;TW&WC@Y+ut0*(tbZsLH1gp z6h0L~UON&OMKw5#Sd7H9#fhF7D>%1`V{ulFy8u>W*W(?ZA+x|B0%oz~?638!NaY5g zP3XL4&50KnO0Avo!L+9v!W0BIEU2XRM1z=wXVgG-RXFY18YF~WRFm1NcGZaiNZo<-m|bCPzo|tccB-8%nS)la$mxAKPC2Nr>I@vxe2MJ^DuxB=820bF(?e*vXR@o3=LknMv{BmCg74I(>NH~{DTL2J;xhF`rS863TmD)F&lWLKtnV>6 zYk=4boo9%V%I=9XwE*zz;=VWdEnt>81Aik4iYrXa1OiV+hnxmhC5?o*XVI8f;y5*V z5jzv_m`=)@x^&?IHr=GIv036qh_@&qqBZP-cYPSO9s6d~&bn?RZ}%NI3(8Vs0PJXn zV=>6}OvKN301-7R5g5T;6@u02Dts6S&KCk*MbUyUFU@qPoh7K zCXA9(y-4=;3Y6RCU9M}9XVkIkvWP*;G@g@inugZ7C?I!d$7`6@tH0^xls40R-IZ6z z%VjIJ$-3x1fA%h#hT_3DM3`td%2vcSmnNCzy)iAGZu|nf%WbgIEU1JG2u&G@7l47b z`YS*NKN@0E{tU*DN1k-K=95O85K)1n!BPx!5GD?=V#m_%HrStAnzSxr+-fC0RP$ki zx~6&sf5=sZh65wIOf!2<2W;fg)~wV71#f3BjAJKva=-a~4XUDmQ}f#3qD;UwZdW(g zrC%(~)E%j(cR;*A`1HjGDXaHV2GqxFc~h*QKe@qee!zM$EIH?CA}IM}(p=?d(x}>R zyEp>Es?V&=vt>ZHkf3ALjeHJKbq?l0*|P(yMqDcDwp~%k^H%ogD=zd!sAxxoR7~Xk z0}r85DN;-%@}I$sCUp4cp^F4lqo7K`E^@!y*Z+5+#-$z{|K?>GHA zG6Lk%+%R@p9E-7QcNhR`y|SI#ah$lCsmu9w50AY9!0b+HJj05AMy9U7gs3*BbnC?# z>81Rn3((pyg5Sd|b#*rBQ5HSac}{Zg0>ytbeo{aN2b7F^njKu?6r2I8Ipee|4o3@_ z$MsBWByQE5IQ(({Yt3Kf8{GvAzBv=tY;%j)D<=DnXtn478V> zBhkjasQ2n)eaJ1uw0ieXrxO27KqGdX_|$z}-#%LwUf17k5d0n64b8xmQJ3PG<`jSK zw^owL>nTgYpSzp)M7j!Sx8Y*VA>9NVubpb8F5di8=enQUO9(62ey|Yj?I^~W3$|+s zP44UQvkA2Z-xdH^G_(Cw*upWvU6p=PX`|AS>QnNsc3A0RQ!H8;{Ivq@@uL}1fFQUV zs|cIt6Opba{7yc#abW@t2FHm`mOu0cHRCUyF9tPXxI^Iokui+F%Uczx7uLOP$pB`k zoDgK*AuCBqM@;g|YURk!uj{b)B>OP}(L6O-5a~UQ{}$2j(RPDa`6z08Vzzt?lD1}j zvTuZh$#E;=AUI7dD}nL52ExcG{q_S$@(jHmKvG4n!a?A)rlI)b=_IP-WX#G-Z)`$$ ztOcIp$JOZWGT#UI;yl3n0fKaII6Xn{nqvH+eO8JH>~p8!t9q(8Cb@Fiy^nXDW}bY8 zaZ2pjV8nHCK^!acE{jvV+$*_Z#9wm z9}wzMOKSNf=tqjqRkTDGy24x}Vd10B6m<}IZhLX8Dz;!51Spsn0qw+m3}=2P4eg@b zl>&dfq6L{&hIGVNIe&v}OgK4Io4MY2XC{^IT=)qG`xLXpxs4U;g2xeVnTUZOAGz|4 z2IWB6@*bjDy3jCXVL^uu?)D-9S;xVJ&Sn61@|0lhMJgUrer)5Xf-RbeVs~u5H|9*M zx>x@{-z|Yci%j0skjI)r698F!$WB$HgjMA+f8kdiMi4EWvCwyIGvK!)>H<3xrCwjO za*U`sO7k^tgF{3BJ!gLOTf8js5l+BI1z_XZBdwV0rY`_;N|?+9H(>- zv^KM?N4s>7-fwFBNbdpxx}qHfGktAIu*L{OOd7RX^?ejWiDWd8Mab*WK{+%zd=F?5 zxT!I0Z*Oc6`RfwwLa35@wI&WMI4XLnbKaUQnP%5F21r>vU30+2rD=Y+{{C0+aYI-@ zFuLO8$a@EoMzIYg1qMK8GYaP^jSAUxoaXKfkKlA8R4hq=MhE?{Dv=;wGvXEG!l~s< z$xRE(Z&XSLSs4!%4;dg)`ys#Wf2T8Uv)$i{s}tmHP|89wPKBc8*&6IUDgs1XdSmPb zXF9MHA4SO?(c+GWb5!-5bhr91(oBG@Y6+>3Ix{MY5o?l~0>ui1H`&6uWY5jK=h80F z)cEr~9lzaR|7@7`2abXgKUTbCR)lw9syQS3ra19-QXZ4Qx-t&_#}$;xyFCZw`MqfL z>=Y*imF>yhz>c`TM=zO&D|Kr_7pRn4$Jg_MP7AuG%^cnQ^rPHisY^me)tV4zCUt-1IPx&&E#C|t-s@a zA>pf#;164Pc7I%HqlHbO)od#po+7!}cn}dlA}P$l#Lc`8a;JUA5m@kc3mXI*e>>6z zVHJ>jiiwh&z2~5ekGBT$EE?)c0$xH89gL3RZ~dB1JC22FlRyA5$2+fnna~IIJ{%`5 zM(lOD+H4V#c-EWoeCssHESX0%;Jy@eZamPQkdj&k-~W{idSD>IYNAhel7XDP(w!~I zO+osvjZB_5*3gO#sF$o$tWI%3LX70OI?Tr)j^`uYU*Cn!xb3$)-gv>buRF`zoXcG3 zw`M3pv<9U}LGbiW{UFKMWdjY8V$rmYgXQY>PBWy9X`nkPhMS8jNMljMMmmORem2X8$IVYb^)>>l=cV5; z$&SrP``}scWf?S!GD|iSTfR@!ojTbq$gQG z*+A$~de=NDqaXy!H{JS?d^NwP2BqnuBWkc^Za(h+Sziyu zk)StaiX8QD?~j4z(2Mn40u<>l!mZK3(;ceNNvJ(t0(`>N3-MVlF6_^AYP?^10T~~L zGLzbq_pgzBx3ydNu~>AGUHH75=6IClMtIGKI;LCtu@=NJTHGChAAMC9Q9U`6(+Xf| zVl&-}=4e4Bk5Oh>_;y^F?O9u!UT9j_8KeHS!#80cN>Vr|+8R9Q15+?E<24ji7RlQB zF}>k;@6mcOQ+eHHUZ-Y;0Dj$6yCE_W_3t5E>qzl#d$8HpP@UBUMUH$HlJ&m@NO~V~ zAwuYp)x0;`nYDfRVw!M;;PtC@o&AjNJ!S5en&!8CG3#v1!Fh1H(p zB-zS1p?bfJQ{PcJ!Bz8#K`c z;EraJmJZEIKBRRM7Ng^Wii~mKdTVyXJ{<#w3D?=``nR^)749_9JzQOA%Fbr?CARqx z9;aUu%oEc${K_*nvG4m0uiS9p7gc~c4pc=bV)#9WOEy64#T>Sx0{6DSF)CUEZ0$g+ zcso%V7Q(OK@7;1L>w0cjN#5SOk-80=$|N5&U)fsjEBZ4dXTp@eZ-!`#O1zmG)0O9h z*%fm5==WE-@w|tu!2$=wp#Son!sxzA%;&@Sw9hVMc;F3PoSe+T)q|R7)Uv@mji0Hw zrl=0aN1T`@VC05@n`-F2qL*D+n_`fuMwLWVA8w(Ui0%KAC-5a~H!yzE|4GJ>80sKh zU#c!pbw9)%P&SQ&>hho?&<(`1`_MErRSIAilFCbJ^RM+P5lOwn@Zp9r-hW1#=8NLm zsaZ_lok>`rwXNYkpys67A&2pZ^13P{31MZ(mnJ-YL}vm+4fU?EIfsh&pB`T3XUhMT zN31}euctl!=xaaX?faDq)z)xAv=2h zD`9*59Q~*4f0_n#QJLbSdC7J;3y-{@RjqC!P1UF{?me-uixKbvu-bDDa1?$jxhHBn*nUY@cJd&4_X$9*HL_qsU`#Z5Xrn zwoVJ&*M=<*A94%Lfvwa8CRr!zXEdJ1HHg7$Yvl_idgmzp-sNp%Mwv5FpX zJ_%Sa{ z;Dkx1NMf+tWekIMhUafJJtk8{Oy`0P9Ejq?Xc@)tuiQ<8U>dqYZmVfaVbGrlreUsTh}KmQ)E zx)vaqBLN!)ruf&(=-)x;HFo_6?lqZg4dS_bc_AAxWAFkn)=L4`M6m}nJ9`h?$I z5`-T7?!P=91+=jJ?{JoKfT?MgQb58*#{rmZrblg#PWE;PHL=gh2ChQxdGd+OFu(HP zWbs^8L{25c#7!LE-)*70Iv-u^LVZ0OEJT*rcXu!R%C=o2nXuA{rMoidXIAy4c-ZS@ zL1}ny25C**vni`#8anD~gQn)%T1!p7z9d}p|4jYt3(aOgQ3!YGI$X|b6jd_{#&b4k zSlH()xt5;sU@-BJtw<5rEhtc+2XRiM`Xy_bb=InE_{)t|hP^;cAkX2+*P^_RQyhf0 z(QY1NlR?b5x;B15R?qZSSNR^f511<>4_Y<#d4-xR7%Ko#2{PnG*+RMv)u2huDbaf6 zN}$-=KfRjAHLr&$8xLh<7eE-s%Q= z{8}X4l%xp{$-TFW*Q^P9eA~~>t;E?v#`v6Iz@7IxLrEGqX5aO-c~rQ(XBjN`zGgtT zH+kqHJ^e!(?XM%z_N_ly_`$Y5o2v^~mMHj;%l11+n~Sh?A9TYtLFCcAEkEXQY@w_Kq* zC?2e(5WJjHxrG5K$%+Kfl-SplhWV>D_xL{ELroY1J?d5o>BvK)OheD+uZ(s0sch8N zg`m)7Is|*$)*MmaQ&b_H$oQ_^#ecnd4?%9S6vR=I{*G^&SP&nEg|}4+*&V0hbe4z< zAyXR7Q$%4lUKiXVM8}Fg5?J}fC)ZS4H16V0w;rx0q73-#MOwq(FrXU!v;4NV?Y=AL zfLUjW?vq~)8Cr1$_Rb$qvGBO2coxpoL@D!xeq0>Ue2Rz@>*dg-Sl@2#vpjhqzL>XLfK7&2_lajHh*| z*XP%zImwc%w)GW$ZwG z4a9)==K#F<^o&o_c)@#fbck4#INyW?@vp;~@$n5*xYeNBN4<3h&5Ke`S#F)qxmT=> zBCPa(2~ghgZx*ZCjJ^y*z$ZtwEE6==4r~Z{xXcEoCa`C%eN2%8ZoYa`Wz=0ah`3Er zKu_MSWbXo7VJ}4s$(-GUw z0qchNATv z&l_4+Jz>RWR@jOtx8&6*D03l$5HTS~ZrfxG7egj*E$#{xqMDTCF&U@$^^5bC@~wJ$x#<0T^z_OZRc-xk#N zEWq29`~3@Pt-8mWjk7yX_}&9juEcp<2%yF_0|tM+>*nf)Ymn>b-j6<+k`VIqS3Bkj za|n1jSu`td15m5+BA7F%w^32pkQ(X>yK-vg*^kzZTxe?j29$_z3t=~|G!N7L2RJqJ z_kvq^3AFhIbyZxWm>IXE{Z3@L+ z_)47ut?A}^Xu}HYW5Lk!Es;5=a<6QI;diJ^@QWWw$x`54GUC(F)|WB#Y^~MRmf_^0 zc6KF(xKZ#Ey86-~ZfRRKC3LVC z{8>C--IMY%F!~3F3qFD0njF*Vwm|Vxzn;gMhB~~$j(PNimv^yDBDCJv-3mgI1$gq@ zD+ZWor2HyrRr+};n?dI>hmei-=I)Sb5f|9>_vig8k7^Hc)&%-%~J@BWqx$DgD6eO7RF?SE*MBLre(qJ@DIQr=Y0wfj$FW1?458s zB;OU&z;GtxG~_2_BIFrHL3ZHBK%|6M zK8NAfbjHv~Ki|PPa}V6Dq-Sv&=^#|_FQ|fN(SO_bty;==w~30KI_R2%3~&XMtt>M1 z=OD+|+$bd6*Po#rl-1#^B*6;>Bzmtk(*AnVBO%XB=T6u%q8$tg4;cO8pVn2EVNRf7 zF=?kj_p3WSZp<+!+&|jT>@QVvxL}F$JPw$oI4^8NZ@(3-Q9RTF=}Q!iKA>1bT1vHf zabImc3wJaB-1NfN>w5l@GUoh!Q*WHV)qo9s!%M7uZTh`T7f3V*VF|Rqs5JZ{h00fA z;ar3_GM?2u*)~KiGm_s^ZS?}g`bT1L9nc7(T+14#9hR2htse8dk&cW#z>AZmGp&jB zn#(wad2kV@VRg0}wa?`YZJw2**qBt#{aq+X4eu>zW^!@M(L=bteUCmC;;+&Uf6`7C zPr}T5YGSj`XBneD_;GkP1z>}*lGR4t8ta?c_SHEAcA;0*h>?Gq7Up4Y!f0@If zYLlGSZ3Q3s>fsz`+QA&gpCz6mdsA{WPYgbs45>B=ULu`elhm)`^STfR!9&M$8X$f1 z^#=M~wHvzQp5USE1b~_hvH+HsYiC64NY+>myXQ8Qe7uOE`qD z3YMZ#q%;sgo9JS&*D}9(TG1Hgf|7q^UI0vZE&~&91#=@f)#e2zhrvACA6Lo%n=RgHT+4s z1{tz(RH_*+cVw1|1Yh;|tD2TSDgzobtVW{cW z`~wx0vJ#aAXv7MXF$F3ibDM21iw<2y=Qpr6e0npabsdXL6;ItrGdKTX!DOdV%~gh4 zgJpbAdEf2kfgR#X81G^FZEqe2q0e$G$QQ~YP&WPUh%fsb@^PX7&S?Eqc{1L6wYm?+ zC*%j9U=1X`P#*ug1d}8{+}6mFZclnG!~ln;QCHWBSq1ZzM=t^N$4)!|xeX{h9+3J< ztd+8){vg6qNs4E|%1Qs{A-Gke)J&Lq$+h@$AqV;tExxGVsY1(-?7Oy6z3gXZ#m8M7 z4{T`9r9;Ws)|SXJV#A=p(*Q+)&?n+0K#=YJove0ZY;}uc1sGI(e!7|rR{~?H;8~u|twztjP|tzAkh^?G)T)4elLUXjzX`rbD__HMMy(lwgFq0Z zwVIyA-_h`?*36j&9V%J;MYz9=&dYu6QGW-6Kw)g^)*}B&f281&XGLbIJtjjLCW12! zS^9h%!OInc66B}i*f>BL+D3-<6!R;EJMP3CdYtLuRSz?MihPW=YY`l=2hxvQ2y%&u zAyw3qbX^9VKRc?>Vv?`8NVL}=vt0cE2X_WCE%M~c%}{6~l{fJ1*wB?NBb_2#xNo)) z>l~(WCjxn%AfWA+<7DpD#ghW7L~oVqqSx8Kk+1}WZ-=na_ZN~nU;kVG=*0sqff^XV z!z{1<5bf;g6az$U^pU%RwjrtRu`@HNSRfS{$s2yQgmrbRs61>WTyR;ifaL(a(2RIg zz18&06`Y=zRM~5>6}(^s8@OUljs?X@ns82(+M7u^5;Rab53^=(&_?ifH0bRFWZHts z)7Cu*dbt~U2m%_%?nP$%qh3)MdEW45pf z7Q={qBF>1tXJzSlHtli(&z^=p#K4~x$wa>3KpfIS`sE;9*vKh%gW+v+S4<3wc`c2v zyEVI%k#he-zvnS&FP@YX&nY{Y7Bcm$Oxf%%e5dm@w+6Eq5!EQ@M zPOH$*0oF2AVS*U@axo)lmqmsqP1HoCOs=f_vHGWbQ^32xSX3sxm`-h55A9RW$iE|# z&KiySu#?!Up@(FHJ(wc4x`@qD&$&YGpzm~w8U6*o=pJ%iXq^(^M0+qA(h4{T`P><< zwiUKJD%88hFvUyL1K0>}5!};iXIAtsuo77$gYJ(&A&f=sMjxcBpv=bW@!H;$TwYV@ zJtctHP@I4b=6+Bf4%PAShO4sh`o&?Ap0Q>0h%Q(Tic?L*kIu2{IMMV`fUvd5tv5Kn z^R4UpJ9DwEo=Lq_Q8>T=UbxDRBB=P%h~jQFU1l_JO@-pm9@@%~b6eY(e`7{J2J;HN zc-`WotooxI8SqOjXPs<65BCNf-KF)=t5FV=Jnp0O;1~(qg{xV%4E2u2|uVpln(DdF7@x#I5XI!Zz#Gl(b z!xw0V#-1UX#3JKLnz)62%JguPyu^n~vwOG;*Vx2y)_h~Q8%3>k0zK#FE|0d9$P=HY zk_J4aesy1Gius}?KC=4Ne%wr+py`3)B1<%mV(vQ7>%@=aCpuO6{Yg06g`KuG91nlP z(aB#BfM%3cu;HMW0jlIDb!=42IW2wYkbCMj!$9`%hbR=XCK$SrO!uWp=T}cOLW&Z0 zz-dC(L~YYF#%%w)X{$RD?irK|Y$ul*OjWIs2@0xb1vc8B-bdFLE+EN)iem`JjeC@c z&UE_3lIpJv_abO2Z19zPW>u;xwH>MKCh!H23BZ_s+pRzolRk8in(V#lhw#t7hRb6{QZZ@x zSW2RTJ&xu~N?$F;IfQe8R3R^?V9S|ZuD>`8R7JE^+71j~Gvtl;YEB{X*t_^tH3K*z zJlKt>dy(G7!k7bK-G_=>x|v|e-Q8pWRC2m3f*&JcIN&c}ibAb(`PO+ZI!kvtSRY-J z55BD0=O~na`*%?ndi+Pwuif5idL24+?iggww59a$xc(j`aNGL_LK-QEz_k^YTFY*g zLU#J@UcAA*Hp}NzcG}eMET|w@Ttp)_SKy+36Lkc@kk*I`Xq_?2*DoACJms#tS$xgl zQUy~o@hnz?jI(Lo3~|GQ?S;ajv0>VT#@UR=42_|d=_7mD_}qlk*~9YeSivA;hz(9O z+MQOZu%@}tW3HK2>ztyNnKpGQ879O3sBH%~u-`bP3fRs)tXeA#ofb8aXfJ2^4&2Uh zuVrP=sCVdojq0AK^M$dwVvdF|{+H=9Wj${K#H=||*dusR6_yhhi<32Le1dA;LX$jL zYm799<>U(!-f2^#MD7GafS1qgl|U*6GsTiSQ}BdL+E*`BiZT4z^1&Aivq?dN;DQEM zG?GQ_6pH4(K&(=Lp+#4-SAGpcoB2y1yL%mqXTy&#_ZaUG<&DyJ0Gdz3L&Vfy+K{b( zY^1}|J)aqW7A9?0Q^>q^H61&wsA7UWP8V(B7BKpKTR2bkZcbEa>bupo>Bj?cn=N!d5pJS1!gQn-z9lS8;8(`em$rT& zH{*#!9><}RWJ;u$Y;K&;awqt2rH9dP0qR_zmzyP7UWl@+sq9LaxGWBQ^IVNwOKcmu zX3<15AYMtGXdGAA*TZ<&pekC*h~q?&)wBZ}3sFaITD;W5xdsCU2R+#F-N~` zh|~_AqFZ4jy^Ps_W-JPKEnGc1@4$%iD%V9JkLsj;xB`WG}}KG+ZPlFLXQIV5?GHZ7?@Yg^syW0a9BZl>r!)!uw#ig{@D}t#i*{?Hf|qE}*+2i6U`x)Ki5^n5y}&pPZcLC9 z`PLq!jpeKm^gw1F3OQYlz1&?8-2L|*w3h|k(E(=e=`||3y(S7sm+)Es7q;_QaEJ)2 z5v3S6U*D4O_h?5Dl}dVB;(-L+DU67+LcYB>P@IIs?1U!?$;pOgDqn<)R5nvUdZabH zgMwayr+^%WSc~tBSL)#gJaJ^U)PjYNd`d_3tWKv|;}qycgN*(VjXG7HEXx!v77#7y zByEtPMh;?hoEUj);4858(JslPnM_LRLjzZBp-Uu&ETZ=4nYd*|hd->n${Svlolod8 z!+gk@l*P%`+{%rA~7x^MIDRgH&pE0N_DcSffv2ZtauE86p}l)UJ|PEMIrGaIeq1-Xq3lUW9;M=u-0{a_oMM3TEL$sOC>olN{3Jb=IdIs4&7W7}rv-*lm%fMcdd|nf-%8P7iN_ z9OT?FTN@F-Ez0FE2DBXAQ0Uo7P52Ldo8_M|UFXV=Fn^3>efouq5V#l6cxe-HBPF&U z`kN`gi15G74j2#%D6{uzyHmMLg-`OUr)(=^X6XRL(3whLL9Rn!!Ow5RLOg`f{3pGo zCfbc+(~c@ajwkcKgm>MtLeZ%%8I0&U=wy2!Go*)wI!s3i(3CmQVDV=*V`!!5rI)z= z&F!gXKsss7v?E;#vqoZY-8L1@j~*}(KmkN~kJ*YH!NUt1iJlm*B_qgPoQ8QZ_fy|m z4ktFJ$5>8KbU6gyRCthO(sdmbXj}(U&v81ERzoYjlSw~;_h#Q`Yz$m z#4WA8U)FMH$mz;3)k`!qFeYwNZ)yH(U6SO?Nd=apa)ve~dJvP#E(Dm3S6(ZLYRPuy>|lm<=CMG(+|GnnaLqhGc$8`<0hi z(}F2`88w8&I;O7*$p>B2*nUem6jP}HIQ{^?;x?`j9X6XO~-|ldC?#X{~=G)?m{X^lbD2bg{bSGC=AI^^G!i%b*!n9kQQ&f)7J5b z*m*kLYlU8Qyw7-c0|&UC!I&*SOh={z<4PR&4f@c01GSMapUM}-oD648dgmCBuhQEE z7MrDCEx;x1y38oawXFIhBDQhVc5;Hp?;eo@O3Dm##*qQ`q*XC(-C6z-xu%h0;dsk@ z`9M*mf&$f7Qn7}-Q0e$Xu-1iH($q&F0H%4s@v_*%C)?v5MKiz0w)WbM)w~~tH*44B z{1qK*Qr!9L`(9Hr!58v<2T)}gyrNxvbCH=cxL$lqiSaUA9`|zQ8B?*ymOY-V=CEz= zsZ?_XkMSGVjHk6!f5VOQf>!_Kn=$fvTRzY(&D?bQgLUkAo`dSJi;2;4Bvgg=9mCQI z@+^lmK+gWa0Ojdh#EJZgQlw@(Qrz8QS?WEb1_HSl680(+y0IsDUC9XmC4HibdpsX4 z%}&cfEtoGidkAZRAIJt8cllu1!kDhxbZI{LFR}_Z$L+SQr|dLoWOrU_!c=hiU&~_+aiEI){!&u;xtb1 z@gFVEx3vA~x&J2G(K2B4+%-Qi)^+hR-5+)sS&T7qUyg$b8>)kjOFeA>yhA)o zx1=}{#YKlVf`$QV?Q{Fto#Qm{p>WX z6d@<%;orMtp8duN4l?p7|ELpRQX7yo^N#7eFJd&Nn0a|XAuYdTqqr)f%ivV1tg>SV z*>ykZ_-uIjK@8T9G8$aOk+t;iyeANk&qX{>9^yko+GRnOB5yUrF;YylF>K-B_-s^; z8F*VIUdFz9R5KtL2HM$BXXHg?&*FGa&UH-R{!aiu5Ww$h2{4yCuvGNCS%JG*UZXY} z<5Ic~xGP_J)ul85pP+WRiR}p2+XJ=!Y_Q82!5LxSD*=Ge!!0TQ~qnQz3i$wPOunyIZ~$R@laSLl5$ejW5$uYY@+*EK{>LC;qu39z{TCO3-! z39X^Wc!Wtk4sLpOO$2r~zqsRpbUr}MeldVEaO3OoPgl_GWbNS>k^{cphcE*HI41Lw zTvP6z=7)23Nol3IC-+>Q5SUfBZ zoXYFzbs)h=XNmLd)Jsm@ol>xMkqwd@6N?+NHsW3jzH)fVRn&Sd-IAxKEfta;Tj$|>j$C4jX-6D zi2|2b!+Rdwlbwu ziG_lIPP#>dwYXK-3=X-zX?1CdcOJap-9Rmuhy>}perk+sz!b@gOiqyW!s{dc!-uWI zi>Gq9shN1HDnr&XlTd##vGNZkcO9zM`?H`HwYn7Utqs^X+Pn5jUMp%L!lrz2)Z$B% zAa&Gujsm+^tK)Rm#`y?i2>B~E#ZZ0?syv*n>zM`V@*8hyEWEcxpB zNfG$NY-!3RljMjEs_Ef`m7k~&QY-ptC5co9zc0%Ps$UNt8u45ZP88PF0tR34Z6FXP@kx?rRjO!-o8;o{VH+<2v3kp(z(~XiZ%d7 z%Pyk^f2H4cZgFu7<~#HT0fRi>p!nupF+M>_WqM=ne@)r9T^87?Pf;-po2tST46Jv$ zxrTu>A(}6UKapt)J~}=@Du0${;9#0z@r=JbI$W?>Lj>k)d-Wh=u}q$kkmTXgGa&Z4 zNV=)o{e&ZGGqQx`D)R0r^0@mYWp8ztBm3c_DGjf`jo47JBIMryXq@Am3f2?<7ewfs znm$bjrs#*>h@0fQS}{x<8?>5S-sWIUDv&#w{hRai0N4wBmj>&0vwzMo?z3juY(6R@ zP&RLv$ z1tqcvW^s09tNT9@U+lAqC*dnw$6~xn@DOV*K6;HxWm7tr-G$T(7n|*Z7C9n@8pNxu zL1v*766PR`^u2W|Cbej<_G43{j=taw@5d_+G7}hwtinF1!pIX6V?Etd36;H?Y?6*390mKSU>8K5z z8J0PSv^K|t(zPh&n>j5jQciR`Ay15~Pb%TQIK<|o_8RP6Zm7tjsF8SO+|KGR3M9I= zgQM@iWv8WSBqL|t!Hhl|glP>?mEnKXA2vI0#e!$ZpD(%Z*IPBnQoPn~x%x59eB%2yp>}?ICB#cR? z=5?*JiY3TpITo5CTV87HN(TbhkLEIrx8Td{#~n`xDzj!7t|SMTQCZ!Su-_pLJ$eo5 z^SnkiwaUT78@h9rP4y2iZuqsc=uHwB`Du|#2@&*G4#=XGNYDXeqT(&kJ+QVFNRj7V zxV~Y?`t@_|i5W-hu6vBb^tHB!!8wtIPI)4JXWmD48ZfE9N8JkR0Q@s>M*65yIRvVa z$h!EEbWxGW9ovQeK*TD@e$WygsBR0w;_R7)L%}TZ;k^m}!Thuuv}MGnog1JB+pPt1 zKixI!SuKldMb#DTQ#R@FC4fnP z@`0C#&Uw-sEtwbsR8{ADYWA3)WJ6qI$iBOwpAhl=b~4PFb77?pvVU~wVR@}fb}TAP z(NdTa+vrA;2rb#*DXEm~D3C_&j zNnQ#9%&ix%w_9$}d%-VOL6k3Ak#}j}!}lNWM(Zau>3o2659~n5y%Jju@g18G9U$x0 zS6ay<{cni-0z@G9Ya()<|N50maJxMp7_(?t$;+*V=0U6go5<$0>0h z?0Ya9`KsPLyx0mpCC6q6@K+qg&@1?WExP!x8$b}0d$P|l6R#En;C%G*`j(&tv++b)jaN$D zFHJzVm>jDRS3V%ntjtc2h{=9wU=2B(Ezjtw6g$tb@DnVWRv6(Cz>T%xc$;jN!ZH@j!*GfIH zY;n1G4e)w6eQa3kOR-0zCu_)XtHb=SqOU7WEHI!-O@xLcVD^BY4()_okjL0b(mpz<=CaDQHoWexd3+{1=CfLD_bZPM5$WF3^&USqc( z%5cF$x{jGQS=Nj_*uo`6B8mtuzWD*KOvBsNFYZ4Z_K!k_oOC}z(T=3)B8}|r8Wo@x zHcc{RYS?$}YA1=Y9mDW!Plc7l*y^0(RHl`Y@5(oc;gY^@?d7kC2w0-Co~iCix1W4@ z4K}Z#)&7UekYla!UXO}ZK%YJv_C)`hleHK(T-7?9VJ`?YWx^$xIXAd)PhE%yu#qsz z9myu5OC04}ReEp&_0(#hg0*N@v9t6sHKXwn05C{5%c(Sgz37{iI?(HIohb{5_E-AA zS7IvRPKM|aOdd?#7`6Y)$fI3WnMb#7>lh1Ld;6X^s2DwA!;Inn%-@D&5L(^^4q0g= zTgjBET_0J`f5c2@?R&%k>K$(BT~$zqoEj3MJJp_nO99ZDM_nF~$EuP4zAta@vKj;? zhWP<(%aP`ZQKRy-aS+Uc$g!)z)D!xjH-lji0dGHv3)1y7Ni&$^;t)8bt_n?WWu0$S zuk$9`U?uHV7@1o{5mS7CLt2aFjJ}$o0o(wozUXSHFN_S8g&%di;U zPUH-r#9X$J@Oc;I5QI?{pirutGq6AxO=d50@TVL4jhyNYZlMt@T?bjb{4n7+3zhjU zk`byt2j`#NE7Yt<FtPgQ0?Jt+BPhZaIE1aT>+d@mE5G+%sJlABN?fgqTADhyTZ8<|~5@1jU1Bbc25~ ziQwt9A0&%-+)d9Mn`R-Z+$Kg zejKpHElHVRcWJe|E*Z1l>eLBHK|Q(mNhHkYk&Qa8f0UNwm>;>8~<4!_|FEeov zn58VP)u#w84mBrkH|{R_w@7EUNUd4AZt$w1gvb0TZ&*eSlDcQkFYML{#vWg0o^^9* zqf*76)F4ZOuNLHoDq)d^TRt%K2qV(Ks=BUnW`l>bdC!j7+~F8^>a&il7_a6;m>Wkp zTC@`PGEZvy*G3Du6liNh{odlBJ=I$!uWhMQG(bmKINGmC^PohEZX(G@jon`}kti}x z5QSQXItARh`xylwv-HiqGv_{g00JckF}D0>C{Lb19hnn>l0sZ1NPX)X)KR}%fWgw4 z(^lm<2~B~SK@gkB!cN**yCVBC;ATKk3IWgayMvjl-R%^Jz-1+Qxl$Z0mw*81bA)&A zOx5AZ%rL+ROiy($;uYGa0J$@9i)J+b8zM%33Im%Am;;lN&T^$ezDDm)%y&wwF6;_rZe(+Ga%Ev{3T19& zZ(?c+G%`3KFd%PYY6?6&3NK7$ZfA68F(5ZGF$ynCWo~D5Xfhx(FfuYS3NK7$ZfA68 zGaxVuFHB`_XLM*FGcY$aG$0@#ARr1aMrmwxWpW@dMr>hpWkh9TZ)9Z(K0XR_baG{3 zZ3=kWY`bG{Zr#!@9NTv8*j}-1+qRt*+qP{xS+Sk0*tTtc&))m&_tbmptNEu#qsGPDVxmBRvZY8JVz?siBLdy`6}mizydC z-P8o2Z0Z1DVg@iXGBUxC0fg-xemhy3Tetuyjj8^v1gO~}_Fvi20$lz_vN8N0$>@Ki|FJrG{70gPVPXQ9 zSQ@(kj7-ff?O+)G#hav^nLU8*KWYLD0_pALbbUqq1}s zv-B`EQLuFRhiWrJn|~Sz{JYP4B%v8_xWFNja{9bOzm9$ zP53{#{CEBDLNYb=Fg1o*Tedgm4z@~b4XyAMEt;(armu6GTl zhHYys2X+&2=aR9$7N|fy^(!m)yjIGwj2Bs)DcYdCqaPe;JAQTH(N3I7mjWeI>l@B= zpQZ+B)*__v+KB&kZw(|YKWG>3h74QZqOc;s;V?||-u#;dR(;3FuGe|qJyXhBjQaQp z`zS1evpD?z8!5TWl5CoEeNmlj;qR|Qa);weS<*x4oHe zsM-y#Vql$`N5_|{wffsS=W+`9MZqrY@KVf-5Ib=PbY;P1MVpC%+V$!!`DcHL{NwmW z2Ml%jR#=zGowLV-9Hz;Kd}yUIMd!zSuSH0J392FRw#FiL@~9CpOcU&VQ)Qv`g%3LV z0cx@_ZEGWeD#^PZLQnOUCM-<9Wsjcnjx^9p->X?|o)I@w3^4<<$5;kBcX<4Ji~WQE z^hQ%e6s~Ooy*6hiZ^wtg+@^gHRVcyhNEF*oc%1+FS*T?JUfj`y`urV+RaP`_P7W)S zHeUZ?#6?XQHKgMkeQitc;N^t83WFIKPXgku6XQI{nVd_s-E710cvtu;I+j_E_w#b} zNA{G;kSz+0?FiikKcHud+MG9m)-x)={UsA>QdMq{VI{_`Av?X6HoEUJxuUnTQ(PudS~Qcc3r{S7zgJZl zJe@C%Lw88C=F4}>I*n$BdCmL$LSk>Z+-3$eZ6NL!+PfDmonh}pMq=sh{l=1nm^#mg z@ZSq9HwcnK{E&}X-{yMh5_XN@J9cApKhcx^@b%F|*PBzaQtEA6=&M}URwnV3Hktdx z9adTFz~zJcF*qI@yQ6#6HWWrHM4vhR@e7OJAf9II;HCw@o?}Fpi)d3{AlvjqV`NRt+8UzV8Usev;7gE2F@_0;M?Wi_R8X4}ARmjtASBDI08? z>GI4|*FgCVmurS$SbPN2 z)|IoX+u&s&jDP2G%3?yi$0KdKgrE9yJ#Cv$lWL5|+HywWRsT#Mb9IZ56F7--Mz+Om zbK=Rr*9cUR&r7jA05s-c`!Sg~d^#cnT#<-`S5k>Al1r4dg zF9g`2XWSVNWAM8X4x&SO?Z<)Nd>OX;6Id?%cDaEgb5!t(MWVYCicYsr4D@~$rF02{ z4cm>}lB(jcOS!;^-H465b*(F!<+uJ$4;GlS@-JU58|n;bzC%jh8Mw9f=b0|G64TJGGi=_@zI&{?`G4$Pcf?wH44aQ?snPg(w%0Wf6=HR z#hDlHPWzH~43@D44|$!mfZ`*-O3RvsQDUHlU0YAYpE>>E-`V|n+UM}<#1zSuB z$s$?n1ojzALNew|Ol@S}!O*zj((>eJ>;IHZfdi6}E~`(N1O5$8(E#!G3!dys@7^hV zyYDyIr9CZq_xdiC^pLz<$kI-d)4;1|bDOO%XgwbpM^h8!5ASq4RVFQBziw@uHC~b5 z5(Z~rLm)&)L~u%yKpt2qjVx{MoLEkJD!KqSF7<8tUl}b`QVFYxTsjDV}1wu3rsEt0#Dg~euji(@3$?dJXaXc+%@+NC?5!4L|z9W@<-1Fs{Bs}zVzsn36k8spS6X^#+iqpSb zK_Gk(Ac=416BQdVqIXwtFJGohW^m_i!X1^b6bN90a-iSZ8?Ti@In11NOrD4v;4Nwo z<4p_N#=TM3woS7z7fT}Gc{{~Scur~b;9v4{=gb)w3COk0d85lP>Voob6f35HxONH59HN~or3X}b*Q`?=yoSw^k*e?Xs8Mu}{k zY^$`9tfJ<17@_S2ouxkQb2h#`T#vAdw2jmXdnKDi$9cA}5gs-KZsxK=)H{_J^cx4K zztxy>R^z7RM5y)_3K)(hW(UAfCd(G{3R8GHDU3VNAr&tt65jq%S9_`5mV_&d5X5~qZ&+PP;| zlEZi1HS-O(YHXl|Z9dao%?CvfJc{?LYUQC;COK}6w$q`uXxO}R(q^f1C!hzYqh!S$ zoG4}sRjS6DxiagBo~c%SW>I-(NmZlf6P*N!shk^h-`(X01Pe?9*AfjQder8~<+upk5lL*v^Q&>nP z*ih7wfiTsxNG?n~PRT_2Z7@D2d&AG`mPHk)GVLaVxK%HW=kd26SsJv`?#~H~>OmD` zwt~9_Q6h&LnbHUV**e_tX4Ari1Z}>k(VCW$OMe9UO60EeQm|8rW!NHZbFsn^Bp}^D zdnenT!bXd4xhys3`&S~NC_1d-dORd3_aE5hlU>YWYTF7+HZtG#@YWfVr)x34omQ<@ z2RFQdHq##5w%vS*g4!bZ@>XA7ZYZYPZTK@AePl#z#bwv-Gzst=Z634o0NG%w$7`*+ zjdHo9vR<#&o!oM=<1Li9_U|op9m8ViO<50W_5z|0LFlv^LkPJUGi&|i$|s8yrANB( zdy?>qbHOuEam+*0AKi@he;C{aokOpF*4vJoQO_9+ zeLPF}p#%Ktg421VWGWWj@`VcTGtQZnyt z{o9yxeJ?ao#do7TA6Q%Hdi)GvH^l&|;=@(ZjN=_48uJj4li`9JSUe$&#ISXtsHCu_ z^Wpos{L29cuM3F}XKsP-YiS}z4!P^PnqGbbmkaejPG{u3r04)l(LwuVpRo}IQR?BT zh_f5feRQSB?Sg?Y-RhKzq}*fW^^up#IdYy1>A6wPky!V*ZH-0=FfDNHRN$bUyd+0} z1@P^J2C<1^3F|wdZnjxWgaBTKJg(kT+NcWTCg9ghee9V+x%(^r9YO8o7g|>& ztIGm|U{mJ9wP5^|D&}+!ijTRi1mRoJlNlB$&sRvAWGh3XN2mTvqmRb{rk@Wk9xR#2 zZUV2UiZfaaZ8HlzRi;Ls9@QpnGku35&#RcF!ynVxHV%S<8#vPx)gS7c8mlA~8uEe2 zoE&Fcq1+U1aYCc>*p~cKXs6847S1*=xKhK<;Gu*(yoCplw9SV3b(PYPSnO@L=a=bJ zBlgjRW|<&jJSpsV@Ba7T+eLcMq$Yv-^!oIl(`RlpYfvLo>lZ*+XJPh3aWfA;%^fwc zUR5Zvqw*zRH~M9)2{e2&N)t^)<+(8XpGQU*_h;KQ|r=36qk-e^V`_1FM1HcZJgml}PGXG)oC$!7V$7 zx1Bc4W&cB#=p@sL$(xb}JWISp|N8^CTJ_|RpumD`*TgqPUjCX6 zGv@TLL`O48=rGNGh+HUUp$%6Bf(9W;46Z;C4aW;L`5--Jk8(5cO}>@I^j02KXVF*^toeei}SmmUw35^3-yeXHVB z;A*ApAvU6(!lCmXtysp)r{J^c4)5D?f-e&J{qvch%JH{k z=dhkfB%$n_B9PfmQ=_54$knHSLdegpf*GQsnO8#c535$@Vh>5eVKXbR1dXl@xc3$X z<=ps*%UEv7)5!bm<$DHwmWt1~#i{lLu=Ogc=WUZfjI7E?H#n{tOwrw&8XTv-i+RYX z6LD=P{gb#An6$a@TeMWxad(+AoB8f%$Ylw3HX9Cs{`ZYzVJwj}_ZN1INz21Q27T3T z<5~Wj0;+pns6-E`LE)(3=BTQ);dXxf6sZ3U9bm7PK^20qv_*o2a&ZiVcE1Bd`HKMMNn;ZNK2PFLn=kj7*J6tVMoLWp_K&`J)(+?yQbRIGBGtiW%4kkE%XJx)h8 zv*@`|i$z5D7blTG@m}cV{Oj1Nvd))oQU>JNeVv@keNSfgAfW2+r7)-N#k8otLLbDX z$Uhue0JB(`lVZR_WOiUTP;RgY==rAT6lpMKM`x#O1w2=3gp{kif_nx#)AHqtk ziDUY25@Jmpyt?*X6dTgAAkDsS*ki+p16>EEvW0nEB2m+p+rPKb->m2xxB$tYoD3r; zmn9e`-3q3PsE-!WUdOTuB0g=4$5sB$y6cVfgyO}R0lMR4+I~u1gyZRuK^>4*I9Asv z?#z3}h5=&Zw71yZ@_v7a&$#RggG>r6AXJRoPsIQT!V1ey>Z6#v9T&A59SnUdOiUT_ z{V0kBpOQxMZ~-Yb0)rw>ZS2iUf+>xMh7avP#VPe$S(+-vm75>6U2U3^?jTt2+vM8c znzGv4UNJ+%t43&c|GPE1SO2kO{qsfE22*iMz8r##47&FS_?6K5VPS4SX4x^qC{od< z8wUpXQX4;*{EJlj^nQnwsma!$+k$+Ncq$2sNby1(P}AYQl=3a^ALMcRMw^R8=XCFrAZ0~K1?u1#ytqHIbW z*)l$Xqv;;}sSM{wd>LImWKWk|kv3agt+3bF6Ma}F5_q#*M0hbNFLzU5`?%xpsa~w_7XT(b9;V5_jgaxjzTd@`2m3v ziB7`w{b9x=mpYkyDHSnC#mB)XflAk{{#VP^zBywUW{L^rr_f1tmNldSuK6~nIg6^d zpQ^-+W}knPN&B3)urA9mnn^7ziB&07=8=1gx#WKDyXFd{d+JVI&ghmK=w)qQvR9V* zY42h_I@0;M&7c~p>aBW0!8|1KzlSfSmP%6yiLi)lWEhh9G*}S=I!%Fruux&aGqn9p z{puS@ZrFZ*MU|hpOWhyML>`r|eh55jjz#X1BS#2%smz==ReZIR0Fki~qck~C?|E)p z(sV~>;Vdh+mQqo#2u{8x9y}p+7x);7l40KH8$PutXmXB2nY~JO(X4wf^|oK4Js9Kr z!Y;IZT+S&^qWK(4--^&C)hkIl4*M|^C2x94c}`xQT)2vTlWa4nD`D~Cn|+b_wY)Dt zhj8?%(w6Y=?DxaswUBRa)L?n7QkiOwe$M7%?qEDCg`jJo^B^TM7c5Phsv$a>6LVbg zB3NWhsKf62WzmRt`oAr+*3-cTjG_6Mz>P{{%oq?O_asPAZOEifBX0b0dIJR7bnb<( zTek80!a`H4b2e-u|M(K>e~zRo3KZWqB>7|^ih)pG7WabNR<_s1j z*n0+$kIaXQh5!dl3*FFUFC`p#I+NnVcFeKmUE9-k%} z%j|SXQjjOO6h%vFe>I24P_J-UX2tjD4diDh!oIN$Uz1UzJIS5>%DyB9ELBk#mktG^ zPi;`M_Fd6IM751Zx)r{YGprJx(DMqp*fS$QXaz<4Z;l9!cyU3AieL`qD5B{@B)uYSl}d8I)eW^pL~BWsHKS4r zt=h(bc(qMaaw@~3(}y>6>A}Hu9n*YsC5jQ7IIqz`-Uc>;}Wn{9bruQP8yzsMkmrjw8yP(rXbiJ zoTd_$b{|%S)2(^bBX7_&B;-wrv!mymJS5;=D2@Jcetm!ODCKveZz`V32HUp)`2S7Y-X8#pfku#2HfJD?q#x#b?rZkJ%!^@^o=J-u9UiY7Ey%qh?RpNRVo@`vNh8Y zsx$CM(T@i{GNLM4xr^X?#sLh(X<(;P)Ie8_e<7yvN z92GCt0d;#8h5)7$sudeM&_97~aE4d!qnsVif6OVkYUwglN1#-oA;K6t2=3)T4K#q| zVi1I9Fw7kRpqIpk;TiGL^!a;y0hdKc=<=~V0{S7Srj0?~dmQ&VkNK~&_G4Y`GM1qVvv(Q7*e^~LUC zQziuCYm#xfiagtKQou&*`X?hp{|(zzE$TRD<9Zc*J6OgtX@tR5JN*?xm)KRzSPQT! zK%DzvRf$46`0Y{Fgj22%)XlrK18S~PH~q`?hkfYr_()iTz2h}Bwr=6v|H?3oKI%XX zN`_cRc!nyR{SfUwy^%2P_fO`X9_;B-3An9$cw{{`;7M8@4tRq3GQtWG3`L+nDb3=& z)=lAPFz7z2ej5Esa1Bv8NZ~#>CSY%+VK)Ml6M`6xqwuqh6=-J|+JszUW-OITQMgb^ zBV5(b8q$r~kcHK%LziJnYNl95yBvBU8CHqZ+H>l@2~B=0jI#asD%OKFI@6u^_^T=vF(`m&vUsI0L*{EB!@9}YeHTv3!Rq4aVjG1o5 zAZQN@2zU*>>j&(g$6&$LG@y5!eB&IK?EUT&!Z0Kd{Ev3>GH-aDj zM@UFqRloC}&3I@=H|x5q!Hfx{^>H|$wlFW&uv56-S=`LLeo6v;*G~BAHTKp1h#Alk z)wKHqTRmM^425uYseypieFDa3_onPMM9@uPjDhB|;Cf5C>PXcU?TK)R4?|9_PG%QP z;?!S0t z4Rg&zz!|Qp>DrhH-qqFSpS~%wPab>wmGdRNiFUR_WghGCDKhc-4!$%CkZa1;{2rH< zfO$P9O;-vrrT6e_JdPf8ugxNcucu~Dw}j&^lGBCeeMavl4~zH>jq5#9SKb<^MP_W= zBw-D#VcL*ZGCm3M`12F|45liKIo)6e$C9bqFj2kc{qCX>@=JC1(|C}@o_sr{YG5H@f#Jb-a}Dh1OBj82qK z%x-o~B#~H1vsJELz7q~T)!|!nB*Sq>5fj`@*vv%T+@(GatCy$pawV@l36CuxxA{Lb z_BI;_DjAm6P$%W@GeX|veh>NyCx0Pa71O%G3p>Qh8u((n#}>i9K#rKzQd}7R_35vu zjQ2uod2<57JZt;5b^whuKJ8K&(GZO%yZqIF(QZ@z@nlMZ2Jcy7w5)bRO#_eF!u6Y^ z#tS&1d7oh_tar3wfkIJAIN1|_)$@)n0{BeaBjVb@7tr}_RrKhq^5;7{jd&{iCK*FN z{N?q`L-?hPals1a;%|{2Rxo7)SOaqGF;637Wp{W8fq)1;)vh?Z;hH*mk*WQqx~PRi zx39^ipOwERKfdl5*2Fq>$%&)!um6s^{}C}2a(&0FLhy+dZ_ zXR=fS-H@)+*7|h4%)%5$;`@>Q)w{}KBRrC$<+8; zlzQq9{Ynfu*nqVxuP4yCQSSb>0x-uKaQW*WiaCuohaC2|Uky(_QY4b>W7i*dW4!13 z^>Uc*6a1&;DMfad^OEra16N<=0?Vs_;fd{3o{@E6iNNp6=)^by)<6OA70*30HS%W3 zk5aj27DK{26HlNn9A}Yf)xy2?lM!{AteoUM|B?0Yk!1v2Lhe+n*o>YrXyQRz8}MfF zmUgyTK@uydl0_7HJbF;qFy;GNs|W!n)+CYg0(%TbXp5lHJBg*7$3GZ@)b^^VFt z1#7MchpBxaxk`u{cln3FpR!05DM&8*-3H}oT?pf-q(o<{P8Ne89rAE!%}C4xNifA( z^Ha^?FUwt+)}Bh%?y1_<%CbesWJGnRW(I+(gF+e$@@#TS_~k*Nk(txV(Iix=7c5cH z$7k(bx1}M9B`KwEvddx9ei!U;_AXKgO*FYIk9RHak$J{(a|b&Zb&%Azfb0}YcTke- ze3H-_yagvbLGk-&z)Wk!Bv*j+_e>j-YQ=kSRD8!^2-Ma^MBY1Knvn&fmZ!}Jj8X`i zlhLV%*VU8;dywB!#crIWj*xjJIB@9$=GI`~D_i#hP9^!JYPSz9@E%p*T?<3}$k_sAI=+QX7xoQ z?`C1-(n&!xF*LmCg25(WI=Cfp&^z6u^sUoniotp2E6}a-lLC%GRCP7d-3I@jXW?7m z5E#N27fc&7TiO{jJJOvaU$DPpk#4PfpH)*>7N%?;_AM7ti^gg%ZrIQ%47DSQ+m@7! zGgm#RFxurFuswkzGb#0M1&q2qI+aS1X}}Tlfqtb*1%3!RcEEV3)=?dlG94~e2h7B) z@*56;)28%fazW$dvgdPB8rltygLpwD<%4ZV2zmPImG0y2bM4U7Y9yW3fbYtW%U`8$ z7a5O9nz%*Dd)%Lg{W8A>jiY0m2@Mv=5v#skllHI$Zl0xlJ4qQAELjP|1C*IgL!!QQ z#aB-5NY-!&gHoQXQ?va!Ui;|z(BYF&5dg1wyhA!B#fooOPEmc$1Vvt7IxgDovSE1! zS2a)+chi56)y5RMWP-;*cj43?R5+ud#whyC0!jsi;+_a>o-9V^Vju;%IoTYkEkUQ$ zG1!)S?9SSfi0EXC%>}D*LdfQMq%hHz#;&f|Gr(s8 zz#q)$8-z?oGKrMa&+pSMHW-I<9BS{GMLx2Ft~-d2)XIh*=?9t9y#w z88M!aL}JJ(xUF(P$SeM4DjOV3zNgfB3LW+gaSOs#%DeHMN~A5M-;8Kuzs~T0?8Nwc{OpPkwi<1@JG1i7C#QnzM zCjf7W?N|& z!{Z%u-!@24VhstNz|wf0ObM|DzH&nRXtBt;GQL$ANZ#h_(HQkzIXy+X->Z{(2iz^b zgH~Fx%*KpmGpt3eh(fQI1>S44ceS=t@OwBHm|TtOED#U%7@3w)%K;^9g8R^i6uxE9 z=w72#XS0xfJxAbN0a#vN?*y>%r8YQm1?QEuB)2d{ODc8ShUlIFvwlW zdDXo*-l|(xA@0~((DtLXvc|At7oId(9>HMH)rAcs&l5SidL{88zB-@Q+;N7ik>rlx z*8yx;G|np6>l>8ytioDY7P2oA+$prx9F}Z46uL9DS&5m1IbrxPoK;r`m<;)aDDH|E zh4|f$2kg=-7%ymodhfJkoJf9{)c2SbmR|hpvTZ&)tufw9L9*HRyN6BdYJ%m$3TCJm z-alKTl&r<}GUe|u)am2xq74s+!Df_5i+K{wKX%eBy#ls2AD8aFNN??XEJf;b5X|ZW z{)9^T7c^mUPswl>kVA)`o1)-sJ1Vg2$6SRp7Z_qm@jnZMd{UV2@zDwQ*O*x#^x2um zeRQU!wW1jkRR>_3;>NSGraXwQDhG3sfoTF$sSi=P;RXbQ9H`TCw_8}l1u0!F*oS(P zOX8jT0@9-1^kYV7-o}ldsGY}QZh)ec#?-Ptefi7~s92$>(oJp|xBO%VwBvDv06KHt zehqAZC!B>~^A4x<`VwZ^<<8CEm%;6|f&=B2UwS#IDM@riW2q)2eqEIuWk7Szz)uZk zo?ics^xqo%H~YY!DM3*KSjn|HlcBmp>R|Z160Z`;kNWtsjVcJJS>mh~A)$>s*SQET zBisMH`WA>1n7JfT95T>JGRm>(QGFO3 z2-2V>wSkf86nCPDI)PHb_ge^o3KAxfd{t=sX8pT^t*MF{do}#6Tprmrtpm}6$b**H zKar9%*qjXo1s*?UPmN26G9ftkNyF6aG>Oa8t7|Q6UzpA%V$A9cI`f)sDnRvlpJQ8V zQQIDl1~!l+uhCV92$8#^>O3f*@vd(HQVeoG+>rIGN-(;cSLqccu493?&8%<&CFw~F z+CD?rFkE++ws#yVjtm4@ zLnq`_{z3UYOVqoD|`JoKW;l}N7lJ521jiy^|HC4li09pz+l}T{o zExs8eZ4p}_?VQ0CdE_H5ob%MbX@@6i+_z(*%tsG}?M8dOX@j8nBvMG-Ok&Z0JIu+e z7`}YB2Cc6nc=xaNSlHCK96w@S(LT8C&x3V57eqIIP(`(;ie4&p?{k22k6 zQ=0u4wKpGy3#;VN+3tpgv%FUWCS|v}UW2?OAE>k0WjxRWhI@k&qY9eTm}?*~@XEJ# zgemLOH|N~d-;zjmY%idSZ|jy5$rYQdXig$jP>!da6Z>~EV8l~`*MEN~k^hF!c(sU; z>_C|=^16RX4+|yd>k{{NEi8)|k1grI!{4m>vsH7Sp+_IH3+fix9qZ7ZP{S7W9-mMN zBQ6wsLmD8-nft?8gZ0rfv<^K-!gvs9vD)F-9Y>aq|GJW)v6eG%Vq{xBeyW(;f6a48 z*C+f<%rKZL*;31QdapC&_7@Q=s2Cs0Z}|=NZWW_2#%sF-mf$_A!EktJbWw1C+szg? zs1iKt@*Ssa}n~H!Qd}H6%0lM`06%m#l}Q6-&P|R$BvUOMeXbHrxO(cC|Ap_=x0nodZptc zAmoXfE+y>i?E_l-+mLMJJIl?>L;hqjH8rFJg)ncn=zKWQJ{;sI2Bt~e;B}5|11aQm z&hilmn)F~5C34~+flv_GmdVkefdy6EqmL6;JsYFF`Ob>IW1B8h_sE+wmfGM6w^y$p zo{EQb>_RYOc!Ep#Kvck!0EHi8j(5|w7VAn$8bUEZSioHC95El;z>#w zq1%9;B3qMUkw6EBO=5?vE9F5i1ufN>p6Sa%_=7Gmb`h4dGEpWSjzQTtg4WsLP@)s4 zIJ*!M(`4`?f3E| z&w=W^(FQ&nU(3eWj=;kwi>=2zpUO|_fWco@x^`w;S$869HIe((++?gdNqNtyGNrcO zI8Y2#&UEaD2#C9hxH*KROUhmCL08bT*1`mlhhoU1ppe8?6`R#&uU8oT2jj3CB%ykjN)@H>0rdPW|mG-96YPgU&HY-m^*cY3&m&M=0uaK2Qmb+!x!p$~=^ADfnUg{#07lwVW8oC1fy32sE;>J>Hrn z{ywC9zZR{YIWE`#j+~xy9)noAv89e~4S+r`J4uYVrxYj}%nHkdx7c9%oaZ+e#Ri#Y z;MA%(xhnSJwym6(k8mEHpIQ!$Cy=3o+n>Luz*p9v_8vS|o{ya?(qch*f;N-%Y53c& zaM&HyDj*oGA1}f$PV8UZHiJ3Y!*#m5m<(mLWJ~RUx|ZEu%aZT=sQ*cW1pkQ)YVtb+ z$Gv`0`V#ZAMk6L~u7QLQX+&6VOv@I99(7ib%bp9g<_ z3#M;~3Y&MKXW*pm$gqM>{tL^5GdE<0?6_cQoP)mM)ZR=;eUYqEG5UN+`h#e~F+rk6k zE{UGSt39OvNk&I`lhm*U$uW6TGo*yN6pY(A)sg*5b9wD>CcohRSlfAPXLv;;cDx47 z?ztIvMyJe`L%lFQbG;^0<)paF%+vp#NUIlaWWo!zar(GCq$bCAkts z6<1@*E2MYo8>V1QV6W(Zappz`u>ig;Q*gA>dxDgz&VtXSv0F3lW@JtTMmb5BLRKeQS0@*G@Vh0kraemj3jZ z-D(OMxY@Nlad>PHEaS5TRrQ9pQHLQ8-a|}noZ?&f>3XD5&m75L{y&|EKr|Vai1Dm) zjHaJW1XFa1y8e1=(c58yS$1he-))+h$GN^glrw?EoK-&ys0%-nR{Ma=V?rby#mD*& zx@{Sygo}=JIZwm?8v^f@wxyh8FCbH|YDln9!Ww%*Vwe^g9+Ze`I=V3*v%zbn1=;jB zsJ)DwhPy4SD0*Iw#^ckkQ@Ai~l$K}Px2)k;*qlX}iho9B-8wl}?LBUeWabLRqsSBO zdR>+7$sI4bt!9?tFyVV-b-9J!d9k`T&M%TL`+Sm;0Wn}=S3BI{`a8ertRvW!$em(_ zLu4%AQYs{Nf8QjUg4q}6jF`hp-b|5QlWYUsuf>?@&pYDwQ;^_`q|?e6;5#S$|6I7% zoc3b#>SF$&VrYSPo|BtX;;-n7Fny;AEAzeM_cU+4)rkR+u080i~Rtt!gHsDbCYMU zpw%P~y-<>-OjhPlaq{9)S{rRv>5Bd5FO)VRL8h{OP4uQJZ7YyC)SPT9Wetc&p?>g2 z@>E$}5{>jX#7DFgB7M8ZGv4~x9VnHm_4O0=DNAr~(0t>D@(L6Wmk1QcKt=M$%e9O@ zR5CqM(;dC0%=-Y_so;+Noc_2*5-yZnP6V!K$yhCmhc4?kfkrW>7yeX+id8h%1ksD< zo5dY$8!<}JyGgs@*@0yvJUYsOT)#Z!19&4;?=;bN+x>xPsae*a@~(pa{gDH_aKt+U z^-C-#YA0mSq{z|oag9H$X5=+hke0>9kSQcj(`$;gEYrF+S-33K9fTCRt)Z$Jm0=>j z+_af6Y*XZG68-ZR9nDx9!I(G3_ZL5QzUxmIN{!(RFsf@}f!Fub%u}TyX9X6r3h1S zayBLf8^l$e(Czo-NiqvMn&D7wH?lN#I`;~|w5f&Ii|uKo`p!z=lwLXEK0BI%1d+Ux zFS+hZ1XOn+*~y%Y;iHn<4=arQG*0g3oa1llSSjHFNY+YzWc<4l3?~7qURIlfpIC!2 z28jYZr16OYnA#fw$=ZaIH4_;xC~gj_D1~h%fhX??4NHezi8rdyC!~Rt`gcWPp!RoT z6G)^5%OXdNiF*ia>lDWB@~w6~bn!Qj!clgG_;9Cpyeceag^rY8N_%Vp*)Nutw9I7w zbzg!N*JSCQ6R(2Rqcd30zc7(4SIshCU`4|V{FZxFu6a1P{EwFY40AR)o~_BCnuPhtn_D=Nlgs7qXHM|9tYVjc!TtG zet;AT-M8uww%px)d zYY_x9N=~x|J_Hq4gM6K?J+qIqEP#|x>mLP-N)@gT_)&%sfQP<(wg;wx__GCXm zUhvnM&(nrz`Qcuzt3~5b6`k8^63kyq3n^9WlDtbEYK~+WSO#Bd7-H$cCq}vLo4nJGk@kpw z9xXcecnh^INo)wuQe|V=L!OW4PuJ2Qs-KaJ2<9b=mmfl=*a2x31KA$Kz{m-e1*ElC zu$mIt+&fwf1W4p6ne#A8cdMPoC*yY1B61N)e}+OMfs{o6$e{taE!cm)E};X~MUR53#4NtCt^a$201lbIq1}JUP$HX9Zt4(hOT(07Co3o z)g)5~dluOL9lzEl!Gb?jsP#7?oBWByK}6D;DNjDrildb@^M)!?7=v^crv0mrD-cTZ z_~n*Rw-qw_XSMP)wOel)VTef&jo*j zaj_@eO(OC=Lns__BrYxJC*50BqjYn*(VVPOcvu3Zv4}POpJ5ofKnVeP<~Q?lENK#!TtN|(If-Pq$mJKtT*_Wqufb=o^qjg}<4z#RNVlD1HK_BALafEo z30UTWz8siM*P`R3!@drgf0^C_v<7Q)yjBDKfXd%4ardr*;0;B?L)Gt z()P0~JS@kJ53nd~--{sf?J*%QD#)Lac5p`ZUf`$l)*2r6z&j5ChYLWl4u#&K;i=-y z$UD?|PNHREMpI}j;OZ*x>Ju$$`CS|{Iw(tB9;2PBdq6H(947+6v?0azo={8`r){~V zZ%zbWH=-pZJ^eJUv2B!|BB@Ru5oBY{C1#ejP>@J!($u=V&l|S;R8L^chl*WQo^A#3-!}!A(^YvSVBetvAi8`*3FB}y8;0_2YBE~8Ze+@Rl zAZ76d(^Wmk_1`<0R_{HJv#^8dT+W~7oc9S9@^ui3nGeguTc+e!e7vP_&;!Zq_`7;W z2f|9^hz~zkxuQ4UUfJdZgFAFrUvl@ykgH`DCXE(9OePD7#i#d1CSp5~rAXztMg%jD>!wQold^@}h9nhDYJ(J!vBUtLWvs4{M*Ue|p-T zdrw<_i-<0)7kbB+*fYf3D+cq<<~SAp5klxeMt{T1RTCN*og+Fq=&RYV9zP%+S04ik zI~#cUK7^+)Nh)I$<_osMWr;N{Xu3MVr{4#<(p$0f*X5EfgiVY2PU(8GEkF0t3m-J< zn&f%D<=2|4>evr1R1(aw4v*aO+6GltW>I&S{tYw3xBh3)Q0!}a5CC0d(~}=4B1b*m zgYg(Hz*7vS>={r{UKe5B)MdW;nHew64<&^5dfc}A*Jw6jiM%aa%hwFuY~*Caoj!fg zxBn;BodP=PZyLmlx%?Psd20225FxEePr~>&uA|uh7hX4^$mw8H&L@h+`Qu>eN>Keo zeeHMY0vTPn5$wheoDO7nEyzY0a}1aDM)GHN<~j0mxDQyFfYK>DCiGLN;Wp^V`ex%p zYY~^6pXyoa(15)*SRIvStcGHNpfbIG^!;%ilz)4_+Ci_D-#aew7<@PrcgVQA@;sbo zw$MN>HNgeZU2FcJz+w8Jo3_Ch`q8Syc8m5;7s)2_bohj3CDgf6`{q`@3eQ3+;&w|I-T zFIxvYrW6y6V(hJYWt2IB&|eVNBQpFlM)r2O{0_OgghAsma~7|lP~&EV5zc`$D0!H0 z+6^c+aw#6WMzVbA?5#u%Sn5+$NgfE6UAc_GNU4^LQ+<9)+YY`W3GKXss!P=O?PE70 zLUXF%-m40^mX&+0hmJwdU5kF~gc3GqPA(AV*D3Cp@-3y;tw`y5-l$!HrO*0Y(l0f< z*IP*$LEPU|z6-3DMw#r&Z__RMXHzV&NMQ1uZGrUR4tW2bfqx}t@WaePA9$$+( z-%5fX=Cz!wbRkxo&}rf>$XxcNSVw(gJxQIzOv0EZF%JD#yk!-zfhBOknVFelV{_6Y zCI-Fd8$fePXo_B+p+HlaMB}8yABfG6W)09 zZPPEBr(crRS4pw>`4)jLO=bCpo-SoMszIou9b-qO~O-B3WScLI|MAngGZ&FXZ7xA+hhT?Vpaog^s@ z@f1j=3Z)@6uAbv@TYJyJN)<6#m`4dq^jAyR$`sRXJ(TK*lZQIX$ur>Bn5+74ZhV#{ zGoWX2CqM`>@z`mal&{9g$->;4T3{9O-L?My}TVW9a*;V7S-zgY2{_ARZ69h+fnrwINc~~H-{K6HU@uyAX=uC1#mBz1MWf{hf)E35 zlB`|e6C}c2dVL|*?CSQdMbrwCP`iXJjK1+|g?4a)8DHt?`?_k#ms^0l2A1RH(BCSF zSK-riJ|Bz!|Ge`iX90m0Pc&gzjo9xCs7<|^7TBlCbNnitSLok-f9ik2(Qnn)X>RZ< zY>=EP)MZ)T$BB$Pd8kJGlAJIJ!b;*#38M!cpIRd!70&w+GUR*xd_6qCFFfCcLBz`R zK$urY5n}fmZ&fhi7~u7L6A?w9QYwd1la$nJGnNW!NVu`Z^KH^A{i%cE2tda*lY*t> zMq6+(53jA09AE6oleNYQSUI^l*0GM6vBhL zZDx8(Dm&<-G*_RvPDOYWza0HyX#ba{HdEDv)delBhWn&_31omzZMzEEJr0jl29^AUGje{Q z04<0G179C$Veyx}0+EHGj#>Z%>_7U;F>9e02bH3ToInI0VRaCy_L4kiw)?p!+)=$6 zQ$``Kqd?cp7#9p&{IQ?R$gx4#qP76$+&h#7Py$4jCv{I}bclGSi@RL%o403zBN?G z{PrioxwWZ6m<>R;$D2^r0(Poag*AhyAg!YPSi;NAWAbk_hyC>Zb(XGX**>GW1t*|N zqBQdbXAJ|Gy)gIPA0{|s!!5mdeV3oegifZ4O0-%=!qi$W$*#S1;EA2zIKs)jJFF_E zD+ayCYLc!vwmk){yCh;GSjeQeq8D54rXU3BGayqf-3YUkuQj$-;r(kctYl^Ng%NRZVpB{zDD!w`2$6^c~!&Y zZw+9~ooV}$XvY%b%8|cG+F_r^iC@L2td878(jYM=+M|o&q(h|b_hq9exT3l_;i!4X z$rB)J<7HtGLWD$0wtScQ6bzZtG)OSaDw~*LI$kN7dDP7O-Z7fQLL&&@5XoGGs{*ja{=^^1y%8Tg_TqH!_WZipWuvTlo^+0COyPX;G^<02BF8 z*?G*d)pKU3m8}q6O?60_(XA!JTe@@*nxCHW#wldCU#pOl!(q zOTu<|t-dehmQafZ{LdZ; z)wqqDU0;rND^l=1Q0MKX(yuc;eH#bHy#X3>OO=S>%~c+#e?;FSN~6eDgcr|}(kg}o zCHw=cQfF?sv7{4SFkY8ZgR!Dk5Z&z#CvszXU|#YT=R0wvGHKec3f%LsRZ^vL81U4Y zy=nYz#UsW;fkNfP4*{(G=G5v)P@2x*HFm%ZeYB#r7yN-Xy zeFNAN(#_?&%>m=He7p|i6(y96w478+Pj}ok)3q|f8vcZ03Xo-65fao4bQ_5_v2K&x zLJZ}2t;ymM4?@tp@+(~)g=D6E7{dc0S@a2rs`)0Z-NJ4wZakt>xnzy_7Zp9C9KO3X zpB@0fQ_QX1oF$gEfwqw2+v`2JA(9TM=Vq{A`$*qaW1|vz0S{dT;lya^I9oVQo~SKf zsVpUXF32w0^V=$ua8X^gWYA-U5+NrP%&wrEsjfElPFboG`}(3myNdvva~|3+Z{2o4 zHlZ$5ssq0k)ZOb+2kk#lYrRi%MOhzOba)yU@)#WForD zi3qdYbH}#>--A>^69j1V00!~&%Bg#1gcd6G`xAO4Mg(6Pv}7H85cv+l6~uB#xioC7 z{(#;p4LD4Y!FlM&!RO*q3Bl{e7~$rf(Yz+Zm1`cx^v!iZJHkeK9kaElrcw zACRn#7ck`{e=9=ysirnSfbRQs{lyWDZuskj5sg%CT5bYQ2u=U^$_Hdm!Dl7FcR6ap z-ZUc7s24w({iYVA&^{I(-5PDc1+K5?vCPN6-Y}s-k{hH8$x{)Oa{ruwjCs&OQ>N27 z5}{~6*T17$?rnezJmr%FQk=1JyffAMKEKL(EQ~8D1gjmw%RtO~^5}U?2^E@3WWkl+ zw!s~kgztL_Xd>le5aQz%+XKm)V1Jxa|Gjmy_NJ^fk?Iaq{gmWrtbT_?_SzqM zTxjMyUvNoOPgxm@pr{#Zc+bJZcb#v9a-=eGP~jksol@ut#SbqTzvEe14Oi+Cf5jO- zkXz;0yHuGP2kRBP)Qy)j@qB0V!hK=3g8fw5QOxOq(b)-Jt0V`$iuoG7x+a%co(ZeG zU|gK=78USE;sHlum#nrF7v%5TbetIzP*m41skuo|vN;?2Z*L$c5lNDtyYaDNiAcm= z>$7gxt=#8|aY&v_&@Vz_Qq(1Lo;DFT=$jLvQs8e(q0+SSm$KnZAAaqj1M7)7DOal7ym4+ILmQgt}Ta|4X-2p~o8K(`0FD zoC=l0HtVSb=-b->&_B?Mn-Usl9-<7=dh?V5dQzQ>ONX~m#H&3UCgbud`kt+Sxt<1Jtin~`5lY8Y`f>rdA? zr84*Qau?=C*loiNq_~{zsp%Gag4&N{Qtg{ev7poI?8!blaey=WPP|Fb*proXp<<%j zN?Om*ztgsk;kgcJ3KV@SUz?5xO_bG3kP{$53?}Nf_`ATGJ0D zf5o$lNL_uU_EO+u6Z1k`Dmz2umGID^RKlx7REQBo6!=jM&^ibWb(fixuH?HbkLeuT zvc0uZ(0h?_tF7n0pkSTarqGtPQA72sul^#I{5oMttdo?v$UuTC7Ws!6o-^gqW+v7w zYB~}vpnAjeY-(be(`Ao!FCIV}20Mk!S7I}Vb<bnWt|YHM>QW z$w*ifCRU>l)!w1>vLZ$qKQsym7S6-dl`uqz>5@~m$DvUSb7)~nIE69XwiT_W;|TNg z0%jMdDkHIGQI^<(@;PGC(aOIqb%Mh2Mr>4#5veCRk{7U4%8?fuIyynutRR}+9Fdhr z@A~@zEC!t2>C~Uq((BQy3XWwqfw(%SBP2*A#y}Yf2y?=Cg{bY-;Ek3n8(Gj&lw!EP zU27~@CE6Gc%fuVDJLv?Fq^}JBt?e@yt7|86Wuls|k553Z9<`hA>{7GP6>Y?o24mQn z5;a0sy8*^=3;n$h3-mJh#5ylS?E)2g>TpC`qNAw}?h0nn7K!wSK@1rJ^JKp}e63EJ zN1Lu*4Z)d2Dot#3Uhd6c2lS8vYiP9ZdVf>V4)ylL35pU$5O?qoasxRmo8;0t@+-Ar zKA7-^YWbw4Ig}k^rk;oQt@1DY6&pft;lS1$Nj$BcwsDm}I6;=VKoMle{{cQ6(2)w& zni-0v-A5*V+HNQ>dhoCHssx2X7eugM^2Lhs>JxZJUPp!19D>vlNs6 zraFeH#X1G=;5r6l&|X@9D$3Bo$J|~r>*@_`fKu_s3Pg7<4?+RCATPE~l4vrVqY51; zQAd!!IBmp(Ww`k6i=c%APi6sJU`_&Y0{p5a+wwo)zSutrR!`B?L~#Jqavm+0Lpm>g z@$Yj!X?hN<>Q|hY?g$et-rX77UC4?RvyDja%fizgjDeA2S^%J5%gb-ktk_xQMd zrfpF@0QkqCe8?PHbf(lTmOI?Vl0J#<3E6vh24^hJu!Pb?GC_M>gccT-ZGoZKzrwurHG@_-J<(kEBaF!kM52wW95*B_I!am zAb}{GsQK5M#LEv$&k3zFYC(8g;F`@?oyHeb^KBa{VW!YrTw%em4gOBEGV(#}kau5!yD6x~K7F)%X9_=B6^J%@D&ffL>b%bLltZURxIX|dvau!UCnF=)ThDTyCP)rR#~n zxM1(sjBto3Zo47%3P_*#zxp;xQ)h)dffPzW_n7pFw2PG-1$Xs1*Z^k)P-_`f7bl3E zkHmxYS20}iuoTOt`^?Cju#2{CfuE3wc|teVT`wZ{2^-m?ZuX1EYtJl+cWJl%Y{0NM zegwHKlK5Bw5QuXizB;Ix>$@UCM6Yqy=|rtqt7ceQX4Wz?J6bg>A4{Hv@%P8BrT>d1 zT)$-xX?)zN0gtRg-VhrX zMjzO`4g^3`^Nc(fy{ZcRuj+tU5P_braY&E=QpGOGllu*z~O9tT|~+(@Z592JaaPonb55CR8Z==Ad(>e z=0nebPb~?f#h4i)^C4N*u74RgzECQMz5Z`#e`k`o;8Y50D`kaw2D< z2)Jgn*@erI;da@`d1&x@|Kb?6l^v-uLgwKrs)Nee$Qv+N$ik=`e3cThI_xsMO5#K) zADb{sMV98cTVxcy`(7CvL3P3^iqh;-cJ;IBii{|KCquO0o9Pi<{HlI1e*1Dd_w7Ej z_X)_2c>^8`c)|f1UWMlH9YHluu;xrxdQjP&C&LFe7z?n3Lt01OAUhVY2hJuFv_Vvf zySZ&zPvgzZCh&nub%vuDzz+E`n$f!zZ2rBQ9gUCRjNL;I?hswr$(C-M4Mq zwr$(CZJW2v|7Ma&W--akrWUoXvp8SX`#z=>*0c`&h+kZ z+xk7{9J;a7h{)|vh;S5;hELR_)}`;*>7xA4fAShuiW zsMZ`ey9c;5{Mu!8nr);F@|kbik{k4Bn?5BpT6I#@;wEuEkf@g=YUCFInPaq;m;x-M zA+q5Oi$?R9`oj{ETJi9A$L|hs?GCBo+{KpBP8=l1ZjyB%R{*G3C@*YYx-o}?N*T^X<;V-@R$bQapn|P_`|re?p4yxw{v!DM+R_oEfw((*XU> zUPqbF;-pWoyB^uc>ZR6q^Nf$A;a)4y(>*Plzu z4{e(lh9?jj*R5m@0_%5k>L=S|3T6c#x_Ids zwGBgYg24xnf2gn4{x0n+(PG0s?l{OrPwT);Gw~tzwWsKeOEuc*0efVRvNaTxCR5@@ z<*DABve$y(3*#uyjt6N9n>ii4zTVu;#$=S5fV-z-ct6-PyJUmmPn2B0DGCY~Q)@0?cSMTwJocm{az)TXLSYsJL|! zMSNHCt#VZ5mt%LKeN@AYR)Hn>3dWfJS=oebT3Zin z^@&ZAV8;!maXHkS086^)XjNifxH;bt+bP>kF^}e?u;v}p?`8+u=Y2!U;Zxw7!%m1* zvB#B)$}nj|=a?-9ASU(RiXlQ+WJW4{!^*aL)TQ@`I4BaN=gu#$U_gT)3nwHg@dj+2 zC3fG~_r6oRC8`uE{drY2D~Xu^rsru0&G5H2&Ys4E(STbPd&*)b|MW*Y>;xUu!Z~TD zRRoKKxxPJ=l>mKNx5Tg)H@_mqlhIZ3J?QJ40|qJ|r#M44*TOWu*DBcRpfk(q&FTu$ zZ#67@hSAc2UZHg*KQcrBH)a8CNJ-|z@4UV?_vqftuGq4SNWD?-ld$SZHrCGjtWnOP*-#wHup1fddvWl$?ILrzj~Vi{wCB_3}-@>4QXpi;`zPI8$H>zSqB0NvUD z>-`vJbj3G;M4JKSqc#sC?m`njNG@2;TT%c{-GZH2PJa|#QLwS#gIhQD=hd3Pe z5mYM2_F5+ELTNg013H5D_2g?_ZY)A={UwzVIYBs!Nh}6qxWH@*&mU$}1v^htf+-c&Cl+!d1pl9x-lg?7H8!u#DOzKI@|k zmv%*6phY0(RFyzu5*APPx|FN4@>Op7?N}-WZ5OULL0SbTc%Z?iGgITO=K(0-!}uL#WeH=1z8%%kXM>WHQ?2H$6Sfu^38wlo z3K6V-t6lP`OsAc{XyYS6Bf{%w%TQ(a5T zeq(Y$0%dn0`_!$;bEITymvk7N>GiREE@hGd%xZP?IGwZKz9QZ2c~h0bt64+y_=9Da z^LEFP=#tBF!`;Ih6L+l>abmamRRPT1cEbmJq4}NT=IuvvBibk-JhzAxmUhhSP%K?%BmEBDPQm>EP}isjem^< zg$r}_&Ss%hX(Pz3s6GZ0f7%>2{+HP)LK5-=1Cy%3o&%s#MF$*mL^GPMAff?shL#-2 zYWWb$#&5Ses*!ut-=g)G7IpqPF2j_c!BT@&3WL0SHF5n488oq+AQ%nzUApP9-3;!; zw_4EiHO_~%-8h?1!-DzQW92qW@FCpL8HIabq+SBYjIM`k>qdNHhcV&FhoI(4dsl4% z7<(`l2qzcz!U+|dN#oy1xlx=nthP>C3&ij%4)#FEAU}1-Ueo9?XcXSuovRRBi#4AW z0X$I96^MGaKnWS@K)|4iCMCn5wAT6sdT!!E`auT9{+ER9;%lTtRBzw=+C@8JVrH1{ zBMMnK)D~{WL0x+>lYZ`4G>){I)&1dUTKF!Jfj_SU*=;E~s=IIgYs@>cM3s1>>X~wq zqo(`Hpf=BPRqL#Ch)A@>FG8YQK1Nd1IC>SodD-*S3?S{Ke3m-Wr7JTgY5;N2r30ow zoV7Ms#-Vqo)@dW~Zj)=ZDHW4;XRRlOy=sH4G2$(CqzOoJ1UE z-6l_YcYvXDe8GOVP}<378OWO{0x~uFr*K=9Y7KiNwvD(bNZRX~8T4Mxb^}nx=!je= z>L-km?TpwSUeRS8)pc6}us0hhJ(U6yq6C5x(C0dG&*j1;L8^< zI%I6;S@6wprW^aows5+}BZmSlx-2j1vM275TL_1YzqH90kNsC>`Gk3g`6q2a*>OzE z4{i#Kk?Zl-W-S4IiAuta?)A~z!x#|=f-Zh$(8wDt)Agi5!3484CJ5qI9uMgiw3b<* zRtY!?37K+O!}DK=9SJ~c4<%?Jd|@msB^F=@&P=2|DJO#Ho4&T?!5v~<+x;qWC0y`s zP3qj`^sOE8=jQiv7AUaOD`1n(5c_uAE8y%7&$yvL{5YJgC%!sxfIv&)0(-i1~tM`$^4s~vPPI)q}oIiI!8Xoct08e04_~{l zl{+lt_}zJ|l0x?YnMC^>9+~>@ihcS#?`O~}$Q$$*6h7VfzrhwL^aq}G>QEbxr7X4pPSM{d z$2+tH*V{!>^N_08czK_l=?B);ra4G;*r&iLiEBp9pR10uH9(!q59&xoRfNQjI4PP_ z1B))4P@J!UygA|Mvk4x-)F@Cgdq^Y^W?6Rio@<F5?g;L*CdmbbH- zT3P*_x1W$;EXpYjn+8KgE7qMa@~7L8R|Z2NQzZ=L3Za^<{_$}rEtR4no}qI)twqYX zl*THUzayQ=rd#c`y<$d17cbWEe_mD2ZP=Wd-xArE)+h+2>5Zi_f1*$0<_thTl~qaS z_~UH+5z_GPs+fZ=qWEcfLoJ-ekaeOJF`?m#qwhw5H^7=FI%rdavZ@PRn+_))T-==_ z$=fg;0YUJfW?2;C+DD9$4NN~ZIs}GZkp0sq1duJS1FZy46XNH=5_MIptE?f3<(=td zf^gXFE{?naI(KOLDz|VHzrPdy!Y+Ba^5<3Ztql#)?zspogotCeuGZUn>l^h%E5dqj zzK*NS*Ri&31~&&uyraDVk~ zt!r9r(hSn@tk9esErFmpV;+%_fU?U^}7 zaG^#GNOvA8s-ASoBY>(0JMWBi<|NBmZS0!eHCairb_^XR)6?2h2+eK8oF^1^QLCv2 z!76!ttI0ha*2D}7)~1M)`WIpYH!-_dY}e7;g7fNVYC@7J#eU+8p!0v9g%P79?;RW{ z@bA67ZbLL&KtlNM9>TZe zlVCQ%OZM)Tfn8!D`h|zyk=T-eJdtrZSv_JQ0ZP?kaHe|&(a5OSml@`sjy9yNlFA5f z_i5-~%dVrT**WgKamdQxHVIEh*%TDbD%O!K%XK+QXJGNv`dUUUc(lCXra_cW#_HN4 zXcT8lSRO{*mFAASrVt_C2x375F>wH&c?K5lbg>4N98c;^rsm;LKDQ0|8m@vJ&j|!o zWyHgr3nv92JV$UiA_1Ou?i6@_FO&ABlYq#}I1DW~mTqA?v}@U7t0d0q&eXZLB3=~H zAdHC)EouV(dY2b3!H=xSV1~Ipf-(hHt(zaZR~h?e?<;MR1aCLe^oXNB*vu#OQO79f z4@M{o24E1KI1_3}UFN6}^gSv9Q5&pSw{EpTaldY(M4{>xF)X94;3OQNJz4JO7>UC(Ea4F|r@sbhix!qr>l|F~SF z5$m()kIAZx2#BWbc^$U%`1WrU_Znju+&X2j5LwUKno6&bd>Zv|HHs9T4$x0p6ATEY zqb(UI+;t(@^8Rb?E;ph9bulW=%!4aoF<>`x-KDcg_P)&27%UEV3>(Xf$+^KuX!l1s z1Fyv+cEQoJ9<;NgQYdb~+4HdUT7$b9A4WTUtT7dwoa7kypz!2|67jpqvxS1c3GOk= zXoj#Azqn5l}5uBcdKQ^)s`m=NcLC zJ!(Ey{Pf@?F1WJnAPFM)>su&cFMeCumGrDw(~VeE#e@erFGO~=`bs?QQ)l6Y$|%-Z z1aOA4mAv3uCT}zRF*6>c+D_lOwoo&R6 zu!5&HH6@EAujtxJ2uPd^_PamBP1l4}XDhWI>`8+1wI_t*KngaYn!3DjOoUD33>u}I zEMC97NVll(aVp-{jc~j!--T}zcs%4NkX02r`~$4z8hYon69@+s2gt^7G~@melgG`8 zM=bbZn%6&kcg}bwe2bH(i_JSbA|(D;8-2Av+KGJtH*3qxO?LsMD;~Ppog8AN9^%$c z%9WmU(A6h**apPXSA61jf2o%R@C7bGBq+=QEO+8jyOg-~%xu_8a(N!_9` zAs~ppca=Il_f>XpltY=>X_|>uupzz|qtDpD0PEsc+6AQFU$4p~N~*5;djrrFAzRCS z+2I(JSlW!6+@Ji@mitlL)$<<49S( z9N?)A^=ZzBNg8TfCJ}emj)248&91KGSS2}?>CV)?G1RpA6m;zm6_9(!Rx&{D~bZVQ$xeg*260Pvi3us1N~%*DnBStf_%=EVR)yXtb7fr2*L z*Kn}F$65?)qe_p?6|T!0V(M#Bv97;vI&i8jYpR#pjL85vIua$7I~}EK1&AKmeybpz z4Z9npeocRyla&iDbKIYl0M+puWP&{ z1_HAWOgs+R02X84hndrgXauD!T%!jhqSmFPMTYR%k^Nkc?QPBG%-dRhm%hF??u4&w z4omd@T1ozY9$)lqtskZM)ut4fjIHeS_&4t4S3#%9A{m%imCryH^Ap|m*EEBPg{zfU zFBFYft$wF3BklycoDZT4qf!JFwihNi8T5+P@Si*+99vfF_)LPkjvVuUt=IWg_{7gE z+eP}Kj4@vrbHYWbs4>e_ZSc!4j9(|WP{kDLci69xmdbkI;J+o@3KB!;_8eM|G`xWB z1R(GWDRKsZ3f=Nl(q@8>(*O9|s5WDxN&AlD6oKo21K0tfc#tw%FZvlyg=~hr^4xIz zzn3F6pTO;BX@@fKuXjLZ>bb-$Eazdy#NxD}uFC-jvEvC2(hk#=h7zv&80HAIv?cOq zCH^+Yob!Xva-3asI>U=!#}^ThOCm+14i=EYhVK~`b}Y}MV%^s_LTdNCxJ#=(-Sc>; zaFN4Np6YFX=YbK^)?4C^X~i2;g6O0@@W`JEGi_g%j@9momNv|_F)*`ktT#Okq)&Vk zr+e4m>Gnh%OtNA$TCR=2;xjWE;%)W&5K$0v$bcT9HAEYIYTXxX$VRzew4o@{a?Zzb z?ulS^>JO

ZnwtSqv9-!#bPLkDe`HRP(&sE~v4*&^~xv=AS9CYABp2&xATv54}_O znxFv4t0BHTO=bPDP;t7$rr*cJ*!V&E~Hz&06K{qFF z&sQia(%+NvSVtX^wVy;C!L4%ltGftt-05erEwFrze}gu7!lhQ1 zok{0(EE-E#sws)O0u?s4;2(zX2Nhl96WD?JVy|a%I}(iXQt8Du$Oz8Qw~CYAKynng zpKGHMEP=b3Pn(vw)S5MDRiOZmh9W^Y;&`-y&2@lJmv(*hR?&j-VRnT!jRu-X0|5*z z1j3yo_wTwtIzOQ__&m#!;-R7Bs%LO5@o1CL%YL3MnaTRAFK0#(nMcUzY-T`mJ8()& z^a*{X#}IbFLHBpwyJb$T=>cXX(Tb5HKB2y_^-;ZZF&e7dszw^r5q=e*3MGgiJfd?8 zM}Qoj4~52M$h?y+P7%;)UM>0t>|qMI6V@IIdxsF9Ulf0@#(03gn1;d;Dr z&_^=cXa41%HXt?JTdZFCXjp;A=XT>7T2~1~&oXr8XtNIe;i|w0=MC|0iMreW?i~}9!7ma{QRLi}ZQWL4eLP`3 zU_66`*nMhCEWSGr&XXBW{{%`!jZ-R0Wx$S>djd8{dXycNFH3FRGIhz17Ae|y7E7U$ zgJ4HZKT$=3qOStD_(FA`Qqhnxxo$?&S9p&hHv!UpNbFw3iI9p*n%NDijxYJtaB{@8U_^G z1JY?_wfOzRO)v%9{{1Ifr64kww{{TFCExbQaf(;XgECVydfGgHhegENs0e;c`kKLD zxJNC_ATF=U^>dxNn>@?%?F8VnY&$RwvlFCMsQGG}W3#PhRUd`WBh&pgjBt+VBEK+` zgWj-2@iCp&Lx)IiZ%JIWHPUig4f_Di;y>S>(d4i+%gNv|#@=$yf*V5>`?ScJqP8NE_d7hUgWB2B zjNct-;@TneJW!BXvYIVq46_IMooVePy=pshJQrJoxsY&G5|#RwF#KH7)XVv2OJg>!+$GqpYD)EpI@w)0KOA5W`(rqzH{^g0JS5!pJ zD(GCTuq^6E&|LH^dGCu577f<6W07s{bO7pnG>41tLbJ06eXgPg7CBKs6!H8g zJS51(6LcJ5duvU%qt@c&P_c&l*_pq71BT+&MKkU=X=d`P$@{z;v+tUZ)<5EJT28{F zQni0}lB3>vGb6kU>K7>n`jsYcpfs6syW5jE0R~}ifhmLfPt71{bG|p%6(0Y@%IqSk zImTcYup@R*4o?`yY?_Lnb`b-x>WL34T<)|ZaS~=dcm{!VF>vTWB9pK8XTsd4*WHG| zp(L8a0*d%I$|>BZ+5wf;v=^zu;vmW}fp=Mjog6j&&M&wv* zsm{>gbgMn6#3-MGVcP)Xk_H;T6)(mZjNkL>m3#2C>zIyDP}+85nu!NG(N z(R92aY^5h^ybNChC43;24LT~=e6kxHUMoWP=R6{T?HFF7w^VCenFju7+Re@}lJ{;i zSDJGjoTZ26t=>o1c}JJc)y1crfGOmJHh&S`7u8LzI*A&ihR~CsKPjbrnE;x2qj^IT z1j$5S!a&F)-C1(EfoCfCM2HMWUT|MpBSn!DOR^Z=OP_C+Jf1i+=-(91kceg~(lPmN z>tJyHF1hD_eoH#RYC&OF&UEvE1t{I-&jyI9hS9riv#|}Q?tfbaVoFxe;VBq%P)PvZ z0J0nvAI5z=A$4Vad?EN-4BJHVhs7B%BUm76DzU&0)cpZBw472o>nskwoe`Pv)M@^? z$#7m#*Tarn^Kee(zuwE#XELDsf~MAVRe*`n@^hog52vomo2oX>x0F-L&f>|TR_B5> zOf23EWm2Wu;JpX}hSP}O%lcnDVrGW_%OhrDVPfX^Z-n@Ndc;gD9E@!LUyrz5Ii5iV ziT0m8{Es2V*8jI`?flo;YJ11e>~=b8XR|DQXtF$!g!!yc9Bky;I!lH3LKfW|{Rc(| zWYS2gF&YL21_b8Mv_f(5U@RHfEShU85!fu54#*|hD99w)3rMsKhztx&v_dh+pz8}> zESlNrEC`BN@-G}xxh6J-_PPcKQu&7FR)-cw2J(G-XD3uUSI0bO=l#OBa>dNrKJHAnAtScKxVnI2l(r@w>7q{bg z5F4XY^Sinm3&`wmQ#I_5Ip)vYhyLoqH$NIK3Ndj&Lr4O1KtV)C2rbHY-=Cyr))r!e zPxXMzyAumhH18Cqfu$He-k#B`#8K%e|zKq4NV1gRD(bKpzrUR%WD#H8bWF? z0~-JGYhiI<{nG#23=A0YYdz~T`RS4ciT+(nV|8$Cb|9ZO%l};SWca%JT3h_?qaY;Y zcB9u4gOdZ&G9wcM5<^pC1Cldy&HF{yB}Nw)N7g>`gZ`1H|9$@Lksu?xB@%5s;*5#mgnx&{R0n z&NkvCY>4k|e7yKR^H^635UeAK@fc2f(GlxdYg3Jg0jN4$4Dc)C-l_yL?`UG;inM?# z-A3?!i#2Mw+=1LG8GbAz$O6zYeAz(8i$1>$STCoqK2ZO`;lLWM?{Xj(9E)5f#mlUa8WIaBEAuKX?%$FK4iHrBUV8c!b(6NDm81j$LDx1le*m|I3=rctZ z!Hj%mLmGL(#yj(K#Is6>Lw4gS=yixQ%RrsUN*aPHh*|1Gan!^W1HHYMQ(xNVc4sB5 z6S9XIOakaT8?OiWLwAN_%dPImw2Rss8fln$^xcT`oxxkeWD+D|%PizIAwSP7YC4)F zaD<6!aP|<^19jX+td+1`RLY>y^~2N;29lS24THoGX&jAo&IE)1YR%?1EyfyZyQvUC zw#AF^OwAogV2zTbhIlVLj|0SB(K??4bZQcSNP(Ge{@@fs?GNcuPzXjRcD7ug!>XDr z1d>O&&Wyz}cC_wzRnOkvou;$Ty;cU~GS(bdC4+KDd1&VHP=yDSATU+&Y{F7c{b9qZEb8gB&1TAK>f)oe_L*poEX2rqXkij zp8x}7E@*-c&mj$cC@UZ7iplq|`?+;=*AS+RM^bFJg=l_JImLoi(jiSG>8%(ihGxul z646sCqwD?mmY_nNuF$Q#DnQ1uT?ckK>`1Qd3cPWqlXpjuqY9pF@^&*J6bFO3iG?*#Q;gjKA z8GHy$E74!M-9}?k#ZdkxTOIHgGK^ezn?E*9xVCM2B-uW$+DbjzW^cMS&0Mn{9br2u zYFRL)abMF7_iYcp*t(jx47ZZl+d}rT1Og5H*S>u22azz(j%*hXX1&aYR`eZ;ViKn7 z92O1~!jP1j1uWzVK&&hHlLy+ah-tNZG-QP<8z^PviGgXip}wktt=xttW<2Z5B&KWM zO3`f<%QKk^={DRt(08f#_>(_+*kif1R+AyC~ zcE&`H#w6ZWXmG4c+DYMYS;}P^?f?ZsZ%ddZKqPzoH_BtNIz5&c$l-mNNtt_6nWcRPnGnHLr$HJeFhdDVCt z*7(Dg*@&SSr96CwnZ>6uP;*I%cr6d+Es4S)It`&gdb2K>o$SgB<+wB?eIZ#T^bRQ$ z;eKON8_ZPC>-J0ek6xt)p9GJ4wG>9t4L!Qj1R6SK&q2aQf1Jcscwifw!-7KqBcsS# ziOMD6DE@(m7DU{xHa|#Xc__t@i)U1BK2XbC}-7b+~;|(vMBtZh|y-`jkntt~%Vn=^)EwpL^+|&+$Jl)Ti z>beF=Drf2LnxnGvJXY}3#6j=T^354pGZ1@4){7^7-F}~hyg-6tck5MV>cmMxwOJhg zG%swP)L!lb5r@DBa*EDDVX>=;tT&3=mihwxI>atDDuYm&D+gXgN~qRsZ%a(@Q$qVE z7rh9hm_Nw*iR!;=1czVy1mYZDiss==-sx8J9(v4!lryKdvHQju%7>IhAs zvU-QrS>Hz_TP#EWvTug)dUh1J?z0ebRX#)=%QMT9@Woh+>K1=@<@B2hwhlp+31qQ4 z?JDo!s{(&&9;^KC^X9`_y@Jw^D_-3OBysTqvI%0ACczsa^f`atXq3z8XLrOB@W4Tt z247?x&UZ*HSLw~rP?BUhk%^7m03pd?=ssU)q=yq0n?5 zQ1<9j0HA*$j%^rhD6$FTd1^p?bs^sUZ@F5u-5 z&TYeCHwBubG)^6*@PR;fN=r9kS0iD{KvqRJzZ->RGc7p_%*2g7!E=F-Naj%2F@1;Y z6VD!7AeT0oSHl zHqWkh$ShAus)NJi8hs>f$y5IqNEo$Y+;Gn$R@Ft^y{^Vp^ES*9@04e+%fFzq;GQ%7 z!|H{n;pQ0#L4=9-(1mZ7uCSx9x|$YH6cj4Y9yHHW(zY~MuU6L3{8BNp*^iJ$ld28j z+Fvx`mMq)LYrEvid3fY6YVB#U@?*Brps6;BxAd{a_%ppkC|L>>G#U_C2qhO5uCLz9 zW@EKAsHZFQCKc`=m_1ZVh9X0443fL1+h?7`cNg5-q+K#P=M%Nrn5JPe`i)V|>Xq_H zVj(x4QlFL{|DAyXG^QHGZGf8~2lggWs8ly}akIVK+gnrBcI0g-*dVV;>8mnvvBFCQ z{p4#9+)-K7^6EA^no=)*l(0RWA+glPbO<^)No?-JH=ju9O)o5{TY!uJLjVn4~93?l`&TYn;2CN&b?kM6=QFh}5 z(0dcfHcc6{M3#7*T|Is)67^V%-{GXUCD~057z;>iJcn7^TPhn*5afm;wx4kQ=49m> zm3adfJx;`Ys1t6vm9)@Vm2vrFsO&>A9u5XK?x)EMJWs?FS(l8M!$3jEj-Z1(qCrCI z0@6M`gdyE{;#J4mDhzLnr%biPP{kTkp+AM^qAwTFSK|ti`uYxg@!bjf!s&qk7*HQJ zR$#cL!VW;8BUz`dwO38$U6kHAc`UEDl_5gpFqHzVKrxfZUieK9=PJ+pe}q~mXG3LC z#vP@cJW1<&VOqO&X;S0kzEnS~F+o4!7Ho`n-uChMnfRNz>c@*EJMBFas;6T>?x!;W z0s5-aUUP7Q5C5_|b=v!T#CgvJfVroEMA^mR4olhD@W1bYni5qs--tuZctvDA?)K?i zxLNBGz4KzV0V;rXV>1YujN))73|$X{8L21b#S&M0$y`LS!nE~R&*{_F z_A!wf!PkkhFb1v7&4LwZfFLH$Ftws-j^uA3Cm_}prEo-hIRjUkT}kG}p-(H{eaVlU zH?5`RIE*lZ5OBaql9J@w4nP98qd^VcChFF?N)60|HZfvi{DUz%eB}4&Zd9Z!;8<1S z-+u|&lK4{>IgE$W5Q+@-30e#)VUN`3 zdAaUnkPdv<^Uu`W!%^faj#$K;89*eR5Nd{h6P{>o+bLsvSz1i#*+;S!HeS5`^sY7% z-2a~70>OQ+^4p?{n#I?P{Q8mPNetf%fnB%W`E~5``n%4`W||*TG%B22Tp~ISP{M<9^MFD* z%S77y*90^(>zQ7cx%@3F-fwmX*Dv%ev;7an~0%~*5)3fe329iu${=b%Z zugh+(+NfgU$o(PyRL33Da`u|7bv8Opa}mgjeu+@9SgtSU|FGFliY2@5wc%?+$Rmdx zQtV>2v=ALCe5p|OHrxdS@9+vy?IAM>c`F7!-DO`+|}HCbPU6-qKmKuK4ZAFhg<3uO=@es_VUsccH|>( z<0k&JIS)PWpXs_xTwf3eBI|^Ez*Rm~f1D0J7F11BYL|Dd4L;=HiG;K=W&e#c_2p*o zf&kbi+;o6}4zqJ;45!ZQ13=GHuI}FaNk8TK^5!(ZMrpKJ%4hSKuhUw<0rF%J@yw=Q zCko~;fthcBEyVbZ0G_WbtUr%L!n>&5>u=U~c%Sx+q%CfDsOdZJ`t#ADg&UePZ=? zw~*0+EldfgE?n70{TvuiFKp-Sr0#DH(Q(Ja;W2_l;m?AET1KozhH)U8v#L0(Am1Tc z%kiLjwO*4THPAaEP={Olwy-={a~cg%4BNF~t+$oYl!o_RGG?Y?9uR4!;fT0e9S`Tm z&q=;69#5Cll)EfuK7fnpi)-^xF1AW@=GR6kq>xm>d%M1fG%P2F*Fh8RX zVQp&Wy**M|viqaoE(s{;XFWOaqAV&)2?p>TVD1r5=@556aQ*jwZjk?4Cd&uNAat8i zY*I|zD3TdqI=+YF&b6u<9qc3?GI^pj5DWrwR-W81d<{%sl#wy~v~+vgZ0jANY39ia z!b+?&ND+-&k+OHV07MZ;HTGl$=W>wj@nTHZ8N1}N5QP1bHdl%>^V~M1PTRJGwiN1@_z0*SI_FWT;x zWw;QkR#7tTUj?zv-Ywur;jMJ0?!M;9Q;zE2@f$$st-R=1VT%=@X+V`8F$0&uE}Z>Q z`~6wPqe8;23Wl(LOp)4^lCu^{83*M*9E`jb{T078Vi>IzX{TU+wFiwEDik7I>i`C} zq#4h)?-Rb@e8zL+enKq;`Rb6dT}nxZe?GeaHfIE^zKg=fen z!cPE$^r>f`ug}4}uXsrM@2}($t+LO!c!tq#NUaP;u-ppYR|IJjX)IU9kWfEmNGs^w zQlH2T6R->+ID6(EpAu0U5mziLAKH@0h8WC_W9XR8`oUn}d1yx#jXW4=L(%ENA&6Lu zV?};S4E5HbxZ}o$bdCuP5z|y8SLAop61$n*;5SD*20qhh$t@`ye(I(E386iFWQ!^z z+lJ<2!LsJE8{_Ju;>ZZ3U8=akKSYvg=p69_wfl%%LZf(+>u0O)I2J(qz@))Xc*VE%p}Sb!1+&i^i4xk4`wFdok}wx;|}wKj48YxuV}V~dM_!gi`!)i(tvk> zLM?-o<>w1q_}D*F2a)b|_r^Ok{W#=#G>6T)iTT)D}$ zA(YHEne1hv#}}gO6c1OeK{~?&SxtBi)lQsG&To}+%_=J5DPb2-HXZZb>&a^cq5Y7G z0&B@d%Iau<;yZU-6c5$jlmZ{`{ziHoZYj7@y4_ReLvR{ju;>Zqb!5Q;HRVGe%)kWK zQotf&lJ1K&SqHiO5R&h@0oq@}+sJD>Xr5DNODG((WdyxaD0 z_)@ehAn-84YH(nGLnTjVHLig{&cDv}09+)YXfg{JU8rj2W0ELWaPR%Tmp0!kodBXF z6v_5gaxCLg)XjQ+15ou5%_h~8#;`ls?J|;DfypvF=qc53);nDYD!8vK=4`fVPM$4< z5b93`L{r>qz%rerUh2$jbut3Ve4zZ%?V8u7!R9AP^QtP1JGG+;=>GYtnq3 zl*@W7r*BUaB2_&I#z1{*=xtWnqww2=3U=FDrA3sKuzfjrD5+dn-> zVQfI7={Ll_g$4IEFDudIEU{GkzLYY+FtIHa6?Q-+{$7ZmE^5#xkLpir6T9`K`vowt zkXS!p_G;N6yN^?MwI$-R=qWIDxX0cQUfWGn`N>&|Ys_zxtOX-KxVMb>QkcTd^_y%Y z?gPbhwn{HP2|TSCUxno}_>xNB2WrKwC*YBH-@Zls!MGcZgZ6lZN7SOT%B8yDdc0E? zjE^A5#J=kw(*vIG8C}DFHD;A6T=xyw?7Sf<$3=Q;0Ho7D$UN_;tN;UL-3V++wat9$ zvo%++TMMO|poNS31gi5ZMpaoMt?C8BDm4{VoU!3T!?hXRn@Rj+dJb$C&t!pZp zE4^yIgq8nJ>WSv8cI{Hqsw9yHjh_0O$`-=!DNu}s zPorCdPeW@f zZ^?i$%6Lv87BJL`e6+fDA@gn$Yhoekm8*H?90V972!DV~zX<`F``;LwhAA3S8F=BmKiBv~G)- zkO7*-e)X41lv6ou#wcnDuKyc0;mzS{=ACn$dk%vNGLu^~tR@zUWD(B=ef}sippXs+ zwlbV~)dH^y=~k z(XG%S{xM>*ns6qEl`@8~+Id9NifX8p)omoP&aCY-&vaLN+fr+*R_tFxZ_qaV z0DO|ReNk{hi2JjokpCq5;%?~cs8y^M2DMoU;;MSmxhmeoc;4KjP)lAnt_6DcOP| zgv;6GlnN(VMFw=?H_4Lal9*Mb5o55HM(!xgv*^mi!sAj@)ptqfa>#q^Sfg|A64N|W zpSdg{N$SeFzz;J5kD=3&Zp3GyMuI_iqTaFEsvxOR5~2{?YoI=KK%tDOF*dE>*?&)6e?c^~ zty3e>#{CyRKzL=QsL?{kam`W^Ye~d%(n!lLnkFz*&UH z)!PIQqY8+*V+xTqtSJGR4xSD;>)NvKG-9q>-mDKIy4lpM$mr`23huL@l|xOSNwU-d z*lY#!5S-+I4r4E0~%@-b@ks0OHHCC?1~t=4TG-;Jew7=GOkDOkg!CJPLj)${XFCACr_1W4BJm%>&S_Z`Ey|(Wwr%5V+qP}nwr$(C zZQHhOTYamayQ+U;t;|%Ck!`G41UFM7pf$m$kYMaN?hF*CE72b)UDt}*a45Jgc3Hq; zOVuw6aW}7nGX>c1Iil7EWvS5s>H%*kG`#MO$nisCSm|}{2xsM~&UeLx_(D>H)-0XL zHSsU*Bn4>lZ<>j@kf9CL?)@kNoy^z&S z3C1YY2dk@33nTc;f8M`9Od(q$3VKg7S2T=uR3*TAL*hkU2f@E7lG;Q$eL8r;mg(}}JlAp6)e8P~oGUm;)S zVu1T@C&U;*Vov_^zzTPkrD&Q4rywvq@t2WZEmw<2;@@NCGL3r9d17m%Lkp2Frvyn0iqdwNKztQp~B0f3Wfup7<0n=}!+%t7S281sV>0*_eB|Rk` zVatQzDeeE;D8_U#kl{ypGZrnc8Ns+cXCJ{ARcO9AcFI*66m^@~4P1bQ7de*N zY(%)rtKbLtZ0SZMni(QV7)hBH7~UO>!Zswd6Hx}6!YUX1{`Qp7LPn)%wY9y|7b3+M zGzzQGzjy0s?nu!lmgs$c$OAPC z=J}vjJKx8396DDpfSIb>v}jeW>u65vIXCmsRcyWOgPWA@Y2kT!g53K+6pAi_O|&N( z`fQbZF=^!*JrBZfAL#SCfDfzKRddFecklJTh3wH8O(tx*vhj1dOvnmYT)&M&vH5kR}4*Zf>c%DpW(>t^+SyR;k=z@IK0uZ1k8tlV6%J-n6Wu!kz3abs8VP!7m>dv zdOIt8?qN@nN;ODN$*F}_U_7V2imu=2Sq8vWFA@~EDDriy@7zZP7z) zv8%`b62Q0RW*CSAA3G{*1n6Sp-+g|##3h zlcfG)aY57wRBCfy{p_v%hbIGqja6Zv__-5?wB9^)O*_er6_ZD8f&?U(5AIZfqHSdV zBKPs~TYPsg1iScDq|@Kt7Awy($bYX7W(UDi_n!?DAGL>4!huWS~n~u6^DL7eW53v5*7?ZmB#BBQ5atYWE98rMRU^sqg zKrmmh!WHwCV!%f4_{>`ntO0XGxaWf!nNk0mZ=l#6^mra3peSZ4&84pU>D+qqORT38 zvukUO2lH*dZQxe2a(S`tQuv;CsD;uDGM2==2J@>?317naT{s}dr0mX%tns5)p68Wu zST*kRYH_{;xe;6P$sZ<3#fdZJj8q8YTPI&MLk91@PZyTscqEe6NN7ad*IQ&0k2JMV zVns;DWV40uDyC>QXS|I&BX@+!cGw+J7iYs#VZm03Am}6|XdW&A3j=+MTJo{tH;Qxy z0fa~1M9&I`*!Y_;n3O_@_|OVc$bgV}xUw(_Dbyn5_0(99Z0YnGgy%1F>H(=yKhGaY zqPG7h3N~O=J_>M0V9>$4=#l}-DOx~@UMOuEzNTZLZq25hp#YZxWbdM1^CAMQD7-2r z4pWXOnmXEZa9Aw!$Eaq{mI4-wgAFurt8uN?-DW(vkG=qcg9}3wMBNhbBREGP4c4)6{cOhn^sh)55^!Tw^BoLYCh6952CQ-zWd~hn~%lM4SN#>-- z-{p17#0i{I(}Fnh^oLz8+2j}Y?d3`m5a0r#6C2xM2TFBy9pM{;;9ey4Ny;U~W0 z>)O8QklNh+V4I0k&zX;KgbVH1HJh9oCb4L+} z+IP%g#S^UKt%`%0!PGdRl9l=8^Q|JzdbXAvc>z90?-FKX@st>XE@8n=N?Bt_s~Zzn z;7O#4V1_pczHE7VdewgRV5<~*4> z7bx_M^#VoY0m3JY!Q;LgL5F5St$Rt@F%TvZ{8GRm zTGVDvmNIhe0{(&(C&$+cfNHB0&c*m(OvkfKb_X}8|Juh=GgUNa+Lrzo7F0ymvAKKi zfIyx3YJiw_6MA0Z{bStSm!l7vLHjR)5rGBY1EXaM!D#RMi4LBi%6J;kTpKziJ{#3sma^VzQWy8oi#$=n-x~{ORYHbeANBP%wct||*ReD0a zJ>;w_(~@EYNkhpfh8&>IQ`bSa+?BY`<4b)VmcDZRew}Msq;qH?^5oe8fm=$-l!Oxl zrS`}q+I2(cvh3?Iz5FEMasy^@{v^K4zvo47>-? zBu;xH7yrY$RTPSPp5Ey(aT38vG*$h@9FN?%QScS-eHnF3b% z+@uT~vbWYz!ID_Dk4wf&N)z$(BuB>v%O~tqo~Kc9i4wpyZH1@Zd+w&T0UC)n8bup! zi%Dh1OrtEJg(My@uq`Zng}KWK$_I#pX6Ct5a%qbQ;B=hZDeTjnla7DWH8PE!8Rvw& z5$Dq!Zj~zvux|Ewbxqs(gdTF>BI6*FSAbq2S12;>kJ;C2g8S`pHjX8D=E@-#(Jpz6 z%4;9<@C}%32bt};PzDJXbc1s9ZV4y1+tVkGGTn*s;esm*@vx@cA95GCd36vejyf6O zGFFBO;ogW8qxD%O;E1fjFbl5x1~+(@9D-NWcVq5Sx)9^S2^Cq$CrPfi%D~{OqPw_M_s(slt{T?V|_~ z4uod>tw>gj>slYHAmIz6JbN&FJlbse1^X4rwA~n|^!0f{D_{eiyI|+YK1OqW1%1oR}HjnC)5MZuTilm7*7Iu^h=L>WM?E?Ix~M?(?QKl7$K9T z=T_fcLRfI+M``E;3exXk<@0h&Y|{Y>wZyU%Jp)k|lbKs6l-CzE^*GvjzC?f7?O&Ob z=Vg!xc5FEZEqCfN;lvG7GC}P|`}IGSj0CQ&J?!28?B6zY@wBR?FWF^jJD6y3Z8j4~ zT%5V_|Kuvzn4<9P+)EQW3!$o6R2@HaR(Cg4K{B@X?(Oyyst#|8lP88Cu0Q)CP6Yrl zC-^)+&*aJMPva?CcE*t0N7xR?bw#Na1&E@SS8#i6VelV<@=8K8fw6PU3POpQ%DdZ9 z(g`(Ll(3?YK-?LSg7iefpKsCw@3^E9U-#6Qla4g?B5;D%RR8jYbT#>Ze(31agD+RUA|TJk6%fp1RtK4z*u4tLz- zR}kS-;C7Z6K6hh`@$PLvn0M=~?-&G6EdIr^Zm|kU2Xo=7iA7P>&TY9h8Pd(7>N*MiI;W8#ntVh(wxJAY!ObIxO9TyGD#xJ_bDdS-6;l zwQlU4Mk}V+*V~FukV8F(l%2|M)TDij-fF`-dH^NzmZ^Dm;v})_q_2E$jg_Z(QTqFc zJ^)dEMuz=TD)5rzrV0s(4y!4*X~M#@;-`-C2S1Apy-9x#oC5=OYy$nd*TvImhY{h# zcy3gLDZ%MOMJe9RW3RKfa_v+;Bg2}%95$4VY0Bc z`6-A@;jtoip11FPXY^0R?^hZ%6*2MCO{;LKmpm%N+6yrBS%X@Y3~j}oXiIOh)rV6r zrv>(JB@R<^%`}&irIwxKWo8U!_JxnBSf0u(9%l}og8~Tk1xrLL*0TSiJZKN|4}cb| zD|Wl@l^8OsE-Vp)>VBvgutKJz92;L?7s1GHKAuLc9&w6sM5 zd%j6#IB`YDTt3XoCh_Ka2lE_qe|(CQ%#A%$sfbQ)Onmv^N#CD$s8^scRB#9)jOcPErMoaS%tH* zow6yL3J2s8jvccZ5aO1ynoBFrs~uS^Qu^EeO9dsK5)L0*IKGG-AS`P22lJnXLA&p- zy8~&1IUpn5mMc=aOCq}KbViEWzw@p1%3%E?4)mp(Krc(kO(9OHrl}b>Xu{E5#<|sA z{V1Kr73zSgO;25H4#_olCb}slM%@7kxeoLtS@M(KUdSr6LfnIz8904=FzaXv6so=J z?n-plOH^3B?cmb{;AtY|+RBoR{fgWtDTDtWd+3KcPynym2Sr=8rT3&`;M+%1(RiBA zyhEAAs|VhM<*AZ9wm`Ihkq~8mS=06;bgxMjEz_8-9oD#bFWf@~VZY!j@7iKbT5{i$ zxJk@FSmfk!YD ze6@@2&kEW(rRg*(lQ#@KT?6;v{RZ_WEDMOeKSWPZTv`A z^-fGZ;H@fnK?Y^Q>Pw;C4&= zK%1`2l5ROz1^96NQAgY~m32@l*OX0;Pw(ytP~f(bA**Xt4oM2YJwcHxnT4sBLuz^Z zw*tJCv>M@ja*nXn4h~=kdGEs>{6us+d#5{1UbIFka3yhmo{Zk*irDyjc-;HhqdtFf z5+0j?Kv#LwGGE?bj(g)t@cUg~9D;stmLtt&zpIit`%Ge^znKe|>_v4fn&AkRQ-w%-VVDm4cax98SYNS^SRv(T zFfdABv-d?GfOggmTWe=8&^Oo^C)sPb{s~>7@fs*Idx~TTE>#aEE*FsR%cU*%Ekjry zBY2#j&*$HREdvcT+FA)e2C<(a{;+M1UokfBmk8rV;a=N6KELft&0m}6o_o6~LbOc| zM4T1^4yce|olzU!!C_yWH2@?RJmJo@t`df5wt5in5rF!>>+v}&J@yt{kgJ5Nqg!b- z;YKTUqZ@YLj<7VS7=r;Qf@X0GKQu>`GQ8OUh{O2PV4z&@o2^yeKl5TuqvCkcb|MU& znXCol$N)&_X*LwA5LEXF9!fyVK(^#4_+~^6C;4!p12Exdda1>!@2D+mck;e8$248M zp@6Xe6#3w$+5Yn4D(G5k1Lt}S&;O3LSn`K+R zVUK>IsD5#g(nB9nlOHJkOZJb*UxW4OH&@MHbtb_hc|VpUma0qPc%l;lUBnT{V4YFj zd!mBzDw3VH*fKHkn& zw}q|O!4Qu5edGA1E8Ky^))Ku@nX4xVzd#k?f_2&B_2SCH8K4(Q9tSOS9=iHzD&5zX z*8d6gJ|CXhAnp4jZ@2sqc?X?GnI@@hCR2>Jb88NCPP7LOepSUvP=CCzKpB&iWfU;+ zzpv=DK%%W*(pnOi0R49rqe@U2eDAeVzl;M+q~q)` zL4U}_VcA1zdq+D`I#L!B&DD!^qI4?l>|Dv?u}%Ad=a>yTw6=X}>~`ol($E8RPJ*!q zWiP1nipfq@!;MI3w~17HTRT@zYraeCmo~(m%1%Q33U1~U5)Z0bm%#P@h26~5A>3jg zF*TuzF~WR&FyHN~YZ7NYj^1-`3jGXrnFpKsr9n3{mk6g7GyPYD0Gki(kWW~p0lLiT zw|l#Y=CQc+FcgNa#)~Dp>#TGsPzs2~K}UkVsDae_1D7OktN%)nizi?z@kUN-xOD?l z2`Gqr)URH!1%Y)MLS=~YTbJZGjW%`X2-n%EY~-T0Okb361d5}NI}Q^1FdSxQdcU*a zHn?Y)8RzoZG0kn2y0*l}V%nUMA(fyu%kR{$P`MX8>f=_(fwq>At(o8rE(vp6H;MF^ zSaUniSzd~+5+DwOR8RhD0A<`(G4F^dKWv1Sza#C0reL2tspV$le$DJI90+_cg#$b= zI@=%loCM<%Td096bf6+WM+Wn#G~u~8gZk*II8@Kv6fK-CqXmp1(^?oIlZ7pDZ%`*% zK&-9fM1}>pGH37uEZAtuVEm50OF;%k`AD?Ks>3^=$HZzxH?QoYu~i}0;Lbg6DQ*-M z_YK-|HNR&mY^ue5Y)tX&uo}O=NMVD28pgDcWVMI8(fHr-N#G7>yqh9+U~8&to;DbQ zp6)mZi+A-F9y&3&i!JF%FjD%#OFWs~_}?hu!G5H=FzYHV*MfVXLJIPIBLFJ2FVuu_ zPJI{2+j&c+)4c0=LGr@%{rV%I^ zep?odr>^Y@bwC^g2$md)`w30#mEQhS09MD$XN>yl>)eBKeoY2m+EiK8b}Xc*gM6nS zZYL`Pm7^U6Juc*CgA&kmN#h5RMpO!>W#Z&WQWXKzUfQ<7jSioi9$%3AKDzoC_9ZVN zx!<`b%0XyzE0S@n#<5R5yeR~ww=IVdgYl`t(FOr~&+8skGYW=YXtRroQ6vUhZB3~A zg&7JlKnBu^Sec(mld|>?zy(>Z&FP!hb-W2Astfxqg9Yl~G?T{AYQu>fCBQt~S6C=>$#aWim+2 z4j_NConB>AQ#@~O_m7m&`6Sy0zQcF50cW@8RS#j1rMs}-h0i+h+1dx`;hPSO%U1(i zwK2AfpN3ShNvL)YoK=L_`(y$qJQQX;V9M-&7&4)e9A4UhDS&?XS^B+pt?nkj03iNX zm0<-TSDhUq7q`oE$=+6lQO!mI=!@wYK8YlZx0WYAk6n@qL%*2KAaFMBVaFVA+JQu! z;%$~|czo_03~g>LI9PnpcK3+hirUz;#Pm_;1r@bL=o}yRf)^FSQS8!QiJ^x@FE%|# zicfwBW%~W!<~myc2`r;wR=QW3>IRK$Xk+FiEnP23<45h2IPCoYl=~KEpi-_zp{=^< zih%?^#UgP(ggOr}jbnUGVLUg?SXlNhaYV!YW6Utg%8RK1=y#XZ)wmSp@RzQqeS7?E zx?EL5Z>**?YsPhXOjAA`dXpYhqW!JyP_T2qZ3o-i>6nq6cY+ke=DM)lom&<1;#Wu< zG_L`*PAZn{RIwBHF|YAPeN6++u53?E2h0)yjS17;+aHJ`LCqe1?=P!_Cbq{*4|)kA zl4BOXP#v3NYU%08K}LfXqyClYT%ZSwpsVc9r^BT<+zd728p8l^D5uVYm6eUy9qnsa z7e8z4_(RZIGUw zX|-;cvDbYgb%5zF`bjZYKdEu#f_;GvL` zES}O)xLf>;h;9D5u5Ain0dFnK1W<^j524Es{P=iaU5}JKia>{mXykOo9m&C5KK$V@ zS22OahR$1ra##|I32+Lux8r-POkHf!?ky42&o3{rM-e+)@u^~ZP@|zP4^*w%MVNj* z1bn1m!3r_UtkKD#d3Yg0r?i3<=XZoSHvhj)igUFYaTnj_BO-F@DBSfUkN69UBKKPm zSD)@z>dNH(?T_2~fIYIj%ND2?B=Quo+ri^!d{PfoOeJMiwV^@Jz)J9OJ$Z5N@L$2N z(d9?<3F);6W&qe~;p)!Ms-A{4)p8^0U3zi0Y2}Nd2m>j&wfh4t zd)a^^k!D?gEt2Il2v@kKDMIC0*o+1XOl1n`1pn-syD2!%J=&1gL>oqjk;Vy2L8_M@#*qcGn z=0@g&=%YcxL@Zg609Q8t?h5p2xc#yRCnTxT9&zqsjOKzp{m~-`QhKuSl(mW^#-cUw zcw7Tcer;|5z;<_q*A4_d>_}&Q%s6*bmaBvPkE)^4L%$T1cC^2w_AzXuT^e{5Zc_mGsg-V?BFWXT46Y zU)z}$O;G~~ow7i~5$i`nMS7B~kW(2BaUOevj+zE+BD9=Tp-m@+J>x3g>)aFcyG4|O z`TwdY3H>~Fy5oYt{o2DIqMQENB8Eq(e?CTQW10IgSWU~P+3fgdy4`Gdwvr_($(h>1 z%~1B=J)`F#gn?UEh|nOHJ-5w>=pF`o4g%Cgm`i$&2}dt_;z=D!5r7dZD;Y7}6>rU8 zIX*BLqk!szRx4Ga%{F(vqCRfh1n00XXSIs7oz~g{Jkhr!vB64VOg~MN?cV3KV`R2U zCw^j|2MUVI70F28smB_+)ew5s?Bc`Hz0y z?$>QXTA8QVFiJhbE1l`(7lDvmxt-{9YPR|9S5lvvv>rJ18K~rgAN7pQJx8!Kyc8^{ zs`*54`ARHw7Q#&V+U9pC6)l0Om5C(DOaCmCb?Dusz^eqqipmP-Fqfp3l`#+Gs#QEj zBH?BJx6u|1g)ZdrCcUd(Wb%>*3LH-c3BprD){6zlt4=S9)`RdWNh8j*Vx@_|wm zB-Z2N;&;}Tb}(SS%o#~uw)Pem!Qs0T1fc$)X(0ne2?ArVO%&N!kmL~FT} z&;C+!{F$^xO^b05hs0q8#JIKb3FJ40#SpE7_$w(qSKXPH35SMvv{{jTl6_(VRx#we z9xR#B)?I_twwUBZ9z#y#mL->N3BE$=5PE$Q&k)y#?YU)C*Cl*zSCyjf<&f8^5L-!Q zcCW}kLHO{g3>d;RnQfcijV^Ry0UPH)x;U@`8F_YZww^qxazMZr81tKGfZ zn(G{ETQoQ~*@FNbU`@Y&c z7Bbls_TB9hVbhuHW<)l#`dUGu+b`;H5QnVA9e98I@^!fFJbdV~g;9AQ(Me1bUWw3X zB*uxv@w9iJdTjK-TDHh+X>muUXf!s^c1P9Ems;kbS%sP=SG{dEwnwmK>Y=a)RkXvD;n07a5aL&-8zQ%5F(?0aL$ky3t$wy?kgaCq) zTU)S)!chX1-V``1)-+7)PefxC{)}6lmC|K5DO)eFnt=$9#`$N9UCMb9)5OV=Vh$v| z`zQ)PjXo+dsO9g!-DR)pT215IdxQ(b)?nWr2n^n1CKjEM&pnaLssmLF+IxtpPI*Dl zXl$vhF59;LdywVjqjMQ|)qM5eLMm2+MeJ;U@>%=oQ9=62nCg$63hPdSW>~06$5xdu za+0!b?G9HvT}Mo7_1R#|g2?k)hDT;`!E5bLVa@nA`Sjj35fzN{dH;gHkYSxEp07u@ z6+q58{B;~J{>)A$l!l&+lnz+B)4bMuFS5_92fv|LKI8SmcKSz1G`JqtlJJh>-!O94~N*BmFW8O z`FzJRCksdf$1Rx`$QX*c6`RWq&ZcSe$dG`d5u%P+JCq;d8NjW6f+1cT{qv4?GzHTd zT9p(`t&JqcsE~S>(a_{zvXz558+q+mT^S2yex=xwFULuAEuC^%dhyhF4@_somBeV^ zOz~>oYm9y>b?2ot)5`qNfU)xFOHkpuPtX?|f6ZT`p?8g<{{Lp=Q}zf#J+FHJNq01B zDfxSl#DYh;KlkC$V$ZQ7{*p8{&WAi|byhWYFexbqx8}+BPv?8t`dC~#M(^x57ff<2 z3oTRh(;dc*-E-nEy=JVMWYKhsm7Zrlp9Uj`-rb0sPDDRSHEvT=<(?E`TDpi_-lB7| zX)k`L2SpFSn(l%khfwaP5Bm6ur7tSYT$Q5kF9$R|Z)z1a3=diUx`~u>YNZY+T{8NH zV`UgX5k>ODGZWDW2M}G9)3_zeEnn>Oe;*Ud~ZKW~;LhtJxW>g@+ zLD_We?W^m}-jp(m1d7Q2y9@jD%Z|RwTcSM6VF=Yi&4!wKjOhUWFXAgKJUGs8Lhz!! z%Qmh9Q3D73?;YJS5a^KcM7n4B#Wvi;o0PZ9;DC7^QZ4@N;*|pTR~}S zxQ=W(2?(=K3*7L~lC=Vi>l{Gt8rRFu@j*I~`1r*S5xf3RG}ojA*VbaEn^r^AK& zlzv+gsN9jurr8eYD4ORD}+T1SN(%8N8&Cva%v_$`zK+W_0h!-Tif*EeJEf{ zvfZw%u+{5x&haHVN=u+DO#IYnhq2O|*+g?o##x4&QJ?sN7(`sOYH1t1bc}(a^S=zQxFS-x z4|Rc8@_MlbvR$mfu_eH9s{RO+JT$nrVGp;yuGVu~MzYf((~Ey&-+)2&j2U-CLv)!H z`&A1vuBGJYKRt{gJ%zGmk3K-YS($iifR$V0;CB1I(D3Yd_XEfD?fkC+4< z8rhYyR1@fQ;SerSQ?`d%@im?a@FdJ5$U%RHf{!#-as}k8CI#>IsgJ%L_(Am?ampQ9 zop5h8wbjssg2WO-&YLmQ2$fK?QlCA1Tt0OxpMM5djCxr=KLqRN%d6>j7v)+YNntn8 zQh*!9jD1L?7RW*g+BLxHjV5&}KzF+S|d4(K!fbm((ZZ934^6q_VHhaP~r_b)l!S3K9cL1jyfQ zTjKeqQ7hnHmUvGBj!1|$$}yV|8gCKQ!;yiwlq2ozOnT{%z`64h=d0mF#6 zDJt=!+_5wh;OxdmhQ@kxm~h>Hb0T&8-gAPDM*b_$uM90`Z<5yhJW8<(0|J~5p|niR z^zg-{pFucge+B5pzqe5hC%}7SQSG38SwIXb$wm~D=vD#V>gsRW8X@6_!9l5lgO&J! zglIPgW+Y5y?9A5(@<%^2huFza1C}_te9QvHz}_zxY%(kL+K73BQK}(JuT0{U5b{)) z_zRwa<1wMAatn1fK3n>-mqPapBg;spSTJsXABGQXdqr~Zx3TekOErNoG7RtG`_h(^ z4h9Ow*LaXNe#48!+b@>X$&5OFzwSBpwB<(41n4+8CZtN8p{-zMy!S|lhWrD4urBIw3WuC(35OmM zd8VwPJmN5-vih3fJo$SeqRx40DI=*u3x&>t<@j52A0wD=uSa* zAFp|C>fYXlgcs=PBDv^}okZHx-}FjkA-&ovMo|yP#%VIq4?H$5%8Pl=3(K$<-QqKu z+3$rSV%6WQ$?o%Snk%6@`_RE(JK|>q8k5;o{KzPeBjIW46t9-yOhAtlGj`s{ zPH>Fv9l~E!o43@zp0O}xY;2_YxAyY4)5d@UUPU7&PP=!|5aaA>89FP-ylYzXcjm?Gjh2QUa$0g%$zR%O1ps?Ej58S zl_rp|QG@ZsqbxJmO1rGcMJi-^ed)tvD417~7p(^#x;v4N=LBBCg5=`8>fRjGpXqBn zptbd*G0?P?8$4sPnit1mvU2^proOS zph7$9#+k|mChm3dZTqTX9aO9lI3!?9zF4br;COj(!S^*)2wyRBZLfC_TPY3tw;I_e zG;+DQ@4YZXSOvw)Kx`|D7bR6eUCWpGG8p7{Qfwg?6fip4wmK-0T(g-T=mQ9={Yjj( zs?M)uqKGCBvVw?K%qzE3-Amq#J^Zy&6H>@T-~UpCm;P zRTgbiPl9V_(_a$JH5y&onJqLs)HKM;@zgL>Sw~|sdWP>= zDF4*P%hNH|!_8DPlRN0jqS63TCM5{?2}fX~+V22lDnkN(3me5cUf>oa{=WT1gBBf; zC9bq^)|(TwccZ_Spo+-<9Hb}I!tb9bI-J2!RA*RptTF?CC-0)a_xT^In&xyM<#Dzc z+@mXH!n6YDUY{xv34TdW(Prx%UGNmdhhQzb-^A&wwkrXK3aSq$bJ=>gsK-uXa+#IW zg8N}ktOQB)DpUt!pr#aYCI4ajBwn?CTE15yPO!4v#ZkOr`{?^XV*2WIHm;|%ZA>80 z8rp0aX$rE<`}M+A64N+kOQg z&?;Ez;lv#UC*%w+DTQ?OUFMK$E`Cf)6RMo|{^g(17OK4qIzKOx(C!0kl)XY{ukdfi zoxvN^VGqmlkM~}zK^r+c*VN>a?2Z4(b>}~*igDWQ-h>WnlM|A`6j-P3$Ri%!ur{#9 z`(qBQv*z|FlL|0S`)G|SI9Y3`;dZXy;p_>L+^TBJ%Z;SuBmREwVb2k<=Uw_jUzbV^ z6tO$(7_7a$@0vkKz=JxFI#O{52krs*`sB-zubH`)@Z|b;e$og`rm%FHUgU8FTFA{O z|GuL}_K(bpJINNOCn%lRC)ht~CB%ysjfW%Oy=YS0xXL!o+-5&tlxQf_Gsi7XiyaID zGlR*OIj<@Rdx8z-8M~?)X-4@fJl|H^rb!~|gs0iG_dR~ig1UNdFt<$QgrK=k$o+el zhT2}$Lp)Me)6S^_Pf*egaX!<0w$qG;yTe{FgOd-%U{Wh%P8Bi~U&R@cOpCP?KGC~U zffcRpLr$<=&O%JdMs1Mn37XMw3Hg30qE_Mr2t3lmnp#DPP&O z7OQL55fDD<1nVeY_rHJ%cF&{#T8}%=Ga=+ly@%9th~(S-c@ z*|Z+tl$6JEhgSUD$lR=iM%S{ApF#Wa;!1ucr<8ld;#F=4(JPLS{EmzbwsDsom|px1 zvlzZKNT9pU!QOOg}bGHgW+C$wExsga<>w^ytPsyx)xNh?F zEyHwx-ArZqov$wGoKBEgP3t@zryGVdTgXD1HNT7_)^d`ELBkhk#bOCTx{(wpQ1w4c z($eE{!kSKG(EB|m9oD{di=MZ^18jzL3?F_iL?}p2uJl?OK50Fqv6hpqVyz?qHQufu zIua8I*UXR03{b%y?uHz#sG{;#)tcz)z!Jb(eVF!TTH1kF7w!~P>AmBSikZu3@HUTR zdLIMPCjRIW0cjl_Nl`0n+3vy|wyW9rW)iFsBDo(@uQVn8HE3-4O5PZiT4a1>9$9P1 zhAo{cC905;ol7e3&sTQT3p#>@XXDo4BaNn@f?Trqk*T*glZ!zFggxirMZ#`V|ovK+PqrMY*(C42lEP;X3_aPFoL2!`z92kDip zSY~}Hu29%bnkBCkZVa+K%1E*WZ2fH#a{vfS%`VJRfH>(fI+6u0)rV{!nPgU=869tr z&hbQ)2K`7cPg^iPTc{34j$)o2c@35d2d~ zqT3U@-_DI{4jqsqz8dl;OY`!C?dVV$@i&_*QO)uo2<^4a>Sh^jHvUa5nQQJk{H5&w z$wdBZ56x-kr<)X1L`A|FM9BdbX4ZohjsB^nl0`D>?^g&tyuGM#Tm~pNg|U~UZo~E$ zErt!+aZ~()=m4&qeB)nZCGN2V*ZQh}0mzJX+`+;t>V%$PLb&MkJW?=&we$C`^x#&1kLG?<{8;B<@O7d_Xm*{ zxA>)Kd8}B8KOCi|`E+{iUw=hnj3osjqGg0Vde8}<6W*(BEntLf#DnbqpK}wdY|N;H z%3sd3xbFrk!M5>IGpLVN-8S=(5?|MoYwE>mEVWC?p7RXUD`Pf(w_EiR=vkEW|4u00 zGRfxd&DH2m_PjL&kJPhdym^u7nlwic%5jz`7YSdiet5v8rx~L)!N}O|XJ!T6#*kI^ z=~@|tv}8)y5_j>VS6N-O+kwn~*s)wH&8ug(t#u3Fio#cyER-O;Hw6*sOk=<`wZo2$ zf0Z3$!+!dO=*Y~HjWpTmYu0n9)E{NB2mjpSkK3Gg-QwxD-$tdaxLST5IdupFZ9c5@ zW_jc_v1_!FiNGxPSi(40v|FD|6<@Qq&TO=UyA}_oZtrIN(En0%tx5j`J$6&dE*PxMlg)StjR!A@z%VbLCwqUpt5gud7aL$0HkZE@F2{V$_MWJR zeUyI`qq1Fb=sc|=a}eWt8KG$h8DF8@=e21zm3);Ai!C4XlH7M&T*dY3oW{S;Dkdjv zcvkdl&>gs%*n2$I*AVYqp_N-qPL-WSiF?PdT04h_xo~jpu(@ZSOzX;%i)j?*=?#a7DF;yeaoX{dVAJBzvgpvZcxs z{+CbXb=@bKcLS(|2Mz6AMDOf#uoLQZq)YI(;?^3wJW7kC@u!0rSdoTqol9|g)PMniSW)dS`(Nc_+&VN^LibqwWwuwavzrT9)}fYyp}R_ zx_Njibyt1{1|;hxUi)A%?oI)lJ;J|RKL*v5s#m%qQ(#VgA4J?ic>_@d;zAL2?fz8- zwQT;`+1PR8u`nyi2M5h85>SXXVd8^=@OH5anVch*oko{RdK{b?T3tg{Kxay)6>@v7 zLc-<+X<~1@-Bn@GnreYDm{ZC`YRswR?r0@E7WQ`^@)aVRjXOn6Xo0M#txgJNO?A%Ue&3}O(yQL}kPmE0xN z_kVE~82>-c0tX}G|A|@PU}IH>6rVUn+0JhiIXspeaYopQay3OKxD^^p(*1D?^3#)7N))U`bHrF1T zn=jKHxB6W7mBwA>heCn`2S=xcJ6DjuG{31TuYYH9CQ*D$3Tpr4bgZ-pDI8cv=LS26 zWO`@7JHRFZv_I!KCV(;UcL+d21;C-~?5;jGwG|sc4aW|jh<|ENMMz8#EJpr`@!he3 zku5C3{rx?{gT0FxSQqqvHkTrJ0D$c(fqzL14+KGNbs=>X32c6f>LQ4E5RQPpl9zvE zS4K|^2min*&ha@^A+S1U0O0GNEWoL3EE?RY#|{Wy-PCy#rQX_o3qo&R}@%A5bkdaE^+@&Uqa7?A92&4=-*9X&o3?mF>n9? zG`16)Kj!%4C}PHmUgrd-CMRI~uTHDI+ppXe9pPHvH$bx=OEIvzKh0m^&dp7VG%i1Y zrUN;+nHw7dM*g`mAP^VOayE`M?q3k2OMS!J@897so#5)sa~)h^tg2s%(U052sLJFh zv~hvq(W{!Jl+srp(vQ*_*w2>^iU1nxE!jpFJqP*?-PpV#fGLgsAzsZ;6hme@S35X)$@%lMlU(?Qsc z$$9IIL%c@m5g?}G-qC53koPM;Y~63e_=gibj##uxPOrqS+}CI=se0CIEiu(kLpK2zmiw$0B$J+$eCrDGQh>?_P;L^@wYOayK+J9eBztlyZ52@~!% zwosmvLvP%BRlQ0zNA?yVu}RmdqF%1bN3kqkel;B zo5bdEYos4XjBG!XZRlfb@)vpSO`0LJ%DYFUrvd#wPg(v2gkD+ft$QnPi#o)*;XYy% z&Op?Cv@up~bxE+*n3fP?N7fDJIEC#Q2K1!mm4Dsk*MoJV0eL_@ge9wrDNleQ+XWv< zgk7ZrCo(VXJVJJdtv)q?U9d~eLc?jm4ub7-q6@d|)4$KhGeQWJ^0THOfweb^`LdT# zQWv_>AZyfN_ZU`rV1+(&Bq^4r|ITi{?Z7c_1C8lPuarU#^$yIAi}5BVH9?Ge55q>& zOdKBVrTo=1Qnh+-$M7G0+cys#zMC@MLmI->cvD{iXt*W|70z!4hgf;FJkOJ^Y;E30 zN0E_}Z_}ej*T_TGRS6Dnf5Lf$FHXqOtAGu%JY^Jac-ewgI0joTADc&*NFzkH%)Zw1 z6dB|#_2^hAyvejiD->)`>sj?--|RAgj?ewRuthZNz(iRG>=j?8L+2T>rfZga*k_OAk4sI4%jzdEoTcRg&$ET$~8MVv^1BWem`d7kJb3f(>Mb!6U<*GD*^M!nZH zeS$9%cOnR_pYcApQ`q2ZyYq2}ae(#U=!Q|rWW~u8-Rq1Z5j^<#U+S3HA@N$UFFJcR zDTo4E9D;&xqU)tF@Gfnj5Lj@9Da!P{oOOz?U+6ccP=FuG49-4!XWjpfnsE^@kz{E1 z&kb`DG5zH{03D*~JxZXE;h-js;q^guuq?msLAwkxi5PHQJf?Y?C9WHmwoiH3AoMjt zvLtr5mts%)^$r@k110Dv^J$g_4C;k_9LnRRkn{#SAIDhuPG2vP+$JyVg_UzZDoXZD z;$t2pJ|Xkzms$E^^5mgE;nAv{wGM^ly%jxbr&8Fb;toDZZK!|HZU8uQry~*?+iR_s zO(F;+thqPQntA2irNhX=28%(!tn8{!!u=hJ_7)XcB`x%#n@kM6pSjfM&=ti}Z$)}@ zU8;$|2z?>X`0~+2oAoWXp)uaF-@GuW4R%Cj@&VkW%SNTdnq^1}@j$DI&uDrc zk$KOS;qm^~pf~YzHZkL&H>VRSc*ep}vCK*j&6~t$mFDkhGrpwJiBr>ymQn79+v!kV zebfNXB-WS~pqQVMPL$Qhz5#$4e16X02+MZ8IZ6*)NTMl+-L}hQH${%-+@86e7vDx| zy^H0non6Co=+C*XsjgyFA3!|1>tX8hSR2ug-kl`orD9g}7*g?f9$zl-9ak4~KH=YS*`w(%@(j~% zd*^a6$bWi0c`2DHC#>+9mHmk)TM5`OSY5N3A0;NM+O0c+ zji_DER)%tO;CwJEpVeli6>*F)pS`ABHFSY)*|CwB<7Nbz41?DcyP$$2k3J|d(kgT6 z(QuJi)qCZf7ME0>e*2`pP7*;d_1armckRdPMrzvh@O4((rp+A_1lf8}vC&o>v|En< z=d4;epG+C#p?l`kd%>u665s^upS39bk5(alZG%g^3+y8<_+E7Z{WnZH0_Un)s#U3^ zqWSIc8S2sWqBB=yttjJ|I)yMx7ShsXbhKoQ2}9Cld~=vvMAEv;wvuA4hysIKb74e~ zROpVLqL}Y=Q?zmaJFqHI!(r!A%>(TVHY;JQYW_R*y<-H7`k1{_5}(Gg`;ltGXi|rJ ziONjbBB5KQ3~bX^9Aa;Fm5!0-WALaK7UxCjivb%6D*W>rU!TLzez15nBQn=}=9I>h)ylC!R+?4$+Ga zJJ=>D;|a3~oq^%Swe1z(QmBFSu>+h3O$P!bg54hO+#~`$>k__(_L`bmdEkobcS0BW zeW{%~QYUm)cE3hL(taaEP%OZh@z5KN~tK1fN;B17D}@8luzxV+#@RxVMc530ZE zOco<+*}MuAe2-alc_EJZ^xeFIkkord1XUp$%TQcN#yj7N-w#Y=nJ|V~xlQ(dk*K*% z?h3f$`)nw&!K})gIoiFm7E#)m6)!CCxNiP!#+o1EX0ZPyUa@Mk-J&_nYCD&*r@UDC zX9z~bcgN^%G>WWvb94f-#pN%NbH}P&y-&*%uDb-KV(n@SHWeY`<_avp-1#7ZZ+V9i zTPIj!EVy4zy~-C~rNHmh7vA+L7z}oFl-Y~@u(<1rDW+n-*&oSHC~j@46&OY6%v5H4%~eg?gl9erB>2i0v?|Y4TTcBIwX1SmhOv`7K7Wo0uaOeF*y9wA*I~fUS@|G8?p^)$L zWqIrVSh&?!dRttQGoz%&IDVK%@lDAUzXkJ!D|B(!iiX~Z4wSJ%QW8+?k>#bAJt)pEA%JFO9D|)n-CT94>=7#| zO^Ej6ut&H?%y~s}fpK_TcSdCTeiSA|NRWez6;GCF^wFmK6-Gh?+4DEpz}G3-1f?CB zdak{M&R#eB&hC_M>*^94Do2xe704PzLR`jj5R7ti^Jw3W{#tDH3HSW65?z(q!{Fp) zW8$O$386UPim@dI!lD*P0ZOwCo(a<%0#OE%q`y&r&=Pcj*NFN;x=;-2Gz<+kE0B2o z`^fV!WBN0M`j)nU>05CfTO+$HGi51oc0g63axd(*pHP;xkQrK=k$zf-)g`)GAEBw(_;t&YL(}qUUZqv z@$=h}S~exdt+eJG1p~>4hFuouss|_K3X0LJBIF7(n^7l|3vjAYthKZ$&lx_d>k4mRNMTW}fZjc3^xP8wx)X8MUT%oHprGaltZ=cM>^Y;TB&QI_hDIL@gfVT^vRHH2ZB%08e zZ6W{d_!#f(jl7!|pzL43n`h|*o-eu4T1rXzAT+nqyl^z#FK;ODWHZ1e9Pcm8OOF;k zK|6>H!LJ6`rhpIjUkMj`Lk(uhqU^H5Fe$+hf0tsKg%({xiWprH>DvKXI-R*<8hf+^ z9>eK5cV;kgR93yCDyK?7Hbf>?m|xii#Wp{DeU~YIY(QihW17Z@3=h9&&Y89r248D=xVQ3{$?!tJ+v^!Bn!24jzMPFrY2i^BX}h=-Aa>y-=4Mue zzmTj;yz!oaFj_-TQ@cjHDIsFw?Lx+{c2&crkD$G=do^C~bhOafcRhr?lJtna<#R!U zC`?B8o$utEs81K_yo`@RsnD|?fdIS9L)G%83MARMIGVU2%`3qhaIUPsaB;r3f|YGX z-@L?h+DJ$94ReDG3$IQZpx)+zxG~oky~h&6#jgH2zxf+_KEbg3O z<8zrp=FA2T6B|qgr5fOzLmPWJ8&N}2Kw2xYw)b$_K1A?lMptNM*PJi1HTIa*X;uX% z9x8l2NnxoSY?cTuj->_^fO2>2qFY?u?v^>5TD+&(6vweaZ1H^x1V60kudY2Xw^lek z$;Sp^dD`I6(N^m;OAZ0SgJ$eqb9yDZ9@2xR9?iB~Vd9|~UWGNZo~)vlUhoGNVv%9i zCNdzEx*GuK4waXQ&d_l%TN_IVOZxehbgYDS)$ZF#fI$Q87 z_M~WvCW)T@;yOk5+eiLLCfyba?MCU%kunyc8Cl zQ&lUOwk$4-7zf}4XRnMOWXH^As?w3qIOvY16tGtu=zDqubE59#g|{}xs(SKw6lTiYk8`UFY&qZ)3BUMfmc(V#1hpQxVCVs_wg)kes@f^B_!_rGBDSI?>c~} z?c2m;0&aH~NE!9HakCE(CVr9;rma-Id2+G!18ZL={Y-l;wE$*I4&iLa#S5;&7n9je z$hN2Ykm$f|9s<%}@{@dMh~#&wu>7QK(i~UH^2j>(ibLl!pR~6_eELeCG$F*?<&@qU zOHfd%S6Jlh_=IcO#C_0KPS%-F`}IIc^j>c$EWRX`%}8|_Z78gFSv&C3FEmyy9z6GX zB;r7mu;`?Aj>w0+NigXoNK9;R^DTv}S9}(a>0N*`hw8O&*ruyEgvOA_`sCA4`GOLQaN&0Ujc=27@wyO5#{@n>d68&75Z0*&mq zR*oLnjx%0N;cfA@y*8sA2ebz%<(6{n-B+7ih?Wr`A-8u}I&kM+QY-mz0Qq(+sor-~N1}mZ&DuqU4R5+h zfe99!D@PgQQjM@ywFMUC*ITI*E!?rrB&w}^%8OFVRue75O;@yj>73r{Y)8s`tgTx6QyA*(i!qQX; zd83|gONKRdu%UFjrCEt{<~(D;hh`*;=W=zIjgk2)jC@9a?;ILtdNuKyKtLRU#BwHN zueO%p2f%9&=PA&HtI7H>Uc%n&QG1kZNowt;;n2BzdFn_E#uoz8iK4{t58l8Fx(tYp zW0txpx5Qp1L{V1zrFEz}(m6so*p;dr5&Tm~5(Qp~U6(YoTxPzf z*i6x53%oyL^j5R#g&r7%8-aGBk7K00mO>Zc5K76&^3}D3q*0*k27aeaJpW`2@Ybsf zw=Qg(coFnyPf!aL$0=!-CGFLwoA)EaGZLwShz{ZE%a%FhGc0C|es-B6Da*|Fh8>n& zu&2|X;eNV2o!jQKlBR56Inyep$3$;1Zj=vU5G`=T74(@&1=q(3y8ZQ_7v(s&K9R9=kjHw2X#pp++FX>B7#@5V#Eqdf43n> zs2APqnhXiJXdK%Bky2kNI`{~?wP6rrS&+RBp+8<$pe@iI3a&CR#I9jYl*{kx++6~! zAIV|*(s_i}P+@}y!K)L8a#+{1KH~QlB?wl2_POW4cM3FFdN$XU=N%;}z`PqBQ^=l2 z!Qg@@breN+)3?5*96z9+KAeepOLJ5k`*uBN^)gI$Lfwm7=IueW{$uMdc9;GVn{-Dt z+Oyp``YN}GSYOI6Ee5{9T6d~jZdXXS-BYbpzq_A-{TMWAu~Z5T+h)}6jNy9DeXk@k zQv_PwY&49$0K)yd>d4LJ;dzg(3+ZbrPbXO(iBBlJ{dlpa-yyqSpDB1O@-IVjrStvI z$ViGr+WbB1*uD~y9jp=Cz2cgAS5K>t*Ij2=0CtlIz(Saj69?UCK{qWlqp;r3v0nAG zM--u_ge?TH-TzpR<6;_`KkkE;1F@(9%p(Q(>Q?EF#zi=ka0hqEU0BV`yBrg%01}vz z>d^@?6#rQRgU=C~M+4i6F+}(rD|AKFEowxy>i5b{~HiOcE*?SC&bAb zM3XRnRs#i0y*jt8OgDD-~%x zbU;$@uoV^5nzAHDt3d&#>8x3EsDMH<3lwzEC8DkZZd59w7X+bhk;RbhSCFKSt#b;O zK!{iV^rOLvVl?fLs@KrT_;>{1kgZq1Xhh)K^~&>hOZeNX&5Fm@oH@u5x2;*M+>Ep7 zLC!14ebAnw$m+aQr|;1P;f;sa(mU!YKXax23q>mar)H$h9nanw=wk66hGKJI_PGvO3DqhK+U1Dq(ZG4Z?>4S~n#a%$NI}Y`vcOR6kNnr z;2jkMI`hFabSGTIq)l_>$jRd&P4n|`*=PiWG~5WnuoeMcMD{CEf3U=JZ&@elORr#< z@^)6C-dKRmwAKkAtgb`*Q12(jQxP=7kJ2&<>hpTpv`V*~9$@y25iEVV!#>4XiTg6Y7xs;2J;<2d85qfI z|55EE`55oR#_7zk;WkQ~TIqKLb9`wJpR)icdaCA_1UqN&%a$WS+de7vg2NIy;qWT2 z;l|_UT`p4};O2Ix54>A`ojFn4G?O?}z*eolYYWamO$?DbNHUBg}M;VhsFHoStnEziSz8Rc{7j`$ugMg4TqI4_?c?YNfgX?OCi?PmHgCLNjPtx+auzVcwMk zg^<0RerxU~FgixW|7`+5<8rftc=#N-duRftlMxY3enosxvkGe*BEop;?Fy)a=w9`S zCr94S)zdjayk@-Q z8^rg^#QBc!M$c=05H`69dw7O7sBzM_+}yK!-%Dx%34xPHeFe>&sdNpk=c9+CLH}Cz zr}Uq^)ORJpa!c*HX!Cp_I{x8hR#ijZep~=;fCd5}IDYBV9pe5>D*8ZQ-MbjfSo;7~5<|>k_5AnI(;^5gj$M8Sr0||;ECP(@In$VaZnT4>7!jP09p;}*$0>|S!SFMDGy#Nr)ZTQKZ(``}8!=Mnf==t%DG>z6q6{bdIQSk7B+`!q`&Pbf zJ|=|KXKEs>E;C0NY4cTrl*dM_4~bVjzvba?-o?*i980y67YeU{GF%FjWFUsYe@%fm z-AjliEvIMG6+ur4D_+JGi$}Y*E8wv!#*4!(HQ~05&>m`rU|*|=p~}_XrMkhc>xm$C z>2Zut#*hGvRKYH_RS5c9-y!PPZ?TE#G4O)wUdePu(H(7Ns zRA1V%D2h13s&et1!Uz)*kzEU4T6HFo%kVpuSl+q**cZ*Nhv_iqumcYaR1&vKu3Ydl;2q%oRS z(~V|ytZp`wixXYp%R9Sx!b1W=5;D;8Nh>P*2S+Ah^i7S0N{f-5fHU|9T;Uy%$iva{ zK>z`l`CkE0RRO4&n4lO*_@`%gcMz-%AVB1^7QT^y%{TwEZEe*T^DoVb$$?s*M*OcN zb4Yl7cszZ6PCfqKCJqA($WJ2x;8YLu-_2KCO;kh8w;KU{7KhuZfpMe7m{)8CpiM$`# z_+KbK(~lGzMtBE~|I?m9e$$Viq8|ju&k0!mZxsOy0661clxu5)0&@e%zw(i5>zkYc zd@=t(9Qb4Kf90DSnf$*&j13@L?SFm_e?jp9ncph{z=jWM9H)L^{j!PrZ1D0J&_7fy z9T78n5x)^u0lz(TkofrP8?SpW`F)<>I|}(Y!=pcbsoz_pd{B%PmX?v`5=%dB0KXDa z{L|O|`r#n_FrR8tNMiebK!3$4GW~zKxqtB=bIkwLf9vY>0bPK*{ynE-{ITFp|9Soz zVSMW)mzU>kv4Nt}x&i=UL9zLV{C5uhL$gOOedn1RT%3XU^M1g8TT_1DexMM*jzAd% zbh8^741fgZ%neMHok>F+pX!FY@BX^U{ zMAsG=VJMBTA%N+M)Ci*@|FzblTQNW_t-(`Z0#(ZKIqNC#XE~psBc%p#l$8p;VMW>h zXVvN_KTG})P3;uxeb@`QO!g`mX2w7VwoV$gE){VNpFQ1Ysf^ykls|6m)Caft!Z#RJ=)6HckwhGyO3Y zLAme^zHq@(BE9rcB==~d@&j%gyBP46ViUYN`c;eE{7!yk-z!Q;q$ubi-&Q$^1{!kj zd&qQZq?)cFPsu8NhsZDEeo9kkNHVh}hlviqleelL;O@xoS{%k9@L!qDZ>xx%5s5Q0u-_JYv1oJXixDsjhhCJh5WLQgR}^Z=(YqvB>1JN=Q{;$x>8 z*NXSSsRf?c=DPsW!0$}(LkKI-lHU++yP2>zEBGy}-k>Y-$q0L}V%G>`9pru7z)~ae zP?b!JqQV|7s$-t%{cd^mzsJ&s^CP4>pKIplHqy4=N>`9B$1`}N5v=n!g=z1kLu>wL z#5}7n);4%*Utxi}-{>|L+(~i|wB~6?Bc?SWHduCxhK30*?#f%OzDku&pm6sVbOHb> zV;gM0)2v+MRuNB~L2g&6zOhfaIikS)BeE7P&B45I=6O*5wPT9;inN9H+UFeq%kr4B zK!HRwiGCPpm17C`vza4w`d-TNjuP>y*RFUEX8b^C0OYPgxLq7WE_ zbX#IZ!xsiknTt$eQPNhKRA)=6x;SPKl|-#g4B%X!B_b9cx9Bov9AIsy@f-R2SSFMe z32u~{G|FkSU=2f{u{jE`=s``#_HGPmh9k@{>umnT@D4Tbf4Y>iD7h154*9}11e2@?C!+yPh(E8YjUPaql`Q`k_72)FWKg+{ z!iPE5Ex5I;Ih~Wu{SXRj$K;%;3I~a?-nMrmlsLJbHc_O#Z4;X#iHT(Hw^HI$K#N|Q zDm8`mg{X*Vsk9iFkKbDj`)bd{6EzCInT>10L$*n8|aS>M#n5bsV z$MzP=2?l7a0M?H3?6u8pSw|_Q%jCXx>YxWJ(t!! zgzzrT&nitYtG@bSmO8>vs_6CTlx6)AXvwU!WSMiN_PL{fp07qcXc0ii`D~WLSD=|t zw0Jjg3w0GtI|r!7@Zx;rIlp(RkWiFZv>%9_ouz(I${R|N(uSIqWY4Zcib33JyixkG1b?0V7@346$o*6cN8N z-HZ>%o%gLb*BynZy=*^^uI8L*kxXIG@iP^YgK~rP5HcJ3t%xR1H zA|;7Tey>qu_AEVNP@yJ-8Cc5fW7>VfNr$FuhcEdIXW9xUNy|N?0ff>giTA;W>!?mf z*ESJ?1g)zWYz!4c6;HSM|QMd-JX7Kta?90jsmc3BJ~iIhgIO`wyp2?oa1 zz}oma^SG|UD+`@k9fw3XI+g}%VOi?B#SsL=;f)=KQd+4t9WMmU*gC{oJn?d0YY&KN zP@pA)EPP21YR*!Z!&^o6PMv!9+w51$8imXx^o{}%D&t5aG&-qZ@h_gklj~dLOe6#I z$oXP}^g33|S4=BdfCkh1m?gVDHFW(t{32Ct`=~7`hL|z!;3?H?D?USvT2_qXi*ckt z!pgztv|PZ*!nI2`~-HswUoa1j) zHgHrPl>z(b@&2ivUpc+^wL0;Fm10jIizYtwHMAEzgN0`u&l`jO#hvfI z_=QL$U6);uOE-y_(B&;m8|-OYk60+R`1V=yGN4a4ATFDJ(TzjGRmZbo4EL@&{w|M> zlq25!A+8?hsT-2z@emR7=7xTFBA9UMdmJQz(=POvqgqOSZy%%G$0_E$wLn!o&Ni4I85 z-h$oHvhFam%1&wyBxEZqGAAveaSj+erF%*g_ZxiDTyk_xW8GjA(R8DUfb*g-Q||PJP#RCOd+SxmDxAKG!!}DvOg~2asycLsF;;;qVG%DFxxnfUxGD=;Vc8I9 z-3B2BRcAhypA7Y#O9rwGf!OfR)9Dx9#Oqe5g-&d@f!Hkf$~81>G40nZBsA3}3Y_F` z!YlwtYy-#;o_I>sw$btw)p&3dH6snSeE!BaBX}I`yFg;J&Ko3`OHI;(=S{!g9uI`X z--*Nc0nK(<_ahbOnd|8oTou!$Nw}rOiVi`lYb$H?%l)Jrejt_(0qAWq!$>!C%k?&P zg9nrik}pO~00J@`8jj8u3YI@Tr#l0&|Mr!2WOPmmv-J5GXB~^{%MkiMfrL;HuMy8Z zdOLdfT?M#^`y}J9wjA^5kMNEvB1?&}t zMe<{$V|uC05d>=nyB@>Xs#eJ+Aa5KKBbW*Ln;Q|rE7D>xiNvVEx1D%8WUaf&JsLjD zqJ2eAMD5Yi^TaKRZ_O7z2cGAm?#`Xjl~aA(>@UN|evyJ-vrH}tr@TRH+4Zy@d2Y|u z+%&gM+(O&HG{v=_`T)$J=LBG18&evK=#iAsuRzLwcz@N(sjZptYHlm%#D5ldmPTk&9Z8W0guScfDFTPWWA1io!kDP%;{>s zB$?kdJVZgnpGm8bev99T8@#!vOZDar=bXf=529)MD}kxt9W@WwzOJaqfMqqMN`{vF zw6T}e`tL>F2>GN*4`g;^u)@G7XOD@~6M`-P0!#P}tL5{Dhk_mp8V#%d2$@razq~BN z=xT=6JQk4j#I04PW{b?7fh%V-Vwh>@NDAhSGj2JfiY-LnvN%1H!?L$%YG8FPx3EEZ zd&Xc(Eyt=f3<+Hx>75ctYc@~VB?potWDvSPrOVFd}yQLc$Q~8Mn%}y;F&enOY*Iht2gI6 z=VFqrAJYyZtM%8(+YXO-feLTCZ5?qG48$YxKmnKC1{V{w*1StV&V_2{xq+Dx-|tgf zO~$jS`Ga&Tr4){A;*eXhA@W%kb@!yxN|hRkGmaeBiyDIkGNd;2(ZawVDwA?Z4p?!A zO!{QaiT>jzbLpZH@?j#OmwiDVs|7sraJJar0?kS)s&gi%uvDD}Fek?>0b8wIR&S~$ zh!WushVCVhfs^nbxVe|cPVH44i@>&x=N-C$345Dk8=&>Z#lfODj|%@e!R4|X;4<-tB?U2i-SBy;iNXm=VJZ^S8Zy1j^JFbT z!EN(p&0B`i8d1S(M2lO{!Bt^uXAlLSBKzflX_b}w?0V-2RKM|dxV{CosXO&>WHBT> z=aE!<+v7W}L*GmHzzI{fF>${KiN_IXT#Mz%+U$Il7%MXy@dzVzo>o2g&D>IpN1B*y zqOR3Knd2vq2s@1BdneDnsH49LoXnOb$r20gb=y$G8Wj>wG|m-tYspj z2clPMcY|ACt9ZXL3wM13p9#RFSQF%aG{xVUD%knQ7*IM_qy5JFbRi=tr(_CYeex%B zmX%0?xkzW&&P(-ED|6x2f6;PX7b=H|U%YKTxoSZ#y=xO2j7SjyM(|33c#L8e^@}OS zP93mO$6E&kRBugrLO(yg1k)Hv19GY`G>(^V^UchJAzsKKibuXxK_JaX-N|e=s4_&gfkB2TNh>NoE~FcwGi5ScxE`9 zHrOpip;ldLt?nt5(&-fvmgM?K72IE^0Q9|nZV{&(0Ey0~3&g(;f3n=R25p@D?#jsO zLT?*;xnvL#;rVQXtIXA4SUe`Cr5T@Q-+^>?`((?hldLva7&E+>WbF1(n+9lMzTVJ# zSPLNLrKTy0KA5?gSrAv`KTKca9HQoecfdL4z}dRMQ}rK^G<1z~t`?}t5WHPJI6l&t zA|7ZRk{g_H7j>p1TsG!A^TZw5bQg{>mdF(WxU7V4VwdIWt|QYf;*VvWn6I)&`sYJH z6gRRo_`HieM=nV&pm6ycBkzI<#O9#=_!^EiDGO(m4sqkL9|TAFouSXbXkq%gxM4*6 zzD$a2HPVsUp~GWO03<6u3(# z6HqWqZ$IdTemGuh%I^Wq$6wbT>|gsGw{Op&OTCGB7lK;I8=kBq#$nluKA^TJ!Y^=u zt;Cx#MC4=jdXPGca9~`ZL=USfAhMefpOUxE$)NcqTyFn>V%-W@IL+1W+F*xD?~|2b zY$&}?Ux?P-vJj(G|6P79!+oMP9f9*IgKeg8g>KHog6VNl)cg1;t+=cq-n%n=6DaiBEl}S=?Bqg1*NNcNIS`d*2VNpNGEsR<;@RUM2 z`FNsv50WP&MInV2E_14d{?5l}cPZ0l=FPD%v|5oh_Y*xfx*vRRF86G9>^LhM=n}u`VO4kP@0hS*<;DD(DtHE3 z{5;p@4ImA5vsmyyN*qjW+2-$5ATp5@78#BVK#SF-p#G&^A*CSXG%JO4Z}lE`njbD} zHUHMCS}3SUzo+Y&z(UUoZ4sNc@+8)rT8`5NU(V1U@*bwNK`OF}hp3kX^+ zV?^5xxQlBUT_yE%wGJ!h+1GP3rUep(b)t8pZ0Ukm>K}7Nr-ucbEWTkhQ}}csQ(mX_ zx~U8uOa`#cS34bfsx9NIV_LVVC8y|vz?LN+wfxWkVG<#}yqGg_PmlM|HCbBusO0%i zlj2kX+3L#l%!AIXkLr28$c+g<4EP21T0aawUu$CEh2ZbowQ&ZwPiQ}W!W;q~;i`Y9 zPQAUY46XR9v2TBEeSVNcUPod1GGCf;m#sGJ7mS=ah@^VxAb-?D2{?t1yx?6jwKFQkcn z2lImm*MaK%5%Z6IqL_bQKeR;)#v4vkKz2RdtViw~2MuOKNN<(4$t9C7J3U#uZ~Z?Z zeHL-CFIWnItC8qORP~qBJ^&vJb|siOl1jJ5A()%(@Fob=%?dr%G6^ zvVNS+!(HN#BMUbLL;U{;LDoaZLzYFz6`ZGXfMI;#bT%;LcD|h3!yiYxHmdvFy~t>o zAl}qYYB;Qm)~=1IwHVI$jXRHNmFX8R{vy;=d+VWcW%|L5c8tHKc95pIUHDg6J4$>gQ2&z>+_McHxf9niZp_yXS@A?oU$#IZ zEViF6yxc6C4iZ4i$vO(@1}6RqfNG25JI(f_^j;e;h|k?7@fTsTjK*O(K47fnw?KgM zvGi1vYa;l;dM3WcMLweo*iNiV!)YV2Ry-O{4p+`Xmain~#i(hB|8!(0J7$QdJ==6`dLR_v( z#8tBX+h=UU?b;tbod4qnP4p?X(0T}X*1?u3W4*4o^wBAcS9?jR?GjqI!5Ywr8L_H6 zGRG}VswJ&Df9%?d!s9@D59X~ zD(bi}dWPZj98VhyZl5o)rK<(<>UJ@7BFegKKt2_Ud)Aa}DR+Xv;yG1*Sg7ifP7-#q zT4%{M6(vuO4W#i1%|Ml#fbt2~5(cxiwm9UQV-SrO%{Lmz&)ag)0-I?+s}qX%u_!{v_G0eEAl) z%Zqgq7E(m{HVIlUYS&tpb-1Wc_9nC4FGb89wHgF&XFpbT%gBf}Rwxaat6MYk{_Nw+ zT7~h&8oGWQ%U{wQ0S^<@K>M!)%{4T+B&n;1hhAs72cle$^qG=9ac zM?^C_2^4pD=d+O4$15CA{iigiMNMvI;w(Q4|50_CJdyL@HNl1W`p7J}g8CKdwAbDo z;0DD_R@fDzkS8dcsm2}CBWmpqTw0c0hIf?tqoK0Xv}sy2OX_nuw*C8dpg}oIR@CV| z5R6lMlW!aJ4Vxt%ihwNY>4-yLsqeKw{`07bJ$W)N*j%4`&Dm|n_iQQ%`C|MOp%fd6 z-``Ru-)5&Fop|8Loa&2%*8=18PCUfdRg#!0!u{$R(L1Z7&}k5PG!i|$ZIKTPchmCv zH|c1j7`U%`@1Pj@ZT<82A*1r9*`sricA_F8peytp4v1kV>XaYR%(=R@dVwz?*&lcC z11VN#Daym5=INjIQd7p#TPfqVbprm0sTTfSHos!$a?A%2u?GgE zI*8%LGM!`Ck_Qi~tGNnkvzDnc_lF*?;&vVu7B!J9EBqi>-+<%C%U628jn5Gr4Bxm( z-vy&?vsgp1W4VFH{^h3Kych5A#-{zR-X!v_1V8Lc|9RV11O$CLGo?y%Uu=mx+q-#x zDg9kmwxc&QW)kOPfLx-ftMd8D+f=6t8nwLh{9`(I;pUSz=G<)}`QmJ@@02Uwfke;^ zUbj)qo7AHo{AI#I=bR6c2v{!_y8)HlnF z?O{c57hsgrA`NpspV%mh(fQTS{VtZnLfcm~(n_u&UG8}M!z2QK(zinc;b9@%CMa}G z5!3g^gIU?ZkW6kTyDl2c8=@Ke0-966Vp^fj@#=ez87$)T=65)5AV?OuX<&?W7E~Kx ztqVs?_=VKi=9ISnFhukX$M2#v2P$CN8_^cj}UXms*H1i`Sd>N3e zChcg8wcuUGMK5burBNf>Q#lhRD)9;u$)tm_9ft-(j5@2J zm2Pl@4d*wJbxn`9E2g!CbVw^;qLLAIa0|N7=b3HuMn~OBoJpQ&kweIe@-NxADX|Yc zQ$d`do0}pA+X~br1n#Ia+6oGb;Lp(o?Mv+ia^kG1J-^t~Z_C2b@O#ncB-zUl2Y-|m z62pSsj#`PtUE;!h^Y7R7Z7*0o%dBmQ%v%47_EM{h2Z8Ku7*)Olb=obS|FjBya}Uhd zUPB((K=H&Txa1oWoaBdT-ihX2-Q#kS9(`NUKZH%wQ+^PnUv<=I&enFNy9D><_E1k) z!yQPOT#U+An2i7yB3w_G&*Z$< zgUV_{8F(3PavF`1W?P?(xkTslno}?gH$-yh)6`C)GGf0Z zBxMsP*E=3?y;%wp$)68-I>2Ru1;Y<%i)d#W)@&q9jy#UVdTjo*ZG;$;>?8V>^ozf+ zhSPT(B=Wwd40FVk|f6AywhkUA9tRWnmsF zH4dEWjlBTyiIBovBMG6xGv7el4iI9-0~bU<|(2 zYSCVf9yILf$P`SLi)*v$xnR}=>qQ+bHH$^XX3w6?1vZaYhEsN-iP3#Y! z1Y9x1|7P`L{a>wqZ2x2KW5j1 zrrC5&o$8!7+B8kI+HAFMm=sNozD;x7Wk+PZAAUA9FurY4y~TACCI$)*&aP^#4B?Is z_79Fv1Is7Kr6@NG)c>{t z(>FA+w0zUa%0~YY>R&-QJO75IXB6eY^6P4=s0%6xpy1O^7E?meH?n|^OZ+r#uWm$~ z;W5t-Z#?#O7J;+>jWx1<#+iKMUGZs%z4>WH+f!2mC`loi`7_LKFQUd?^f@QBvNQqP ze{)%18vgB7_(5>|48imN#Dy{gDCKYPnWI@*ff8Zi`)e-Gj_!_NoI}L7F@bV!0u|@P z{9au58Hlo`uHydn_5X#vvuUrde&b!BtFNPHZ2aQ1IVaXTgJ)7|aQ+dsXC%Dv3I0&k z0)D?;j04Ni=ve>uK;Gl2{Bo!%acNn_{i(g>{YPF&k&qS8RaTF>R51t|Kt`t-I@^>G>0g z2w(5;VyORCN)LDehyK5gKb-!V&!IEF1r`SfXOK7OY^vZ>rdjDG4xBo1RE!d6pEbQHbT}mTUPD1$Eu=J;UJ=+Pr zR-`PSu)^%Q*^#7>Ygz+d6r@%3Z#5gfO0#}7@N0dc@?$Lw3jXg{4p-T|4Y=k1z5A&d zPP#-#@{@6t6NonIs|)ZEk7Tws4+E-+qH$0(LSN8;?Q&`{jAs87?QN*v8{6PeQ_-5E z?$dzQ`U~^9`+w=BuV%l!{PXYcKuL)|MlQW3!-P+E(YRjSuSmt~?JcY_a0*y>R+EF#;R?6iuI+Jgxl630P%VjaWGnq-jk za%8|z+_b5=G)M|Qs6;L<*d}5XI2?0e6Oe1XD+50bp_^efY-DCCP&|2(vWI&F>;3L* zwSVFdQEomW+E|8J-w_(ZsbJD{nV^unV(2*>&ue!?0r=WW(mtZ%Q#cYpzM6F)XpL*c zZu)!iY+XsU*@IFWQpOO`%uL!s68>JAWYBOxqRIeFULcD&1qRQ2^xDOQ80QwZ;FK9y zMB0b-EO2o}P$_uo7x^yi$kKZckaW!1K~&_16=$!Bn|o*P5#FE&!K9qjYdQVr&X0 zPtK;C4a;Tb36IW+6V90*fQ+6zkFMZbzEY>!$`CQo}=DD*fXXTL6lS$yiL54v3qA*MQ6h%Rh12T za1>vgBGS)jT#!cLeVNbHaU@0H1+B8U~ilEICSkZ$P-4qWz!6wCo7deY5;h)EkVnID$gDQC!&y0gdeDJ@>4J|&kt zY(xI0Cq*=iiDjrFp7r;t0*GKNRi5=KJEM^At#T3UNTg83!->9R+WJol_KRcC&YqXl2t+ zK~Fbn;U81^ff0h~44jB`%eSwSWDe0wEA4NPLKU#gf8;pmp?~NJw*YyRLG>{qek)4C z#VMFv7B6dHS5<3z=+unpp(V!6M%ma`(+OFA{l-tp_g9@d@Y<#0Og8Ngxc~JH&5!!%FOw1B|HTA0>@%?d&uxckiTt9BV%_KOZ!!8~O{_a28#K#WU=f?} zFM7_#(c$Z$xZ2-1slLpTlRLU7!>PcxSJ|SA#eP1DJfMvs-TW8{)~^9JyeFoeO6R{m z5#`d*2}uyEi@(tcNLRC00o@;{kaU9{uCp6=uC#rdAU}I zJED93t|^$V&O?cTTc?w}0%)LyqOAp-*kK8+=5hn|`UuKeaM7S6nfTE*Kz#-$T@%?e z90PIdGgm2_@swYMOo}1Jxi_gso2-BRUAJPw%xQlxO4ze{mOfCxfxLuv6fg#F6FOQlV`k?4_}zfL`G2@{$w{i2tiYv?R%Ma>i7tPDBn*WP}v zAQi$t-yg=&NSL~*wcYA2nlWy~Mn005#goK;oKdHHz`h*8HyDcQq*Z`g;WDGCFw5Eh z1Km7X2N@}T`C8W@^~!T95>lyMvJP-U9pj9*@_Z3TMy_ zjiyG1CP{ctvorE$hvXK{8oEI7$S@8)eV+k~SY$o65pS^-I!$QFWhn;%b;n<#5&h=Q zKZb9A0maY}n05!fCO-sLNCdm3-rod~q#Iwf8@l*l<* zeKCd^PHjVOM;2BA(uy=k#?!LcT81`sXTz&Tf546b%94B#Q$=B$Lv1m%l?3P2*W8itQ z+x$$m%Sr}D_LwX&wRpOC{B0SAU7sj4+eIr_oJ;7z>x`E)_FiPuY#kR3|dJ zcNK8$PSbwhd$$i8}B`e{1lpq zK-Gi6FOIk!nXV#mEH(TiW)ooqC9Vda6;K7xq>d26EFawJB0K8^6E7ste9L0FnI!ckzksF}70c(+qX-pUzFWan)rXaznNV zTm>KNr&BWjgom&G${9Hgd4#!?v4w8{(MT<%*@;AJImUX!u0=YPuFaak@ZrdSKlJ0E zurKqrD%P8G&t^oo;6?XXpTSE|W1n=nE*4%(7Br&}oDJxyP_j&Xd9oQF-Dj4B!qtX; ztkD$$@h2z8NFsQnh?vZUMX1kvbmQyb2}$SlO5n<)Z&qULSkaJOUz}xF6r=PYH(LGVX&y?WUdfl&wB5MUB+|jYO zP-b@9YoT^JRAOHqMK#@G*!8rf?=PShyIwzuhs#9|FsV001FQ*oQz-gpa$GoE<>nz> zX%r@%gcU}X_xU-9VuW$pWLYOk&+zOz`e1rLRVSsfJp!DrtKg$SG6CdDFHOcSEPQYyvJKKQ+Y2DB#$=M?2SO(Y$7L4_cr5JXW)@OIL3L(pz!b=E1BjC zM3PratiR$WZSxSWSY1^5Fo;tAS%g^u*e|s{+F8u1@V_g0SQ09n)~)YRGyG=0sof-Lv z7K;#g_Nuko=WOhH-i)d*DNR-JODU^YTy%|^s>Fj7@Eeq^Mi3R80Re;2d^GxL$rpS1 zjb#1!FIF^3=au2U?8Lx|Itl_h_8;#q3Rz4h*TO?$`L7q6^5X5N2SI4k-ct^0@xlCh zN7IggY)(ec6-2px`a!C@smfVTbPF0BWT|?n6&B= zI4t?E3D2KdWJQe#b?;EbiPHRUmtWD>?>jXvEZNpa8JX`s-FJ1oVfkji%GzLC+WCD` zH7*u~0c;xLB@95f-_~=&?CngK50V13^1?t8jMGebPDX_2!X-us6=qkkl%CixY7M6p zC=v3Lb`{T`tBP6qZ_f=n>PyVGt9V7~=pXam9i~N5&zhrxWXewel#^J7lX-8Dd3r03uVw%F^Wx&6|~ zY9!`eCBZcZE`Tdo&1h2Px#z6m5@6nhf{sIS%>-a)zgz;wZLR>Vc2V6vbnvUN^;N@U z$cn@i{U)|QF4p=O<6idZC(g^ z+}GOkHcwI!w++JCrBPJ?L^UR7g-g$(-`%@Po&QJ@3Z0g-sunhI;-_4P4Zz$md6i=r zTbUWTu2WHC!Aw8V1klf+8WAH))lm$p;4`^K>z|K~P6xs4*wZbk?SrV%s_nB*L#sF8 zc!gggv!;i{D4|}L;o`zsXt?@wPb=q?I;z2Ng~f21L#CE)0%#AKc+`lh7!`})ah|Yn zz7FNoZK6&HWq+;Yb+q6|81kNq4OAUBp*{@8-eTA~3}5>KsZ3)=YynV#60ZYQN@jJi z6;HMAB11Pw9YTvyn*978RRF*WW$qW|Rb@8?`D-D~Opvl1AL6i<{Bf$#+tC$V{W*Lb z%Wk)xI6g)0i6QiP+i~wna*SE<1)f%v8Ys1xQ==Xpz60j!}WiJ9w?Wd zhEN#yZ1L;A3d8!OoHe_RnP&@W61Id%jH#{rWqU1Y0)K6hMUSi%$imB z6og{Kp}`n7Um25bd;~E8P%@_@2Vf!2uppw^5affKtko8$j^d##}LM!3-E3+(#b{Z9r$=NF^g|`q*FHF%XZ*1c)BLnV9 z65J+5!p{aImU&)A`M|BRQSjv_u&`e4s-SU~rU?by&SYP@cN#$%iiaH%P2?vidOJ}H zF`s&W#7Tf;lazDUZ!5jzrT#znMS9MpgH+ilhkFHX$7w5Q}QG`$9Q`EixauTtVUu;H0#1!(E5%g6kW6 zKj$>@EYVw)xqs49<`h}sc~~JC8zG~{>nHK_WhG&c6Zlk4&#>c0syptzt8MnNK(^x# z^jd)l>{4l_5D(E7CJQ26z?5+Bns(?611uz37^RgrZ;mg{p>YHA5CF`Osh;vYF0hV8OXh>Gy2Q4Q!iILTpTrJvAKjq0eRwsdq_11$0+{ z*>-B2EaxoCN$Xr@^Q31m59EK@9|Yn%OAbPoYB4*?{KIKOnQ+I*L}o{SHEh zLcYv25Au^}OPtF4$H)K*!3#lUQX{()y}?HOY84H3Y%r0hq0g`>{c*c3*4%ClN#y)m zrs*|DF_L=*@GG7!8)HL^mOT<;iuP@tJhNYHiqE{FRE_oCW*t2_+sVJHt{(OV*~|#a zs*4KFN_g;*TQdN91Bql~wJTrzT41%YXm@5s6vr)lxxbmXg0P;IBR_6W-E?Y{cclqZ z)7J z*3`s7Wr{h}Y|~sw;f3Qum@Rh|1(1{@KChaP`PwMgRX>sxcJk*AcV>g~|31L@Xy7O)`7iMv|*Mj}^rD;p=(a;%&Np@G9 zg^(m<5>UD#8Ixx=CX?-!eh*~Z_^|XYDvUYB5*a>GLT8Gg*M+WaQbvkfXNK-tApK8s zz|<{4)pIw;T+moY83(d27g<$hSaA|sZlZTSFrAL0(0>Xb=h2HS3}b4RZ`9M6VA4;m zo1cgn&4)C{#KK~NR4SG=x+!|IkIjp}@IoqI*SDRr`lO)f?yD$^wT=fc<$ew7rb_Q$L_2vBv_L6?6Om z?EDxBy;%|ImPn`#*#uQ4lc>8Omty146T304<#Ka*#RMnIib4*cqi zJ9Ce^7f-8J@NBT;h3q(-#+G#OiY*2P6wO!++_l+e4Wn&5+V__oC%zaNVcSroonPNO z`Or2L44vq z?;QSGvwoHN-exF~JUb-M&gS9Dl(zD*ij&=*41S&iLJA4OC*4@^%Ebx#Q^J7|D}A=H zM?=bSG4ZfBd(3y0OgQ;zM*pSxh$%EOdAr3(`TC>j5yXoFk;uKi$%C*gOIQ6L7{2E? zj`g>C6X4o4x}W$A{aBc)oUCbreq0DvEuSr}@hQ|Cgy#M2DBWlpFd+2{3_C$>QZ{B}6n8Nw=aP3OE3=&fD zSp&7#MpGHcpaD81N=+Ua`?p3o3cA)5cw3Eeh`=fjMs@-0u>8F44a&tBc$dg04dMVt zrcnSvA{NgKa8slILWaQ>RY|yowC&IULXeh_+1Q-e_L1nbC7Vfch@&Mmadp5rrq+kZ zu_4bYV%h8b?|qbJPuLdpJCwSa)iSsk#XIlXl+f|ad=q6}Nt}zr9hwTOw<-+&n2aFf z#{IhIget~CE76q2W{>gzo5-s>LvnS0g39iFJP$WN7-I-hufJSimR4HLEZ)O%OeJIu zZ(g9_A-MK}|Hf0g`gPG5&Qc#*(JDPgy9o)NY zGLyQ=Oq7p$nRf8xXF)}B?rFFgzj>SXy;>bud~ZGy7@2E2MVn*gZszW)-8xHOtepm5&sSfQW=X9l zTScOVsgT(wJ2WL$q9Gc$ZsKkqSrI_$Q-DRE1D;zfulRgN14sQjsR7HE*}!H{&h-9n zx)>03B(-npiFD>NhK$8>RfB9;3-ejL^p56#OB-u%fap{kwu%o{Obi+spp_JMo$izo zSe9xpa{Xv~U?Y9lx4Fj%7Wxq0oadD@7#kZ+!Xx-D zfq(5n4s;LU+?oET2lY+$@1GOMTWJ6fJxA_BT4*FAc(VU!6J$p^Jwj3b66}~PG$_dB zl}<6c$aqQ}uD{zdWv0iaIwnN`3DO52XLBTxq(^7G`&U}G*Dm_e46~joVv*I%jwCf3 zs^dN`1&hZmz&|JxHZ(_4aU9KuNA5q*w(63D?BeotjYM||(~}6oudjUg!7VIL-GPD^ z8i!e-1{;~xG}M9D6i9t35^nmFow)Ai;XB!}f}a3iJTAyMY` zAExsg_Lp1I(dZ$A@Xl&FpGg&8v_bzs;z1S^{d2Te<_#4nEffQ~Oj}1z+rVlu*`)IH z2jj0Ov6@{e?sxhuy*3y>;M)Ov^+CJ1b*&iDC7z3cX~&BVP>U?hVxJdsbSeM6UqhnH zMv@}W*>c=^OpR=VuUoCG=AD$L(LTfJw1PEq{&hsE)(fM!CCmihkvk%OX~Qv2u_6iz zrCJ-N3WPtXgdhg(z6ll&3flh?;tJ!>)w1Dxm{Y=)Cp`ysy(cQ|iRq>6V`hQ_@Lf0V zxY$LsaAM6<3@&H_)+$V4*>JMnEXv(NRayu}I#vJ3sYQGn`Jp0hRa4!8ho=b#spKIftxA>jonV=SeuH`21crrL!(=$*( z)q28x`EGWF#RFL}ho&rgV6>H?Z#3Ys6{0?=e!{DmeNbIx%s{rF13L_t|G|>Xi-rGt zi$ot@y@_kwvDUV$=TeXyN&=I!lCUEeg|AJlC7>j%a(M!>uKgFE&xTP|R9mzAwo(b3 za~^_BuBQ>-uj3_D?@&ieQ=T5{=JJ`L>Hw&O+7Smg zLR#G5J1G4M#{%B8pOReH6QwJSlwSIC#1R&$eEMH-P1sRlmsaZg=WfH&U;$kTk9BZ)20}*TL2RhL`J;7F?BjF`TAT9V){;5XG zFJ|O54ytu^^iiAbOVJj66~z?xPYPZ^1eRed1`<8#IH6*SOr8f?Y948y@qN@SdJ9tI zwY{~cT~gaBRu~Hr*q^b@LkMD417!hd`x#GJPXqx7D)D}#?~E7X12dm0p`khc%P!_< ze5fH%Z4DznhL~2B#+gRD`m#N2>~~`@f+ReT=zGjt#jMBGy^wkwBwU>*rIOSZP63Wc zj#(^AV%YRB-Bg28+*L0DyhMWGAn zV;XrvNjM-+2Ht}cR2=-mFPHN+0?8F>m3bwn(bdRr=j0xlx-QxQrra9*-zps^1nRGoRU_ubIZzJjJ8h z1SDJt8{uDB>P&Y3{-VEE2>Y;Lg6<|A-dsLk{%VT^1bpwc2*6ameSr@6!G84*3y)D-SJa%scJhNF#gO+tGZW(CP zVJrvp5Z|gkSF_|}#(cL*1Z8hzXk;0p;<`G`YAlnqwQgJN6CZq%y80}FMzN{SoJYlNEAGDGxa%u@&{W!#kL2qBuH4Rx&{wjcMleprab?w{ zr@N@(&-d@pxjf^@W!b}ph$`?0(Ze;=>jj%+mKyh158L)z>7N^K-7Qi}lJIZwfXH?~ zz?s42d~`yfIghD(pbBht8h%)B@FY6!zAvf22l|y$h+Fvfh{lTfBkRC-1(i-$ld;0q zevSE@ zH|CtH^=OwLfpMuvrYk9k1V_=5QsF+-mBrGkTQn~bnGqDCa8grx~rqpD{JCWOnln#Y~}G^9430}P+e{InLwuk=^PsdP*AAs0b9n3q=H7o?)r&q*Tj z@nd2AF^h;q=j9Vc4p)h|0&w_D?2MeIZRH<0Wx|dmg~Bk4pVogdoFeQmH;uV5)59ja zA`^WQGyD8Ni!-oICk7DnF>zOiDT()fK0nImDcB8J2;CX^MMn zuBdJ0ldc4vg}&I zSJs31yUhC^tG4oTGF(a7xc!c@08}?P8(1L-+gV493R63)g{fu`2ZvQ9An9Bzi(_() z*&X;70o2N-9$*teq1(1DO^V}mdy%V~5U}pR%0f8aGLqXhpi;a%&X3bqM5G9)8>SXY z$=BFfBwPRpy*yXnp5^E*(_AI`O_&jik|`#JS8J13Ow%QPzYy5dmJ9Xsex!H~7*2nu z^;SWX#}fZ-h6vZI$sjYz;HOC0iC29tfwO%gUH|CFccXrT6^ekvpvLbe9M%%FI`uj`V#cu%Zl8rGa>>qNu)zBHqkIUv!|F%vVSz}dChii z;A7mZi;3jI|eW{2o+BU$d^%r6lP1GpCC;wLc74Oq_g`r z^w8!m{;t<>5H@9Ada!N7i6Zb*KIaqX-XM6GP!WK71|AZ^+1=dZvIOmPOL!ed`dDd~X{B$~DQ+^rGPdu`eQ7Q^ImH>%x zXCK(YJ4q6fi>v+)Ynh3@{D{9Ns0I0~J-CH3v&GKQGZ*oSD?HEr#zTU&v)bp$e{!F4 zKxi+GB|DUCuh2Aa;x%6a%jqe3M0O6su?eogN1`_Vr3%HTUlXiip2;$-BciU@n^jO^ zWb~l><%^VXH3}rzW;Gai!L2$|V(T-C{&zF|x%>lH2brrUWKUt=ALG4QDy)HFw|1_vZ3Etkr(0r$akyxTMllEln-*DjJ4Lt|G7foL?&~^;f zyhr`6FH#|#SZqHNEQai{I#@r<@>5+3c4H?z*xLl!1P8g9^3!p5U=Q#HJx0U8+SXx7 zamA?*?Q-350w_Np4vh&R=AkJQ^Hd+tRj_Beu!$6Uo?FrHm$4+IjI9NnNBmU;^hj$G zxs=V;`@%wO2i<~R9OlZkw+p1(5JqgVc^#X_@copoL`zTc0X7sJlZR$Ve0r?O%1vq| zaq62F%Z&+&BKF-;On5_Do^w-&c++|9caM88`%Tl3`L$vgdBNu=F}&Iw7e1TTkG(mx z$aaPY5lAF0;X&OO*AUNw*m7>*zqz15=y>ryv}LAJzMQcQuh?KH)ZXqngDXTk@7L{C z&X@yQMlnA{Uow-87Czd-K8t#2X07Ysvhm|x7`j5>g@yIrx(eOa%Yj;FmkyY;G=7|f z?VpXI_A#|MvN@#7m~wn&`-G6ep&H`SCGX#UFK`BupL{BqJ$^?UxY&Q($k=Dwo zPWJbYlwp!VutcU~qL3YpWLZpdB11s}GcoP8dgN0$D>h9cJ0Lo+k}(jyi#jz{8V1_L zs4?6)!!k!z2II357D4?Dqkjn+|9n~VXh{W%qGCXX0n{Cv$TUdDT2XRoTJo#4B}uTp z0?K>B*Yf5&Id0ub>x5clxJIc<#twL^pirSSY~aO*K3fR<2)sDabqENucrHjG%DoaU zx1P*+4|GYIAUDNOJEg3}7N>*O3`I|7CGymRinu+=O{Y+PcU7A2u&I5PCT;0L-~q)*WSck){KQdCTZ21}pS?_M=a<#-7o zx`Q_s6e|^|CVIQ0aqHQXUw|r^j`Bd6f^=!5#$)Z2kU)}EY-R4nhDyK%03USD*xhWW z2F46APQV+m@d}s;4Qd2`8-hR0Z~XJZ!8D~Tl9M0c*lZ$=xJK{sUM|sKH~9IuS6a!b+S>RFR}u@+eco` zt6H0!hd~$hJ#y&SaW|(Z7r9}K;x1b+aE3f}b4k>y3pV-8Ye>aqFlcJbNon9D2B7A2 z`zI;ns_(ljXCW5*en7`zZXMf?Rfc>h!1wJ#9c#OwMM^;n2i3C z#?x$nEgEPV%25d@3^4p`x>qlWksffzo?V3@;DU$h1BT-T*HU(7khDSxsLX>@N692# z&q0EI0-Gv|TZ;2|?qGl*R;>gJRYw7_k2TiS52Umg^Eh;lWK)}&^;_HM1rj7)=JeOp zVcn}vrE-W|$l+RykSa0c>J}Zw`Hzd!m5pJtT!oi+SNEYIMf6J4ZTZB<3+Pqfv#e{o z!KeRY7hwTo@a9ODi7X2OFK<2qZhFB5hAO<_MSZ9Be6hYl6B~7YZ7?@#ob*UCLRg9B zckh++_w8${!BU$Zqp^}}N;rH6G%GjBbL8jf&4G@~nojDYce1$#P5TUffmQGD%;qa8 zw%R$vnEfFxV#UBr(uH;BJE|Zg9NG{9iFTf?BN*Qbb}NppUGtF`rG;N;6%>r0J*?pr z>rZIzO)u0NbA9vbGdd_=6$l=MC^!!_%awFm5;bxPDOZs@iY#eVG(^6m9sJHS-=n&|hL9puf*j88V`G3{MhUlHwY9;fsdH8qTVQ%~u zN2&mw4)AABIB{cXi%Nah&ZnT!3}52AaBo>X8<2;lB4KMzG_{&ycQZSlkf%}j!SuI_ ztm^5kU$NeB(JJ#vY;C{8Xp=mDaUQw3d1&JHh_#)DL(?T#LHmqNv-KHuu#;&FG8ShK zQ!#?CL}d1}^uPY!!6qY6KUy=xmV8};>iS2a^YiY^j+XF1sudWDR24B(*A6O7TIm$Y zRn|!2vsEZ4_x*0A=RBzu>qu}f@pQF_l=_GO4DtCckV-yRrccm4G)?n8YhFzfzgM@Y zqXi{`lg%KK=l4>3<+$bqL1Q$`8=vF;{r>-6&$}T1*aKa?W3On{GFU-JF5w~f3R32K z%$weB;@iK`Sc`%*9G`?LAxDCbmhZy_Dw@MXBO+_OH;&!J5TNp~SL&%mq*pJRD`)p_ zq2YFWaD}m#LPnHM27ZuWTg_u`wX(FAyawkbDhw##_>1IR*(ekbx%f`tTz=TN#PYs2so4(5UG#dxoNHxyAwr5>h z95%62;uUl^XbuIegBXTg5)7xcBh5E7(RuSGx{@*KcXJc)jSC?)yTzayaUQ`f9XtQ{ zKo?wlfa!!x9!&ip9IZFl9+U)Sz51Edo&YCJKsY@m;x>-VLEMW_T5ryi;2mhj7LaL~ z%^BC#gep}!Sc1fqfce%{7~U0WLS02mNO`;rWKN4%D79V5F5&bx*0I6uBrYT%jO#}I z`YYK-d}q_V3X}qtl=rvgqnn8}iIFv|qe`FZkDN1~sdYrza1v5Ac!FPXO=1RJ1{+gH zX#U#XK)OC{mbe^j>lK&8@O{vzb8+|El?Qk6x0(`4F*{jlpF_{hR9ue+$H*dIc-(L| zb6kSE>@t(*9=t>tEnhLGdbrf!#J)k>ThUB3?w9sG4e{F9&y6`KO}^ZmyIX{IzpCoO ztYinmHZ&5A_;~lyjg=`mIHdBwlqjWFpNbYzG*d7xDH3YmBW>R#Nw=fqrYQVwPCJBi zCn&l(Ftx|`r|D7TZ_;Z00<1fqy3?t5P79X^0Q>N*j{=_x`z^OTYO;WS-vibc_DpwU zezL(V-7}n~ixp&e0gtbhUpK7_ASF3qz2fu{e@vp<<-chB)e>*c&XC`b->Pd9r_72V zchZjGKtl+Nj3(3Vy0cY0-ngk+@Q#$?f*!ki8tjrJo2V!oPed!CC!wY9@noACWq1ocUt60men zRSGG+>-ftmd-~`-R-G|p?6-(wHk-W!E9V@)OWUn5Ql5g%#P{m1oaIYduyLXJq=y(2 zKVQ!hRUU;|1$ruwJA1c~A14LEPw&F>Q`xwxPLLjk^IC$$b1LmFg~NcEJ2Zz$RwfxR$|7uB^!Ma2PnUQ^rU zNrRTzawe)gC#9$BaRn{vj{u8QH`$YM9?R918|BJ`g26F2DC?yNM|%7 zORN_(jrqQcHcFXf-w0MsZ*tIT8j+7@gVoRuB|HSEU}nR?s-ik68!w<*Kc=LOd=)qO zZnHL9ym*(Ie4B=?h)~9OZ+sI`#5_-4(;AoR2t8JwX6FO@G)-w!&l_?Ur7OAx{=V|n zRG`1@xADmQsO&I>GyRATN+<+I*Oj0o(_OgQoNH9?c7|ZY!*#dTl0Ck+P78gLzkG5| zX|53)8GHoUx5e?LvEBbBB5NsW7D5Z=rCz!sP*ZZNCfHH3qRP>?qLeZfr^p2gG;dK} z@JaPf=&r%a@Mn%N)tWs4Cm?V>MG%;vaGnln4& z*VSj=LkL9Y;wq`~M}$0pTT~_HkO&Q3vMwt(W#JiwHUaAC;f*$z25<>& zg7dm;!v|liElVQh*{EOXbsEll(yi6i%7fzEXHmbCSpMYDy*oia3%%}<@AJ&`H`T`Q z2M&?*1XHx{3{A!twtO^u=m$ms`duoAUAbgz$)vT%E$V9$eh4SRuxT%i+uE0$>nOx- zkH+B8y;vr>fj=_D<{s#RYvh19lWuT90ibr zLJ2`kROcPchHZ)4Ll}q6`t%36I|)d+jz&#h4Ez9=agoKYs0gsrFW42CA_~&XpT_`p zCg;6Z;r#|=HEVaVh;~ANK`$@et)~9vL5s>jC0iTMUMz6RRUt9t#A9(d@$?jJI)Kca z%Zt}q4JjShUb6s{E3F^FH+^nlr5EumC?_mLGfgtKQ>g`0frS^A)_r4Qo;&t;8aKy= zcW$*Ioj2-KqpFYp?wgDdcOKCJN=fk2qV7K{I0aAMuy)aR$5D zZ;|kbgjyi?Pic*`56os_r!??go4A=QHsDNPJ>X@pCQNhpwE9IkR<*Iv?h+isj1UN> z*bF-wF}Pvuz;G1__G58>G~kzYB7OnvEFx{G#Fyl77IFiMprZ3umU|4>sw+3kOaQT$ zw;ZAC%u>L1lF;MV=jHrYiH| zWu!H>^#x&0A?;y#3%SWX5O3Z$lC?T{f&h4~>ZF-=^zY?kq+ty+A(!^-8Z)kq2=S(v8~z8X&GZvjpBp`pqW zCKh@~M#x-RQq%w;it)8CwRCAkOlOZn_~2Xqt)34GF}PjTF$;?aeI!!^0;bkKy?f@q zo=P=G?k1#SCN%5?OSXO74YBbWE>rh*k@64yOKVyceGQfk(8+&`G*Gzk6iqxwyNa~A-t;R~gA zeo8h=A&o2UPtRRB-(Y))V0(p3K=eaaemirRpAtie9U`vr04HQ&P~GPp^JOrwB{5>xDV{Rd={NU?VBl z)?rkk6cg>F#g+l(s?c7%Hz2OyJe>z739YA+$9$o5oExXMuJZeinT&Yn;C3+DRy?9z zlLTahL==Whg^AlJa7f#h7vG$1 z%kKwK(6p%eYm;PN;#`$+ZG@Rvz6!G*WmbM69Y_@8SE7(oB9P%3U*7V(zb0&x<#=)+ z5h`(1lF|$kc~SqWO*&jmL6`HAeDz{P0BtbEtLQ8R+2NUZPIqn(2~*LpaG$mX1`&nHu9(x_dNQ z3FDT8cV7X5L=JRMhKjG{VeXviA;n|z;~g=@0>6bW_81X_e+;#y+PBVaMN*@woUxs& zU=hxV+pnZVj}Aq}&11RV4&^KoG}uW|DEVJS6sH{s?w150yL-}P1&eT^Tzne3SU#r= zZ901O^wOv>0!(fMO-%C4G=#epU()*c=D;au%A;hoORD+#WQi_z{nbgp5Nu9LH0}S5 zhi51u!_-^u^|IPR%e&<8NsD!9hR?>JDqm(~{%~IFT0zi%9dp+#N6u4OFl=7YH9l6D zU|MjP%m~$l(OHp*nWM1hW#znA9UKUgY*QFv7QN#a8rYa$K}SBV-?k2Jlik9_@b zj*cs`-IkB<7OY)}UDb(BQ@zwH6dxbatRcme^>K)j5d6`h_jJbbZ(qj{`v8mbLtdYR z3x&|L#S|Gojv!=!OZG%wOq8D26@kG39hfB46Kg{PUdtlK`hFSa%=}F+4yHQ<<^Tl-AEA^&lfCe&}nk{zZK4lhuiynthrX8CL zGR5d-Vu@H+~i(fk04grfvo(PbfC@PIav~-Niqk1+ED)aUpnf)k!Xi6`4 z0h6MBWRuc#CaSJQi85HK6Xa350~0#=^7-3_63nnu5Wzq4Rupq1cJxh*Ev@b^wS2&B zh1XUE)O81z!psCAtB}l@C)>KG-b1AT2EI*Cs*%@|oc44FTev?k;+K;f_%pJWzxoP7 zUu8dBB?K7h+>ZC# zYrY>o9$I-i^fSHmjs`ZoQ=@2`J8gt3%ksT^3#OREdeNr;lEYt?j9fe*p^kYkJ6srM zrW~m_922MA7pG~Y6&mjmYoZ%F{H$~N-LJD^(<-xL!r|4QW!5=JMGmpwu4-!v3ZS3J zKtE_wc4!LxzX;iJCO76qMycR*X+hiH2>cia)U)o*MD9$$Ul1rycGNCZvp*z6u?fgdqzB*&1Oiyeq?rCeq>YnQ&OKlcKVd@nud0$P zn*KKM>HD#M_d$@FRD2_SJ4DobDk1P~$@Qz##HO%>($EUJP0_R;lQzZ$c&Iaj*tnUE zSd|?QBv=p1u)+T_k(4R^l?FWLQ6nV|w;I*OsG%5G0Fce?6zVOjJZx{FDL^A)b?#5c zFAi~t<>XJCqTE`>+XIz}=Oary_stg_J)a`so@Y z>7p@MOusheyRQ)gyRAC)!_KtKbo;N`hUj;D+k&Dp5<%E_Px$FTgNYGkfmQe>hHWreHT(Sppea>E zZzV)u0;_Y2=^r{+GX+Znz{zPerT2)SuxL1R4Uohiy0fVnXoqo#&!SgZ9@ZQbL*>W< zH7<$HzFCKetUr8)7AK^zEY~xh$mf7nCxr+@E9@PAg<-7&MLE{jIM~Y5T)b6|1uQ`m z1_Ducdj7OnJzAkb#WKj}gR!%FrEI{37KW{OjTOAZ0tY%Um&y=&zO;zH1}vC4=O^En zi2C>>lcg~`R4ZBRA`ikq5on|AxS^fGdDiYC*sNM@RC1X>#4JD?@SpvNxThjQVCXh` zO6mtk$gqvg9PC!b*uNJP8Yu?=#r>1$Q^0F(br5wJc!R7rPLry#ut4g-OFEraa?w(x zJp9)BL1ia|(^}D_V=Jy{o0>Jh1j#;)yh&Id9(gJ z7w80uG)jO-feL0A!MT+-jzy z*PKSZ3R+J+qWMv82MMV?df&I`pbJjKTpbCn z7N#z&jC>~qWKwj>(+d>i8JOehB(QLQ7eWYKX_0d}NwtjpxcBpMU`*S-APXD{r>Mc> zSEiZ31O#l0TQu3QX$tVllkaA{Rd1cB3M#0EZx?sqYWaMi%s)ng9k81`ze!j_GIESI zh6z{&B_7nXAJowC3!!FjH|Q|cVKU~0;Vs?_!+tcRt81Uw<0<_Cr=)sdtnV(w^{asg z$TzlNN)O6wOc=zWGPJ^7PV-6%f)8QiA>wtGAocRdwp@dK0j@0iOI^65hPsp8g2|*| zfVHC)DmrZiHbZ51{{RE`yGU4IB}|Mzkc3}8zeWS};R z`O&c_Dc+*RG?l=$Cd9q@&fAha*1c0LzVa<*cA#ZAR-;+D^+q;zrL@1-3|TaFu45BQ zFq>iS)l>&OSNoD~Xm3MT&tl+{pR%kKPGJc^qRh2u2Qp+|U0BUiN@M|nK0$4;)M~78 zMKdPTY;33mFh zYIr-_2+=-Ci%nVh%h;{q%eAU*`Uc-3+IxfuWhfZR3^{pBFNX)k2|8zkWl}1?cSF=` zgXb7B5|V%xFZ(bkR%+MZAYGQ@uu~o=Ia zUsn;I&7WkF1EaN^`4PICR%+qduA@oZXmU1nvI)Dd3pZw-Ef_z-bOfxQZo#e;LtY38 zJrHlg7{wMzr20c4t=TC!6m!ZY-agFkT)#-UU6!ar*OS^l6r3K27;Ry7mUocFAA1PQ zB#&Pvlu*nFJg}zGEiV3iCnRKkX=-YGXBJ=4z!5kgLb&W-?~%uJ53+VccWz+QBsUrt z*cG)32(92Ig*lar;|I`!$kwN9-qvbX>J@N zx!CcC*sShpbSr(%)7?TTV@49T-7slRly{0rCzMwhLyL0)IMsEpGSot)nX0Wg!L)_F zW7oAeM=K2x0!XjiCs;F33V&1;vfFx@#JJgA!Jt4ar%Bo~GeUI%biq%H9FdX)A<}QF zcoIL~u3JzWTLGoz_{kw{Lf6qm1FWOoZDx68uzgQOJ+u{0W)7d;*H$cww2Mf0$d!6D zGA5dk`rikyG2+J~^Y5nM(cR#<1kc^8xCn=fUm_ovEHP^mm#b9%wvGr zmUe05Gvm`Mg#3u7DZTDlO=1yCwkYm7J9jnWj&hehJSU`iyz;p1NC{a-M0NeTSu6MJ z?ebLS0pF!Uz&!{a4B3!1(N>w+#QaKOiOeGQYL78OX3kWI2_8=>1pRMP$|z7m{!VgC zlDz4kysO%X^=vu?L&rV!v$r%od$Q@LfJIWM>U?4`;3QF9Fxh%1u80?{-bKp-&0s>2 z!TG|D>-0F0D}#5%!0zBw&Ha8qk-nf7%oW%vmB||39IH@)Iv&+r$JIWQaqlkvrmkTT z7GWs^Jw#2|mEe5bg}tVvL%&BFzIQtzyQ zCJPGPX$C?D+tb6UTNx5>z|)RE6bx3L6s_EnsfDOa2^fN_J(wQpu19gjGa-8KOY}g# zp2RRDHEC?_r^{Ij>}f5QJ75LOeyS@SsF4rk|B`vEo7wl!Lna zb%J&Q9}<{=77ZA9x3$dX2stmlsOrtPcEdf!#U-(ArJ;I{&$Qpqlt9}_l08@tilHFW zY+UxZH9Zf}Y}P@FzyCWXoJhx{u)%o+wm>Kbny-};yWexfN=GIu(|TW-&)ejB0T46D z0*PqsSn|m=r?&+Uxgj{w51O3@5LJJdOjQuiFbP@jlQ28zxTDvzND`P_8fV;{TbJG1 zXnA(;mYAb5h{2U86B@;oHJMPwaS0t>@ePu67Izlf?|S;qeXSTrP)`|fz;Hl{b*5HX z_`VNu&-o1M1*9^FhUSK!L=YAXS|1iCh#oUl^~uq$uCz!9e{HTIO7k5 zl_xc_9rlAyxiC zO5bCn=BqP1c$2X5hRzpDXYj7-#;X-?AOS0bckFZIYp98X4(lxUaP4a4kkqGVGbW#C zI(Rq9N$(bb2c`Lcq3^kH%CPSQrft%;&v0uJ=?%k|YK$s%7elnIqP>>$C=V%9-cVZ8 zcs>coiyl>W*oD~5ZxbClp=!Ei9i^K<2^pN`m>pTR5`ZLb(oC4>@smL1iMWc)dJqHo@WA$0)!T~p#A{W ziL*4&IQQ@!|FP^W3drmwi(jA4R0A6wOo3#r;?|$O(d)-*9PYOF=1L)DJ3)Yap*Gpj zoGI3EtqiW$hkyCgms^$W@oRkwb57%FM~TICItvFTuHq{fE^|!>V(OAhmn@SG`pKE` zZw|WkcSeOHL6`jn)2Aj+=Xbzn3!*AKV1t?(2X9$&)2G|fkovD$Ml8~lf3gdMr7WV^ z>CK@`P{!4Psd}VJP1f2_qI=8Oa-ULYBA{(ORoA2#VwsE*%MwR(dUS*_nb`4(Ls2yN zH8>Te?L6+e#m*Nci>TlFy?(6sW8u8^o}s!VXI!Eag%o;AB(LlSJ7;}A-GZj3;hYmP z@hvmq|0?4qk0k?w^{>uNioxXIGj?wX^3$3{`|_%52Zz1%rH<&V7XbIFWpp8>O7 z*WkO_=V^4p8bzeG+g^6#BqvVRN);yjLwq~yEf_5NIe()rHu9Vru97Cbqm+*4_RwBP zCa8T>BBdOPZF^SPxzO3M%Vo**ud6fm*|s^=->m+4r zNItuG>>-DhgbAIn7r*t#2mgt6n`8C^Vr1&~5|)N+!US{gGvjpQ(e3^85OFs(?uzSE zY>?{t*#aCi7Q*}aLFsiMlGb3YUJrK2{^)ew^6pp7>Cw!GY14W_~@RgZs1ihL>VG5YnIXNjVV zcghTO4(FcUoCJ+A52>>#qXNzUXk2=QDs-uMHtBZuO4_w)m9@D{Rj=;37Iy1OwlZwS z-(#E4R0O9*LvMdNpiNvEOtGfs^~n`(3}eewBV-xrRwN*ei6MJND)8w3gi?7C15Le=iF;2ocgPpf%Y;V8MoyQtG0GoDZS^{d~!#=zbwl*mm zL0Jj;__#^*?zbGd#EbPR&Cb@dG#E0>6^&ScHMz!?{)8`i!t^vx+HxBESFNHHfh!){ z$m|g%g`SP~XsHq=Vlj=V|8{_s;Lq z!s3H|MV3hK3}amOFaZh4(*LIa;7OaPU$E!aywRu(OIPPX=BwA$LsdXXF_;V#i90X@V%pIl|z>HnNSc0IQKo!``(>11qxt)R%j)QeQf_ z35p8o!o}4}Ir*LMh0KfF1`|H;u9NZ{hxz9d$krPvfh@a$yXV*==uS_z61REi+lFCU zxYU)ZHW8Qlmm9)O#Xs(?DB)()wwNH5Im9l2LnW>=|4+G+&@$u`?<2-J z8>%+B1|wtw0-Y+?JEnG{F&JKRJ-fxyY}}6kFA&7SLzr`*56dU0Hw@xEV!(|M(V+l0 zLB*;OY9SuZ8a*l-_on0!2eyPV_Wk2KaZ{W^1bAoemXLkIL|MKWX_NkW0PkI_&*BohIzL{VaLM)8RnUC` zI7C-{4}lvns$TnbOI!40G*}c_-GWn`-%8lc} zf2{vpRQfmpu-c{1GVIle?m`sl-_vKA7#UYflkN@frlIR&XA*(j0{(oOfGD zTH9W9yXcLkMIB&Cpzfd1;((*1P`&%pt=_vA?{(9KqPx^AqcwJE_-j0kh>J+-haQ)5 z2f92l zX|1m}S*`Hg%Tulwu#FT;Q6d_wDW`$%UP8*|G!6gxe9Vz9YQ&wcRhwFXUaV`nDy=WB zFef{UR{UT!#*E;9fJi;H%xD{=x-6ysurBeV zlW?w;tvSu(v_@J)Hs@@ICI9xBN**2)xV0Gz?izM9!=8-9cMiklTx0=80Q|| zDX1W~CO(LT5jR!OAo^f0t@vT_p87&y?Ik!7KB!GF1l zWR2~2fZb0c7=naGyvn+R)oF~EZ@`I~^tmBQ*li8{@%1s0d;u-RP+HB~<^eoi>Eatu&ciH{nZI$KSU~~j4uPCx6{2Gx4 zKq1i&CdH!MX?PUs6^KGLh}%Fa^`^--bj+g+iV1~;xfF@!2>zlm9@JOFC_*=sOla)A zVoFUD6~ZX^rMh&pDTH00K>W5)$Z<6|}G<}5&?#APDZ_C-!9J8QNVA>PTc@{{zNy}qkk)qg~1R`8|>*Q z{eD6vwsfZ6>U5xUphtf3+>4r3cgUQUJ4FP9Pkoro5UH)mYC-q=5)b=p3r4td9Dn-5 zbC+!Y-TjE8E9J78=;W1ghS#G8%y6D4U-#Vw`8QKXzL1w4@+gXCfb-fSeR4_d>Z^Nm zpTu`puaUcozqj+`H4~gIDiR`W( z3W?_xH1WRZQfv-(t^UU$h z&pP5}4&po+lX~BHVr}{ls%^8 zs1YUjFF!)ZSvo;yhU-Pa@{~OAp^Vo*CTQ3hu#IIADF+?xz4|Bs^Hs_dF3iK}oF1-d zd+7@E*+9@c+jQ#FN^8NQU{qj?I>z*@_(i(ICh`gGUv#vL>p4iX`*R_Qe?=Km32|yxhrW#XFdU(ZE}#a>2u`{*jiUHkGS#2UP9V+Y)H=wQU5F(O?(SaxX1g2&W8j zgIeOytzX{&!2=<$F!j^lgF*^19W+ER1ENtbm4ou55ur~52SU|1hA|Bykk+&>k!rVJ zO7&GP(jir`L3Wp+?|HfH9xAM%)MeN&HhG`A0loM~2at!~&5&TaH(2JtI`0(xl!szd_ZJv;;gVE_P04^GsEq%3cn%sykv+xLO`{ZZ+6z z>3A92Vt_<^`GqI z7m=vrBowwzHNYDR8YFZ=1)~i-7&DCPAU==zExzrT&x)p9PGi*d7`vD zg~@1UDZl+&enp~V&)BZpDKZWCo;6c^q0(JOB>y_*Wy(d^QxZC}*yPgK%YyeO* zL|#&-4CBlYTT6Qu3e!!$A#I`WdIh;FHXS&)BwmPT{6ip0KFRV{*PV#~m@U$u4pyJTmf*_#_k6tM+^Z4UYO5>j^Ms2Z-=?>NihOYPgu$*Mp2yxq7+|Wgjd{|$}J_N zN5Gs(yGzMCa<MX>{UC6kH0c<`dS@OTuNSAP_#HXAZqFw;aF^hV5NQ*7)EC0Cy*o4hBqmG z!IA9!aJwfoQfK`nHuS97A8i9t^@**b$b&$)kMq6mIaa%|X5Rnma-Ji0CuPIO7Jla5 z7Akv+hOj`0Lvl7(t$U;=-Vs`1uPgFkC3%WcEmvIA|E`{NiA}<#neK@P1v>VyGx|0@ zE5JTqz;qs@OU=M!C5w9v%Nm(_q%E}~@Zegu>Gy4p9VxaoWtBZoIOyz3_1Y_F`4zW|nK zt*DFWEczzkA)Oh;Ej@4EFSUii_uP>xWUjq!k6%il#NUWUm)bIy z0;G{f5N#Sw7KcY7GOY>?Y4i0F#^GxSo?0y)Cu7cBa2$EQ3fxxzHjG!{oEHzCzu{Q8 zcev=<9~VuenSc$P6f$}K_OJp2|El(n2OIiIzOwO#lHovoQf~$gt>fTSFork5Kkj13 zi7ommV=YqV2Z50kM;2i~Fu+D*-pn7Lce3vL`VatD&L-L1gzUfYbI$SR3Y}dZ_Hyp` za=YG>IqmUq1`u4Va7(E!zK;*bX6Y{!#Q%ajRB1}J7C zv-wCNEDdm+{WGnZYWbp09{^)U@@ZW}Y-gv|s; zIN!>%IkXN+P?u>%;M47c!G4%m+NQtcd8+O^&MGVSL{W}`3efP*?(o8n2zfMn3e)9LvEJMXTEpRS;qF? zA6PYqO;bAI&#$pp;XRLxAGQsLsVo_ZdG3;|T8 zY*{_uauDtmd$J7CFn|*XNd3i1D#W7s?JC|T^8eH|jkWV(@r<4g4jj$$!j_!;qrStr{n&@}?zrdK6W2&~8S1xwEWSv!xT2QPzZ0D4Qz6IG% zv;)T)`PKfe;hs^E#w9WQwC6!uLhl(mAq?*1K`0JKnCX5mxU%&TKa{wRj(UW7TL@zL zVDz?Z4Ijshg%8QU(k9+bGQl;U!jq#MxaSmrE9KVOQwJ_L^*_pdng_Sfip=n~?0@qr{ug2x{V zUlekZ9`0pEOH@mv|JsAh4+?opAVRY(AEvI^w6Br=iN_hRoTE|qM;wG=2r_41BDl;P z1|2P5eqy=io7_7;Z3+jJSFO71O3(eah)fg0x!$<7A8F?s<(`(9B18nt(kW-8dN8z% z5bwBh+}P;Bf+>cL6_&+H)BFat9nCwOexXV$Fs^#`ZD=&%B7x?L01(ohv5~MT7DM8R zQt4Fs@XdXthcSY{@zRBwRvi?Sm(lw4vn?VO*p8(IEqsLOzkin-^D@7aF|Oa?1;P^? z(Ss#kfwTQKylCCr3r?^xcS|TnCV-P=H2tDIEF@qWQqrsvMS92?Z$*sTC2&-R5n*J4 z;pL1CzFI3Ed*vNI7yn$U44NcQlS8akW3#6rj4XYZrLy#8@~OYyD+4PF?{Wjnh&Nk5 zH$J{D+6u8{ODDzG-U%(lTV_7x1bb%kyEeKPo9k4pkmgKXs1Un4SY+#TzNn5Go+Ale zGBQQe_Xu;pidK4MG||VUpLJwcvZ6%Aoj$GCy_i%rcNX;YP;;q)KJ4RISVi-UfSB<> zDN3L+DNE<_wK!>DwYMQ9L7^==)RreN^si*kRA@deV`OVlJju83y@+>AHL_@zk{v9p zQlrM`%4!(VaDjGI$lg@!xKny~G8@%Fu^Y{CYcyCEAJb)IH4&y)-0_NY@NS27B=Zay z_i3E0CK&#O_e}ZjneHWvmh#QaUNYLt^h#pV%H>R@1a^=v&*#pa&fO0mHt0@s+_Ag3GjZ@~_} z5qk{f!(bhe#8201vKFIJVf4CuK}k#Ci}%)?v4H7U*jQcQWJ{WY3fvLPvv2>jhNHM*1(D{#XU6wdIMQ&s4;1jAiKM0 zRw1#>MJzQ^81z~#bc zogI_&kQhPTkT3M6W2_|kk zi2-(u8p~Dx4VsOT2viKMCGueB#GaUL7;eu0+Rk1-Xi)|p%p^ytwu)3FGS98@a*D=L z1Nbbv;n(U;H2Kvyzw%eg>MOYF9l!EHt8Z*=zf;106w^o*H^Wh-m^tZT1XZEk%g^tI z{waQtFZO2t2*e89?|0@5ifc5!Nsa{r?c3bauCJfV*0U(0ydxg6Ln?eY(J2p3!Ak9K zoJ-loo4Tz3If#~lrsuDmgAzW1zXdAlYW<3FxF%IQ1`|*mz;KhBI{~+9P|ErpLcM>Q zdyaa5$8XtM!`A43^SLMPs@Jc+4Jr=U{~IV2$`8#CiP25XsG$D`W}Oa#M8v(9Ax^#0%6RviDU+luXfWL8WBjO>O-N|G#dl4r2$qxmI4BE$&m~t^X^u%E8@gy}4fhZ|T;U)ZOPi`3-ro;kkZ&ADNQ&yl#Ol(}+=k5P z!gvByo|OrZEQ<>eEdxLX1}27~6j0w2T$WVQ5egkJnEtpY7?2rL@UNt%1X*BacXW4V zaUH1t==79q|MXhw?08cAZH~ZHSvepol(K(%aTJAsrY@h7k{m7{Ax#-HB5N~)3v&|y zMJL9FCI*lxb+puNwlo=l*_%9I#vdo3p(p3xNgoI2(oa@EPF6+I6#wva_O&fwV_A4A~a-$6g7q7UmNUi4q6LyD|k}ogEYF3j=GIrhWtaDO{_RHDt{_Ds5&JNLg+cqe6+EA&6eiZO4jO z>wj*m1^&)aKZSu=_wb=CScb!$uFVu53o@o?=1}g8|J+tEYq|q|)P%JxZ#6r=3N#*d z@M~Rw%0rE;slZ(^?d}un8t^LlnMM@A*G)JOn=Fw~vcjw^ZoB#B+eHxL=mPy4Y zmOsOodGl)pGn*hNyBQDtxAegwr{Fh(yGTbC+bF6b95|qsy4SWtx=?`JOmA&MI2g;~ zHhTXZx6T?J+D|@ja>Al%GwCF4rjhbGV`6c7@bU@q9*b#IgsFS%F#`H_K4lX5p6F-9 zz%Gc$!Vn#A$_=qfX(;q6{=I(lev2Ee&@YaDoAyzQiR8wo@Ja38+~HT;XbY>>?*3C8 zL`d)fROjNEoZofgV}7}C6={zX{`-6f;X3|`K?+`;v|F^Yx-2mKQBq;y0L+&%tuR9z z=NjCQf#vO)BUtld8ZHYiK${Qf8jhdO^0+%Cn^fd)3?yHAF=`NpPj0qpH?Fd#8GL7N z;5C!W5d5pwP5E;DTO&Xyk+_mw(r#oyO#ZP$mak3wALU zP}mHRaj9X#@fO4Y{`!LQzEL|_zsgbYvlR$oC|0owpwgMO5`(6X@Qs`%`N!p!rlMqw zkwx9(Z}`yKXOib@-r-HcHx4HrO%Ju!)}t(?{M@xbce4hCb$q4S(98Wh8tAE9$xU*H zi+9c5zXSeLACDx^MW%9BYC!2vnhGgT;>!fVM0osAz{wRyRFv0OPXg1K+)YzMbvO6z zGyl6lvOYAi7E2`|wyFw9Zb;o&>jw7EL8Y z>m)>B5v^u(vK7I@70U}TgDOy$y2m0yYg-FJ%%5*aIkTTTec{rrT^Q|{fdvwu$|qLt zwpr^R^d)3SdpdCNmZxIvW{^J$;T|<75!usnd<}{Jx~`Bk{AurTTS;tE-L2;Rl!g84 zgGd;UtWvt0+XJlTxprEQ-8?{1W~#Cpev3Q$r7=6On|B{VTN}C7mm;U1Po>G$rHWMx z7*pb!B~!|sCLfjw`E#3O*TRS)U(4GZGT^kweDRia={2gvT6A^AIQr_fWZEeC2AsH_S(lUFeux%^c*h?w+4s9c^pM?!Ojd9Ua)$D7@sZWD4s7H~a5x3h9FesD#|V zgy;4Gh8R~UrvR6J1N!Luk8Rr^)Y{Q>bX7=KvCP$s7j7)hING%JreGhSBQoUTFFha) z=Zwwynvb%b2&m7&lETFjBFQ1s0C=VDh8fYuC@$=>RZe*bPPbQ*|{+ zd2cGkDkbyH*lFG}zFrb)A{fTnblLhs-r$QgKxJn## zb>K6$AM9w0?Rm&agiF;!K;SBmMb+mv=5pdcMrS?LHpHV<9h?dsq=%qZ@U3q(8-K7= zfXt9FYshTCLca!0Ts68qVZ8m1zBKfkgd;!p!Mr@is1leLv#Tn6UNZLoM$ayx`%W%~ z#(FZ7HtDS3h`MJeQ8H+T1&2zv&`s$@-14O1aHf;iJE|B(CDRX@!gJ|JJ>u{;lVE;A_5V2BP;$3KH-qjS0So=i1)LpjgswK=vX!+ zbS-wKg~<^}OJNebVHRCOyjPpRk%)`P&x;&Cz(i)eqB_{nLzHI=%Q2gE4UWJW^oBD#!loLL=H#y<*=DsU3EJ=vfXPYO#|EZ^%fHkY%OJ z4LS}Qn@5>9?}7OiDVV@J4=D4-Ui~~q zP+j4>3((7w&_5jcdHlIc(^L0RdOVx}#T%qmf%F1SQH1_1&b?*%Om*Ie4*jAXB zDm;>5w@l&cd9jMc#EG=4YOjYqX8)&oI0l-6rxWrrPc{HPZO5W2%m2bG(j@psIs5B= z#e8~a!m*`2M59`gBO2cyft^JHd_4OrtQ?K%jaZVRST6-}mE`*}g!u2nawbj6R+*j9 z{Jl6;YLrr%nnyWmq>5Z}-`at^8;jzh_*GZd7B$-D0=ek9QdA6FF?hzVcq+ieAox$E z`wnh@Ih`ac530QnwTE9ZN}Cb`0uSX4qNpM%enn^qL6%I5lC995UYT!Q?|cF$Lbw+) zN@)y=Ri!_6CjUg(l_tm8B@#EU&Gh!7>Y+Y&ctkHGSGL>^M6@VN7I&-@YGBY`ADvxo zx5$B9&83d%Fox0ucB5A%nu^rA(R{c*84@B!CMb!oDCnavIcP6Tw45HTN&bT5V+_`Q zQPcLNf3^MO0!+(n(e48WfBL}jeGPz`so5$%$0(T+u;vyJp=&A1=4AEs==_e_N}c6O zpk-q9@=+>>Ku3gW@uA$FDb&_9D1txY&76HhS{z$yea5XtFEq_zMoXT(jU7obUg>JE z40ufFci8HfkasELNOpi%tvb^9aXMIfJ7&N(`>}m=O9WZUFGuiu4J;YqM~-InB_-Jr zGX!5{npcHii754i>ZYkMi9a;_AzwW?hF^0Q(?c+fh@(-8O!fk;5<;>BP#1Uq?w9`9 zkR6l!!ttHje*oMFULj^W+(u&vX@>8BwZWfOOJE=(CBnVNDO;NmiS-62)t*|tQ)(+h zl(JRBcd?k;fuc;&(N8C#WvF``T(ggzF=|NNsoCJ7Q>0F`40vQBLJ^H%`k*viD4 z<~L-pBP^g5BE?L<=`97UorTJsscF=H(CSClr2)kPrVBh~$Z?rSx+$OTB@XbLuoIF% z`CUMP-qc@uQ&I+v1V24rNrRsblr$XUg*n6TXM0a^=Eel|rrx7o0q;T?;EMA2l?beJ z&Ibf~_Kyc41NhJ>V%v0582aZPts979x_1@h$Taxk&1H#vw^XK|kMaeU!vTd{q{* zbXaL0WY66jL^=iMO)YnimAOCsT4b{?o@seWq)R$u29}JE@1{wZRs9{ z{3ku$G?FK~4D0i(Qjslrv7!a zT(UD9-k1jqgy2@}CU7sFaX}Ta47*hR%5+Z*J~Vw3mjYmuWbW(5BRQImkEsal9m3M^ z5g$y>A>nFuj%$O53DQ2=JMARM)evArSIz5Yw3hmSMFtjj=@Niu&-Mq@}_?5{Yg%m;vK_Lk4T?FY;@>gHMVgZz0OMznU~!{AG$I73ac^=yuPTG-fu zm+}`;LmlW;`Lphv|6v53Mi%OyfK+eu?^FS}ynsvIgm|<2kc%uJ?C>{1qZiya3x2)9 zWb1kMjlSXDRV&aT+;e)#!bf%kM(2zoX+cHD7f00(G{X&_sm;d;ge%Kj${o$Tal9=E z(F=JPp190(a$!uC>Mi#c96fZQy5a)H{n}pi9YDsJK$ELLe}vUyY%*@aqlMB~C3<(L z9d`o`$^H!TFiAy@2Ema8kP)@6lXYO}iXqU0#WtZ; z@5dq{u7Z~MFfoRZ8PdvbAm>GjK*--VWDxNKWgh6wvQE2_?YlKDg z=Bv;rN2)S(A(~rajc%L+a)J%3Dx!muM&>T>v^UGYTwVzTwdK}i52!c*sJW%iXiKI& z2bcu<3F@rfgofcQYd$zy9m}fXeWf=|Cc8RkV_91o9M3FmMH(a#5w=EHIxZ+G>A9@l zD~Nj53^Cxwg=RFEkTQgrgoqmC%g`euCk&y_~onrZ7Sgpe{<#ES8vl{=J2@) z%XygGBl4Q!B%`0dj!0n{iODqM_EEE9kdTs32jat~W+*Roav;s+J4lq#Y5996>S9V}wpE|cxc4YoXK8~YLitwsYqR4!Z(;y&#=r-*2qtF5Dck~2{l{P) z-ye>1p@vCaeg#jYN{4Y8L7zd&3>lYMorK+F1x*lrshc>c1srg3F(LCy9h=o0D~P0%w*ur0 zL4QHa58vb_WXQZnYX0clfr6e~_dRd-0f)J>EDnADwNzzMU=NOeF0k4p*0WQm2iIMn)9t za8xRzO1b-_2gGEG-Vf#eZP+Ket12Ru*3APyBjbapnvGsIY5@di9KxQO(VUkPu;Ry&Dgc zT^K7x-dw!gh0##y5+6Z)G)EkAy#JmSJ5M=1j^FA(11co92xBS{O#ojKTrK375lz3TA3G?mYJlb@Y9sHdx}Ub<=@ZFLB}OOd;kq&i$h5 zxgZkg*fx2`89K2BgG^I&;KJaoQ(*X&U`NwhkKopyMEe%ikpe+?{6YU6>GZy%I^8vI z2l#j&0Mqf;7p0`oa`ED?AJbD#=JvTs;2W7boitOd=CJ@H|xs4-{iE2EbyeBafVq1 zH4V|R;4u95zHqSt(#aT&b;!aH>oT`%8Nbu`?O%tg+m~#YU4GMwBGoTkH zHZ>lly@8+0MZb|EYh0Fd+Ea{E-Xmcc3kl|@umWnusx%zCLTw3WB z{hLy(#usz^sGFG2jZ7?!5toe`oe5sFjV8F4)@yE;!lZ9cs_y+l(;@e|khu|9$}%do zMnFvreBn!?41;r|J?67Azu%wfD|tRd9Q;O5vf`*E|3arM;fJ$;a*TlQaN~n7TBAwn zQ0Pch<{0~u%xG072{9DJjMiZ&q3i=ODBx&kAEt(nw!i`L;@0)1#84;h%#?-x_Z4N6 z3L;O$ai?7_+hcYlwjqyF7OtAoncqy1d4rdgmNHg$CvUdXcYp*g@XTmBh%;#~W_h7R z*Znp)+biCGDzhQ{=caev{iYjeQ7!JHPbXql3WfGdqH)n=m=-^~1kD^O){W z{%ToC7+YCq(NnuRXTEYDQr=FEYAsjk2V>e}AWUSxI0fkbnp3vsnrNHv&ru+10Lb88 zO>_9}P4O_^ylnUluHJUU$6^3RSZ<4TZ41a-GgepefdIkh62N9B;f{fwRRKCFt+wU4 zD^MxEJx0MmXh$%B-R&I05X^9@6N`m(s7F15m4~}>`K<% z%On!`V(+K4NqI)flsku`CBnW1q)E@ymWuH&)13ekxD^d*;5vS*x;Yq;=0_UwVH#$! z8q}6Eu;uck$hZT6+8C^kS{MA8-Xi$o6?_h{%7R7?;1J{Gd1DbjoRHkm`+6Fr;#Civ z$$xv>rg#Fy+Xu43b&z#b>V7(p(3YBm-F)Ak;A1WQ05iIdcmF0cY=A5J)%q|&F+AQr zpsd6)r&9K^Th8J`ft>4z`$ByeLy;j{arm4`IGN+-%d3f`CLG%gPGiA4Eb0+wE4))FF)vpYk`H)<)lN#0!nG=h~< zD*kdX%YpY4l>^oNO+G%&)KBm?X8j=&k1v(_fCDUTEouK}S#~jj{j-B3=<=MzL<-yfzYPfa&=C>Y&U3$SJaHsa z<5JQ!s(5Dxre(||hlj00b?CFUB2)s{vDP>Tl&G=lQr%%%-qb^XiJtW1DUle_j)$J2R^4JE?Dk3vIh{fx*T_Go48&zwNm z0iOkcn6EzCLFVpnbDkFqS9*#Csi;hC1>8Z|ah-QjIkHuF@(Mr?vV4<-;qD=uDlFT- zC1huRtjdp&G}*9FD8W5;o6Y#8=ULwHIA93>j(oWGVbqP)W`VL^^}dABX=dU|?`T`b zLR^|`?Lx#ba@{y98ZRg`oVc`UeqA1UZ}SFLa+N>EaH+s4O*2G#*oyCr`$tlKI}r@Z zR0$zIH*$RGX8kLbWN-fQtVTf(4$O!>-4JL&nqbxoim}>S`}8x#vl zj~4(s`~tzJ)JHaHD<#BR5hQ}gV>#2sg(?XA#VZKgi5Vw@8Jl%Gz&|rsG)vU{`PIZi zUQV@pPwqB>7B$h-ToT&zvRuaK#hLeJeU*vB=vLc1un>&lOoFQa3O1AI-u)8x^BQ7o zZL7L?Vy7=&Z;A#Y6`wKsjM1XK57KWUzy3-wwIW@i3cO9KZB->xgRFBn-RGyS;55E= z$&moVIe*aI#rfyifzl@NeG&nR9$mJ{!%-|(CXEWPR%sd_(F#QDdpGi2%ZC)B(uxaq zFka|>iAb7sgd}!9s2~m6L8c^>bPt>4p^+vB4-8Cxo!ZMT_RoInG7PcRfRE8k%|v-$ znz9=RB`>o#(i8l$nAKn&>f_)<3#A|QUuPNe<6Y_t@QYZw06FyXYP^P4kka_;pCy>XMVFe?x5*fOXGFyE@DEe33K8@Rnxts zeP^;OuE9x9oCo7#Ke|rT6`gOEhPW_X_Y}#1F(>A0yB=Q(k@kaX+$HW2&YiIOPWls8 z{UELjSJ6cP>#+^`J@ZAtW1KNMHr0pVs4$|GBs4chK>cDm$U;BZHkYFjB$)}{0l^}d z>xwD=pQJjEd3ji13=k$;=fM;uAcmtSHf!9Rw_e7X)#42!ERI5Y^Z)yw>b5qFdTPaNQLp0LrB)qmHEPx;1sUq zU_x6lRTIY^Idld(%=@g1J+O(e-2prYiZL#V2biwFD2Z{;{KB<+;`VAlgnQTx%e>0V z{CBv4u7Aa_y$Y0Vq-XPb=S(AQ69MeX(dcMQNEX8s! zPE8)P!R>yVqA$320;T<;tt1I!bkl_eF1t`!O$lmrFqe~j0=lTyXH1rCWBjLViLqAc z(ODcLl2xb6yoA14mK?`e9}8}bcE!dRE@R7%+!XorUYjGY(~5b0n&j9wG}Qs$5UG1+ zZJ}%<&0><%`a}X0b)>}~D{BqDY`!zBW^$NgbcKQJYM?#i__{qfA|`BNTS;09AlkyC z^2`ITP;jTqi&vK+Ylab3o9Cjf+#^- z1q*YKKuh<9c)22fxmzZK3Ux2 zOP-1xAho4rsh!VY@3Dh7Qv4xez;{oZ!2Wd{^!X+Si-N*_t~(nJCT?HLv$JZ=g{ohW zCkYi~<4Nd|&d!&uIv~~X7F08mBxf6G0kAZY$&p&%|KiD?q=X>q)$$H>W@}8aGi#UU z3+Zbl9_`*!$jZ1@BYOSKK0T1v8tzMnB!S66vq#{SRI(>u(-RArKqj6~BSHi~84JX_ z!_m?z@~Ww*{V?m%#XG?;%aOLdP@L+F1oc=HR| zL#9B%h*n>eQNg^)QxS}wFXUxwC(b5mgnQKHh~L4xt6RT`{mECK6%Q}Sh9N@)=IMrF z^;rx8X4`VsCh4H=>!Vh#hR+%9Sw7+G6>0Bb@tjbC_p=X zHkyCiyN8Iy0mJu4w^&aL9oa^s1&?*=i$3A3*>(d`v0?RBjh3UBiEz%Nt)$?<3fT4t zcJ`!qPfXpO)PFI0Z&kP)IAO$RY&k~Y*EsIoyn-LgJFyn`O{x1U`AMkWy%6gu*HCu@ zG6`apSXlo`?PY!VL{yY&Qz`f2vzP*mthnVmco(>z<(p!s=Q)oi_O^Jta9)frhy5zN zAGPBm-|>}4py2$=dX;+15He$7-DJF3v-7|@N@~G@qF(-z)fW*#F@p%P7oz}Sc}xic zSb51%&AW?aAdLk=gbr9Z8c#;=h-qDqjNn+dSR}0BG2Xc4>QMt{A@dA^GfrvbeZH%~ z47ZGMR%2BG2r0T|nigb4Y`HM^_j#d}wbEZ@PJy%$9`gIU_dN`WHI^6v-nB?vo@st~ z0t;btbCXcLCh4 zpfsCV8jN+L8X<0$sWoTXu@DY7RrN3)mW_ zFYB+-+SL5LykaInGKuUpPhHKgYR+I8S=UZe*y7^5lEW~A5t`_WNHZ;NPWvxxsRbc0 zohIUEJew|WBG|Cq6u$2_t38q0oa%D>451rE5$dFfif3_1r74KmlsN^SDzRPJG}-?BC%K=etXMT2QXeefr=olQl! zN)BdTTF;C~`oO~BrEc7Y&f0+5m-So^4cB`>zc0^2WrPfJ10Ciny23fbb5vcdN0Slz z#1~}4MU?m@?wt?tzdyp_Q^&*LlGp)l23GEQ#ICG3S@h9EnSBzH7@0N3vH$!$4>n<+ zd~NTgS0>JB64HAV!l-bC<*2zDke7&G`TL8rI}cgoq+bq2%%EXs+*<@p87tGN`Ac`t z&`wh;Za(O!lgTIgK@{>ahDHHr;a4gCIeFH96bDIFmL~xp zofqixkxT4kptre;COi$6Q<}hv@eP*~T8QU3CyiFZe5c;2yQnr0max%C;rVm?}n#Ik(O*fdp& zBu@g8l{iKL_wzk)J??3v@)&_S{Ctk!8iN7c6!w&SWb>R`&yLd+UTJ(pT?tiQlbK5`82DShz|1d`sR79fe90k z9cAnkUcwaG4&wdgiNni^i=(KV*TC3X*C{0LHH zTSOXf(g#DXqknpRO-Z_MgcX~K7D6=`l==)O@2o_n)iOjwe5V*i3@L@i3PK#x;9;pm z{;N=rM=Fv;m8C?WL!Dk8+!UuPI57`*QMsrTZYC_k7=OlA=a1kuQz8=?SjYLVHsITNfc9--R?U1=J zD&c{|wiUwiu4qP~AuX@Wr{P#rw5Sg4(Xx704@aik3cW791&>UR3a~SZGs0#Dc24f3 zudPIejYx>l?A;i^vl6>q49+ZSLeCZ0aB(6Kk3~KRhMa6lqON+{K@Zy&#pe*uXiT2J(!a^~F5$3XH7;r_}AD?A% zDJbe_j64d)q?-z-)a#F4eWBNgQYsuQ7_|ngs4(83GZEk0T~=F&z$n>&WZ>}Dgx*zd zlcd?=kLF3-eZ;}PSm4%bX|hg%Liarcw>z*t{}iqI)Fe#WVCV{AkXMgO132piSl1;u z{qSKjx&%$+_fTV`cHqz~Z)6WMGqKCp%K1h>l`oyt2E!eIonSvbbW%&o9n$R7$~U@M zV{GmV*EcMv1ibjopv~BtETo0lJ>=X)6Sag>d}eG;Ir_n!xVp8>x@K?=)?u*C)>AFw z87Afy_wHAb28q%`v=NMnQG?lX^$_F|*xc3p3qasd+Wj7h`L5;$=~*KA0TaP<`sI`$ zoF)lnf3p|CKJ@d3-vuak4bfO?sXK>vp)yjlbKxHn9@sVpC=2nXKD`{-$OB?(gSOn* zZCH|&+B<`te(s*y?J2&-8JvpzxfwFw-kye0JsV1;C3(mcX}iC=wJHp4rz8FjB;xQQ z4Szh#$ATr!gIY=wHwn!|`sxAfV~~lBW^~{kQ0V;_>J|$uHmZezJE8+wY@0`lsqsZ? zYwEnRW=)u@m1RXD>gym+HBp_vmdP~7sFyTW=zw|0Q#SU_!dJ0;MQ(GXj;wc-j4Fu- zeoy5aU%P7_RlF(dxwpemOWb0?D)8k-C$~N&g~TTIl19VLhFp(!H0f~+F)rJ&p5_pU z$Cz>~nrAk+ci4z|?Z(jWM1rwvuza(452z~fU{9GXDNemF))28uoJd!AjC^ebzUIZZ)Nkqk4t)4x~*1~ z6B~8&nime6AD*iC;=68ZR&Ot4@13{R6~W$Wx2sntEnu8=f<8Cwy!Lh zs2V+*SV6wuc%7jbcZJsx7S!>eOhE&dtAzzew>fr;@&r6rQRXcMuuN41s?H1W$~GcU zkM-`6KqI)&w)|V?829BV_=ohkiOo5boxtLiV9!Y(^A5ph#qp_dawp4ZPJem=!Y%Hs z89I2^iffw49RhTk4@5Sbw#_#8;fY|1dh~1rH73b8h~4_ zQX+A(ig1y+d+=Ngg4L3&(V>c-^HVo+vR|8-hU_eVf8&uDv%GzlB$tB;9m@PN5Yx7V zLOYsnJ?-;v0$r>d{-Fb~Hw5TYN$icNv7Iz%*%gy+>Z9hS}km|%;&^jm6qeTl!Eg@}dh zBvq#0*);J_M`Fp}c{NTvsRnK8be~ihsLCCU5pm5Fhm~uoSmy9mMmJeV1d!Sa3AfD` z1}PoymFOlfrj^FDUYiu|!olFJ_uDSzv^^9;phH^!Mg|fUWPD7)GN%L*rRm7ktU8jk zyWoL|I7R|tj_ewS3$hA|&Dl4QY3VvZoE1)wyzaMjvpKNG47B@!AO$(JBA1fljqx-X ziNTd6XG347pPQ16*wJr8zIp-oTGf;+eBh?;ASd>fT2{(Oo7}|{448%iK+qLNJ2KLE zgV-ojWQaALg!*ic{^ZWl48%*&QVcoXPr5fTw2geZ#95WD_Zs8{W^YBCe+g_p!A?3| zD%UD=Po&3_W28Ggtgo9kzp`aFn;{=IT^M>LF2j9PY;qzX|0I9|T)Zn$IlYppTGc^6 z#bO@JXRIh=xq5iR_R^;#aE)FN>SW-BPj;t2e@IylzQ7S{NcPt5lSpJT4!nmrSr<9Q zE;d9l8sdGGYCzctCH=OU9#29!1X+o&ykd48d$09C`wM0i`!(*{ajmn;(JHi=-xbnJ~OunRLqaf(TO|GkJgo;Vo_C*&cis{dl-^;ky{En%+eOhZ$?0pbugtADO?` zGm`g8uQUd!)D&wL$)#>YZ}p&rhbHbAWG-vTwHRtaSd{SaMrUHudyxld>4f1*!L=N5 zkM4sVB`+8=D)n?ptq<)23}nEy0?Zjffj+z}hiCWM=WJ@6{Io|-?RN=ot0*b`BNxGv zD9AReZ-E{`1k~|MEJDslj)UuTfmv&~)m-zzg*jbh6eF)XeTL?D^gIzP%XWCpie)iH zRwdsVs^4`A&8Clw)co2-WVJwiJ4HEor4UUalE@B@HQ4_sNPbMPqxZ^NIzL^`GIiwq zQh2h1X>9q>l`by$qP&^b87!sWqMAQ37aShanIk6E=kTM;ImmUAlOvo$D5~`mVjNwP zb}~YdR&kIRR8IK?N_u5?RK?pa>U=?Bm^XKW#5O{sU3$JGB0-Q4%j~KC*v@BEIK{M| z&IORJ>#BfgTv;?5a$&%rbhEb?EYRLM@FZl0e72D^jCOCLA5*L2Z>gdsQ?{4O&?H*= zEdDj#H4=4CxKzLOVE~8$T{+}~c#;Syk3Z5MO$5BNM#?2`wcRg6Rz*?dzZ`5*a2B95 zmA!TROwM3a)oc{uMFR<@nGVSB7=k05U)1(yBrG*S$;lZBb%g%ygDMBre+!UFA+FnO zLjy*Xrb)%7*`VImCL@lKSo`{!A9Y0QmwSJohM3yG1_v_Dl=)WdPHmy&@9DO@0J~Rwd9XD*(w|lt3VkO|i)w})7d#1uzhJy@ z%Q6|MwlAq?OMWPVF>aNx@Bu6_suzB`kW6=gj!u4EzNvomtXCKxOa^BazP~zv6txjL5#!? zzczV6ZNF(U`KqT{V@gu1G-=5YJ^6H9gYC@|h%Ci(yUhXf~`-^4ydX zb~o&PEcwqAHQC9o*T{AJL-uuW_-@?`hjVU*P3BzaSane0bLUZ3nJ%o8Y@X__1WL<> zunfN50aoKIxM^inkD8}*H2EdyaItK{;r*R1)#_==T0EhHqPkZ#2ew$MP!{-0dmuQP z8_lvP!c^8gN);MgKuOfAqyl&U_9ar*7Qw!9Bke}pQaISVhFd<8&IJMs8-@4^hiMyJ zYCL+kw}NCPXTwLRQKXu+s1hG~wc?f=UBs70Z~!Zch|P}fFxK?uQBWQlL#)rU1^>f3 zL`iEhToej^A1AE_$by4F+H@qesV`hyqa9a^nvPEF0N}w7I)55bnkY$`3h zoWLs`eOV1-mIX{-M@!5$uu!WWfAAH=R&dvbKoU3Q+VWC&oj1=^0=Q_P!l+t#oC;(i zBazo0J?il>4U__=t7~%X(>q@zviht1Iof85WnAwXCGhewpMRBrYE=0617PA-xX2$eNmBi5vNVzY{OwMMRpP=2Gt^Fsp<07QfZh3 z1%yy44o4Jj5n>TlKp|tvJW|eXX7i(&h98L#7o_`cZNb!K;V%q7aV*nCSBN0|^9;|Y zWFcVPJ7*OgX?^unSheVGTERc_rUM`(c)-yI!6dm&_waAa;^)6kijkcUp|$eBF-Kb9 zeoAtOB2m@iH%R;i0Sh>9-e(xnw%)t++o(^HidNf!G!`#;eTwbsM7!KI&AF*42Z_S; z;Z^LJxp$e6Po&%1Z6qT5a;@aoH|9OGHbW$Y)TYq4)C`S>bIAqNg1;f)Sxhgr;rW7I zw&D|GWogN2F7d$OX7?b^&mSpJ$&pzua}vxC<)YjR4sXcpL0=wQN$57Ub!v&jU0L_k zB#$&itc)Na4t&+8Tj$xqrKX;r1X0Xxybhr01M-<&TQ!Za&^ql{wShsm$amoropLBHniloXckS|B)N29Flnk+ZGvt!O%!{2LFnP;gxT=t{}L51zR-ox9&{K zdRP^_pcYxVqXz^p@c!u4dMvN*h9(x#YHKfn4=Dwc9g+bzu`LWRd})_}O<=U@W$(eD zgTk|+&GfUCLI>Fl*}D#wNIV2@r{p@L1xebmfw(%b&8zhUD6t^uj5q(h&Qryjk@cKZqJV zVi+at5eFcLZ}og2&-Y@j#3I6%zpt~l3~P7`mo@Xgf$cYNtPZ9DTymi{u+@O8{oo6u zzpbL(jY2OAkAM&^*Au_borZ(?mn_CD_uuMB!0H%l1%_&4YN5pOGPKmmu|MLPa=w3lmy@Yd+QvCN`6Ilxqh>s6}N>Z z)!Q@5`K#OH(5e2$nNKzf1`Oq6Pr{{7IH^C0LHdyxv9?w#Z!;`xi@O|;U#3(esJ?T< z8D431k*m#A=nBy}Ft-x{Sk3Yq`xo6CqFZzxR6d%uKo`{LSGP2}(A)(-J7>KykwjW!Mgd=`WPf$w6JYoqA} zUC7t>A?9}1uoE-m5)t`t-2~Mo6al14bz-0W^S6^B4YAlPd&=51x7(W$ zS9UG|RqgtgQ0fbv;|eWwxYdufXa-g`=!)w(JR3BYuweGgee{6g_fKfyuXoII9xw#X z{qo-j@ZItJ_3oZ9e%-AlI$48bgYP<0waFr7tbfpwqE80t+Bc5D|IWPBJ5hlE6LM_U zK>Ox*p7dgJJri1)zAuUylb&OgfV68TF7zep;N<0ce zQN(;?GA44;R8ZY~4S7g76d+~?teaiUE0*2t0*UMsbfcoYwLwsK%{xKrk4iw)FfJ@- zTzA*_P7`A}CwwVT&)PRY!Y3;+!{Prdo0n-o?)xOr5YA)pZ932>Uu<1Sp60Wr4mNNa zZ}=qV&C2vH^e;hacY4sH1WBNJmdKDxi>I@xtv@4(IK`6ZLirNJ7!tc=(%%abPQPsK zQ1rn2Rxj4KTX<$I9~+?Y#m-m{M{L27&yT^TxwJ{hzE-?dK{OWL54Xg;NPBjCKg_d( z{xdo)mMt@mYBoWWMR+tO8?UyPlV$j!vsP&Zkj@LS;oG9$BlaHbyTGz&IvwYJN#8^~ z>|Pe!CNRhfZ=;7%C_&Gw0r+y{3fW|$Vfz=}KP4r+n<-dgjm9O#dTMC!=B(Kw$T4SG zQO1pof-4PJsc5}jK;Mc>JAYBtmnv5^etB{TA=UDlS^RG?%Hu2$SvlVjkXz%RpjSo% zXXGWscTssR9>T8ifclVS9#NjdhP1tV~odJej7 zQ7du%?D9R8+p21pa|QIB%LbL+-h;!o zQcJ^c&X~ajHr@wd?CCOzd0D(p0SQ+js2z@RjqpLEgB@4$C(*b0`CEwz?%>kOgUv~c zU;!{=P`&%?M)7CjZCDQ&brU*VD-oj(k|vpeH@;*UIu6R1F#s+++r@^m*HA*9M0)y5 z*WP>6s}yl+O49Cn{$-s9?@m9kYe1CmSv{^mO(5szRK0H!@z^$seen6otQxaI#m4li z$bnvLz0gg3SNi;x2Y1J2GnBi(aYrY2@A{ZLshBvq@re0U=;=w{^pQ6>_S3 z-s#thuMob{Z&Vop|w&Oy%^zu#D$ zYz`M0KHq^q+}UO|lrkRR-pn!`uzCoF8mnKbP9|V~4=G{UDmGPE z2t97CpvzJkHX)k3x0gNn3(6khTli>lKx8@0M*sIiu>ZG$u{C$bh5u0mwV&vQ9r%VG zs@H)pV@7k(4yEjRrf=8IoXS9>7-U3cT!sy@62jWVEVxbMkVy|icB+F{2Gh-z6(QGQ zP?GhP2}>#wat{TkDH5*nZ+4`pvV&-fQ^;op>MVS&UrnTEr`0P&{1>rS4H4<%Iv!2n zpDi~MeFGj7M78M{p$AMGB+B%b&wcXoEGMLCam}5aB4U__4w`d~ z{luB(gv5LW-?5m!eHK^|uYN8#!#vM`ri$IGmv}(mFz6(X3%GEqMA8=kb-1rOUb`VL3OE2#ss(|jLFm8Z>pNfZ8{-w?n>HovI5N{zXAbm_ zBV(6Hr5Z@e(8}tX@T9RfuJ&^7dOYpfx^v$Scr5G-5DUxR{1;DBFVy7 z(c#EvPM#9{gLC0Rz@UpwNW(mt)4V>h9lc>BtIpD}8x3)``u(!^g+WiH!KF$l(iq2i z1+q%}+S{z@wHS3ilmla4^XSN*km&(8q*3S^r=k*^HJAJp2HAJ`*eUBZG*L1%&+!nJ zg7&*6gk27cV-7=2npn6%2YO`qvzYtU%?kJE{TevXwdi>JBc%b}#_He3g<{c=Ix5#C zCKjsS&HHgC6qz>_c`Kn=_IJGY?U+nN0E6cKZu~qVDM@eVd|BWSI1h8;$fW(9#dxui zJcMKeb8ISeUw4BgMZZmfS|9y4a^{_*jQy&sWz=q585^SI)y+dam&0FlO5C4~oPmw% z!V5g!{CW$m6Fv?O!ehZ2$r&Kn`Rp3uoXeYCvA1CkmK)wPpc_jjU}j55{TwjhTf7vJ zIGcmPLdx(*t;jy-Ng42>4Bp71Asj+B5&Yoi>xKTtwO-uNg8zda!@}^t=rIHwEFAw0 zg&`n-q8GKWax!rspcl0=a551#F|su_f#TzXa&&SqF|dYmTTfDviK!4p=zO3i3rTv$ zb;||>9!M~;03g2F^EP)yJwjV!*hW~>H}G2Z%_+Nn77ce;3#iK1+0s$j-P>!?qp!Ot z35Z#!(d7NOaLVAuU)gy{Io-=kYu{LlnSj6X+}ZK%@=@wJF7v#L@Tkm5FR@qe2Dx8Y z&9dq0Y52}jerqxKO!>!qez)|4$S)USk=8ADfWrULvSGnLGI54MPZs?vFpN1FVEQ^s zc-mR;tYkcMR+lyCKgm!zmCreqZ@hNp*9)=uES^-Wa;CT(?#`YTKf$UR%+uWB#Sf{= z87k)Lbuva;g5M%id)&(UGimPQ-b45O$%0p6-k?xHV9`qVz}@zNROK_>l@oF&!|NmD zdg|GxLq`rDB`LO1b^gUz37z({n$xA}&DS0SSaXA3gVfG;S(@SD+jYs!e>1|4Z{4_E zF0)}n%>VrJHdVOkz_H!d(Ys{*D(R$YQxGNCAW^FS7ljGMfvzww7DFGU5sm}Js#jwI z6dQ^Y15{?26N41PBtRnYOK;<1k$7?l#b> zL)I(lOLK4Zg}A0#X9@@F3iWPq!?1LM1O0h0t8yUc1PUiccABBBq8(x`S)( zTD&WAC72b)K!?nK7Un>Q4)Zo(g6p4kt7(h}>%LTu9Q2(;>8IrSl-jjh5&SO&Vho2OlJMDG>&*?7tS%vnXrV+x)q7((FKX= z!MM!5Es5#b8xpfqr+DU0?lH_Z&at#(ssGukBr&_JA~CzA9>e^UbO_FtbSTyx!`!AG zOM8uHzN7t7f}B_bpier4|6MUBweg=8rURS{(%&O$EMoWIC3`xU4(6Z*+e{@EM}fJ> zfMTS&koaOwt{EqG9t)lU(>j^01E>7Dv?*u*=-y|!&%SMjmS))A!5L9M5dW_MW&Ga* z%EHO={~l251R2``287_7PpBJ0MUULn7%vrwutC9bgN^bq)h@DU5)mjc%viP`A6`81 zB^5Zq7_)869^izrnwPGeigys7-v&K+qq8l^YsSvVaE7!n?FW?83skN^)Y@}USBBItMqLJVgFf?X?Y|~q{Fi~(oeYNMiCcCKavEzd z{zD&H8-h&>C+kv5XkM$v8)+F2uZN(vqW+XmK{CFY4Q1XtENTMSk)9gED4Et`+&>p} zKxjOfch#JmSo(3?A%{}SQ0vDOeK=2`orw>TMIv$Txl6undHYUyg@y)2h8Fld(`MC% zlS8gmpIlh4GzKGB|w6^LvRZa9D)URcXye=nMl86t+mfSwdt?-{_33W zUb`1nNKLBduX)wD$GFG)JS)6EKZ9QAU|U7ntq?lP?j6ivN&fIrr?d*jS@Ss%P3vBw z;ObuT3>LWPs{h=2_x&e|dDhbxR=g9o{KjGjp>S@H>Gndt zZS>9Z4J@1tY2ZU2ANGIz_;B-b|MMRoWm&5gR;sWD`Tp2fg!Y+QqM@M@v7Fss(hO@mF}z5sp%-Sy+4$=1 zsKQ)^W#Mf>;C=@4qt7Z1yjqJ}8r%m$kqtKjnAOu?1DQ3Mr%(FHQUhkJ?;6Y*lWsw)ACGUHD`ZCMkLr3#DmF(;zTTAF zlnsAA#(RU`@vOq)bYI3ctwK0#Zp`MA6fz5hWf0BYB zLnh2OrqMI89}ZHlvtjyxoTYyI*F1}dF72sKQ(!oAE!JNyOHW!|0*A2 z(0j1-1I*;yZmXa<_Voz+MUKjm^q`L}ABM*^%|*`WQrtukv*2LKfm+xJix>xVBaq~1AqF>D4B1ZgPO1JB`N(4`4VAdI(~qg|R+(YDX9th< zl4M=CGS@%LF3v4GZwX5+i*dSdGt5rzBi7$#_NBaM$r~LOgv-mB4L`p(Sl?N( zEf2f!^e~OCm!=W5v|#UIjVulaO% zTPSsK^!#Aq3WBF#k)g7Y()4YiP@xjN!eF1He{y{e{Zxz5A5jtUWp*!o1}&_Yy(v;U zF^UBqVKM_0M|Rhk{~#qJ0>1=70?p7TuTL%#FaZ(-jYw^#eeYfn4m^cAW=$5UV|xqA z8-R8u97vbwY_m>)OSf#ReM3>|$W2jNe_gX%I$&M(oH!7Tp100+8_cV(Yx)*z(5*pY zk7;OV>GRWEzRAm{ah3`%3pB8F^ejc(ET5h&Yy{;TN`E_Xx6=v*evEx;vJ&}rxJ&!N zX2)P9JvR(pLt3Yc=%OcyDnpluqRk@4S(ko5P=`{-HTgnWQt^i9+|j>@?NsqmWtV@1 zH(fh6jMJ+|Kc9eT7b$oP(*xdbh0!}lq!-s_bk_Zi5z8;tqQTZ~AOK!~y5O1qXD0aqt%h{}czAYd-rAalrL&!9m_%9Q?(>KgB`) zvd_a~3zX=jsOnBwi!t(N0H4o*a}9b(b!vt8mo z>+oDPviE$?_{S{9bvw!gv&BU#3YY_TNd$X4wGlqoq;0lxC!Gz6_dZE#s%<+S^8EZg z(Bx`Ft-5p;^TVBZ0{^s*TwazxN@v!1h|1X#O5JptBXEO#8bX7@g0Ot7lna55%CyRv z+e}RLVig6qrfrjcZ>G9WpL@Z){-%zCnT-+oG7eQ#76EE|1nW5$?#we*kQ$WH%ZPl`G!b>Q z4`IygQt8yt)Td!^XdjtfumeWpdxKb$6`(fWf`HRkzgx?t!2SeAq>o{N%k0R{=L76& zgmezy3+XssT21PvESq_AVh}0X+OLnS+O;>0e5Xvkbow~;COxC|iGqwn$*}_Sd}gF_ zC1pd)oX^GF>%GQ)Z0W@~>ut!!H+%6AZoayXcuI7bo$fJC^I8- zcGhb2qIhg;97%Tpwg9f#p7?r%?;_`TDehA%OC^%W zyOj+Bca4)L%V{5(>}QGAa}MYEGE~IPVNf$I_brlA>ToKyB+ae0>YQBZGw;S0e9j-@ zfakxM1Hb3~k$ZkGNvn%rRn0Karb7P)}4~Na$OX6bkumGWj2d8I1yV-DnBT{S7jBNLN?`I*IzBmB>?(aO)nQW z5?+)h)#;%uo1TtY?^)wXC$6p5+r6xq5>Sv}ZM|5yyao~`;|MHgA1eCItCHsn6UmGEnP(G$=t)i8}HNl&_Q)_uc$W7P~qqx=opMTqYL(bR(P2z5YO3E6+h zP96{Y%O}H@!KEX={-Wma-XFa9n?HaD{DJAcKM?r`e~^HaYVf;1F#6peaNPR? zj(dL~_nSXh`44|U|9Aet1@H#~sniQj|KJa5BfJNL0S^4`IY7SW;Bz0q0rL1V(NV|$ zi~~W;UtZbaNZPoSh1yrw2nZ`X`dO|jwxquclf2og<_M8qtalJC44Ht#e=$Ba%e^~; z@i%|4Hte}S>vR1O2mg4SJS7hY??3O8Rqg{L+=f2_qYp1(RQwD##a7BJR0_s*sMzLT zMy6w7+??-%shy_JpooPd(v0_7=Wd*|<(20x`f1z%4wCEabQ7e`?Cj7E4t|#KQONKM zkSHa&Bnt`xfl=Xv5fB(X)2-@1((5j)o=G$3sA!@yJs$p=>f=6jQ-3L#kI}dkwO>1p zDSPjedD<3io05#GJ1x!nm@eO4DUDXi%Lv#GSY(*&7V)>V(Z}o9mu-J}Kl#XEDCv1}-F`fpkczvQ#l_?LYJW%_i85Tl0TtfSx~n)-Cp zh*2{SiDd+8YB`qINx*lzDJ$PhpAhT|Xz3A28qhnVG3H~y3(ypK8~dRy1$|g*VS78d zSyA~0HAV5|WRy%hn-HO~M?(wfd=+hVh2r)Hy_NYA@}`I%2o)Ohj0Q(fN^1*e0Cti? zZ&So5d{y8FsV2O(?{}(Dza11OIdifu=hfQPAu`;f$H_d{t<99WIjd25eKsg7FZF&d zpT+oCl3e9voA-I+d_N*nl!uplDJW(w%14bZIQ#?#6cq%*1}TVmWKccpCUEIYz8H#J zQ$`e~@(33~-nMtl2W_`IKU=oT${zfP;%+(Cw<#em#PjT|Rv~!sqoNQ`NJVD4q;>

+FU)L8 z-T&*{dBlG(irGDt{optnIW14-O5k1PZc43g6C`KV;yb^K`)PsQ;w<8@VD&*p8_wj{ zjVp4BdTQ0$2-hE7&FEn|JxeU$<1eotVutr0wS$NCUtk6ZS%Hkc@tC0@@YO!mM++Dl zyb!}kDmLHUL8(y;IONV!)~#8aCn>vY#dDPelXgxJTzL)!nHb> z(+=qAuUM=X`c~gtzhi5=f3c^vzhioOO`{W7GE=88XPo3V%Dw7KXEn3qlt15om0&n8 zIm!-yhJAi`a9G5LKK$O(G~8fxfadjL5_pSVxCn*fk**jF&h5A5Is5&n*Aa@ZD4x#n z?aEnu*|9c!?MWSH(Q7rfXLQA_{&CCRM8W4WI1GRbRgf797M4+xihIPs2onw`i4 z<;Tvk`g8+k&}AW12hAwQsI$_G6l6hI?CPcB`xs5B!so{aYwg#8qw|D^X^l9<&3L8- zbu%dt?ezd{$g+=ePu0s_Te5G}x7GMcowuwCIPx*lPX4r-i1`?T6KrtVT|!WypK@A8 z5cSt>^jVi|B5BLw4I}CBvI$?Z6~0kmF_>WuriC7Fp0|#9)`piY^|Yue4B9-TEr6Zo zJv0jvffx0R2uwJ#LCWqxJStz+i2CSb9dDxqYzYs!Kxrs~AavVT?Gw6&1+Vi^s7jva zHIpte$eu$HE5E#k*Bi^{SWA~n@g*1MF)uR`wSje#s{J8y!!C(2ZwGya$1NhBuJMkL z<&*ps#~NNWwocYR5VSWJq!*J%ywTEavjmd2wJe7Q- zhkEAAG>w^HC~O#V6KQ%TR{iZ1{!Z?iMXWEz= z7fXgI0U)===vGhbSD!o|pn~gx)$)IhlFSwWREX-=eWDbhx~F1Q()vFsiN@cQWc(kM znmbBdZS8UHdZ9Na;gyI zfn=D{k&e|EO}**isqBlL+I(b(>XCFiX8)VBcymt$2CFqnE&=v?zMdH_i+SDXGA4U? z(TckKfZiYOYKX3n)EjO==o@8bj@psA@2|}0)lF0r|Nt%-W%avsQ|F4qZc&v0+h9%SxI z`=$ha8i}}u!cZ3T0-5l+vtoxus^=R?cE=9+fyA0y_m3+K87S677*BnICdVFm`|IX}eA1KVC6pri5I*Z;bX zVet>s7uxUB*MBe*EDAbVEM0U(W}YQ~zPbrM4ik*8r(l^)D4A(Y@sCJuoUwD=mgblC zJg8ebU^egV?dEP{F=u!qTe(ShHd3=bfw3nvZ!Rj&97q81p(7nsm43ZlCj5hWF7{@6*J$6oI^*T{?5UE1zGG(xT z+baX$w*qUvqDeda$WpZvrSqgx1s+f$vcNP3BVD8ZRG~~0 z$obJ7Obs1{Ij4qFXEDU`MB4yC9UEbh>U69HIo}v5Idb5KSE@-E)Gug23UVGIV#<*$ zTSRs%z6dc2WEUY9L?;T_IERXMBgmWi{(~Q5g?RW*YKKwNNXRbdwx%{E7}7|J-7Pua ziTjcZx=4C#9A_WT3T&@%%LgoObO)6>vjgLo%+|3XzK}faPiJ;u{8A8-H`+cnR27n! zfCvz+9vdpA(M4SfB+PAg;|j^spF6+uA5?ngo;uQTI&c&h(QNOOv~&;6y>WL9l4laK zKWZQU*x1ymJ=^;1dWl2m#-L@Z7U>o`TP)AxA!r`hasLU0=F-sB@=R=04)n#UzpN(O z$|!-UeDKKz{x$ba{`L$VEjjOI_3N(=6J&ZzxH2q{r|hGv%xCJFpT2#wh2m%EpoAXx z2~vV_MpNc=V?*5ccKo1@Qg-@eTrM@>wr$%LDRcOH?R%g;IQYSCog+yRe*hwNKs)5i8}UZALa zMN=fwWHiA2)=}-%{aWd*CF)yKn-}n*zMS~@bUk>C7$a~|QUMZL>4Bn{Ro@Qu9X_Ib zzWnm#s(zbg#`#+ddw8efPeOG?G5{KN*g+(M7VP~NZ-eh8gYS%M@cD8gOYWg@V;#75 z^0qnXBI@j*`^&QYon>KgaX-1YEayXlRex9(;@>SxXO|~hSZePQMJrUE??cQyunzwd zGSl%FGk-Djuh{&5ikbPwyr74ed0=(U%lfYkXR~}*4ZCV(fl%A6T*5Sp%xJLLhOoRR zu(C%-CE@LB$U*PKsxdFmBPz|4EIx^aja%39^OFWRrg;brxHWr*a~z9@=z_lq%WEfd zEmjAv9F)vEZfcXtFB%!rkFEK$D^aIM-4XVnp4wBUs|5TLva_ z`B8qGYpp&{8TaG>u*%$>6cdwRDrR5}60s?Wld4-%>(CP;do}E$P#lsoLa!R&H3Rb$ zS{ZKYkr(_Dlv6YG5;WXGCUknLnR6&&8A2IV3-r(!R7{m7A=Fq4`x4Y^!N<9phJ<6R zT5Z0P`HET@HPQ6Uv3Tsy28O=8rSem0fNy6Es2rPpc~q9J$ADl4HPpro^^FS(QEs68 z`PNF=){v?+6V4K}Q`(c0_&E;D#3$(@Wg4SiE*S%f2xCY>=ESe5iz;)WPl*$_ELhdD ztP*qEno`Y*OY-J!YEqa3hBPz6m1)$WSn}yD={Km=aO3=}o^C{0wJ2&Xpc2tYXIgW9 z4%e(^(qGXkX3L!`d$oqV@%phO_>=mWLXnRt77GZm&b(X4>$|2+7@wwHSYsk@v|)N; zvFIggIQ^oX%q7zyJWu0>lXv{!EAOO?rV+i;x2fHY^hP<|Gyzqgq1h6?p%@N_7!-(U z5{X?3WWn*YalGm=K6dG|ytsWy_@iteZ@Evy+p{~7a7{V6^sRr$VQD8Lo^CyHGE-U{ zto$wrfv4AUj(enFwD*vbhx-)9cFl!RSSOkKcKFu79gE0{e8J57DCnF%i~ zSASLesJGuprM>*lT$X>~=e2Eru~NzVk%);6G5qJq>5p4tp%|eMTOjCA zn3PBO=uoH1y>A4(xV+GzF}!jSz7&mrhe}6?g+}z+!3G|^ZA%YWCMFkn6|;iUm?L9T zUKFWd6Ci<(N>#MNL}|p9oUy!Ohg#|XwrrAff^#GN} z@~nZ6ctaxEGsE@qWPF`kd55&6&tPyTLJY=+6Akvp`!Z-?$KT`i=vvEMrW*8EIkSA* z=ITOicT+`~LpzN@a790sIgn*zkfmiSia`tNZdaiURV7s-8|fkJ*(7@MjVM(?Q7CEB z;6vNF^(G_@cs$w zie|hP6j2pDY8z%}V;;WEX9+?`yW$yil5)5RDA@BXt-NdOzCC|;)?8X~*Vuo1&J0GKF1`OAncwJl==gK{MHGOFjhk1Eq#PFVsALLH!rh{|`a^+I?H* zA*df{X#8oRK6g2DBVUkf14aFCCzi9K-^_aVi4}}UYtk!h!-oL@7rxfbjz(6GaIai^ z8(_fJe1vt(P#O1jFAtRnjArIPl1WiFx*qCLul)!%iDEG#@0%;3?pcQ|{YLZ13YfDI zr){v~x@)Y`0ks@>Gq&Qxs z=5Q5Uw!iX~OxK`1+V)9oQhz~^!QEuyhlcgb^~5)MTGQDS#RTI8>d%0y0g%2hc|CeA z?!^SH4u#=$P69>#e2Iw|Y9~Lo#tF(CiUfufN*4XKMxj6Sb96>n45)Ex{Q~g-5%e}L z0jKC^9e6I%2`l;rx!An1Bj3U@^UFDkc z?d|4I?6~yId(Lj_BNgNAycG9=Kl+@w600v{D{doo5uh)0iNKh%-WVxTL4zVmz5V6g z>|@%2abklW^uiaZdKgb^aVdhu$vU3JBY=JE((7aQ;GY)Zb$!X=>Y6G{5R*bEn0^-B zycGXauq%4;r;hcgc{oAPWfAT-q8$eGGvbYexg>qnL>YZ`1|qDe;KJwl#h_fi>=?G_ zL5^3}90FO{Zrr6^djW?Le%@%aI@klrco%U+!6I@Um&B@HE^f{G6v0)6t67RQTV*AdSM2Yz5vnA7L26K<|dkd8XcS)&P^TBU+N?;N44OyB7k-?>KJ9QN*c z>b|>kO}aVM1~j|!&KD5pXAt47y*s^%JF$ct3ehu9lZrc%C}Y!}*)aRwZPnE@e)7!O z%Hfne`o^axn#0oGJo<#I`y%{%m{a1OCy#U%wcT!}aPMI4g0~eOg8G5F$)6YMj=f8P zhLivs+D{P9GdIM7iMGAGu10~?q z@`e*?Oo_<~3^f784F`fsBu=kTMTPYuR!1O(Dv)ef4n^}N4ls8*da4q_a1zVj(NQ5P z(LqGa#pqWSQsWihVIAv2f=rH&`@Z8jI+V*4JX8(BQcE{4K9V*mKG}>}{yP`}sKZJ> z@+j90kxDpDByIp=ma+TEyVY10*39pI64#-w%thZYJCPl=pPE!E9zTt)zpEbYz|v$G z`xF9)y7YvrgQ>%9Eo9~M5qgK)PjvNHy{=TghEllU5+e$|)#5VAgvYv-)* zhbfA((A%vi4NdhISLO7#h_Nx-st-Z^KpzIg&GS!hG2K;KEr0c4@D{{!<SlpmIYV z6Co*L&Z=5e&6vZ;@hHM#OJ(l^Tg<*};8AixuhcH9PAl@xri-&9PMi6%v#2%ALP<|T zIfGrg@$+$^x^G_s&%PetfCnH0j+@hMA6*Co&$=nb-#NTlJeyrrpC8@%0Yui0IkF%vX(jA}DI?CKtt;Z#hm>6(0gvD;vVRpVL4+s#&gVdraz zqtv2|l#OIa`cjmVy9LRF%o=IRYcv3s8;+gTwxEcE6@@hfI4{Xp;cZN!IUH%fIjfmm zeyh47P9lsnD>1GGC`V)%fnK%)I-8RVMvGeStLH&wdJmV@dfQ1)X*Ya0pXYCbbQWkIXGh!~;@3lcB z6R#f)1ZQo-mX{(6uxSZ~KK^)_D^%N<*xH4rXzRK}md?6NKy zC9++0zvF44mextqvuFumYp7;3FsVc~7^~svl-Bz>6G^~r5O&3FEJNCRBj$_8Vxs-? zd*4zh6OmYDF<~3^8;;zov1X}qy7z5_e5ey?`tv@gc}oOEX=krnuavgv)jcI@i-g4v z;dcjv2d_9*DhEgtQ6~~sNeGHKGPEWVUNi4YpU}_-)CORPl zT|O|;F7WNa2TlO3aJV?GaGdaiiTF}3!WL34&=!*~WKKJbw}6-JV^=sPm^zG)q`^ej zif#d^if*}DV4}vj6%KHR@yZ(^BBWjoKb==#ipJ;_;j_2&w@R|NYNX?9ciGu|E5abI z(wOgoiL0hQh>}r#*c-KVpKwCtXh_Gu87>_9oNULI(N*?+ z4vER$5>467c_9ynrDNQPZ~y34|5kq`qqe)Nmi+r!t9hEb@ty9JtKOk+QkU*_XeA{D zO|_(2j!ljw4*MY2I;9A)#iDr)?YKg-@%=%b)P|kJN$Fh)0NL-2d-eCoP7WSywsXxc zN|+0pVnmIuZv}Ku-y?gzsU{B~d;L4ImY{vefn35H;X~No5+(>NF+aQ#c3y7Q+%E7>+cl}wqBabj;iwp14r0X+%N#cXeqIBK`PK_W(*lz${Z z7)N1nH3DF}!+5t6k$kmC=tR|kYD~2cKk>Fjmeb%Qs>jkxlE~Sjp^BWO^N0_XNbC(h zo5aogPA6m;9g?4qr3tell zgzvWa8F8Z5k}Uog5$@_icgj(Bc+y;#!t`IlFEHgg%sY-UR-8zeTZd`v{G3Y)*8MVZ zkR`d86VB_?Ytek0X}4%I?I`GOo9qtb#><5thmzN=cZT9;1@c|M&S`E!J;dw-ZJ|FY zv$SI_Bc!x>y~F5Hl?f)<0*8a8saNpQm-MI8(U~y9bJjEG^C|2#n&uShA1tORhNkG_ zLqJ?)>j!7r{6V5s{tGRB1@k<{fXwnb1x7Y_@Tbhb9pAsw6H*(c6L#jqw8}oGjTb^I zCOMlAt-F;;rz>LVS}pV?%<=6It+L$Qb=& zSBY2JwovpAz^yw+g!>Wh8^A?B83#F~ywv*bns79(M5t5Q_>#bLZS1bI1$9{)glfuCh5>7tNtBhQ`~g;==ZE=f@#z$6 zz@)|x!kLO7wjJX?WLD!l;b~$7hv+c%5 zsDRFj0y-=Do6ZvarnAOw>{zjtNR7BF!Y=gfo_lSg*LjK8rRoLUcTyq_?Vi@pbQl6K z@w!%#FvDpRsQc_xnCNg*UV;j2x*HbZ``-~>bBXX^r$9j9^Ay+SqVOARjguiJ9-Xg* zf@7@|R4SV&4>9{dSqa4b&mXwtuJV74&Khx#Ms2Y2YKL3KC-=XgUU&BNI2~hA?~%_R z%*DmKSPmF%Iy{K39oK}kRG9bPdUeXRD!1ovKXt4*oDsn-U^+pdRo-vn?G0M!Z{_z} zJDuI$!zi?zL_Drd6uRslb#|g|b|W@e3UIbtfUV z&AgyLM&sdpz$kEWyYI?%$*u;-p0D`akH)3D;!AaB&Ad1^Js)^%<5COF?@%0~S$t|m zDv;^*Ucu?ZJ;Hb)ghi|e_w{TFkv(EH5jFvnMlV}ggHCTvZ;cm*7Cx)}8Q$a(C|*rZ zIa$%WJe!siK2~q+sU~pQMkbfy&S%({`3!L10=i5*_c+o%y7M%1`>L;XWR!9Hg%Yt6 zPrglnlJsMUPd9EaSC{A_E%n0b#0Ra<;eu8{V7q~0Z>Iav*hzaOnv}(h;eIr3|1}z8 z$^AAOW8aU)KEP-k1&7(Wem@$Y{x%v@=iTxk=pY?_*Ldmb?LcUa(@%JlT|u&>AfZEI zRon%P#si|AL$Tsv3c^WjIxta_0S!MMb$&_92@8(0xf_ZMCIBY#w?;=#7zoAeRM`V0 zH9F#Vl6=w zWB}YnkZ}t3dc{DHtwvr3MW}oAR!7L-)^NxmTiJySDVWGy155-N2^mzM3>iEc4H<05 z{w1y%iy?zUrX9v7mL0|yMjgflEJ9+!zlrP;0O|?u3dcI|evMdZ!7M^J z!mClk4i@oP)e`*o*j)8E9Dx&g|IAz_^7vg5P}l5VQ}p zr9j;O{3$vBwEyV=5A@~2UxpT=zBtjWY7#e@`QFgpKNQ8o@wL9N0CDK}qW_}5ZAxvC zyqaScW6%W!`NvQgv+kqX()K2a)Xs0U^Y3WUxs=;pTF5uMD!G`(HmK1mg{di>wd4ZqlbZd zwaUkmfX+tz(%Hp`Vv_n>acxi9A)M;CRq(h-*hs5cj%LldLnDju2gJOMUpnjZyUrS! z06J?v_ia~Kt8C0AC)S}6MQibw&N?s1&sA;i%ruLVtrzNE!fK_v|I2tjIqOP zT?|WpQYFfge;B?^GX00uAkD1$<^~cb2xdl z$%yn;>l>O@Uz655mfQCHyN})k-|MZhM|AYa5awQRNC@ZeAvi^Un(TbD zTmBZUv@(+I>pN_Nu|fQ>$(FS$DwYaAKy>L1Rt)EaISp6fi=}nq;oZ7XI){>D!j=_O z+3x*pa5-H?BAY#cYiAwrZba*#hVXs{Ah<(OmA8Jj8lFB2b`xoj(oX4s6VvE90g3J4 z8PG6(QTt14O}D!A)0kY!0mu4v#SV?}eh}`|RCViY`UXJN7ga!d z8v(s-(f}vygbof_0WUKGKIS{OS#fN<*V(q;bXFVivy-h9T%R`CA42wlveusz+5Eqd{R`QDCuG$TH+ddH z_JJzazlQ9?vGLzj)-oI6@n_PjdzCeHR8zrB-vlRtlLE_2n*@vKN=Q;~XlloIhA9G% zr>>+<-R*)(N_H{?58XYlmfbh&d-uR{f?;CyXLJtQ#XBm^{PS=>3#@bpQ<}?!=wfc) zO?tjA3$OF|*-YC+c7C54pGU1;E_HQx-$zg%^8P+GPV*2r2)G3zsNYlLGm|~S`_x!x z&C>BcH3nq%Q?N>nxjcKOV?8DYmGjL9fy5Kb?pdUmnVGHd62lA6yYQ z+$6L-S5LzXRKsL@B^m0!bIm=5-gG^+*O=%re9C{ky}zU)W6(xCn{nLLmV3II>j@s# z+VxN5>3{sw{d_T53bgL*y8Pdq8gEy|YhPJOpK) zdcr5F`9QkVS^<-_5{(kZ#g#!{hL9yOoTy}mTl`5ej`aB}ZK@V70SSmw+NJ(Z{beIb z$72=@|0*giMz7&-7`)3|(_%k#6tN?c^pqWveX%JdcU|HL?0IZJzxF)2 zz@7&J?0JHDH;EoX_JNYrpA^}Qzf|@wmHl^8*?}hy*D3y+Dp3Ciyew_Re)hb4_@*xf z9UaH;OXrys9aunSQGS=%EAY49BV($vy?V2$ta1ZRJR38YPxbSs^G{L6IZh;KRp(0t zyMq??g+TXf9`M?Ep$Gqq`!!EM_o}HIu;v*)@z}ct0^s{K5A0iaAyS<`8c?%91L~(i z<+<6F_~c<m;*iR?WE=&VBvl^(1d3C0xGkCq?#6$33#Tb`o8$zVwMtC*Ew zTXUASe&NkQFp!cpL1An)dHr=c8bO>Sn-dQ)a%2q2`lHwIZO)+nhwb{CMxu^P%3nG= z0O)LZAsUEEs|`+&I=qdYZ`}z!ne9Uh@8(8J>}op;s0RAOeV<|t=u_AQhL8=zjGnXz%+Ja6q48kX?XK?Y>WO`dgnu7t{~vtiBV$p#E<`T8>01B>!U@y@Bg*s z=}0X@H`roS_Y83WYEVA9WgatP@VoLEd3rZQ>%h$$jRZx)bV9p>L4$mDCd}%_;Z|B@ z13;E+4D4-3hax(J_)k`VOn9q(6IcD0q*f(ggt>16Iq+_~@dfZ3P~NTi;K8B8cHokY z-`Y@ab}Jm?1Zf$Iz{?uIKBxvat(E1s7L>~?aDpwc3(^7BLj-BTR+qmg#vMRn90DZ9 zIlmHPoBPE0^L=7G)}V?)VHTc;{Ci@&Bk^~M@yszO;E%-k(B;lUgDe2HVk_g#f$gxq z{o)HxsFBf4%LinZ=fMipfAN-w>i({Tq=f&^EsyixZF!P`Gfg}|lXYk8e{6ZOOL}Fi zw(GY$qj=npT`cGQPkHmLS+ws&TKRUax^EI|jdtuyPK$W^^RR%V<{GP&MC&-ECqDyl+6+VdrfS{O8Ho=reX>lCL9D_iWAR8b*?b zFkEj=qVQGsC@0WaOw#iZuD0C!l|DU}pGuABQbS~Wg;*G4Hoq`=3ZzeD$%&r7rB7SR zFM;$aDZ?RewZvw%#M7o#aW_VD;`EudJ7h6A7)YNymrDfICU5a}p6bF&1D!?1mT07Q zBpT8nH%d;Rv$$W5X-MA1g~(3vvgKudgwBkqZHv)TUNH5oTs?|2$4`5!TB`F$l&4}|6!4jYz# zRu4`7ZmkMD;R4)>v&(3RW}(pz6e!?VxmcYoeuOf<4ZG6li3bq@$R;?6?0zONg4V6@ zVdFG@V&D|55|$5?_4W6Hi;U1xfCW#vB~YR`vYU{1eF}`oCu>E*KsPZh{XF?Juif|t z8LVN9($Bjq1O90Dt4VP`9TQ)bPZ@{m6kUXo7hjOV0$UmEwDMTIv~m`pHsJuwy~4%6 zmbLeronK=xFhk$Bp{!Kha<6_bSO8P;F3_mB-|zq}C^2~|A*B*vmPQ4}VxUmL@q23# zn2PTk6=!d$ezg`E?^}!M_pL>|QoOdnkX0MM-&>0Xv47WE+z<%A{iC(0eYn6_@ZtVb`LBb215 zyp%^GKR>icZ@0VYt~Xz^ZvEUKPmg(J?E10e;_3b`kp;RG7LzhSU~G2;1jdjLiF1Fq zmrd;C8F9twJM5bHsC}1NB8;Rd$-FSm8L!0kACr+KE6*5$GP@8`xjP37}fBH4juQ`a=elb${zI8dC`w z%!|6+8`)N18M{T_ZrlUBpDUFRj;l-b$7J#cLaZ@S`P@&%ECS)W&T^hlBmHh~xSo+C#}*!@4;3IK#COIL*8BK$n6v z{8yKvS3Gpso$MO=1<+D|NM#==K=H8u^QUOI|EI$;y*s)6;-7`I=S8yOw>NgJC_I`ws>*V&s&3Fx_+9&|sPpIg&*;G6m2 z^0m79)Y-ueYfwyWe~-qp(xS;CX?x&Pjm4==!G6Li7k$;CtZR-Qg$=~a6QaaLn)7L- zH2l_SXMagP>*o_&ouutHo8~O!8rmi;9Oacbvd&y{3ctEI#k%Li6B>>$tg>q2PlG!& zz`&82Z}I6DD5sS)$7H$sbx%sd2WV&xg}S=QYxXmaC(O&8Y(iH#-GH08t-zdPA53N( zZ6Gf@p@T+MO#-p3x~1VJQOXC?Y#Oj-aE&JilrR*?>Z{Afl`v+?1Oi-%MWW32+uS_Ek6SeiFw-?>IK; zoK)Jrflqe`8-ECp2g*i&MnK*%=ID~$fX8NA( zP6{D8u;kc#XBJl;1T9EdvF+l7R<4MRPP8#9Hi%T@-JdC&*u14pmLm0X!96@m&~jF6 zvv^V;yn^3ldO_3SxUgdSWq;`F;mVn`e|S0n=}n+NF;!!~#29ccKfe|Exg-PrB9})- zlgF7Va2Q2V#f};O8KegTayIW`PS2yS9ZND;ed=k>FyO@BHwHCE`GJL=>}-P8eu{Bk zTKeO27>UfMSj^Z%NHozaWvI9qc?=l1%#oQoJ!pa2lw#>i&n4;xP%^iQzFbvO80{-c zOldwFK=KwVvGSsl-w{B}b$6(S*%12t2(+%XV%#V1ZMXB{2?j$yVWJA$U}o}B$O?1+ zTi7D~Ed@3M&f*>hNwG={u9ZXwGn0wE-~euP{;#Tj9N|jL^_k_R8;Ml5u-5kJZ*?Q> zn0FB2yE25czhz!gtuu3+eABWKfC<2aKCka1!pU3G!L{xNS%a>+?t(xHep=MiVi%@k z<91o4#&2QHDAbUR^&X!Q@S(Z(IQAW#iV6n^#!Su9s2$3o20G>B7wC>Y+uT zxyI?0#t(9dq=44kGgyoSk*^|*BVKbD2|}B7x&aPG(IT5K1}s3E*6}^KafRqPP~woFl#dY*U+fM|>rHq-#K{O)Kd@jKHI8 zVm%z$;$))fnqc8RNgYZ~9I`naR+={gL9Lw)oB2mTIDlKb{^KeyWoPSmlq~Z4W=i%J zC@gZ6Y^<#J$7I^t*;DeebN=nBFAfmz@6Vt8uMg2|d^2r3+xf_SQ*DW@i5@C0?u+HbB$1&HKTm615oi!eq>g&%S>TKX-Rm}GFrnD{8(R!CougSV z#>kC(R-wVT$jedAnyYz7NbepoM@znVxh(4X!gSe2RDk$7Ti|Up%Ej?UWNN>sX`V|=FrO?mHE`HMT^x}e#zWdX@4Yc0y_cnZu z=R$=p`Ym1O2V8W^52{J^%!b#ZVvjRkK`T?XpmMd)h&uDVe*TDZ2sb`U&)?|thoJOS zd}ztf0!+L^2%{!BZ$AupYwO{Cq-mk5XkQLd{DRA>*&-Srw;Y4@x~)uAf%S=>lrL*E zs}Pir+5c$lyQAU!zP%Y4-6+xPgb1R{3`UOsimU&pvyfv(Ncsud_evIeRmMh6pt^gINKeY6z0L zwFdxK9I}LBR5lzB#1d8qgmDsIhq5M7fvKeMKH^JqpB9IfgAy=B)hQOvgoe+N#wDGp zcA`_vw(Mf$^r}!zBQPbWE@5?tehbcb3V1NdudlPrA0-Ajtth|`L^idHs$pVF-JN&k zzlfR2W&Nm_!Y-xkv%+8@Z{d+7cBHGo)u-5}hoEy(3@+_BIxF-z!7;WW?~p==B4{>E zo~E~tc?KXtE5<02LbVifBkHvFN|(jy&V#ezsao-IyzWx}5Uks&Ua4qk$*)c9)^$kC zp{UmqipxofdF9q?Ast(%#`|+9Kro z`&Fu4A}u!DXvy9!@0Z9#Jt=7!Tw7(i=ilExcG*Go>Va9o??{F}8vjP^h<{WgN5Ni- zu?Ldgs_I4`B$%dgZGU7%217Dg?(bK{#%d;{RcF&vsHv$3@7&P#3@BO(M7p)Bs;$Kt zxKb5=DBb8o7Jnhx58=m%`})t`{>JtFO4jmI9MUnKiS3%X7lX2*Klyezz{c4z;GUpg zSyY+-{rcj15ZCDCv217r5OC_SxIold`J8VLxNbVzEPuXe$ttYYVf`*P$SAr%m?cOw zP}FexKuc#wW&}TMRzc;6pRuRF?AO_Z*wEUfH*?R#_K}0wZY$trqP@szR z&>Aa>uOk?!*fD-G*YnOfL2*n4!bqLI;hfg`Nm^3u+&ax!+W^#JDcuo_q!|+Z{%l;) ztkO79n4u3*U{bn$vHJCTsTEcxr-?jX{+dQ5>ql(xwJ|EiMy}TannL63z!~13I&)_D z!b&fZ3g0fVLmlMKQMA(a=<`=%BZiN_OcmaQ<`!`=X-T-qE={?atmh`tmFeskk$*l{ zzniI;@swgHHWp+}PI+w48Cp!2D!PM<^2BQ6mz9yhn~-Z%MVF z#2~SZ?Hv2PkL|X6(pd6qj@wxoyamXW+U?N6AJH47+v)bO!fm4SpKl4Of$Y2x2v)Qv zePS4s@+Sbib8;}~Cb3VDpG1ZvrUr4d5@-4UC{!NQRID?zuR&TT}=A% zt75++y^DFgw%Cx;kKMW}d@b(aXKTeBc+Q+%#b=Ghk^LR=XHxNR-NGVOBN`u2GaJFT zMz$ZZO3fd2gjz1nqEh-_bK>$;4<+X9M&mbro9jQ`t?fUXwwSVW?Qjp{BBxQ;h@&ENdcmH)x@ee%~)?VztF0m4HiGyX7ycqSEy@>{CM`e zeEOhZFSoTEiFf{cQAfq0d}D(zV=q5ReUDR_U0?MO4mep)xWE`cK9e|X;Ce5fz&$nXPA?)L?zc=t1bw zPZ?{UQJV9kb4i%t#Ps5@6LZA#*3W$H%XpT#Y5uJi9l1lx)ykWkocqc<9|k?~;(|`v zNBfMgu7sgvo90eTOau#ltxE>pUS6Kf=$7RywFC+eo;RXGulW3~_h_7#j=bLA%#LoO zclVN|8+^P|+G2}so-xTZYX;W#j+*Q(_A8MS9biTZ@;YznG|st93ir`9$9p z0sUR(nC3()$G@rYE+}LG#kf!686cq&{rAZ^8CfP|biP!6$hyP=eEwoqU#gPWmXxXdw(?M8lUPK$ zJ9D^I$$~U-6_YfKn#cMI1@WZYLNe=Z{a1CBL05KfKpBA{_pNy$m{0~b%u^#e4Et}7 zuGg)d2i1E#Yiz!6F8Z^n)S6o3O&VIYFUeiG%|`05wgp>a?@#;eTWAh)%879t(Wgo2 zRYuAZH)g_bYw%BFb}xsQ_N$f-C&ZX?;*{3kyDa9Au=|_KTBU)Q@m!B ztph|g1xLwKraqIcc#@lWIniAZhaX>o+cO+Y&5J|K5@AO}fhPZXc=+e42cQcN{*eJD z&H@vc2P?dkwI%Owj4Q_1Hp1h6&LR(taL6}lAgBxa6f_+m9PCLG?{a?<4lA6;Yr0E6 zCk{K1nyeIjLAC>6-N2|D9)|B7Qk(PfbeDz;OOrcBh zhc}&rlo;a7_5@N{&0f{MQl(qT;_m8fyclu~RaB`Ez|_1_q+2oKUPqSyOc<3OcATAi znmdf9PCASd%w~Tw>OfaUY)29z@FWVdu2YV6RU-4?7wDLKnynT$KJ5Bi)eo>eE?_+hYFt z$Ip5;=>vBI(GdS>_Rf=Y!6Ep|xN-%Df=`Q<2c^qOkb(+UddviF+?|p`CWpcXs~5vY zQ)~a%;VaTwe9jBQq$qBmgiJJvan+*O`c&rAH#d^Hb$~|;_iRS?J!nqW?fZjdvRC!O zLH=5Y(h@n5f9#K9ME&;`+*oxkim$J624Wj>yaTUJr~?DdU<8gCVe|4O{lB8ED9AmR zjQm2z_USjbq^G1)Yn|d_sxw!=4PVEpXXN0dqdh#2vsFZ*bPAmI1elrJgZRd`y4;fc zR$9LGxkzqRjc1JJkNXDd4g4l^ygWjg>;7bF3aJ0M%k<@P^gw9Rd*s239vQ*o^5P-c zi#P>W<_1gVwHUofC5RZQ*D*BDJ(6+?*#*qZD`Dw7eF%R-_dKF-j!c#A+!bMoI~wuj z$~%}Wokb_ZxwB1|*T!S6DjKIAY+ggt{pm+J_>l1A9v%&P~1HS&RFaCR{H)?w>>1IC+Nvpgw+77#_aQn zafVcHD@1`nIlgEdUIS?PVBT6E41e3!V?h;Z>@~_G{ZD@*<+xmUv^x?9T*8-{FC_m= z0NBA-64OzwKa-&&tN&BC#=@B4f#!?sjct~;Xp_f9M#`$MNJ)mT6DTh!W_hTM28IVn zlo$I((l|l-*}AxqxV$u$b%xxNKf~PBSdcuBRB2?XT@T+14U-|X{o%DS<1PLJ2j`xj zuA26oN)N8<8Q#PB!HL#ys;)U=I?)2;K0WX z<~@N%T#>8jIwt>nqz;Gv*Go9s?r3W-E0jB!+tu1eA7#W36A*?92#WC#L*%?X?a=Pr zJP>_*PbbvfSI^7R0cGWRN6EXRke+va>c~44u#df`9oX(JFcb!Z3W>plP3|N#(ANKbr@lMV)fHt8hA1MPJW#|C zZGD81fTEX^lO@u{<*(8DcJ?0NyXXHJ&j&U@xqIAA2Nn{53B%yxf+BDsenA0||6J9b z!kxY9_TDJ)oh5LH0?N`J>B0kcbVYjFd7zMB@Bh#j5fB!D@eoT(|J}cTl`0qeuRm4) z8@?g-pYR3@4*!4fhA3RYKZn`p3hnJLE(I_}) zl$YBamInMf-PtO4ZgwN3vnH> zN><0{z{kpkDq2AM`EWhC#|9Zcesou?X4z7wh}#-wU!LygH9v1y=muIi9SXm}hN!EM z9zLs-BSlDm)FC~*3}L6!Lwbqv7CoD0@aWK@z)wgZ2fdL9VPoFv(f%GUmIn;{(34@* z)^#)@=^R%-?Q2VFGA0x);PkzlcSo-K0gUA0JEM3s*FBC1_DG9muw&)%D81*^qp(l3 zF6T;7mx)Ok{iLT}XPUd)FGbT}(GNXB!1p z8jdy7F`9o(at_<@>WeD!D&qfLb0nPMx5gqpPCd1evDS`qAqjZ=n`lfrae}GdwTS)6 z#qBc9iD2Pc`{Fwz7tWjE(WC(P=}Z@`unRo(IRfluj&m{X!F*f5Y(++IsyAYR^7wd} zPg>@Te76|ajbZR|YU6%Nf6(HhPc+-*J~ZuH!_ve;p3CpBe+Zh|J;)6o{Qun2zXOOy zx+oiBh>D9f3IjHUg5gk+7sL=fdq31)k{DtLHidzOz_2@}E*kB5$NUS@>;BcSLEp9h z`nkU?1+b}>sSRwkB`_3tD$B z&H~wdKUsG!$Re_Fqmd}DOsefvgzP@ix-5e+sMg3g#s$}$z~*Z z#w^plLv>~!5Y0Nn!Deq$zx-~>)R9;#wP0PQouq;S)d3P=mE3z)jN<`6J-vQOV#P+C zU?_42Tn8>yy4>AmjZ(>#undqVg`*hN`(yvy+h_O7B*_aamnRLhLglJwo?fcWS4li2 z@TP#{xh|y($WrPq|LKI?9p@h~X7_*qcm!v}!fc;6lcA?{xD=cQSd?gehOva@jL6s3ABB z=g;!gnP+qPLjB6zFL{kmge50-Vl$bez{Mhu2~9f5tzW+u=>Uv_TSl1OyLuuQpJ{Uu z?_JzYChc{$dfwA|{UwSK0W3yi-KqHlq4%k{o@iENwTR1k`VDM9;F{2!eb4j#ceIdb zR>+zyu4%*`j1hH?SIc2hMmGe+d}Wi^ygk#*&9fa2k5y}>6Rg>s7OS%=jd^y7sN zdMIrSK}Inpf`X$!n5tdbmHjO%d`5U63X|nvFqeBGaj}xj{lU3VRFJ=&xX9LSV@meW zlw=zB#WH>e-)r^wfir_2(T@d1*~8ccsniBs)NJCv7e>wJ9Kw^A(TQb^?(5E__`GNQi4Ju~$0xcP25rYV z`n6MDW=V|pUO7?^rYw^=$qN;YH?FL73o4JcyGQCwHi|>_GoSgaBs(` actuator for modeling DC motors. Supports optional + electrical dynamics (inductance), cogging torque, thermal resistance variation, and LuGre friction. See the + `technical note <_static/dcmotor.pdf>`__ for more details. - Actuators with joint or tendon transmissions can now contribute :ref:`damping` and :ref:`armature` to their transmission target. These are applied during the passive force and inertia computations, respectively, and are scaled by gear\ :sup:`2` diff --git a/doc/dcmotor/buildpdf.sh b/doc/dcmotor/buildpdf.sh new file mode 100755 index 0000000000..ed73a053ab --- /dev/null +++ b/doc/dcmotor/buildpdf.sh @@ -0,0 +1,21 @@ +#!/bin/bash +# Copyright 2026 DeepMind Technologies Limited +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +pdflatex -interaction=nonstopmode -jobname=dcmotor dcmotor.tex 2>&1 | grep -E '(Error|Output written)' && \ +bibtex dcmotor 2>&1 | grep -v '^$' && \ +pdflatex -interaction=nonstopmode -jobname=dcmotor dcmotor.tex 2>&1 | grep -E '(Error|Output written)' && \ +pdflatex -interaction=nonstopmode -jobname=dcmotor dcmotor.tex 2>&1 | grep -E '(Error|Output written)' && \ +rm -f *.{aux,log,out,bbl,blg} && \ +mv dcmotor.pdf ../_static/ diff --git a/doc/dcmotor/dcmotor.tex b/doc/dcmotor/dcmotor.tex new file mode 100644 index 0000000000..c60e08b433 --- /dev/null +++ b/doc/dcmotor/dcmotor.tex @@ -0,0 +1,1416 @@ +% Copyright 2026 DeepMind Technologies Limited +% +% Licensed under the Apache License, Version 2.0 (the "License"); +% you may not use this file except in compliance with the License. +% You may obtain a copy of the License at +% +% http://www.apache.org/licenses/LICENSE-2.0 +% +% Unless required by applicable law or agreed to in writing, software +% distributed under the License is distributed on an "AS IS" BASIS, +% WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +% See the License for the specific language governing permissions and +% limitations under the License. + +\documentclass[10pt, a4paper, twocolumn]{article} +\usepackage[utf8]{inputenc} +\usepackage[T1]{fontenc} +\usepackage{roboto-mono} +\usepackage{relsize} +\let\oldtexttt\texttt +\renewcommand{\texttt}[1]{{\smaller\oldtexttt{#1}}} +\usepackage{amsmath, amssymb} +\usepackage{multicol} +\usepackage{geometry} +\geometry{margin=0.75in} +\usepackage{titlesec} +\titlespacing*{\section}{0pt}{1.5ex plus 0.5ex minus 0.2ex}{1ex plus 0.2ex} +\titlespacing*{\subsection}{0pt}{1.2ex plus 0.4ex minus 0.2ex}{0.8ex plus 0.2ex} +\setlength{\parskip}{0.4ex plus 0.1ex minus 0.1ex} +\usepackage{booktabs} +\usepackage{enumitem} +\setlist[itemize]{label=\scalebox{0.8}{$\bullet$}} +\usepackage{float} +\usepackage{titling} +\setlength{\droptitle}{-4em} +\usepackage{stfloats} +\usepackage{url} +\renewcommand{\UrlFont}{\small\ttfamily} +\usepackage{tikz} +\usepackage{pgfplots} +\pgfplotsset{compat=1.18} +\usepgfplotslibrary{fillbetween} +\usepackage{hyperref} +\hypersetup{colorlinks=true, linkcolor=blue, urlcolor=blue, citecolor=blue} +\usepackage{caption} +\usepackage{subcaption} +\captionsetup{font=footnotesize, labelfont=footnotesize} +\usepackage{xcolor} +\usepackage{listings} +\lstset{ + language=C, + basicstyle=\footnotesize\ttfamily, + keywordstyle=\bfseries\color{blue!70!black}, + commentstyle=\itshape\color{gray}, + stringstyle=\color{red!60!black}, + numbers=left, + numberstyle=\tiny\color{gray}, + numbersep=5pt, + frame=single, + framerule=0.4pt, + rulecolor=\color{gray!40}, + backgroundcolor=\color{gray!5}, + breaklines=true, + columns=fullflexible, + keepspaces=true, + showstringspaces=false, + tabsize=2, + xleftmargin=1.5em, + framexleftmargin=1.5em, + aboveskip=0.8em, + belowskip=0.5em, + morekeywords={mjtNum, mjModel, mjData, mjtByte}, +} + +\newcommand{\atR}{\texttt{resistance}} +\newcommand{\atK}{\texttt{motorconst}} +\newcommand{\atKt}{\texttt{motorconst:Kt}} +\newcommand{\atKe}{\texttt{motorconst:Ke}} +\newcommand{\atVM}{\texttt{nominal:voltage}} +\newcommand{\atSTALL}{\texttt{nominal:stall\_torque}} +\newcommand{\atNLS}{\texttt{nominal:no\_load\_speed}} +\newcommand{\atTMAX}{\texttt{saturation:torque}} +\newcommand{\atIMAX}{\texttt{saturation:current}} +\newcommand{\atVMAX}{\texttt{saturation:voltage}} +\newcommand{\atCRATE}{\texttt{saturation:current\_rate}} +\newcommand{\atKP}{\texttt{controller:kp}} +\newcommand{\atKI}{\texttt{controller:ki}} +\newcommand{\atKD}{\texttt{controller:kd}} +\newcommand{\atSLEW}{\texttt{controller:slewmax}} +\newcommand{\atIMAXINT}{\texttt{controller:Imax}} +\newcommand{\atL}{\texttt{inductance:L}} +\newcommand{\atTE}{\texttt{inductance:timeconst}} +\newcommand{\atCOGA}{\texttt{cogging:amplitude}} +\newcommand{\atCOGP}{\texttt{cogging:poles}} +\newcommand{\atCOGPH}{\texttt{cogging:phase}} +\newcommand{\atRT}{\texttt{thermal:resistance}} +\newcommand{\atTC}{\texttt{thermal:capacitance}} +\newcommand{\atTT}{\texttt{thermal:timeconst}} +\newcommand{\atALPHA}{\texttt{thermal:tempcoef}} +\newcommand{\atTREF}{\texttt{thermal:reftemp}} +\newcommand{\atTAMB}{\texttt{thermal:ambient}} +\newcommand{\atSIG}{\texttt{lugre:stiffness}} +\newcommand{\atSIGD}{\texttt{lugre:damping}} +\newcommand{\atTAUC}{\texttt{lugre:coulomb}} +\newcommand{\atTAUS}{\texttt{lugre:static}} +\newcommand{\atWS}{\texttt{lugre:stribeck}} +\newcommand{\atSIGV}{\texttt{lugre:viscous}} + +\title{MuJoCo DC Motor Model} +\author{Google DeepMind} +\date{} + +\begin{document} + +\maketitle + +\noindent We review DC motors and describe MuJoCo's \texttt{dcmotor} actuator. The equations are derived for brushed motors but apply equally to brushless ones, where electronic commutation reduces to an equivalent circuit. + +%============================================================================= +% BACKGROUND +%============================================================================= +\section{Background} +\label{sec:background} + +We use SI units throughout, but any coherent system of units applies. We assume motion is rotational; for linear motion replace radians with meters as required. + +% --------------------------------------------------------------------------- +% Electromagnetic Model +% --------------------------------------------------------------------------- +\subsection{Electromagnetic Model} +\label{sec:electromagnetics} + +The key electro-mechanical variables are + +\begin{table}[H] +\centering +\small +\begin{tabular}{@{}lll@{}} +\toprule +Symbol & Description & Units \\ +\midrule +$v$ & Applied voltage & Volt \\ +$i$ & Current & Ampere \\ +$\omega$ & Angular velocity & radian/second \\ +$\tau$ & Output torque & Newton $\cdot$ meter \\ +\bottomrule +\end{tabular} +\end{table} + +\noindent and the key constants are + +\begin{table}[H] +\centering +\footnotesize +\begin{tabular}{@{}lll@{}} +\toprule +Symbol & Description & Units \\ +\midrule +$R$ & Resistance & Ohm \\ +$K_t$ & Torque constant & Newton $\cdot$ meter/Ampere \\ +$K_e$ & Back-EMF constant & Volt $\cdot$ second/radian \\ +\bottomrule +\end{tabular} +\end{table} + +\noindent The quasi-static model~\cite{hughes2019, maxon_formulas, simscape_dcmotor} assumes instantaneous electrical dynamics: current and torque are direct functions of voltage and velocity. The constitutive equations are the voltage balance \eqref{eq:voltage} and the torque law \eqref{eq:torque_law}: +\begin{subequations} +\label{eq:motor_laws} +\begin{align} + v &= i \, R + K_e \, \omega \label{eq:voltage} \\ + \tau &= K_t i \label{eq:torque_law} +\end{align} +\end{subequations} + +\noindent Solving for current and substituting, we have + +\begin{equation} + \tau = \frac{K_t}{R} (v - K_e \, \omega) + \label{eq:torque_speed} +\end{equation} + +\noindent Output torque is proportional to the difference between applied and back-EMF voltage $v_{\text{back}} = K_e \, \omega$ (Figure~\ref{fig:torque_speed}). + +\paragraph{Electrical constants.} +Fundamentally, both $K_t$ and $K_e$ arise from the same physical quantity: the magnetic flux $\Phi$ of the coil. Faraday's law gives $v_{\text{back}} = \Phi \, \omega$ and the Lorentz force gives $\tau = \Phi \, i$, so in SI units: + +\begin{equation*} + K_e = K_t + \label{eq:ke_eq_kt} +\end{equation*} + +\noindent This can also be seen from energy conservation: $P_e = i \, (K_e \, \omega) = (K_t \, i) \, \omega = P_m$. + +\pagebreak +\noindent Note the dimensions match: + +\vspace*{-\abovedisplayskip} +\begin{equation*} + \frac{\text{Volt}}{\text{radian}/\text{second}} + = \frac{\text{Joule}}{\text{Coulomb}/\text{second}} + = \frac{\text{Newton} \cdot \text{meter}}{\text{Ampere}} +\end{equation*} + +\noindent If these constants are the same, why have both? Two reasons. First, datasheets typically use mixed units ($K_e$ in RPM/V, $K_t$ in mN$\cdot$m/A), giving different values for the same physical quantity. Second, $K_t$ and $K_e$ are measured differently: $K_t$ by locking the rotor and measuring torque per Ampere; $K_e$ by spinning the rotor and measuring open-circuit Volts per radian/second. In the first case, high currents can lead to magnetic field saturation in the core, causing the effective $K_t$ to drop below $K_e$. The equality $K_e = K_t$ thus assumes $\Phi$ independent of $i$. We make this assumption for now and use a single motor constant $K \equiv K_t = K_e$ throughout the remainder of this document and internally in MuJoCo, but see note at end of \S\ref{sec:dcmotor}. + +\begin{figure}[H] +\centering +\begin{tikzpicture} +\pgfmathsetmacro{\taus}{1.0} +\pgfmathsetmacro{\wz}{1.0} +\begin{axis}[ + width=0.9\columnwidth, height=0.55\columnwidth, + axis lines=left, + clip=false, + xlabel={$\omega$}, ylabel={$\tau$}, + xmin=0, xmax={\wz*1.15}, ymin=0, ymax={\taus*1.15}, + xtick={\wz}, xticklabels={$\omega_0$}, + ytick={\taus}, yticklabels={$\tau_0$}, + tick style={thick}, + every axis x label/.style={at={(ticklabel* cs:1)}, anchor=west}, + every axis y label/.style={at={(ticklabel* cs:1)}, anchor=south}, +] +\addplot[thick, blue!15] coordinates {(0,\taus*0.7) (\wz*0.7,0)}; +\addplot[thick, blue!25] coordinates {(0,\taus*0.8) (\wz*0.8,0)}; +\addplot[thick, blue!50] coordinates {(0,\taus*0.9) (\wz*0.9,0)}; +\addplot[thick, blue] coordinates {(0,\taus) (\wz,0)}; +\node[font=\scriptsize, text=gray, align=center] + at (axis cs: \wz*0.25, \taus*0.2) + {decreasing\\ voltage}; +\draw[->, thick, gray] (axis cs: \wz*0.4, \taus*0.55) + -- (axis cs: \wz*0.4, \taus*0.15); +\node[font=\scriptsize] at (axis cs: \wz*0.4, -0.08) + {Speed}; +\node[font=\scriptsize, rotate=90] at (axis cs: -0.04, \taus*0.4) + {Torque}; +\end{axis} +\end{tikzpicture} +\caption{Torque-speed relationship \eqref{eq:torque_speed} at fixed voltage. As voltage decreases, the maximum torque and speed decrease linearly.} +\label{fig:torque_speed} +\end{figure} + +\paragraph{Current Saturation.} +A maximum current rating $i_{\max}$ limits the output torque: +\begin{equation} + \tau = \text{clip}\!\left(\frac{K}{R}(v - K \, \omega),\; + \pm K \, i_{\max} \right) + \label{eq:saturation} +\end{equation} +where the maximum torque $\tau_{\max} = K \, i_{\max}$. The feasible torque-speed envelope forms a parallelogram: + +\begin{figure}[H] +\centering +\begin{tikzpicture} +\pgfmathsetmacro{\taus}{1.3} +\pgfmathsetmacro{\wz}{1.0} +\pgfmathsetmacro{\taumax}{0.7} +\pgfmathsetmacro{\slope}{\taus/\wz} +\pgfmathsetmacro{\wcu}{(\taus-\taumax)/\slope} +\pgfmathsetmacro{\wcl}{(\taus+\taumax)/\slope} +\pgfmathsetmacro{\wext}{1.5} +\pgfmathsetmacro{\dexthi}{\taus+\slope*\wext} +\pgfmathsetmacro{\dextlo}{\taus-\slope*\wext} +\begin{axis}[ + width=0.9\columnwidth, height=0.6\columnwidth, + axis lines=middle, + xlabel={$\omega$}, ylabel={$\tau$}, + xmin=-1.6, xmax=1.6, ymin=-1.6, ymax=1.6, + xtick={-\wz, \wz}, xticklabels={$-\omega_0$, {}}, + ytick={-\taus, \taus}, + yticklabels={$-\tau_0$, $\tau_0$}, + tick style={thick}, + every axis x label/.style={at={(ticklabel* cs:1)}, anchor=west}, + every axis y label/.style={at={(ticklabel* cs:1)}, anchor=south}, +] +\fill[blue, opacity=0.08] + (-\wcl, \taumax) -- (\wcu, \taumax) -- (\wcl, -\taumax) + -- (-\wcu, -\taumax) -- cycle; +\addplot[thick, dashed, gray] coordinates {(-\wext, \dexthi) (\wext, \dextlo)}; +\addplot[thick, dashed, gray] coordinates {(-\wext, -\dextlo) (\wext, -\dexthi)}; +\addplot[thick, dashed, gray] coordinates {(-1.55, \taumax) (1.55, \taumax)}; +\addplot[thick, dashed, gray] coordinates {(-1.55, -\taumax) (1.55, -\taumax)}; +\addplot[thick, blue] coordinates + {(-\wcl, \taumax) (\wcu, \taumax) (\wcl, -\taumax) (-\wcu, -\taumax) + (-\wcl, \taumax)}; +\node[font=\scriptsize, anchor=south] at (axis cs: \wz, \taumax) + {$\tau_{\max}$}; +\node[font=\scriptsize, anchor=north] at (axis cs: -\wz, -\taumax) + {$-\tau_{\max}$}; +\draw[thick, dashed, gray] (axis cs: \wz, 0) -- (axis cs: \wz, -\taumax); +\draw[thick, dashed, gray] (axis cs: -\wz, 0) -- (axis cs: -\wz, \taumax); +\node[font=\normalsize, anchor=south] at (axis cs: \wz, 0.05) {$\omega_0$}; +\end{axis} +\end{tikzpicture} +\caption{Torque-speed envelope with current saturation~\eqref{eq:saturation}.} +\label{fig:saturation} +\end{figure} + +\noindent Note that datasheets typically distinguish two current limits. The \emph{continuous} (or \emph{nominal}) current $i_{\max}$ is the thermal limit: the maximum current the motor can sustain indefinitely without exceeding its maximum winding temperature. The \emph{peak} current $i_{\text{peak}}$ is a higher short-term limit, typically 5--10$\times$ the continuous value, constrained by demagnetization or commutation limits. + +\begin{table}[H] +\centering +\footnotesize +\setlength{\tabcolsep}{3pt} +\renewcommand{\arraystretch}{1.2} +\begin{tabular}{@{}llll@{}} +\toprule +Symbol & Description & Condition & Formula/note\\ +\midrule +$\tau_0$ & Stall Torque & $\omega=0$ & $\tau_0 = Kv / R$ \\ +$\omega_0$ & No-Load Speed & $\tau_{\text{load}}=0$ & + $\omega_0 \approx v / K$ \\ +$\partial\omega / \partial\tau$ & Gradient & Slope & + $-R/K^2$ \\ +$i_{\max}$ & Maximum Current & Limit & Thermal limit \\ +$\tau_{\max}$ & Maximum Torque & Limit & $\tau_{\max} = K \, i_{\max}$ \\ +\bottomrule +\end{tabular} +\caption{Named constants derived from the motor equations.} +\label{tab:electromech_constants} +\end{table} + +% - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +\subsubsection{Inductance} +\label{sec:inductance} + +Including the effects of winding inductance $L$ (Henry) means treating the current $i$ as a state variable: +\begin{equation} + v = L \, \frac{di}{dt} + i \, R + K \, \omega + \label{eq:inductance} +\end{equation} +The change in current is proportional to the voltage and negatively proportional to both the instantaneous current and the rotation velocity. The time constant of this ODE is $t_e = L/R$. If $t_e \ll \Delta t$ (the simulation timestep), the current equilibrates within a single step and the quasi-static approximation~\eqref{eq:torque_speed} is adequate. + +Motor drivers often impose a hard limit on $di/dt$ to protect windings and electronics, bounding the torque ramp rate to $K \cdot (di/dt)_{\max}$. + +% --------------------------------------------------------------------------- +% Mechanical Model +% --------------------------------------------------------------------------- +\subsection{Mechanical Model} +\label{sec:mechanical} + +Several purely mechanical phenomena affect the motor's behavior and the effective delivered torque. + +\paragraph{Mechanical losses.} +These reduce the net torque available at the shaft: $\tau_{\text{net}} = \tau_{\text{elec}} - \tau_{\text{loss}}$. +\begin{itemize} + \item \textbf{Coulomb:} Constant torque opposing rotation (dry friction). + $\tau_{\text{loss}} = \tau_c \, \text{sgn}(\omega)$. Discontinuous; already available in MuJoCo as \texttt{frictionloss}. + \item \textbf{Viscous:} Drag is a smooth function of speed $\tau_{\text{loss}} = b(\omega)$. The simplest model is linear, with drag proportional to speed $\tau_{\text{loss}} = B \, \omega$, but higher order terms may be needed for higher-fidelity models e.g., $\tau_{\text{loss}} = B_1 \, \omega + B_2 \, \omega |\omega| + B_3 \, \omega^3 + \dots$. +\end{itemize} + +\noindent Datasheets report the \emph{no-load current} $i_0$: the current drawn when spinning freely at no-load speed $\omega_0$. At steady state, the electromagnetic torque balances all mechanical losses: +\begin{equation} + K \, i_0 = \tau_c + B \, \omega_0 + \label{eq:noload} +\end{equation} +This provides one constraint on two unknowns ($\tau_c$ and $B$). Without additional data, the user must either assume one dominates or obtain friction measurements at multiple speeds. In MuJoCo terms, $\tau_c$ maps to \texttt{frictionloss} and $B$ to \texttt{damping}. + +\noindent Combining current saturation with both mechanical losses, the net torque is: +\begin{equation*} + \tau_{\text{net}} = \text{clip}\!\left( \frac{K}{R}(v - K \, \omega),\; + \pm K\, i_{\max} \right) - B \, \omega - \tau_c \, \text{sgn}(\omega) + \label{eq:net_torque} +\end{equation*} +The clipping applies to the electrical torque (current limit), while both friction terms are mechanical losses applied to the output post-clipping. Viscous drag $-B\omega$ tilts the envelope; Coulomb friction $-\tau_c\,\text{sgn}(\omega)$ shifts the right half ($\omega > 0$) down and the left half ($\omega < 0$) up, creating a $2\tau_c$ discontinuity at $\omega = 0$ (Figure~\ref{fig:drag_linear}). + +\begin{figure}[H] +\centering +\begin{subfigure}[t]{\columnwidth} +\centering +\begin{tikzpicture} +\pgfmathsetmacro{\taus}{1.3} +\pgfmathsetmacro{\wz}{1.0} +\pgfmathsetmacro{\taumax}{0.7} +\pgfmathsetmacro{\bvis}{0.3} +\pgfmathsetmacro{\tauf}{0.2} +\pgfmathsetmacro{\slope}{\taus/\wz} +\pgfmathsetmacro{\wcu}{(\taus-\taumax)/\slope} +\pgfmathsetmacro{\wcl}{(\taus+\taumax)/\slope} +\pgfmathsetmacro{\wext}{1.5} +\pgfmathsetmacro{\dragL}{\bvis*\wext} +\pgfmathsetmacro{\dragR}{-\bvis*\wext} +%% Right half vertices (ω ≥ 0): shifted down by τ_f +\pgfmathsetmacro{\Ra}{\taumax-\tauf} +\pgfmathsetmacro{\Rb}{\taumax-\bvis*\wcu-\tauf} +\pgfmathsetmacro{\Rc}{-\taumax-\bvis*\wcl-\tauf} +\pgfmathsetmacro{\Rd}{-\taumax-\tauf} +%% Left half vertices (ω ≤ 0): shifted up by τ_f +\pgfmathsetmacro{\La}{\taumax+\bvis*\wcl+\tauf} +\pgfmathsetmacro{\Lb}{\taumax+\tauf} +\pgfmathsetmacro{\Lc}{-\taumax+\tauf} +\pgfmathsetmacro{\Ld}{-\taumax+\bvis*\wcu+\tauf} +\begin{axis}[ + width=0.9\columnwidth, height=0.6\columnwidth, + axis lines=middle, + xlabel={$\omega$}, ylabel={$\tau$}, + xmin=-1.8, xmax=1.8, ymin=-1.8, ymax=1.8, + xtick=\empty, ytick=\empty, + tick style={thick}, + every axis x label/.style={at={(ticklabel* cs:1)}, anchor=west}, + every axis y label/.style={at={(ticklabel* cs:1)}, anchor=south}, +] +\fill[blue, opacity=0.08] + (0, \Ra) -- (\wcu, \Rb) -- (\wcl, \Rc) -- (0, \Rd) -- cycle; +\addplot[thick, blue] coordinates + {(0, \Ra) (\wcu, \Rb) (\wcl, \Rc) (0, \Rd)}; +\fill[blue, opacity=0.08] + (-\wcl, \La) -- (0, \Lb) -- (0, \Lc) -- (-\wcu, \Ld) -- cycle; +\addplot[thick, blue] coordinates + {(-\wcl, \La) (0, \Lb) (0, \Lc) (-\wcu, \Ld) (-\wcl, \La)}; +\addplot[thick, dashed, gray] coordinates {(0.01, {-\tauf-\bvis*0.01}) (\wext, {-\tauf+\dragR})}; +\addplot[thick, dashed, gray] coordinates {(-\wext, {\tauf+\dragL}) (-0.01, {\tauf+\bvis*0.01})}; +\node[font=\footnotesize, anchor=north west] at (axis cs: -1.75, -0.45) + {$-B\omega - \tau_c\,\text{sgn}(\omega)$}; +\draw[->, gray, thick] (axis cs: -1.4, -0.45) -- (axis cs: -1.3, {\tauf+\bvis}); +\pgfmathsetmacro{\gapmid}{(\Ra+\Lb)/2} +\draw[thick, <->, gray] (axis cs: 0.12, \Ra) -- (axis cs: 0.12, \Lb); +\node[font=\scriptsize, anchor=west] at (axis cs: 0.18, \gapmid) + {$2\tau_c$}; +\end{axis} +\end{tikzpicture} +\caption{Linear viscous drag and Coulomb friction.} +\label{fig:drag_linear} +\end{subfigure} + +\vspace{0.5em} + +\begin{subfigure}[t]{\columnwidth} +\centering +\begin{tikzpicture} +\pgfmathsetmacro{\taus}{1.3} +\pgfmathsetmacro{\wz}{1.0} +\pgfmathsetmacro{\taumax}{0.7} +\pgfmathsetmacro{\Bone}{0.15} +\pgfmathsetmacro{\Btwo}{0.35} +\pgfmathsetmacro{\slope}{\taus/\wz} +\pgfmathsetmacro{\wcl}{(\taus+\taumax)/\slope} +\pgfmathsetmacro{\wext}{1.7} +\begin{axis}[ + width=0.9\columnwidth, height=0.6\columnwidth, + axis lines=middle, + xlabel={$\omega$}, ylabel={$\tau$}, + xmin=-2.0, xmax=2.0, ymin=-2.0, ymax=2.0, + xtick=\empty, ytick=\empty, + tick style={thick}, + every axis x label/.style={at={(ticklabel* cs:1)}, anchor=west}, + every axis y label/.style={at={(ticklabel* cs:1)}, anchor=south}, + samples=200, +] +\addplot[name path=upper, thick, blue, domain=-\wcl:\wcl] + {min(\taus - \slope*x, \taumax) - \Bone*x - \Btwo*x*abs(x)}; +\addplot[name path=lower, thick, blue, domain=-\wcl:\wcl] + {max(-\taus - \slope*x, -\taumax) - \Bone*x - \Btwo*x*abs(x)}; +\addplot[blue, opacity=0.08] fill between[of=upper and lower]; +\addplot[thick, dashed, gray, domain=-\wext:\wext] + {-\Bone*x - \Btwo*x*abs(x)}; +\node[font=\footnotesize, anchor=north west] at (axis cs: -1.9, -0.5) + {$-b(\omega)$}; +\draw[->, gray, thick] (axis cs: -1.5, -0.5) -- (axis cs: -1.3, {0.1 + 0.35*1.3*1.3}); +\end{axis} +\end{tikzpicture} +\caption{Nonlinear viscous drag $b(\omega) = B_1\omega + B_2\omega|\omega|$, no friction.} +\label{fig:drag_nonlinear} +\end{subfigure} + +\caption{Torque-speed envelopes with mechanical losses. The dashed gray line shows the drag function; the shaded region is the achievable torque at each speed. Note that datasheet torque-speed curves typically plot the first quadrant only.} +\label{fig:drag} +\end{figure} + +\paragraph{Rotor Inertia and Gearing.} +Every DC motor datasheet lists the rotor inertia $J_r$ (kg$\cdot$m$^2$). When a gear train with ratio $N$ is attached, the effective inertia reflected to the output shaft is $J_{\text{eff}} = J_r N^2$~\cite{tedrake2024}. Note that real gearboxes also introduce efficiency losses (typically 70--90\%), which reduce the transmitted torque by a multiplicative factor $\eta$, approximated by effectively reducing the motor constant $K_{\text{eff}} = \eta K$. + +\paragraph{Cogging Torque.} +Brushless DC motors exhibit \emph{cogging torque}: a position-dependent torque ripple caused by the interaction between permanent magnets and stator slots. It can be modeled as a periodic bias: +\begin{equation} + \tau_{\text{cog}}(\theta) = A \sin(N_p \, \theta + \phi) + \label{eq:cogging} +\end{equation} +where $A$ is the amplitude, $N_p$ is the number of pole pairs times the number of slots per pole, and $\phi$ is a phase offset. Cogging torque is significant primarily at low speeds. Datasheets sometimes report peak cogging as a percentage of rated torque (typically 1--5\%). + +\begin{table}[H] +\centering +\footnotesize +\setlength{\tabcolsep}{3pt} +\renewcommand{\arraystretch}{1.2} +\begin{tabular}{@{}lll@{}} +\toprule +Symbol & Description & Formula / Note \\ +\midrule +$\tau_c$ & Coulomb friction & $\tau_c\,\text{sgn}(\omega)$ \\ +$B$ & Viscous drag (linear) & $B\,\omega$ \\ +$\omega_0$ & No-load speed & + $\omega_0 = v\,K / (K^2 + R\,B)$ \\ +$J_r$ & Rotor inertia & units: kg$\cdot$m$^2$ \\ +$N$ & Gear ratio & $J_{\text{eff}} = J_r N^2$ \\ +$\eta$ & Gearbox efficiency & $K' = \eta \, K$ \\ +$A$ & Cogging amplitude & $\tau_{\text{cog}} = A\sin(N_p\theta + \phi)$ \\ +$N_p$ & Cogging periodicity & poles $\times$ slots/pole \\ +$\phi$ & Cogging phase & offset \\ +\bottomrule +\end{tabular} +\caption{Named constants related to mechanical properties. Note that unlike in Table~\ref{tab:electromech_constants}, the non-approximate expression for $\omega_0$ takes into account the linear drag $B$ (assuming no high-order terms).} +\label{tab:key_constants} +\end{table} + +\paragraph{Backlash.} +Gearboxes introduce backlash: a small angular deadband where the motor can turn without moving the output shaft. Datasheets report this in arcminutes. MuJoCo supports backlash modeling via a dual-joint decomposition; \href{https://mujoco.readthedocs.io/en/stable/modeling.html#backlash}{see here} for details. + +% --------------------------------------------------------------------------- +% Thermal Model +% --------------------------------------------------------------------------- +\subsection{Thermal Model} +\label{sec:thermal} + +Winding temperature affects motor performance primarily through increased copper resistance, and can be modeled as a single lumped thermal state. The thermal constants are + +\begin{table}[H] +\centering +\footnotesize +\begin{tabular}{@{}lll@{}} +\toprule +Symbol & Description & Units \\ +\midrule +$R_T$ & Thermal resistance & Kelvin/Watt \\ +$C$ & Thermal capacitance & Joule/Kelvin \\ +$t_T = R_T C$ & Thermal time constant & second \\ +$\alpha$ & Resistance temp.\ coefficient & 1/Kelvin \\ +$T_0$ & Reference temperature & degree Celsius \\ +$T_a$ & Ambient temperature & degree Celsius \\ +\bottomrule +\end{tabular} +\caption{Thermal model constants. Units involving temperature differences use Kelvin (equivalent to Celsius for differences); absolute temperatures use degree Celsius, following datasheet convention.} +\end{table} + +\noindent Note that some manufacturers specify two thermal resistances: $R_{\text{th1}}$ (winding-to-housing) and $R_{\text{th2}}$ (housing-to-ambient), which sum to give the total winding-to-ambient thermal resistance $R_T = R_{\text{th1}} + R_{\text{th2}}$. The single-node model above uses $R_T$ directly. + +% - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +\subsubsection{Lumped Thermal ODE} +\label{sec:thermal_ode} + +The winding temperature $T$ evolves according to a first-order lumped model driven by the power dissipation $P$ (Watt, detailed in \S\ref{sec:thermal_losses}): +\begin{equation} + \frac{\partial T}{\partial t} = \frac{1}{C} P - \frac{T - T_a}{t_T} + \label{eq:thermal_ode} +\end{equation} +where $t_T = R_T C$ is the thermal time constant. This produces exponential rise/decay toward a steady-state temperature $T_{ss} = T_a + R_T P$ (Figure~\ref{fig:thermal_response}). + +\begin{figure}[ht] +\centering +\begin{tikzpicture} +\pgfmathsetmacro{\Tss}{1.0} +\pgfmathsetmacro{\ttau}{1.0} +\pgfmathsetmacro{\xmax}{4.5} +\begin{axis}[ + width=0.9\columnwidth, height=0.45\columnwidth, + axis lines=left, + clip=false, + xlabel={$t$}, ylabel={$T - T_a$}, + xmin=0, xmax=\xmax, ymin=0, ymax={\Tss*1.25}, + xtick={\ttau}, xticklabels={$t_T$}, + ytick={{\Tss*(1-exp(-1))}, \Tss}, + yticklabels={$(1{-}1/e)\,R_T P$, $R_T P$}, + tick style={thick}, + every axis x label/.style={at={(ticklabel* cs:1)}, anchor=west}, + every axis y label/.style={at={(ticklabel* cs:1)}, anchor=south}, +] +\addplot[thick, blue, domain=0:\xmax, samples=100] + {\Tss*(1 - exp(-x/\ttau))}; +\addplot[thick, dashed, gray] coordinates {(0,\Tss) (\xmax,\Tss)}; +\draw[thick, dashed, gray] (axis cs:\ttau, 0) -- (axis cs:\ttau, {\Tss*(1-exp(-1))}); +\draw[thick, dashed, gray] (axis cs:0, {\Tss*(1-exp(-1))}) -- (axis cs:\ttau, {\Tss*(1-exp(-1))}); +\node[font=\scriptsize, anchor=south] at (axis cs:\xmax*0.5, \Tss) + {$T_{ss} = T_a + R_T P$}; +\end{axis} +\end{tikzpicture} +\caption{Temperature rise under constant power dissipation $P$. + At $t = t_T$, it reaches $(1-1/e) \approx 63\%$ of its steady-state value.} +\label{fig:thermal_response} +\end{figure} + +% - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +\subsubsection{Losses} +\label{sec:thermal_losses} + +The dominant loss is copper (Joule) heating: +\begin{equation*} + P = i^2 R(T) + \label{eq:copper_loss} +\end{equation*} +Optionally, speed-dependent iron losses (eddy-current and hysteresis losses in the stator laminations) can be included~\cite{hughes2019}: +\begin{equation*} + P = i^2 R(T) + K_{\text{fe}} \omega^2 + \label{eq:total_loss} +\end{equation*} +The iron loss coefficient $K_{\text{fe}}$ is not typically listed on datasheets and must be identified from efficiency curves or manufacturer simulation tools. For most hobby and robotics motors, iron losses are small compared to copper losses and can be neglected. They become significant at high speeds in large industrial motors. + +% - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +\subsubsection{Temperature-Dependent Resistance} +\label{sec:resistance_temperature} + +Copper resistance increases approximately linearly with temperature: +\begin{equation} + R(T) = R_0 \left(1 + \alpha (T - T_0)\right) + \label{eq:resistance_temperature} +\end{equation} +where $R_0$ is resistance at reference temperature $T_0$ and $\alpha \approx 0.0039 \, \text{K}^{-1}$ for copper. This is the dominant thermal feedback: as $T$ rises, $R$ increases, so for a given voltage the current $i = (v - K \omega) / R(T)$ drops, reducing torque. + +Note that $R(T)$ also increases heating for a given current ($P = i^2 R(T)$), creating mild positive feedback under current control. + +% - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +\subsubsection{Magnet Flux Derating} +\label{sec:magnet_derating} + +Permanent magnet flux weakens with temperature, reducing $K$: +\begin{equation*} + K(T) = K_0 \left(1 + \alpha_m (T - T_0)\right) + \label{eq:kt_temperature} +\end{equation*} +with $\alpha_m < 0$ (motor-dependent). This effect is often small over normal operating ranges and can be ignored. + +% - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +\subsubsection{Thermal Derating} +\label{sec:thermal_derating} + +Real actuators limit current as winding temperature approaches a maximum: +\begin{equation*} + i_{\max}(T) = \begin{cases} + i_{\text{rated}} & T \le T_1 \\ + i_{\text{safe}} + (i_{\text{rated}} - i_{\text{safe}}) \, s(T) & T_1 < T < T_2 \\ + i_{\text{safe}} & T \ge T_2 + \end{cases} +\end{equation*} +where $s(T)$ is a smooth interpolant between $T_1$ and $T_2$. This reduces the maximum available torque as the motor heats up. + +% --------------------------------------------------------------------------- +% Micro-Friction Models +% --------------------------------------------------------------------------- +\subsection{Micro-Friction Models} +\label{sec:micro_friction} + +Simple macroscopic friction models (Coulomb, viscous) cannot capture complex mechanical phenomena common in real motors with gear trains, such as pre-sliding hysteresis and stick-slip limit cycles. To capture these behaviors, a richer dynamic model is required. At the microscopic level, two surfaces in contact touch at many asperities which deform elastically under tangential load. This can be modeled as an average bristle deflection $z$, governed by a first-order ODE driven by the relative velocity $\omega$. Friction torque is then a function of $z$, $\dot{z}$, and $\omega$. + +% - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +\subsubsection{Dahl Model} +\label{sec:dahl} + +The simplest stateful model~\cite{dahl68} treats friction as a rate-independent hysteresis operator derived from the stress-strain curve: +\begin{equation*} + \dot{z} = \omega - \frac{\sigma_0}{\tau_c} |\omega| \, z + \label{eq:dahl_state} +\end{equation*} +with output $\tau = -\sigma_0 z$. In steady state ($\dot{z}=0$), $z_{ss} = \tau_c \, \text{sgn}(\omega) / \sigma_0$ so $\tau_{ss} = -\tau_c \, \text{sgn}(\omega)$: pure Coulomb friction opposing motion. The two parameters are the bristle stiffness $\sigma_0$ (torque/radian) and the Coulomb friction torque $\tau_c$. +For small displacements the model is approximately linear ($\tau \approx -\sigma_0 \theta$), giving spring-like pre-sliding behavior with hysteresis during direction reversals (Figure~\ref{fig:hysteresis}). The Dahl model does not capture the Stribeck effect~\cite{stribeck1902} (the drop in friction at low velocity) and thus cannot predict stick-slip motion. + +\begin{figure}[H] +\centering +\begin{tikzpicture} +\begin{axis}[ + width=0.9\columnwidth, height=0.55\columnwidth, + axis lines=middle, + xlabel={$\theta$}, ylabel={$\tau$}, + xmin=-1.4, xmax=1.4, ymin=-1.4, ymax=1.4, + xtick=\empty, ytick=\empty, + every axis x label/.style={at={(ticklabel* cs:1)}, anchor=west}, + every axis y label/.style={at={(ticklabel* cs:1)}, anchor=south}, + clip=false, +] +\pgfmathsetmacro{\sig}{2.5} +\pgfmathsetmacro{\Fc}{1.0} +\pgfmathsetmacro{\xm}{1.0} +\pgfmathsetmacro{\ch}{(exp(\sig*\xm)+exp(-\sig*\xm))/2} +\addplot[thick, blue, domain=-\xm:\xm, samples=150, name path=lower] + {-\Fc*(1 - exp(-\sig*x)/\ch)}; +\addplot[thick, blue, domain=-\xm:\xm, samples=150, name path=upper] + {\Fc*(1 - exp(\sig*x)/\ch)}; +\addplot[blue, opacity=0.08] fill between[of=lower and upper]; +\draw[thick, dotted] (axis cs:-1.4, -\Fc) -- (axis cs:1.4, -\Fc) + node[right, font=\scriptsize] {$-\tau_c$}; +\draw[thick, dotted] (axis cs:-1.4, \Fc) -- (axis cs:1.4, \Fc) + node[right, font=\scriptsize] {$\tau_c$}; +\draw[->, thick, gray] (axis cs:0.05, -0.78) -- (axis cs:0.25, -0.83); +\draw[->, thick, gray] (axis cs:-0.05, 0.78) -- (axis cs:-0.25, 0.83); +\end{axis} +\end{tikzpicture} +\caption{Hysteresis loop: friction torque $\tau$ vs.\ displacement $\theta$ under slow + periodic loading (Dahl model). + The loop area represents energy dissipated per cycle. + Unlike memoryless Coulomb friction, the torque is continuous.} +\label{fig:hysteresis} +\end{figure} + +% - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +\subsubsection{LuGre Model} +\label{sec:lugre} + +The LuGre model~\cite{dewit95, lugre_revisited} extends Dahl by making the bristle saturation velocity-dependent and adding micro-damping and viscous terms: +\begin{subequations} +\label{eq:lugre} +\begin{align} + \dot{z} &= \omega - \sigma_0 \frac{|\omega|}{g(\omega)} z + \label{eq:lugre_state} \\ + \tau &= -(\sigma_0 z + \sigma_1 \dot{z} + \sigma_2 \omega) + \label{eq:lugre_force} +\end{align} +\end{subequations} +where the function $g(\omega)$ captures the Stribeck effect: +\begin{equation} + g(\omega) = \tau_c + (\tau_s - \tau_c) \, e^{-(\omega/\omega_s)^\gamma} + \label{eq:stribeck} +\end{equation} +with exponent $\gamma$ typically 1 or 2. In steady state, $\tau_{ss}(\omega) = -g(\omega) \, \text{sgn}(\omega) - \sigma_2 \omega$: the classic Stribeck curve (Figure~\ref{fig:stribeck}). + +\begin{figure}[H] +\centering +\begin{tikzpicture} +\begin{axis}[ + width=0.9\columnwidth, height=0.55\columnwidth, + axis lines=middle, + xlabel={$\omega$}, ylabel={$\tau_{ss}$}, + xmin=-3, xmax=3, ymin=-2.5, ymax=2.5, + xtick=\empty, ytick=\empty, + every axis x label/.style={at={(ticklabel* cs:1)}, anchor=west}, + every axis y label/.style={at={(ticklabel* cs:1)}, anchor=south}, + clip=false, +] +\pgfmathsetmacro{\Fc}{1.0} +\pgfmathsetmacro{\Fs}{1.8} +\pgfmathsetmacro{\vs}{0.5} +\pgfmathsetmacro{\sigtwo}{0.15} +\addplot[thick, blue, domain=0.01:3, samples=200] + {-(\Fc + (\Fs-\Fc)*exp(-(x/\vs)^2)) - \sigtwo*x}; +\addplot[thick, blue, domain=-3:-0.01, samples=200] + {(\Fc + (\Fs-\Fc)*exp(-(-x/\vs)^2)) - \sigtwo*x}; +\addplot[thick, dashed, gray, domain=-3:3, samples=2] {-\sigtwo*x}; +\draw[thick, dotted] (axis cs:0,-\Fs) -- (axis cs:3,-\Fs) + node[right, font=\scriptsize] {$-\tau_s$}; +\draw[thick, dotted] (axis cs:0,-\Fc) -- (axis cs:3,-\Fc) + node[right, font=\scriptsize] {$-\tau_c$}; +\draw[thick, dotted] (axis cs:0,\Fs) -- (axis cs:-3,\Fs) + node[left, font=\scriptsize] {$\tau_s$}; +\draw[thick, dotted] (axis cs:0,\Fc) -- (axis cs:-3,\Fc) + node[left, font=\scriptsize] {$\tau_c$}; +\node[font=\footnotesize, anchor=north east] at (axis cs:-0.5, -0.1) + {$-\sigma_2\omega$}; +\end{axis} +\end{tikzpicture} +\caption{Steady-state friction $\tau_{ss}(\omega) = -g(\omega)\,\text{sgn}(\omega) - \sigma_2 \omega$. + Stiction torque $\tau_s$ at $\omega\!=\!0$ drops to Coulomb level $\tau_c$ + over velocity scale $\omega_s$ (Stribeck effect). Friction opposes motion.} +\label{fig:stribeck} +\end{figure} + +\noindent The Dahl model is recovered by setting $g(\omega) = \tau_c$ and $\sigma_1 = \sigma_2 = 0$. Linearizing around $\omega = z = 0$ gives second-order dynamics $J\ddot{\theta} - (\sigma_1 + \sigma_2)\dot{\theta} - \sigma_0 \theta = \tau$ (applied torque): a spring-damper with natural frequency $\omega_n = \sqrt{\sigma_0/J}$, critically damped when $\sigma_1 = 2\sqrt{J\sigma_0}$. + +The LuGre model can be shown to be input-strictly-passive (the map $\omega \mapsto \tau$ dissipates energy) provided $\sigma_2 > \sigma_1 (\tau_s - \tau_c)/\tau_c$. This passivity condition limits $\sigma_1$ and can lead to underdamped micro-dynamics, motivating the following extension. + +% - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +\subsubsection{Velocity-Dependent Damping} +\label{sec:vel_damping} + +The passivity constraint on $\sigma_1$ can be relaxed by making the micro-damping decrease with velocity: +\begin{equation*} + \sigma_1(\omega) = \bar{\sigma}_1\, e^{-(\omega/\omega_s)^\beta} + \label{eq:sigma1_vel} +\end{equation*} +This allows large damping in the stiction regime (good for numerical stability and physical fidelity) while satisfying passivity at higher velocities where $\sigma_1 \to 0$. + +Together with $\tau_c$ from \S\ref{sec:mechanical}, the LuGre model with velocity-dependent damping adds six parameters: +\begin{table}[H] +\centering +\small +\begin{tabular}{@{}lll@{}} +\toprule +Symbol & Description & Units \\ +\midrule +$\sigma_0$ & Bristle stiffness, pre-sliding slope & N$\cdot$m/rad \\ +$\bar{\sigma}_1$ & Peak bristle damping at $\omega = 0$ & N$\cdot$m$\cdot$s/rad \\ +$\sigma_2$ & Viscous damping coefficient & N$\cdot$m$\cdot$s/rad \\ +$\tau_s$ & Stiction torque, $\tau_s \ge \tau_c$ & N$\cdot$m \\ +$\omega_s$ & Stribeck velocity & rad/s \\ +$\beta$ & Damping decay exponent & dimensionless \\ +\bottomrule +\end{tabular} +\caption{Parameters of the LuGre friction model (\S\ref{sec:lugre}--\ref{sec:vel_damping}).} +\label{tab:lugre_params} +\end{table} + + +\newpage +%============================================================================= +% IMPLEMENTATION +%============================================================================= +\section{Implementation} +\label{sec:implementation} + +Here we describe MuJoCo's \texttt{dcmotor} actuator. Some scalars are grouped into vectors; we use a colon to denote such scalar sub-attributes, e.g.\ \texttt{cogging:phase} refers to the third element of the \texttt{cogging} attribute (see Tables \ref{tab:mjcf_attributes} and \ref{tab:cogging_impl}). + +\begin{table}[H] +\centering +\footnotesize +\begin{tabular}{@{}lll@{}} +\toprule +Attribute & Size & Description \\ +\midrule +\texttt{resistance} & 1 & Terminal resistance $R$ \\ +\texttt{motorconst} & 2 & Motor constants ($K_t, K_e$; see below) \\ +\texttt{nominal} & 3 & Nominal operating point ($v_n, \tau_0, \omega_0$) \\ +\texttt{inductance} & 2 & Electrical dynamics ($L, t_e$) \\ +\texttt{thermal} & 6 & Thermal model ($R_T, C, t_T, \alpha, T_0, T_a$) \\ +\texttt{saturation} & 4 & Limits ($\tau_{\max}, i_{\max}, v_{\max}, (di{/}dt)_{\max}$) \\ +\midrule +\texttt{cogging} & 3 & Cogging torque ($A, N_p, \phi$) \\ +\texttt{lugre} & 6 & LuGre friction ($\sigma_0, \sigma_1, \sigma_2, \tau_c, \tau_s, \omega_s$) \\ +\texttt{damping} & 3 & Viscous damping coefficients \\ +\texttt{armature} & 1 & Armature inertia \\ +\midrule +\texttt{input} & keyword & Mode (voltage/position/velocity) \\ +\texttt{controller} & 5 & Gains and slew ($k_p, k_i, k_d, s, I_{\max}$) \\ +\bottomrule +\end{tabular} +\caption{MJCF attributes for the \texttt{dcmotor} actuator, split into electrical, mechanical and control groupings.} +\label{tab:mjcf_attributes} +\end{table} + +% --------------------------------------------------------------------------- +% Stateless dcmotor +% --------------------------------------------------------------------------- +\subsection{Stateless DC Motor} +\label{sec:dcmotor} + +The output torque of the stateless motor follows Eq.~\eqref{eq:saturation}, mapping physical parameters to the underlying affine model. The three core parameters are the effective motor constant $K$, resistance $R$, and maximum torque $\tau_{\max}$. +They are stored in \texttt{mjModel} as follows: + +\begin{table}[H] +\centering +\small +\begin{tabular}{@{}lll@{}} +\toprule +Symbol & Description & \texttt{mjModel} storage \\ +\midrule +$R$ & Resistance & \texttt{gainprm[0]} \\ +$K$ & Effective motor constant & \texttt{gainprm[1]} \\ +$\tau_{\max}$ & Maximum torque & \texttt{forcerange} \\ +\bottomrule +\end{tabular} +\caption{Stateless DC motor core parameters.} +\end{table} + +\noindent The gain $G = K/R$ and back-EMF bias $-GK\omega$ are computed at runtime. Storing $R$ separately allows temperature-dependent resistance $R(T)$, Eq.~\eqref{eq:resistance_temperature}, to be applied. These three core parameters can be specified with a combination of eight sub-attributes + +\begin{table}[H] +\centering +\small +\begin{tabular}{@{}lll@{}} +\toprule +Attribute & Symbol & Units \\ +\midrule +\atR{} & $R$ & Ohm \\ +\atKt{} & $K_t$ & N$\cdot$m/A \\ +\atKe{} & $K_e$ & V$\cdot$s/rad \\ +\atVM{} & $v_n$ & Volt \\ +\atSTALL{} & $\tau_0\!=\!Kv_n/R$ & N$\cdot$m \\ +\atNLS{} & $\omega_0\!\approx\!v_n/K$ & rad/s \\ +\atTMAX{} & $\tau_{\max}$ & N$\cdot$m \\ +\atIMAX{} & $i_{\max}$ & Ampere \\ +\bottomrule +\end{tabular} +\caption{Stateless DC motor basic attributes.} +\end{table} + +\noindent The attribute \atK{} has two sub-attributes, \texttt{Kt} and \texttt{Ke}. If both are positive, $K = \sqrt{K_t K_e}$ (preserving power balance $K^2 = K_t K_e$). If only one is positive, $K$ equals that value. + +\pagebreak +\noindent The following attribute combinations are supported: +\begin{enumerate}[itemsep=2pt, parsep=0pt, topsep=2pt] + \item Effective motor constant $K$, one of: + \begin{itemize}[itemsep=1pt, parsep=0pt, topsep=1pt] + \item \atKt{} \emph{and/or} \atKe{} + \item \atNLS{} \emph{and} \atVM{} + \end{itemize} + \item Resistance $R$, one of: + \begin{itemize}[itemsep=1pt, parsep=0pt, topsep=1pt] + \item \atR{} + \item \atSTALL{} \emph{and} \atVM{} + \end{itemize} + \item Maximum torque $\tau_{\max}$, one of: + \begin{itemize}[itemsep=1pt, parsep=0pt, topsep=1pt] + \item \atTMAX{} + \item \atIMAX{} + \end{itemize} +\end{enumerate} + +\noindent \atIMAX{} corresponds to the continuous (thermal) current limit. Peak current behavior can be approximated with the thermal model (\S\ref{sec:temperature_impl}). + +\paragraph{Rotor Inertia and Gearing.} To model rotor inertia with a gear train, set the actuator's \texttt{armature} $= J_r$ and \texttt{gear} $= N$. Actuator-level \texttt{armature} automatically scales the inertia by $N^2$ to reflect $J_{\text{eff}}$ to the output shaft. + +\paragraph{Mechanical Drag.} The full torque-speed envelope applies viscous drag \emph{outside} the current clamp: +\begin{equation*} + \tau_{\text{net}} = \text{clip}\!\left( \frac{K}{R}(v - K \, \omega),\; + \pm \tau_{\max} \right) - b(\omega) + \label{eq:drag} +\end{equation*} +Actuator-level \texttt{damping} reproduces this post-clamp behavior. It accepts an array of polynomial drag coefficients (\texttt{damping[0]} $= B_1$, \texttt{damping[1]} $= B_2$, $\dots$). As with \texttt{armature}, actuator-level \texttt{damping} is scaled by $N^2$. + +\paragraph{Cogging Torque.} The magnetic torque ripple of Eq.~\eqref{eq:cogging} is modeled as a periodic bias added to the actuator force, where $\theta$ is the \texttt{actuator\_length}, i.e.\ the transmission-transformed joint angle. + +\begin{table}[H] +\centering +\small +\begin{tabular}{@{}lll@{}} +\toprule +Attribute & Symbol & Units \\ +\midrule +\atCOGA{} & $A$ & N$\cdot$m \\ +\atCOGP{} & $N_p$ & dimensionless \\ +\atCOGPH{} & $\phi$ & radian \\ +\bottomrule +\end{tabular} +\caption{Cogging torque attributes.} +\label{tab:cogging_impl} +\end{table} + +\paragraph{Mapping to Isaac Lab.} +Isaac Lab~\cite{isaaclab2025} implements the stateless DC motor model. Table~\ref{tab:mapping} maps its attributes to the constants defined in this document and to the \texttt{dcmotor} attributes. + +\begin{table}[H] +\centering +\footnotesize +\begin{tabular}{@{}lll@{}} +\toprule +Symbol & MuJoCo & Isaac Lab \\ +\midrule +$\tau_0$ & \atSTALL{} & \texttt{saturation\_effort} \\ +$\omega_0$ & \atNLS{} & \texttt{velocity\_limit} \\ +$\tau_{\max}$ & \atTMAX{} & \texttt{effort\_limit} \\ +\bottomrule +\end{tabular} +\caption{Mapping of attributes to Isaac Lab.} +\label{tab:mapping} +\end{table} + +\noindent Isaac Lab does not expose electrical parameters. To reproduce the same torque-speed envelope, set \atVM{} to any positive value (e.g.,~\texttt{1}) and \texttt{ctrlrange} to $\pm$\,that value (e.g., \texttt{"-1 1"}). + +\paragraph{Gearbox Efficiency.} Gearbox efficiency $\eta$ is not a separate attribute. To account for transmission losses, reduce the motor constant: $K \rightarrow \eta K$. This correctly reduces forward torque transmission. + +\paragraph{Computed parameters.} +Several derived quantities that appear on datasheets can be computed and used to cross-check the parameterization. The torque-speed gradient $\partial\omega/\partial\tau = -R/K^2$ gives the slope of the torque-speed line (Table~\ref{tab:electromech_constants}). The mechanical time constant $t_m = R\,J/K^2$ is the time for the motor to reach 63\% of its no-load speed under a voltage step, where $J$ is the rotor inertia (\texttt{armature}). The nominal (continuous) torque is $\tau_n = K \cdot i_{\max}$. The no-load current $i_0$ can be computed from Eq.~\eqref{eq:noload} given known friction parameters. See Table~\ref{tab:datasheet}. + +\paragraph{Not modeled:} +Nonlinear torque constant $K_t(i)$. Separate $K_t$ and $K_e$ values are accepted via \atKt{} and \atKe{} but collapsed to a single effective $K = \sqrt{K_t K_e}$. + + +% --------------------------------------------------------------------------- +% Stateful Current +% --------------------------------------------------------------------------- +\subsection{Stateful Current} +\label{sec:current_impl} + +A winding current state variable governed by Eq.~\eqref{eq:inductance} is added if the electrical time constant $t_e > 0$ (derived from inductance $L > 0$ or specified directly). When enabled, the state is integrated by \texttt{mjDYN\_DCMOTOR}, and the gain switches from $K/R$ (stateless) to $K$ (stateful). +The time constant $t_e$ can be determined by either: + +\begin{itemize}[itemsep=0pt, parsep=0pt, topsep=2pt] + \item \atTE{} + \item \atL{} \emph{and} \atR{} (via $t_e = L/R$) +\end{itemize} + +\paragraph{Current rate limiting.} When the sub-attribute \atCRATE{} is set ($(di/dt)_{\max} > 0$) and the current state is enabled ($t_e > 0$), the rate of change of current is clamped: +\begin{equation*} + \frac{di}{dt} \leftarrow \text{clip}\!\left(\frac{di}{dt},\; \pm(di/dt)_{\max}\right) +\end{equation*} +This limits the torque ramp rate to $K \cdot (di/dt)_{\max}$ (N$\cdot$m/s) without requiring any additional state variables, since the current $i$ is already an activation variable and we are simply clamping its rate of change. This attribute has no effect when $t_e = 0$ (stateless current). + +\begin{table}[H] +\centering +\footnotesize +\begin{tabular}{@{}lll@{}} +\toprule +Attribute & Symbol & Units \\ +\midrule +\atL{} & $L$ & Henry \\ +\atTE{} & $t_e\!=\!L/R$ & second \\ +\atCRATE{} & $(di{/}dt)_{\max}$ & Ampere/second \\ +\bottomrule +\end{tabular} +\caption{Stateful current attributes.} +\end{table} + +% --------------------------------------------------------------------------- +% Temperature +% --------------------------------------------------------------------------- +\subsection{Temperature} +\label{sec:temperature_impl} + +A winding temperature state governed by the lumped ODE~\eqref{eq:thermal_ode} is added if any of the thermal attributes ($R_T, C, t_T$) are specified. The state $T$ is the temperature rise above ambient ($T = T_{\text{winding}} - T_a$), so the absolute temperature is $T + T_a$. Temperature modifies the winding resistance via Eq.~\eqref{eq:resistance_temperature}, which feeds back into the motor equation: higher temperature increases resistance, leading to reduced current for a given voltage. + +\begin{table}[H] +\centering +\small +\begin{tabular}{@{}lll@{}} +\toprule +Attribute & Symbol & Units \\ +\midrule +\atRT{} & $R_T$ & K/W \\ +\atTC{} & $C$ & J/K \\ +\atTT{} & $t_T\!=\!R_T C$ & s \\ +\atALPHA{} & $\alpha$ & 1/K \\ +\atTREF{} & $T_0$ & \textdegree C \\ +\atTAMB{} & $T_a$ & \textdegree C \\ +\bottomrule +\end{tabular} +\caption{Thermal model attributes.} +\end{table} + +\noindent The time constant $t_T$ can be determined by either: +\begin{itemize}[itemsep=0pt, parsep=0pt, topsep=2pt] + \item \atTT{} + \item \atRT{} \emph{and} \atTC{} +\end{itemize} + +\paragraph{Not modeled:} +Iron losses (\S\ref{sec:thermal_losses}), magnet flux derating (\S\ref{sec:magnet_derating}), and thermal current derating (\S\ref{sec:thermal_derating}). Only copper losses ($i^2 R$) drive the thermal model; $K$ is treated as temperature-independent. + +% --------------------------------------------------------------------------- +% Stateful Friction +% --------------------------------------------------------------------------- +\subsection{Stateful Friction} +\label{sec:friction_impl} + +A bristle deflection state governed by the LuGre model (\S\ref{sec:lugre}) is added if the bristle stiffness $\sigma_0 > 0$. + +The Stribeck function $g(\omega)$, Eq.~\eqref{eq:stribeck}, determines velocity-dependent friction, and the friction force is given by Eq.~\eqref{eq:lugre_force}. The bristle state is integrated using the exact ZOH scheme~\eqref{eq:zoh}. The viscous term $\sigma_2 \omega$ is mapped directly to the standard \texttt{actuator\_damping} attribute to leverage MuJoCo's implicit integration, while maintaining the $\sigma_2$ \texttt{lugre} sub-attribute for convenience. +\paragraph{Integration.} +The bristle stiffness $\sigma_0$ is typically very large ($10^5$--$10^6$ N$\cdot$m/rad), creating a stiff ODE. At constant velocity, the state equation~\eqref{eq:lugre_state} has the form $\dot{z} = a z + b \omega$ where $a = -\sigma_0 |\omega| / g(\omega)$ and $b = 1$. Euler integration is unstable unless $|1 + a \Delta t| < 1$, requiring impractically small timesteps ($\Delta t < 2g(\omega)/(\sigma_0 |\omega|)$, on the order of microseconds). +Under a zero-order hold assumption ($\omega$ constant over the timestep), the linear ODE $\dot{z} = az + b\omega$ can be solved exactly: +\begin{equation} + z_{k+1} = e^{a \Delta t} z_k + + \frac{b(e^{a \Delta t} - 1)}{a} \, \omega + \label{eq:zoh} +\end{equation} +reducing to $z_{k+1} = z_k + b\omega\Delta t$ in the limit $a \to 0$. This integration is unconditionally stable for any $\Delta t$. + +\begin{table}[H] +\centering +\small +\begin{tabular}{@{}lll@{}} +\toprule +Attribute & Symbol & Units \\ +\midrule +\atSIG{} & $\sigma_0$ & N$\cdot$m/rad \\ +\atSIGD{} & $\sigma_1$ & N$\cdot$m$\cdot$s/rad \\ +\atSIGV{} & $\sigma_2$ & N$\cdot$m$\cdot$s/rad \\ +\atTAUC{} & $\tau_c$ & N$\cdot$m \\ +\atTAUS{} & $\tau_s$ & N$\cdot$m \\ +\atWS{} & $\omega_s$ & rad/s \\ +\bottomrule +\end{tabular} +\caption{LuGre friction attributes.} +\end{table} + +\noindent\textbf{Not modeled:} +Velocity-dependent bristle damping $\sigma_1(\omega)$ (\S\ref{sec:vel_damping}), a constant $\sigma_1$ is used. The Stribeck exponent is not exposed and fixed at $\gamma = 2$. + +\newpage +% --------------------------------------------------------------------------- +% PID Controller +% --------------------------------------------------------------------------- +\subsection{PID Controller} +\label{sec:controller} + +Many actuators embed an on-board controller computing drive voltage from position or velocity commands. To model such actuators, \texttt{dcmotor} supports an optional controller layer upstream of the motor physics. Two attributes control this behavior: + +\begin{table}[H] +\centering +\small +\begin{tabular}{@{}lll@{}} +\toprule +Attribute & Type & Description \\ +\midrule +\texttt{input} & keyword & \texttt{voltage}, \texttt{position}, \texttt{velocity} \\ +\texttt{controller} & vector & Gains (mode-dependent) \\ +\bottomrule +\end{tabular} +\caption{Controller attributes. Default \texttt{input} is \texttt{voltage}.} +\label{tab:controller_attributes} +\end{table} + +\noindent Unlike the motor parameters in Table~\ref{tab:datasheet}, controller gains are user-specified firmware settings. Gains are in {\em voltage-space} (e.g., $k_p$ in V/rad) since the output is a voltage $v$. To convert from physical torque-space (N$\cdot$m/rad), multiply by $R/K$. + +The controller computes a target voltage $v$ from the \texttt{ctrl} command. All motor physics --- cogging, saturation, friction, etc. --- apply identically downstream of $v$. The \texttt{input} attribute selects the controller: + +\begin{figure}[H] +\centering +\begin{tikzpicture}[ + block/.style={draw, rounded corners=2pt, minimum height=1.6em, + font=\scriptsize, fill=blue!5}, + mode/.style={font=\scriptsize, text=blue!70!black}, + arr/.style={->, thick, >=stealth}, + every node/.style={inner sep=2pt}, +] +% ctrl input +\node[font=\small] (ctrl) at (0, 3.5) {Input $u = {}$\texttt{ctrl}}; + +% Mode selector box +\node[block, minimum width=5.5cm, minimum height=6.5em, align=center] + (sel) at (0, 1.8) {}; +\node[font=\footnotesize\bfseries, anchor=north] at (0, 2.7) + {Controller mode}; +\node[mode] at (0, 1.45) {$\begin{aligned} + \texttt{voltage:}\quad v &= u \\[2pt] + \texttt{position:}\quad v &= k_p(u\!-\!\theta) + k_i x_I - k_d\dot\theta \\[2pt] + \texttt{velocity:}\quad v &= k_p(u\!-\!\dot\theta) + k_i(x_I\!-\!\theta) +\end{aligned}$}; + +% arrow ctrl to mode +\draw[arr] (ctrl.south) -- (sel.north); + +% Motor block +\node[block, font=\footnotesize\bfseries, minimum width=5.5cm, minimum height=2.2em, align=center] + (motor) at (0, -0.8) {DC Motor physics}; + +% single arrow with v label +\draw[arr] (sel.south) -- (motor.north) + node[midway, fill=white, font=\small, inner sep=2pt] {Voltage $v$}; + +% output +\node[font=\small] (tau) at (0, -1.8) {Torque $\tau$}; +\draw[arr] (motor.south) -- (tau.north); + +\end{tikzpicture} +\caption{Controller pipeline. The \texttt{input} attribute selects how $v$ is derived from \texttt{ctrl}; motor physics is identical downstream.} +\label{fig:controller_pipeline} +\end{figure} + +% - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +\subsubsection{Position Mode} +\label{sec:position_mode} + +When \texttt{input="position"}, the user command $u = {}$\texttt{ctrl} is a target position, yielding voltage: +\begin{equation} + v = k_p \, (u - \theta) + k_i \, x_I - k_d \, \dot\theta + \label{eq:position_mode} +\end{equation} +where $\theta$ is the actuator length, $\dot\theta \equiv \omega$ is the actuator velocity, $x_I$ is the integral of position error, and $k_p$, $k_i$, $k_d$ are the proportional, integral, and derivative gains. + +\noindent The signs in~\eqref{eq:position_mode} follow MuJoCo convention: $k_p > 0$ drives toward the target, $k_d > 0$ provides damping (opposing velocity), and $k_i > 0$ reduces steady-state error. + +\paragraph{Integral state.} When $k_i > 0$, one additional activation state $x_I$ is allocated, governed by: +\begin{equation*} + \dot{x}_I = u - \theta + \label{eq:position_integral} +\end{equation*} +When $k_i = 0$, no integral state is added and the controller reduces to PD. + +\paragraph{Effective torque.} Substituting~\eqref{eq:position_mode} into the stateless torque equation~\eqref{eq:torque_speed}: +\begin{equation*} + \tau = \frac{K}{R} v - \frac{K^2}{R}\dot\theta + = \underbrace{\frac{K k_p}{R}}_{\text{stiffness}} (u - \theta) + + \frac{K k_i}{R} x_I + - \underbrace{\frac{K(K + k_d)}{R}}_{\text{damping}} \dot\theta + \label{eq:position_torque} +\end{equation*} +Note that the motor's back-EMF term $K^2\dot\theta/R$ contributes {\em additional damping} beyond the controller $k_d$ term. Even with $k_d\!=\!0$, the motor provides natural damping $K^2/R$. The computed $v$ is subject to voltage saturation (\S\ref{sec:voltage_saturation}). + +\begin{table}[H] +\centering +\small +\begin{tabular}{@{}lll@{}} +\toprule +Attribute & Symbol & Units \\ +\midrule +\atKP{} & $k_p$ & V/rad \\ +\atKI{} & $k_i$ & V/(rad$\cdot$s) \\ +\atKD{} & $k_d$ & V$\cdot$s/rad \\ +\bottomrule +\end{tabular} +\caption{Position mode controller gains.} +\label{tab:position_params} +\end{table} + +% - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +\subsubsection{Velocity Mode} +\label{sec:velocity_mode} + +When \texttt{input="velocity"}, the user command $u = {}$\texttt{ctrl} is a target velocity, and $k_p$, $k_i$ are the proportional and integral gains. +\begin{equation} + v = k_p \, (u - \dot\theta) + k_i \, (x_I - \theta) + \label{eq:velocity_mode} +\end{equation} + +\paragraph{Integral state.} When $k_i > 0$, one additional activation state $x_I$ is allocated, governed by the integrator: +\begin{equation*} + \dot{x}_I = u + \label{eq:velocity_integral} +\end{equation*} +The term $k_i(x_I - \theta)$ then tracks a target position $x_I$ advancing at the commanded velocity $u$. This matches MuJoCo's \texttt{intvelocity} actuator behavior. + +When $k_i = 0$, no integral state is added and the controller provides pure velocity feedback. The computed $v$ is subject to voltage saturation (\S\ref{sec:voltage_saturation}). + +\paragraph{Effective torque.} Substituting~\eqref{eq:velocity_mode} into~\eqref{eq:torque_speed}: +\begin{equation*} + \tau = \underbrace{\frac{K k_i}{R}}_{\text{stiffness}} (x_I - \theta) + - \underbrace{\frac{K(K + k_p)}{R}}_{\text{damping}} \dot\theta + + \frac{K k_p}{R} u + \label{eq:velocity_torque} +\end{equation*} +Note the role swap compared to position mode: $k_i$ provides stiffness (position tracking to $x_I$) while $k_p$ adds damping alongside the motor's natural back-EMF damping $K^2/R$. + +\begin{table}[H] +\centering +\small +\begin{tabular}{@{}lll@{}} +\toprule +Attribute & Symbol & Units \\ +\midrule +\atKP{} & $k_p$ & V$\cdot$s/rad \\ +\atKI{} & $k_i$ & V/rad \\ +\bottomrule +\end{tabular} +\caption{Velocity mode controller gains.} +\label{tab:velocity_params} +\end{table} + +\pagebreak + +% - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +\subsubsection{Setpoint Slew Rate} +\label{sec:setpoint_slew} + +The user command $u = {}$\texttt{ctrl} can change discontinuously between timesteps. When \atSLEW{} is set ($s > 0$), the effective setpoint is rate-limited: +\begin{equation*} + u \leftarrow \text{clip}(u, \; u_{\text{prev}} \pm s \cdot \Delta t) +\end{equation*} +where $u_{\text{prev}}$ is the previous effective setpoint and $\Delta t$ is the timestep. This smoothly ramps the reference trajectory instead of allowing instantaneous jumps. + +\paragraph{State variable.} When $s > 0$, one activation state $u_{\text{prev}}$ is allocated, and updated each step to $u$ (post-clamping). + +\paragraph{Units.} The slew rate $s$ has mode-dependent units: rad/s for position mode (limiting setpoint velocity), rad/s\textsuperscript{2} for velocity mode (limiting setpoint acceleration), and V/s for voltage mode. + +% - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +\subsubsection{Anti-windup} +\label{sec:anti_windup} + +When $k_i > 0$, the integrator state $x_I$ provides steady-state error correction. However, sustained saturation or large setpoint changes can cause $x_I$ to grow excessively, leading to overshoot (integral windup). To prevent this, when \atIMAXINT{} is set ($I_{\max} > 0$), the state is bounded each step: +\begin{equation*} + x_I \leftarrow \text{clip}(x_I, \pm I_{\max}) +\end{equation*} +This prevents controller windup even when drive signals are saturated. + +% - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - +\subsubsection{Voltage Saturation} +\label{sec:voltage_saturation} + +In \texttt{position} and \texttt{velocity} modes, the computed voltage $v$ can be arbitrarily large (proportional to the error). Real motor drivers are limited by their supply voltage. When \atVMAX{} is set ($v_{\max} > 0$), a voltage clamp is applied before the motor equations: +\begin{equation*} + v \leftarrow \text{clip}(v, \pm v_{\max}) + \label{eq:vlimit} +\end{equation*} +This differs from \texttt{ctrlrange} (clamping user command $u$) and \texttt{forcerange} (clamping output torque). In position and velocity modes, \texttt{ctrlrange} limits the setpoint while \atVMAX{} limits the drive signal. In voltage mode ($v = u$), both clamp the voltage; if both are set, the tighter limit wins. + +\begin{table}[H] +\centering +\small +\begin{tabular}{@{}lll@{}} +\toprule +Attribute & Symbol & Units \\ +\midrule +\atKP{} & $k_p$ & mode-dependent \\ +\atKI{} & $k_i$ & mode-dependent \\ +\atKD{} & $k_d$ & V$\cdot$s/rad \\ +\atSLEW{} & $s$ & ctrl-units/s \\ +\atIMAXINT{} & $I_{\max}$ & mode-dependent \\ +\atVMAX{} & $v_{\max}$ & Volt \\ +\bottomrule +\end{tabular} +\caption{Controller attributes.} +\label{tab:controller_attrs} +\end{table} + +% --------------------------------------------------------------------------- +% Low-Level Semantics +% --------------------------------------------------------------------------- +\subsection{Low-Level Semantics} +\label{sec:array_semantics} + +The \texttt{dcmotor} actuator uses the enum value types \texttt{mjGAIN\_DCMOTOR}, \texttt{mjDYN\_DCMOTOR}, \texttt{mjBIAS\_DCMOTOR}, and populates the rows of several \texttt{mjModel} arrays (all \texttt{actuator\_*}), as follows: + +\begin{table}[H] +\centering +\footnotesize +\begin{tabular}{@{}llll@{}} +\toprule +Array & Index & Symbol & Description \\ +\midrule +\texttt{gainprm} & 0 & $R$ & Resistance ($\Omega$) \\ +& 1 & $K$ & Motor constant (N$\cdot$m/A) \\ +& 2 & $\alpha$ & Resistance coeff.\ ($\text{K}^{-1}$) \\ +& 3 & $T_0$ & Reference temperature (\textdegree C) \\ +& 4 & $k_p$ & Controller proportional gain \\ +& 5 & $k_i$ & Controller integral gain \\ +& 6 & $k_d$ & Controller derivative gain \\ +& 7 & $v_{\max}$ & Voltage saturation (V) \\ +& 8 & --- & Input mode (0:\ $v$, 1:\ $\theta$, 2:\ $\dot\theta$) \\ +\midrule +\texttt{dynprm} & 0 & $t_e$ & Electrical time constant (s) \\ +& 1 & $(di{/}dt)_{\max}$ & Current rate limit (A/s) \\ +& 2 & $R_T$ & Thermal resistance ($\text{K}$/W) \\ +& 3 & $C$ & Thermal capacitance (J/$\text{K}$) \\ +& 4 & $T_a$ & Ambient temperature (\textdegree C) \\ +& 5 & $\sigma_0$ & LuGre bristle stiffness \\ +& 6 & $\sigma_1$ & LuGre bristle damping \\ +& 7 & $s$ & Controller slew rate \\ +& 8 & $I_{\max}$ & Integral limit (anti-windup) \\ +\midrule +\texttt{biasprm} & 0 & $A$ & Cogging amplitude (N$\cdot$m) \\ +& 1 & $N_p$ & Cogging periodicity \\ +& 2 & $\phi$ & Cogging phase (rad) \\ +& 3 & $\tau_c$ & LuGre Coulomb fric. (N$\cdot$m) \\ +& 4 & $\tau_s$ & LuGre static fric. (N$\cdot$m) \\ +& 5 & $\omega_s$ & Stribeck velocity (rad/s) \\ +\midrule +\texttt{forcerange} & 0 & $-\tau_{\max}$ & Minimum torque (N$\cdot$m) \\ +& 1 & $\tau_{\max}$ & Maximum torque (N$\cdot$m) \\ +\midrule +\texttt{damping} & 0 & $B_1 (+\sigma_2)$ & Linear (+ LuGre viscous) \\ +& 1 & $B_2$ & Quadratic \\ +& 2 & $B_3$ & Cubic \\ +\midrule +\texttt{armature} & 0 & $J_r$ & Actuator armature \\ +\midrule +\texttt{gear} & 0 & $N$ & Gear ratio \\ +\bottomrule +\end{tabular} +\caption{\texttt{mjModel} array semantics for the \texttt{dcmotor} actuator.} +\label{tab:array_semantics} +\end{table} + +\paragraph{Runtime mutability.} +Most \texttt{mjModel} parameters listed above may be freely modified at runtime for system identification or gain tuning. However, five parameters control the \emph{number} of activation states, which is determined at compile time and cannot change during simulation. Toggling any of the following parameters between zero and positive after compilation is an error: +\begin{table}[H] +\centering +\small +\begin{tabular}{@{}llcl@{}} +\toprule +Parameter & Storage & State & Semantics \\ +\midrule +$s$ & \texttt{dynprm[7]} & $u_{\text{prev}}$ & previous control \\ +$k_i$ & \texttt{gainprm[5]} & $x_I$ & controller integral \\ +$R_T, C$ & \texttt{dynprm[2,3]} & $T$ & temperature rise \\ +$\sigma_0$ & \texttt{dynprm[5]} & $z$ & bristle deflection \\ +$t_e$ & \texttt{dynprm[0]} & $i$ & winding current \\ +\bottomrule +\end{tabular} +\caption{Compile-time state switches, allocated in \texttt{act} in the order shown. Do not toggle between zero and positive at runtime.} +\end{table} + + +\onecolumn +%============================================================================= +% DATASHEET MAPPING +%============================================================================= +\section{Datasheet Mapping} +\label{sec:datasheet} + +Table~\ref{tab:datasheet} maps commercial motor datasheet specifications to attributes. The left column shows the datasheet entry as typically labeled by motor manufacturers; the right column shows the corresponding \texttt{dcmotor} MJCF attribute, when one exists. Derived quantities that are not direct attributes (gradient, mechanical time constant) are included for completeness. + +\begin{table}[H] +\centering +\small +\begin{tabular}{@{}lllll@{}} +\toprule +Specification & Symbol & Formula / Note & Datasheet Symbol & Attribute \\ +\midrule +Resistance & $R$ & Terminal resistance & R, Ra & \atR{} \\ +Torque Constant & $K_t$ & $\tau = K_t i$ & kt, km & \atKt{} \\ +Back-EMF Constant & $K_e$ & $v_{\text{back}} = K_e \omega$ & ke & \atKe{} \\ +Speed Constant & $K_v$ & $K_v = 1/K_e$ & kn, kv & $1/$\atKe{} \\ +Nominal Voltage & $v_n$ & Rated voltage (e.g., 24V) & Un, VDC & \atVM{} \\ +No-load Speed & $\omega_0$ & $\omega_0 \approx v_n / K$ & n0 & \atNLS{} \\ +Stall Torque & $\tau_0$ & $\tau_0 = K v_n / R$ & MH, Ts & \atSTALL{} \\ +Stall Current & $i_s$ & Max.\ possible: $i_s = v_n / R$ & IA & \\ +Nominal Current & $i_{\max}$ & Thermal limit (continuous) & Ic, IN & \atIMAX{} \\ +Peak Current & $i_{\text{peak}}$ & Short-term limit & Ipk & \\ +\midrule +Coulomb Friction & $\tau_c$ & Dry friction opposing motion & $T_f$ & \texttt{frictionloss} (joint)\\ +Viscous Friction & $B$ & Drag $\propto \omega$ & $C_v$ & \texttt{damping} \\ +Rotor Inertia & $J_r$ & Reflected: $J_{\text{eff}} = J_r N^2$ & J, Jm & \texttt{armature} \\ +Gear Ratio & $N$ & Reduction ratio & $N$, $i$ & \texttt{gear} \\ +Gearbox Efficiency & $\eta$ & Fold into $K$: use $\eta K$ & $\eta$ & \\ +Cogging Amplitude & $A$ & Peak cogging torque & --- & \atCOGA{} \\ +Cogging Periodicity & $N_p$ & Poles $\times$ slots/pole & --- & \atCOGP{} \\ +\midrule +Nominal Torque & $\tau_n$ & $\tau_n = K \cdot i_{\max}$ & $M_N$, $T_c$ & \\ +No-load Current & $i_0$ & Friction: Eq.~\eqref{eq:noload} & $I_0$ & \\ +Gradient & $\partial\omega/\partial\tau$ & $-R / K^2$ & $\Delta n / \Delta M$ & \\ +Mech.\ Time Const. & $t_m$ & $t_m = R\,J / K^2$ & $\tau_m$ & \\ +\midrule +Inductance & $L$ & Terminal inductance & L & \atL{} \\ +Elec.\ Time Const. & $t_e$ & $t_e = L / R$ & $\tau_e$ & \atTE{} \\ +\midrule +Thermal Resistance & $R_T$ & Winding-to-ambient & Rth & \atRT{} \\ +Thermal Capacitance & $C$ & $C = t_T / R_T$ & $C_{\text{th}}$ & \atTC{} \\ +Thermal Time Const. & $t_T$ & $t_T = R_T C$ & $\tau_{\text{th}}$ & \atTT{} \\ +Ref.\ Temperature & $T_0$ & Temperature at which $R$ is specified & $T_{\text{ref}}$ & \atTREF{} \\ +Ambient Temperature & $T_a$ & Operating environment & --- & \atTAMB{} \\ +Max.\ Winding Temp. & $T_{\max}$ & Absolute limit & $T_{\max}$ & \\ +Res.\ Temp.\ Coeff. & $\alpha$ & $\approx 0.0039\, \text{K}^{-1}$ (copper) & $\alpha_{\text{Cu}}$ & \atALPHA{} \\ +\bottomrule +\end{tabular} +\caption{Datasheet parameters and their relation to model constants. Groups: electrical, mechanical, derived, inductance, thermal.} +\label{tab:datasheet} +\end{table} + +\small +\bibliographystyle{ieeetr} +\bibliography{refs} + +\end{document} diff --git a/doc/dcmotor/refs.bib b/doc/dcmotor/refs.bib new file mode 100644 index 0000000000..29708bc7d3 --- /dev/null +++ b/doc/dcmotor/refs.bib @@ -0,0 +1,82 @@ +@article{dewit95, + author = {Canudas de Wit, C. and Olsson, H. and {\AA}str{\"o}m, K. J. and Lischinsky, P.}, + title = {{A New Model for Control of Systems with Friction}}, + journal = {IEEE Transactions on Automatic Control}, + volume = {40}, + number = {3}, + pages = {419--425}, + year = {1995}, + month = mar, +} + +@article{lugre_revisited, + author = {{\AA}str{\"o}m, K. J. and Canudas de Wit, C.}, + title = {{Revisiting the LuGre Friction Model}}, + journal = {IEEE Control Systems Magazine}, + volume = {28}, + number = {6}, + pages = {101--114}, + year = {2008}, + month = dec, +} + +@techreport{dahl68, + author = {Dahl, P.}, + title = {{A Solid Friction Model}}, + institution = {The Aerospace Corporation}, + address = {El Segundo, CA}, + number = {TOR-0158(3107-18)-1}, + year = {1968}, +} + +@book{hughes2019, + author = {Hughes, Austin and Drury, Bill}, + title = {{Electric Motors and Drives: Fundamentals, Types and Applications}}, + edition = {5th}, + publisher = {Newnes}, + year = {2019}, +} + +@book{tedrake2024, + author = {Tedrake, Russ}, + title = {{Underactuated Robotics: Algorithms for Walking, Running, + Swimming, Flying, and Manipulation}}, + publisher = {MIT}, + year = {2024}, + note = {Course notes for MIT 6.832, \url{https://underactuated.mit.edu}}, +} + +@article{isaaclab2025, + author = {Mittal, Mayank and Yu, Calvin and Yu, Qinxi and Liu, Jingzhou + and Rudin, Nikita and Hoeller, David and Yuan, Jia Lin + and Singh, Ritvik and Guo, Yunrong and Mazhar, Hammad + and Mandlekar, Ajay and Babich, Buck and State, Gavriel + and Hutter, Marco and Garg, Animesh}, + title = {{Isaac Lab: A Unified and Modular Framework for Robot Learning}}, + journal = {arXiv preprint arXiv:2502.11048}, + year = {2025}, +} + +@article{stribeck1902, + author = {Stribeck, R.}, + title = {{Die wesentlichen Eigenschaften der Gleit- und Rollenlager}}, + journal = {Zeitschrift des Vereines Deutscher Ingenieure}, + volume = {46}, + pages = {1341--1348, 1432--1438, 1463--1470}, + year = {1902}, +} + +@misc{maxon_formulas, + author = {{Maxon Motor AG}}, + title = {{Key Information on Maxon DC Motors and Maxon EC Motors}}, + howpublished = {\url{https://www.maxongroup.com}}, + year = {2024}, + note = {{Maxon} Academy Technical Notes}, +} + +@misc{simscape_dcmotor, + author = {{MathWorks}}, + title = {{DC Motor --- Simscape Electrical Block Reference}}, + howpublished = {\url{https://www.mathworks.com/help/sps/ref/dcmotor.html}}, + year = {2024}, +} diff --git a/doc/includes/references.h b/doc/includes/references.h index bc8a548d52..fd855a1c1f 100644 --- a/doc/includes/references.h +++ b/doc/includes/references.h @@ -635,19 +635,22 @@ typedef enum mjtDyn_ { // type of actuator dynamics mjDYN_INTEGRATOR, // integrator: da/dt = u mjDYN_FILTER, // linear filter: da/dt = (u-a) / tau mjDYN_FILTEREXACT, // linear filter: da/dt = (u-a) / tau, with exact integration - mjDYN_MUSCLE, // piece-wise linear filter with two time constants + mjDYN_MUSCLE, // piecewise linear filter with two time constants + mjDYN_DCMOTOR, // DC motor electrical dynamics mjDYN_USER // user-defined dynamics type } mjtDyn; typedef enum mjtGain_ { // type of actuator gain mjGAIN_FIXED = 0, // fixed gain mjGAIN_AFFINE, // const + kp*length + kv*velocity mjGAIN_MUSCLE, // muscle FLV curve computed by mju_muscleGain() + mjGAIN_DCMOTOR, // DC motor gain: K or K/R mjGAIN_USER // user-defined gain type } mjtGain; typedef enum mjtBias_ { // type of actuator bias mjBIAS_NONE = 0, // no bias mjBIAS_AFFINE, // const + kp*length + kv*velocity mjBIAS_MUSCLE, // muscle passive force computed by mju_muscleBias() + mjBIAS_DCMOTOR, // DC motor bias: back-EMF, cogging, LuGre friction mjBIAS_USER // user-defined bias type } mjtBias; typedef enum mjtObj_ { // type of MujoCo object @@ -3659,6 +3662,10 @@ const char* mjs_setToMuscle(mjsActuator* actuator, double timeconst[2], double t double range[2], double force, double scale, double lmin, double lmax, double vmax, double fpmax, double fvmax); const char* mjs_setToAdhesion(mjsActuator* actuator, double gain); +const char* mjs_setToDCMotor(mjsActuator* actuator, double motorconst[2], double resistance, + double nominal[3], double saturation[4], double inductance[2], + double cogging[3], double controller[5], double thermal[6], + double lugre[6], int input_mode); mjsMesh* mjs_addMesh(mjSpec* s, const mjsDefault* def); mjsHField* mjs_addHField(mjSpec* s); mjsSkin* mjs_addSkin(mjSpec* s); diff --git a/include/mujoco/mjmodel.h b/include/mujoco/mjmodel.h index 2f9cdd35db..49cfee0bd4 100644 --- a/include/mujoco/mjmodel.h +++ b/include/mujoco/mjmodel.h @@ -244,7 +244,8 @@ typedef enum mjtDyn_ { // type of actuator dynamics mjDYN_INTEGRATOR, // integrator: da/dt = u mjDYN_FILTER, // linear filter: da/dt = (u-a) / tau mjDYN_FILTEREXACT, // linear filter: da/dt = (u-a) / tau, with exact integration - mjDYN_MUSCLE, // piece-wise linear filter with two time constants + mjDYN_MUSCLE, // piecewise linear filter with two time constants + mjDYN_DCMOTOR, // DC motor electrical dynamics mjDYN_USER // user-defined dynamics type } mjtDyn; @@ -253,6 +254,7 @@ typedef enum mjtGain_ { // type of actuator gain mjGAIN_FIXED = 0, // fixed gain mjGAIN_AFFINE, // const + kp*length + kv*velocity mjGAIN_MUSCLE, // muscle FLV curve computed by mju_muscleGain() + mjGAIN_DCMOTOR, // DC motor gain: K or K/R mjGAIN_USER // user-defined gain type } mjtGain; @@ -261,6 +263,7 @@ typedef enum mjtBias_ { // type of actuator bias mjBIAS_NONE = 0, // no bias mjBIAS_AFFINE, // const + kp*length + kv*velocity mjBIAS_MUSCLE, // muscle passive force computed by mju_muscleBias() + mjBIAS_DCMOTOR, // DC motor bias: back-EMF, cogging, LuGre friction mjBIAS_USER // user-defined bias type } mjtBias; diff --git a/include/mujoco/mujoco.h b/include/mujoco/mujoco.h index 362f16e9b6..ba4963606e 100644 --- a/include/mujoco/mujoco.h +++ b/include/mujoco/mujoco.h @@ -1726,6 +1726,12 @@ MJAPI const char* mjs_setToMuscle(mjsActuator* actuator, double timeconst[2], do // Set actuator to active adhesion; return error if any. MJAPI const char* mjs_setToAdhesion(mjsActuator* actuator, double gain); +// Set actuator to DC motor; return error if any. +MJAPI const char* mjs_setToDCMotor(mjsActuator* actuator, double motorconst[2], double resistance, + double nominal[3], double saturation[4], double inductance[2], + double cogging[3], double controller[5], double thermal[6], + double lugre[6], int input_mode); + //---------------------------------- Assets -------------------------------------------------------- diff --git a/python/mujoco/introspect/enums.py b/python/mujoco/introspect/enums.py index d4dcdf34d9..bc28f78d6d 100644 --- a/python/mujoco/introspect/enums.py +++ b/python/mujoco/introspect/enums.py @@ -263,7 +263,8 @@ ('mjDYN_FILTER', 2), ('mjDYN_FILTEREXACT', 3), ('mjDYN_MUSCLE', 4), - ('mjDYN_USER', 5), + ('mjDYN_DCMOTOR', 5), + ('mjDYN_USER', 6), ]), )), ('mjtGain', @@ -274,7 +275,8 @@ ('mjGAIN_FIXED', 0), ('mjGAIN_AFFINE', 1), ('mjGAIN_MUSCLE', 2), - ('mjGAIN_USER', 3), + ('mjGAIN_DCMOTOR', 3), + ('mjGAIN_USER', 4), ]), )), ('mjtBias', @@ -285,7 +287,8 @@ ('mjBIAS_NONE', 0), ('mjBIAS_AFFINE', 1), ('mjBIAS_MUSCLE', 2), - ('mjBIAS_USER', 3), + ('mjBIAS_DCMOTOR', 3), + ('mjBIAS_USER', 4), ]), )), ('mjtObj', diff --git a/python/mujoco/introspect/functions.py b/python/mujoco/introspect/functions.py index ff1bcf125d..0ab6df20f4 100644 --- a/python/mujoco/introspect/functions.py +++ b/python/mujoco/introspect/functions.py @@ -10786,6 +10786,86 @@ ), doc='Set actuator to active adhesion; return error if any.', )), + ('mjs_setToDCMotor', + FunctionDecl( + name='mjs_setToDCMotor', + return_type=PointerType( + inner_type=ValueType(name='char', is_const=True), + ), + parameters=( + FunctionParameterDecl( + name='actuator', + type=PointerType( + inner_type=ValueType(name='mjsActuator'), + ), + ), + FunctionParameterDecl( + name='motorconst', + type=ArrayType( + inner_type=ValueType(name='double'), + extents=(2,), + ), + ), + FunctionParameterDecl( + name='resistance', + type=ValueType(name='double'), + ), + FunctionParameterDecl( + name='nominal', + type=ArrayType( + inner_type=ValueType(name='double'), + extents=(3,), + ), + ), + FunctionParameterDecl( + name='saturation', + type=ArrayType( + inner_type=ValueType(name='double'), + extents=(4,), + ), + ), + FunctionParameterDecl( + name='inductance', + type=ArrayType( + inner_type=ValueType(name='double'), + extents=(2,), + ), + ), + FunctionParameterDecl( + name='cogging', + type=ArrayType( + inner_type=ValueType(name='double'), + extents=(3,), + ), + ), + FunctionParameterDecl( + name='controller', + type=ArrayType( + inner_type=ValueType(name='double'), + extents=(5,), + ), + ), + FunctionParameterDecl( + name='thermal', + type=ArrayType( + inner_type=ValueType(name='double'), + extents=(6,), + ), + ), + FunctionParameterDecl( + name='lugre', + type=ArrayType( + inner_type=ValueType(name='double'), + extents=(6,), + ), + ), + FunctionParameterDecl( + name='input_mode', + type=ValueType(name='int'), + ), + ), + doc='Set actuator to DC motor; return error if any.', + )), ('mjs_addMesh', FunctionDecl( name='mjs_addMesh', diff --git a/python/mujoco/specs.cc b/python/mujoco/specs.cc index e3bfc7ef9a..28af8af17f 100644 --- a/python/mujoco/specs.cc +++ b/python/mujoco/specs.cc @@ -1303,6 +1303,31 @@ PYBIND11_MODULE(_specs, m) { } }, py::arg("gain")); + mjsActuator.def( + "set_to_dcmotor", + [](raw::MjsActuator* self, std::array motorconst, + double resistance, + std::array nominal, std::array saturation, + std::array inductance, std::array cogging, + std::array controller, std::array thermal, + std::array lugre, int input_mode) { + std::string err = mjs_setToDCMotor( + self, motorconst.data(), resistance, nominal.data(), + saturation.data(), inductance.data(), cogging.data(), + controller.data(), thermal.data(), lugre.data(), input_mode); + if (!err.empty()) { + throw pybind11::value_error(err); + } + }, + py::arg("motorconst"), py::arg("resistance"), + py::arg("nominal") = std::array{0, 0, 0}, + py::arg("saturation") = std::array{0, 0, 0, 0}, + py::arg("inductance") = std::array{0, 0}, + py::arg("cogging") = std::array{0, 0, 0}, + py::arg("controller") = std::array{0, 0, 0, 0, 0}, + py::arg("thermal") = std::array{0, 0, 0, 0, 0, 0}, + py::arg("lugre") = std::array{0, 0, 0, 0, 0, 0}, + py::arg("input_mode") = 0); // ============================= MJSTENDONPATH =============================== // helper struct for tendon path indexing diff --git a/python/mujoco/specs_test.py b/python/mujoco/specs_test.py index f1c99d823c..a82646dde4 100644 --- a/python/mujoco/specs_test.py +++ b/python/mujoco/specs_test.py @@ -1557,6 +1557,13 @@ def test_actuator_shortname(self): self.assertEqual(actuator.gaintype, mujoco.mjtGain.mjGAIN_FIXED) self.assertEqual(actuator.biastype, mujoco.mjtBias.mjBIAS_NONE) + actuator.set_to_dcmotor(motorconst=[0.05, 0.05], resistance=2.0) + self.assertEqual(actuator.gainprm[0], 2.0) + self.assertEqual(actuator.gainprm[1], 0.05) + self.assertEqual(actuator.dyntype, mujoco.mjtDyn.mjDYN_DCMOTOR) + self.assertEqual(actuator.gaintype, mujoco.mjtGain.mjGAIN_DCMOTOR) + self.assertEqual(actuator.biastype, mujoco.mjtBias.mjBIAS_DCMOTOR) + def test_bad_contact_sensor(self): test_cases = [ dict( diff --git a/src/engine/engine_derivative.c b/src/engine/engine_derivative.c index 3f9b467a56..00267a3e9e 100644 --- a/src/engine/engine_derivative.c +++ b/src/engine/engine_derivative.c @@ -1107,6 +1107,17 @@ void mjd_actuator_vel(const mjModel* m, mjData* d) { bias_vel = (m->actuator_biasprm + mjNBIAS*i)[2]; } + // DC motor bias (back-EMF) + else if (m->actuator_biastype[i] == mjBIAS_DCMOTOR) { + const mjtNum* dynprm = m->actuator_dynprm + mjNDYN*i; + const mjtNum* gainprm = m->actuator_gainprm + mjNGAIN*i; + if (dynprm[0] <= 0) { + mjtNum R = mju_max(mjMINVAL, gainprm[0]); + mjtNum K = gainprm[1]; + bias_vel -= K * K / R; + } + } + // affine gain if (m->actuator_gaintype[i] == mjGAIN_AFFINE) { // extract bias info: prm = [const, kp, kv] @@ -1122,6 +1133,28 @@ void mjd_actuator_vel(const mjModel* m, mjData* d) { m->actuator_gainprm + mjNGAIN*i); } + // DC motor controller damping and LuGre micro-damping + else if (m->actuator_gaintype[i] == mjGAIN_DCMOTOR) { + const mjtNum* dynprm = m->actuator_dynprm + mjNDYN*i; + const mjtNum* gainprm = m->actuator_gainprm + mjNGAIN*i; + int input_mode = (int)gainprm[8]; + if (input_mode > 0) { + mjtNum R = gainprm[0]; + mjtNum K = gainprm[1]; + mjtNum gain = (dynprm[0] > 0) ? K : K / mju_max(mjMINVAL, R); + mjtNum kp = gainprm[4]; + mjtNum kd = gainprm[6]; + bias_vel -= gain * (input_mode == 1 ? kd : kp); + } + + // LuGre: force includes -sigma1*z_dot, z_dot = a*z + v + // d(sigma1*z_dot)/dv = sigma1*(da/dv*z + 1), ignoring higher-order da/dv*z + mjtNum sigma1 = dynprm[6]; + if (sigma1 > 0) { + bias_vel -= sigma1; + } + } + // force = gain .* [ctrl/act] if (gain_vel != 0) { if (m->actuator_dyntype[i] == mjDYN_NONE) { diff --git a/src/engine/engine_forward.c b/src/engine/engine_forward.c index b28c342feb..e8e08f009b 100644 --- a/src/engine/engine_forward.c +++ b/src/engine/engine_forward.c @@ -257,6 +257,36 @@ void mj_fwdVelocity(const mjModel* m, mjData* d) { } +// helper for DC motor: computes control voltage from PID state +static mjtNum dcmotorVoltage(mjtNum ctrl, mjtNum length, mjtNum velocity, + mjtNum x_I, const mjtNum* gainprm) { + int input_mode = (int)gainprm[8]; + mjtNum Vmax = gainprm[7]; + mjtNum voltage; + + // get voltage + if (input_mode > 0) { + mjtNum kp = gainprm[4]; // proportional gain + mjtNum ki = gainprm[5]; // integral gain + mjtNum kd = gainprm[6]; // derivative gain + + if (input_mode == 1) { + // position mode + voltage = kp * (ctrl - length) + ki * x_I - kd * velocity; + } else { + // velocity mode + voltage = kp * (ctrl - velocity) + ki * (x_I - length); + } + } else { + voltage = ctrl; + } + + // clip voltage + if (Vmax > 0) voltage = mju_clip(voltage, -Vmax, Vmax); + + return voltage; +} + // clamp vector to range static void clampVec(mjtNum* vec, const mjtNum* range, const mjtByte* limited, int n, @@ -275,7 +305,7 @@ void mj_fwdActuation(const mjModel* m, mjData* d) { TM_START; int nv = m->nv, nu = m->nu, ntendon = m->ntendon; mjtNum gain, bias, tau; - mjtNum *prm, *force = d->actuator_force; + mjtNum *force = d->actuator_force; // clear actuator_force mju_zero(force, nu); @@ -327,37 +357,136 @@ void mj_fwdActuation(const mjModel* m, mjData* d) { } // zero act_dot for actuator plugins - if (m->actuator_actnum[i]) { - mju_zero(d->act_dot + act_first, m->actuator_actnum[i]); + int actnum = m->actuator_actnum[i]; + if (actnum) { + mju_zero(d->act_dot + act_first, actnum); } // extract info - prm = m->actuator_dynprm + i*mjNDYN; + const mjtNum* dynprm = m->actuator_dynprm + i*mjNDYN; + mjtDyn dyntype = m->actuator_dyntype[i]; // index into the last element in act. For most actuators it's also the - // first element, but actuator plugins might store their own state in act. - int act_last = act_first + m->actuator_actnum[i] - 1; + // first element, but actuator plugins might store their own state in act + int act_last = act_first + actnum - 1; // compute act_dot according to dynamics type - switch ((mjtDyn) m->actuator_dyntype[i]) { + switch (dyntype) { case mjDYN_INTEGRATOR: // simple integrator d->act_dot[act_last] = ctrl[i]; break; - case mjDYN_FILTER: // linear filter: prm = tau + case mjDYN_FILTER: // linear filter: dynprm = tau case mjDYN_FILTEREXACT: - tau = mju_max(mjMINVAL, prm[0]); + tau = mju_max(mjMINVAL, dynprm[0]); d->act_dot[act_last] = (ctrl[i] - d->act[act_last]) / tau; break; - case mjDYN_MUSCLE: // muscle model: prm = (tau_act, tau_deact) - d->act_dot[act_last] = mju_muscleDynamics( - ctrl[i], d->act[act_last], prm); + case mjDYN_MUSCLE: // muscle model: dynprm = (tau_act, tau_deact) + d->act_dot[act_last] = mju_muscleDynamics(ctrl[i], d->act[act_last], dynprm); break; + case mjDYN_DCMOTOR: { // DC motor: up to 5 optional states + const mjtNum* gainprm = m->actuator_gainprm + mjNGAIN*i; + + // verify allocated state size matches parameters; SHOULD NOT OCCUR + if (mj_dcmotorSlots(dynprm, gainprm).num_slots != actnum) { + mjERROR("inconsistent state array dimension in DC motor (actuator %d)", i); + } + + int adr = act_first; + mjtNum velocity = d->actuator_velocity[i]; + mjtNum R = gainprm[0]; // resistance + mjtNum K = gainprm[1]; // motor constant + mjtNum ki = gainprm[5]; // integral gain + mjtNum te = dynprm[0]; // electrical time constant + + // slot order: slew, integral, temperature, bristle, current + + // controller state: slew rate limiting + mjtNum slew_s = dynprm[7]; // slew rate limit + if (slew_s > 0) { + mjtNum u_prev = d->act[adr]; + mjtNum slew = slew_s * m->opt.timestep; + mjtNum u_eff = mju_clip(ctrl[i], u_prev - slew, u_prev + slew); + d->act_dot[adr] = (u_eff - u_prev) / m->opt.timestep; + ctrl[i] = u_eff; + adr++; + } + + // controller state: integral state + mjtNum x_I = 0; + if (ki > 0) { + x_I = d->act[adr]; + int input_mode = (int)gainprm[8]; + mjtNum Imax = dynprm[8]; // integral clamp + mjtNum act_dot = ctrl[i]; // default raw accumulator for voltage and velocity modes + + // position mode + if (input_mode == 1) { + act_dot = ctrl[i] - d->actuator_length[i]; + } + + // clamp act_dot based on integral state + if (Imax > 0) { + if (x_I >= Imax) { + act_dot = mju_min(act_dot, 0); + } else if (x_I <= -Imax) { + act_dot = mju_max(act_dot, 0); + } + } + d->act_dot[adr] = act_dot; + adr++; + } + + // compute physical voltage to feed into current and temperature equations + mjtNum V = dcmotorVoltage(ctrl[i], d->actuator_length[i], velocity, x_I, gainprm); + + // temperature: dT/dt = (R*i^2 - T/RT) / C, where T = delta above ambient + mjtNum RT = dynprm[2]; // thermal resistance + if (RT > 0) { + mjtNum C = dynprm[3]; // thermal capacitance + mjtNum Ta = dynprm[4]; // ambient temperature + mjtNum alpha = gainprm[2]; // temperature coefficient + mjtNum T0 = gainprm[3]; // reference temperature + mjtNum T = d->act[adr]; // temperature rise above ambient + R *= 1 + alpha * (T + Ta - T0); + + // get current: from act_last if stateful, from (V - K*omega)/R if stateless + mjtNum current = (te > 0) ? d->act[act_last] : (V - K * velocity) / R; + d->act_dot[adr] = (R*current*current - T / RT) / C; + adr++; + } + + // LuGre bristle state: dz/dt = v - sigma0 * |v| / g(v) * z + mjtNum sigma0 = dynprm[5]; // bristle stiffness + if (sigma0 > 0) { + const mjtNum* biasprm = m->actuator_biasprm + mjNBIAS*i; + mjtNum F_C = biasprm[3]; // Coulomb friction + mjtNum F_S = biasprm[4]; // static friction + mjtNum v_S = biasprm[5]; // Stribeck velocity + mjtNum z = d->act[adr]; // bristle state + mjtNum g = mj_lugreStribeck(velocity, F_C, F_S, v_S); + mjtNum a = -sigma0 * mju_abs(velocity) / mju_max(mjMINVAL, g); + d->act_dot[adr] = a * z + velocity; + adr++; + } + + // current state: di/dt = (V/R - K/R*omega - i) / te + if (te > 0) { + mjtNum dimax = dynprm[1]; // current rate limit (di/dt)_max + mjtNum i_dot = (V/R - K/R*velocity - d->act[act_last]) / te; + if (dimax > 0) { + i_dot = mju_clip(i_dot, -dimax, dimax); + } + d->act_dot[act_last] = i_dot; + } + break; + } + default: // user dynamics if (mjcb_act_dyn) { - if (m->actuator_actnum[i] == 1) { + if (actnum == 1) { // scalar activation dynamics, get act_dot d->act_dot[act_last] = mjcb_act_dyn(m, d, i); } else { @@ -407,17 +536,20 @@ void mj_fwdActuation(const mjModel* m, mjData* d) { tendon_frclimited = m->tendon_actfrclimited[m->actuator_trnid[2*i]]; } - // extract gain info - prm = m->actuator_gainprm + mjNGAIN*i; + // extract info + const mjtNum* dynprm = m->actuator_dynprm + mjNDYN*i; + const mjtNum* gainprm = m->actuator_gainprm + mjNGAIN*i; + mjtGain gaintype = m->actuator_gaintype[i]; + int actnum = m->actuator_actnum[i]; // handle according to gain type - switch ((mjtGain) m->actuator_gaintype[i]) { + switch (gaintype) { case mjGAIN_FIXED: // fixed gain: prm = gain - gain = prm[0]; + gain = gainprm[0]; break; case mjGAIN_AFFINE: // affine: prm = [const, kp, kv] - gain = prm[0] + prm[1]*d->actuator_length[i] + prm[2]*d->actuator_velocity[i]; + gain = gainprm[0] + gainprm[1]*d->actuator_length[i] + gainprm[2]*d->actuator_velocity[i]; break; case mjGAIN_MUSCLE: // muscle gain @@ -425,9 +557,43 @@ void mj_fwdActuation(const mjModel* m, mjData* d) { d->actuator_velocity[i], m->actuator_lengthrange+2*i, m->actuator_acc0[i], - prm); + gainprm); break; + case mjGAIN_DCMOTOR: { // DC motor: gain = K or K/R + mjtNum R = gainprm[0]; // resistance + mjtNum K = gainprm[1]; // motor constant + mjDCMotorSlots slots = mj_dcmotorSlots(dynprm, gainprm); + + // verify allocated state size matches parameters; SHOULD NOT OCCUR + if (slots.num_slots != actnum) { + mjERROR("inconsistent state array dimension in DC motor (actuator %d)", i); + } + + int adr = m->actuator_actadr[i]; + + // adjust R for temperature if enabled + if (slots.temperature >= 0) { + mjtNum T = d->act[adr + slots.temperature]; + mjtNum alpha = gainprm[2]; // temperature coefficient + mjtNum T0 = gainprm[3]; // reference temperature + mjtNum Ta = dynprm[4]; // ambient temperature + R *= 1 + alpha * (T + Ta - T0); + } + + // stateful current: gain = K, force = K * act[last] (generic path) + // stateless: gain = K/R, force = K/R * ctrl (condition below) + gain = (dynprm[0] > 0) ? K : K / mju_max(mjMINVAL, R); + + // controller: compute voltage, override ctrl[i] for force computation + if ((int)gainprm[8] > 0) { + mjtNum x_I = (slots.integral >= 0) ? d->act[adr + slots.integral] : 0; + ctrl[i] = dcmotorVoltage(ctrl[i], d->actuator_length[i], + d->actuator_velocity[i], x_I, gainprm); + } + break; + } + default: // user gain if (mjcb_act_gain) { gain = mjcb_act_gain(m, d, i); @@ -437,11 +603,14 @@ void mj_fwdActuation(const mjModel* m, mjData* d) { } // set force = gain .* [ctrl/act] - if (m->actuator_actadr[i] == -1) { + + // DC motor without current state: use ctrl even if other activations exist + int dcmotor_no_current = (gaintype == mjGAIN_DCMOTOR && dynprm[0] <= 0); + if (actnum == 0 || dcmotor_no_current) { force[i] = gain * ctrl[i]; } else { // use last activation variable associated with actuator i - int act_adr = m->actuator_actadr[i] + m->actuator_actnum[i] - 1; + int act_adr = m->actuator_actadr[i] + actnum - 1; mjtNum act; if (m->actuator_actearly[i]) { @@ -453,25 +622,38 @@ void mj_fwdActuation(const mjModel* m, mjData* d) { } // extract bias info - prm = m->actuator_biasprm + mjNBIAS*i; + const mjtNum* biasprm = m->actuator_biasprm + mjNBIAS*i; + mjtBias biastype = m->actuator_biastype[i]; // handle according to bias type - switch ((mjtBias) m->actuator_biastype[i]) { + switch (biastype) { case mjBIAS_NONE: // none bias = 0.0; break; - case mjBIAS_AFFINE: // affine: prm = [const, kp, kv] - bias = prm[0] + prm[1]*d->actuator_length[i] + prm[2]*d->actuator_velocity[i]; + case mjBIAS_AFFINE: // affine: biasprm = [const, kp, kv] + bias = biasprm[0] + biasprm[1]*d->actuator_length[i] + biasprm[2]*d->actuator_velocity[i]; break; case mjBIAS_MUSCLE: // muscle passive force bias = mju_muscleBias(d->actuator_length[i], m->actuator_lengthrange+2*i, m->actuator_acc0[i], - prm); + biasprm); break; + case mjBIAS_DCMOTOR: { // DC motor: back-EMF only (current-limited) + bias = 0; + + // back-EMF (stateless only; for stateful current it's in the ODE) + mjtNum te = m->actuator_dynprm[mjNDYN*i]; // electrical time constant + if (te <= 0) { + mjtNum K = gainprm[1]; // motor constant + bias -= gain * K * d->actuator_velocity[i]; + } + break; + } + default: // user bias if (mjcb_act_bias) { bias = mjcb_act_bias(m, d, i); @@ -537,6 +719,41 @@ void mj_fwdActuation(const mjModel* m, mjData* d) { // clamp actuator_force clampVec(force, m->actuator_forcerange, m->actuator_forcelimited, nu, NULL); + // add DC motor mechanical forces (not subject to current limits) + for (int i=0; i < nu; i++) { + if (m->actuator_biastype[i] != mjBIAS_DCMOTOR) { + continue; + } + if (sleep_filter && mj_sleepState(m, d, mjOBJ_ACTUATOR, i) == mjS_ASLEEP) { + continue; + } + if (mj_actuatorDisabled(m, i) || m->actuator_plugin[i] >= 0) { + continue; + } + + const mjtNum* biasprm = m->actuator_biasprm + mjNBIAS*i; + const mjtNum* dynprm = m->actuator_dynprm + mjNDYN*i; + + // cogging torque + mjtNum A = biasprm[0]; + if (A != 0) { + mjtNum Np = biasprm[1]; + mjtNum phi = biasprm[2]; + force[i] += A * mju_sin(Np*d->actuator_length[i] + phi); + } + + // LuGre friction + mjtNum sigma0 = dynprm[5]; + if (sigma0 > 0) { + mjtNum sigma1 = dynprm[6]; + mjDCMotorSlots slots = mj_dcmotorSlots(dynprm, m->actuator_gainprm + mjNGAIN*i); + int adr = m->actuator_actadr[i] + slots.bristle; + mjtNum z = d->act[adr]; + mjtNum z_dot = d->act_dot[adr]; + force[i] -= sigma0 * z + sigma1 * z_dot; + } + } + // qfrc_actuator = moment' * force mju_mulMatTVecSparse(d->qfrc_actuator, d->actuator_moment, force, nu, nv, d->moment_rownnz, d->moment_rowadr, d->moment_colind); diff --git a/src/engine/engine_support.c b/src/engine/engine_support.c index a4827ddb7c..81c3b6caa9 100644 --- a/src/engine/engine_support.c +++ b/src/engine/engine_support.c @@ -709,22 +709,69 @@ int mj_actuatorDisabled(const mjModel* m, int i) { mjtNum mj_nextActivation(const mjModel* m, const mjData* d, int actuator_id, int act_adr, mjtNum act_dot) { mjtNum act = d->act[act_adr]; + int dyntype = m->actuator_dyntype[actuator_id]; - if (m->actuator_dyntype[actuator_id] == mjDYN_FILTEREXACT) { + if (dyntype == mjDYN_FILTEREXACT) { // exact filter integration // act_dot(0) = (ctrl-act(0)) / tau // act(h) = act(0) + (ctrl-act(0)) (1 - exp(-h / tau)) // = act(0) + act_dot(0) * tau * (1 - exp(-h / tau)) mjtNum tau = mju_max(mjMINVAL, m->actuator_dynprm[actuator_id*mjNDYN]); act = act + act_dot * tau * (1 - mju_exp(-m->opt.timestep / tau)); - } else { - // Euler integration + } else if (dyntype == mjDYN_DCMOTOR) { + const mjtNum* dynprm = m->actuator_dynprm + actuator_id * mjNDYN; + const mjtNum* gainprm = m->actuator_gainprm + actuator_id * mjNGAIN; + mjDCMotorSlots slots = mj_dcmotorSlots(dynprm, gainprm); + + int offset = act_adr - m->actuator_actadr[actuator_id]; + + // current filter: exact integration + if (offset == slots.current) { + mjtNum te = mju_max(mjMINVAL, dynprm[0]); + act = act + act_dot * te * (1 - mju_exp(-m->opt.timestep / te)); + } + + // LuGre bristle: dz/dt = a*z + v where a = -sigma0*|v|/g(v) + else if (offset == slots.bristle) { + const mjtNum* biasprm = m->actuator_biasprm + mjNBIAS*actuator_id; + mjtNum F_C = biasprm[3]; // Coulomb friction + mjtNum F_S = biasprm[4]; // static friction + mjtNum v_S = biasprm[5]; // Stribeck velocity + mjtNum sigma0 = dynprm[5]; // bristle stiffness + mjtNum velocity = d->actuator_velocity[actuator_id]; + mjtNum g = mj_lugreStribeck(velocity, F_C, F_S, v_S); + + // ZOH exact ZOH integration: z(h) = exp(ah)*z(0) + ((exp(ah)-1)/a)*v + mjtNum a = -sigma0 * mju_abs(velocity) / mju_max(mjMINVAL, g); // decay rate + mjtNum h = m->opt.timestep; + mjtNum exp_ah = mju_exp(a * h); // state transition + mjtNum int_h = mju_abs(a) > mjMINVAL ? (exp_ah - 1) / a : h; // input integral + act = exp_ah * act + int_h * velocity; + } + + // integral state: Euler integration with anti-windup clamp + else if (offset == slots.integral) { + act = act + act_dot * m->opt.timestep; + mjtNum Imax = dynprm[8]; + if (Imax > 0) { + act = mju_clip(act, -Imax, Imax); + } + } + + // temperature and slew: Euler integration + else { + act = act + act_dot * m->opt.timestep; + } + } + + // otherwise Euler integration + else { act = act + act_dot * m->opt.timestep; } - // clamp to actrange - if (m->actuator_actlimited[actuator_id]) { - mjtNum* actrange = m->actuator_actrange + 2*actuator_id; + // clamp to actrange unless DC motor + if (dyntype != mjDYN_DCMOTOR && m->actuator_actlimited[actuator_id]) { + const mjtNum* actrange = m->actuator_actrange + 2*actuator_id; act = mju_clip(act, actrange[0], actrange[1]); } diff --git a/src/engine/engine_util_misc.c b/src/engine/engine_util_misc.c index 0dd2ca9753..65057a51e8 100644 --- a/src/engine/engine_util_misc.c +++ b/src/engine/engine_util_misc.c @@ -769,6 +769,26 @@ mjtNum mju_muscleDynamics(mjtNum ctrl, mjtNum act, const mjtNum prm[3]) { } +// LuGre Stribeck function: g(v) = F_C + (F_S - F_C) * exp(-(v/v_S)^2) +mjtNum mj_lugreStribeck(mjtNum velocity, mjtNum F_C, mjtNum F_S, mjtNum v_S) { + mjtNum ratio = velocity / mju_max(mjMINVAL, v_S); + return F_C + (F_S - F_C) * mju_exp(-ratio*ratio); +} + + +// compute DC motor activation slot indices from parameter arrays +mjDCMotorSlots mj_dcmotorSlots(const mjtNum* dynprm, const mjtNum* gainprm) { + mjDCMotorSlots s = {-1, -1, -1, -1, -1, 0}; + if (dynprm[7] > 0) s.slew = s.num_slots++; // slew rate limiting + if (gainprm[5] > 0) s.integral = s.num_slots++; // PI integral + if (dynprm[2] > 0) s.temperature = s.num_slots++; // thermal model + if (dynprm[5] > 0) s.bristle = s.num_slots++; // LuGre bristle + if (dynprm[0] > 0) s.current = s.num_slots++; // current filter + + return s; +} + + //---------------------------------------- Base64 -------------------------------------------------- // decoding function for Base64 diff --git a/src/engine/engine_util_misc.h b/src/engine/engine_util_misc.h index 756b3b8ebf..cac5bed59c 100644 --- a/src/engine/engine_util_misc.h +++ b/src/engine/engine_util_misc.h @@ -50,6 +50,23 @@ MJAPI mjtNum mju_muscleDynamicsTimescale(mjtNum dctrl, mjtNum tau_act, mjtNum ta // muscle activation dynamics, prm = (tau_act, tau_deact, smoothing_width) MJAPI mjtNum mju_muscleDynamics(mjtNum ctrl, mjtNum act, const mjtNum prm[3]); +// LuGre Stribeck function: g(v) = F_C + (F_S - F_C) * exp(-(v/v_S)^2) +mjtNum mj_lugreStribeck(mjtNum velocity, mjtNum F_C, mjtNum F_S, mjtNum v_S); + +// DC motor activation slot indices (-1 = slot not active) +typedef struct { + int slew; // slew rate state + int integral; // integral state + int temperature; // temperature state + int bristle; // LuGre bristle state + int current; // current state + int num_slots; // number of DC motor states +} mjDCMotorSlots; + +// compute activation slot indices for a DC motor actuator +// dynprm = actuator_dynprm row, gainprm = actuator_gainprm row +mjDCMotorSlots mj_dcmotorSlots(const mjtNum* dynprm, const mjtNum* gainprm); + // all 3 semi-axes of a geom MJAPI void mju_geomSemiAxes(mjtNum semiaxes[3], const mjtNum size[3], mjtGeom type); diff --git a/src/user/user_api.cc b/src/user/user_api.cc index f5b569d9e1..2317cc3a0d 100644 --- a/src/user/user_api.cc +++ b/src/user/user_api.cc @@ -15,6 +15,7 @@ #include "user/user_api.h" #include +#include #include #include #include @@ -1120,6 +1121,166 @@ const char* mjs_setToAdhesion(mjsActuator* actuator, double gain) { +const char* mjs_setToDCMotor(mjsActuator* actuator, double motorconst[2], double resistance, + double nominal[3], double saturation[4], double inductance[2], + double cogging[3], double controller[5], double thermal[6], + double lugre[6], int input_mode) { + double Kt = motorconst[0]; // torque constant + double Ke = motorconst[1]; // back-EMF constant + double R = resistance; // electrical resistance + double vn = nominal[0]; // nominal voltage + double tau0 = nominal[1]; // stall torque + double omega0 = nominal[2]; // no-load speed + + // derive Ke from nominal: omega0 = vn*Ke / (Ke^2 + R*B) + if (vn > 0 && Ke <= 0 && omega0 > 0) { + // viscous damping (linear), add lugre sigma2 contribution if any + double B = actuator->damping[0]; + if (lugre[0] > 0) B += lugre[2]; + + if (B > 0 && R > 0) { + // R known: solve quadratic Ke^2*omega0 - Ke*vn + R*B*omega0 = 0 + double disc = vn*vn - 4*R*B*omega0*omega0; + Ke = disc > 0 ? (vn + sqrt(disc)) / (2*omega0) : vn / omega0; + } else if (B > 0 && tau0 > 0) { + // R from nominal (tau0 = Ke*vn/R, so R = Ke*vn/tau0) + // substituting into omega0 = vn*Ke/(Ke^2 + R*B): + // omega0 = vn/(Ke + vn*B/tau0) => Ke = vn/omega0 - vn*B/tau0 + double Ke_exact = vn / omega0 - vn*B / tau0; + Ke = Ke_exact > 0 ? Ke_exact : vn / omega0; + } else { + // B = 0 or insufficient data for B-correction: omega0 = vn*Ke/Ke^2 = vn/Ke + Ke = vn / omega0; + } + } + + // resolve effective motor constant K from [Kt, Ke] + double K = (Kt > 0 && Ke > 0) ? sqrt(Kt * Ke) : + (Kt > 0) ? Kt : Ke; + + // derive R from nominal: tau0 = K*vn/R + if (R == 0 && vn > 0 && tau0 > 0 && K > 0) { + R = K * vn / tau0; + } + + if (K <= 0) return "DC motor: motor constant K must be positive"; + if (R <= 0) return "DC motor: resistance R must be positive"; + + // set types + actuator->dyntype = mjDYN_DCMOTOR; + actuator->gaintype = mjGAIN_DCMOTOR; + actuator->biastype = mjBIAS_DCMOTOR; + + // gainprm: [R, K, alpha, T0] + actuator->gainprm[0] = R; + actuator->gainprm[1] = K; + + // controller parameters: gainprm[4:6] for kp, ki, kd + actuator->gainprm[4] = controller[0]; // kp + actuator->gainprm[5] = controller[1]; // ki + actuator->gainprm[6] = controller[2]; // kd + + // controller parameters: dynprm[7,8] for slewmax, Imax + actuator->dynprm[7] = controller[3]; // slewmax + actuator->dynprm[8] = controller[4]; // Imax + + // saturation: [tau_max, i_max, (di/dt)_max, v_max] + if (saturation[2] > 0) { + actuator->dynprm[1] = saturation[2]; // (di/dt)_max + } + if (saturation[3] > 0) { + actuator->gainprm[7] = saturation[3]; // v_max + } + + // saturation -> forcerange + if (saturation[0] > 0 || saturation[1] > 0) { + double tau_max = saturation[0]; + if (tau_max == 0 && saturation[1] > 0) { + tau_max = K * saturation[1]; // tau_max = K * i_max + } + actuator->forcerange[0] = -tau_max; + actuator->forcerange[1] = tau_max; + actuator->forcelimited = 1; + } + + // cogging: [amplitude, periodicity, phase] -> biasprm[0:3] + actuator->biasprm[0] = cogging[0]; // amplitude + actuator->biasprm[1] = cogging[1]; // periodicity + actuator->biasprm[2] = cogging[2]; // phase + + // count activation variables: slot order is slew, integral, temperature, bristle, current + int actdim = 0; + + // inductance: [L, te] + if (inductance[0] < 0) return "DC motor: inductance must be non-negative"; + if (inductance[1] < 0) return "DC motor: electrical time constant must be non-negative"; + double te = inductance[0] > 0 ? inductance[0] / R : inductance[1]; + actuator->dynprm[0] = te; + if (te > 0) { + actdim++; + } + + // controller states: slew rate limiting + if (controller[3] > 0) { // slewmax + actdim++; + } + + // controller states: integral + if (controller[1] > 0) { // ki + actdim++; + } + + // thermal -> temperature activation + if (thermal[0] > 0 || thermal[1] > 0 || thermal[2] > 0) { + double RT = thermal[0]; // thermal resistance + double C = thermal[1]; // thermal capacitance + double tth = thermal[2]; // thermal time constant + double alpha = thermal[3]; // temperature coefficient + double T0 = thermal[4]; // reference temperature + double Ta = thermal[5]; // ambient temperature + + if (tth > 0 && RT > 0 && C == 0) { + C = tth / RT; + } else if (tth > 0 && C > 0 && RT == 0) { + RT = tth / C; + } else if (tth == 0 && RT > 0 && C > 0) { + tth = RT * C; + } + + if (RT <= 0) return "DC motor: thermal resistance must be positive"; + if (C <= 0) return "DC motor: thermal capacitance must be positive"; + + actuator->dynprm[2] = RT; + actuator->dynprm[3] = C; + actuator->dynprm[4] = Ta; + actuator->gainprm[2] = alpha; + actuator->gainprm[3] = T0; + actdim++; + } + + // lugre: {stiffness, damping, viscous, coulomb, static, stribeck} + if (lugre[0] > 0) { + actuator->dynprm[5] = lugre[0]; // stiffness -> sigma0 + actuator->dynprm[6] = lugre[1]; // damping -> sigma1 + actuator->damping[0] += lugre[2]; // viscous -> sigma2 + actuator->biasprm[3] = lugre[3]; // coulomb -> tau_c + actuator->biasprm[4] = lugre[4]; // static -> tau_s + actuator->biasprm[5] = lugre[5]; // stribeck -> omega_s + actdim++; + } + + // set input mode and activation dimension + actuator->gainprm[8] = input_mode; + actuator->actdim = actdim; + + // enforce actlimited = 0; homogeneous bounds are invalid across DC motor states + actuator->actlimited = 0; + + return ""; +} + + + // get spec from body mjSpec* mjs_getSpec(mjsElement* element) { return &(static_cast(element)->model->spec); diff --git a/src/user/user_objects.cc b/src/user/user_objects.cc index c83951571b..5198cc20d0 100644 --- a/src/user/user_objects.cc +++ b/src/user/user_objects.cc @@ -7222,20 +7222,20 @@ void mjCActuator::Compile(void) { // check and set actdim if (!plugin.active) { - if (actdim > 1 && dyntype != mjDYN_USER) { - throw mjCError(this, "actdim > 1 is only allowed for dyntype 'user' in actuator"); + if (actdim > 1 && dyntype != mjDYN_USER && dyntype != mjDYN_DCMOTOR) { + throw mjCError(this, "actdim > 1 is only allowed for dyntype 'user' and 'dcmotor'"); } if (actdim == 1 && dyntype == mjDYN_NONE) { throw mjCError(this, "invalid actdim 1 in stateless actuator"); } - if (actdim == 0 && dyntype != mjDYN_NONE) { + if (actdim == 0 && dyntype != mjDYN_NONE && dyntype != mjDYN_DCMOTOR) { throw mjCError(this, "invalid actdim 0 in stateful actuator"); } } - // set actdim + // set actdim to 1 if it is unset and type is standard one-activation dyntype if (actdim < 0) { - actdim = (dyntype != mjDYN_NONE); + actdim = (dyntype != mjDYN_NONE && dyntype != mjDYN_DCMOTOR); } // check muscle parameters diff --git a/src/xml/xml_native_reader.cc b/src/xml/xml_native_reader.cc index d40e6a9adb..352790b5dc 100644 --- a/src/xml/xml_native_reader.cc +++ b/src/xml/xml_native_reader.cc @@ -206,6 +206,10 @@ std::vector MJCF[nMJCF] = { "lmin", "lmax", "vmax", "fpmax", "fvmax"}, {"adhesion", "?", "forcelimited", "ctrlrange", "forcerange", "gain", "user", "group", "nsample", "interp", "delay"}, + {"dcmotor", "?", "ctrllimited", "ctrlrange", + "gear", "damping", "armature", "cranklength", "user", "group", "nsample", "interp", "delay", + "motorconst", "resistance", "nominal", "saturation", + "inductance", "cogging", "controller", "input", "thermal", "lugre"}, {">"}, {"extension", "*"}, @@ -436,6 +440,12 @@ std::vector MJCF[nMJCF] = { "lmin", "lmax", "vmax", "fpmax", "fvmax"}, {"adhesion", "*", "name", "class", "group", "nsample", "interp", "delay", "forcelimited", "ctrlrange", "forcerange", "user", "body", "gain"}, + {"dcmotor", "*", "name", "class", "group", "nsample", "interp", "delay", + "ctrllimited", "ctrlrange", + "lengthrange", "gear", "damping", "armature", "cranklength", "user", + "joint", "jointinparent", "tendon", "slidersite", "cranksite", "site", "refsite", + "motorconst", "resistance", "nominal", "saturation", + "inductance", "cogging", "controller", "thermal", "lugre", "input"}, {"plugin", "*", "name", "class", "plugin", "instance", "group", "nsample", "interp", "delay", "ctrllimited", "forcelimited", "actlimited", "ctrlrange", "forcerange", "actrange", "lengthrange", "gear", "damping", "armature", "cranklength", "joint", "jointinparent", @@ -724,33 +734,45 @@ const mjMap mark_map[mark_sz] = { // dyn type -const int dyn_sz = 6; +const int dyn_sz = 7; const mjMap dyn_map[dyn_sz] = { {"none", mjDYN_NONE}, {"integrator", mjDYN_INTEGRATOR}, {"filter", mjDYN_FILTER}, {"filterexact", mjDYN_FILTEREXACT}, {"muscle", mjDYN_MUSCLE}, + {"dcmotor", mjDYN_DCMOTOR}, {"user", mjDYN_USER} }; +// dcmotor controller input mode +const int dcmotorinput_sz = 3; +const mjMap dcmotorinput_map[dcmotorinput_sz] = { + {"voltage", 0}, + {"position", 1}, + {"velocity", 2} +}; + + // gain type -const int gain_sz = 4; +const int gain_sz = 5; const mjMap gain_map[gain_sz] = { {"fixed", mjGAIN_FIXED}, {"affine", mjGAIN_AFFINE}, {"muscle", mjGAIN_MUSCLE}, + {"dcmotor", mjGAIN_DCMOTOR}, {"user", mjGAIN_USER} }; // bias type -const int bias_sz = 4; +const int bias_sz = 5; const mjMap bias_map[bias_sz] = { {"none", mjBIAS_NONE}, {"affine", mjBIAS_AFFINE}, {"muscle", mjBIAS_MUSCLE}, + {"dcmotor", mjBIAS_DCMOTOR}, {"user", mjBIAS_USER} }; @@ -2498,6 +2520,54 @@ void mjXReader::OneActuator(XMLElement* elem, mjsActuator* actuator) { err = mjs_setToAdhesion(actuator, gain); } + // DC motor + else if (type == "dcmotor") { + bool inherited = (actuator->gaintype == mjGAIN_DCMOTOR); + double motorconst[2] = {inherited ? actuator->gainprm[1] : 0, 0}; + double resistance = inherited ? actuator->gainprm[0] : 0; + double nominal[3] = {0, 0, 0}; + double saturation[4] = {0, 0, + inherited ? actuator->dynprm[1] : 0, + inherited ? actuator->gainprm[8] : 0}; + double controller[5] = {inherited ? actuator->gainprm[5] : 0, + inherited ? actuator->gainprm[6] : 0, + inherited ? actuator->gainprm[7] : 0, + inherited ? actuator->dynprm[7] : 0, + inherited ? actuator->dynprm[8] : 0}; + double inductance[2] = {0, inherited ? actuator->dynprm[0] : 0}; + double cogging[3] = {inherited ? actuator->biasprm[0] : 0, + inherited ? actuator->biasprm[1] : 0, + inherited ? actuator->biasprm[2] : 0}; + double thermal[6] = {inherited ? actuator->dynprm[2] : 0, + inherited ? actuator->dynprm[3] : 0, + 0, + inherited ? actuator->gainprm[2] : 0, + inherited ? actuator->gainprm[3] : 0, + inherited ? actuator->dynprm[4] : 0}; + double lugre[6] = {inherited ? actuator->dynprm[5] : 0, + inherited ? actuator->dynprm[6] : 0, + inherited ? actuator->damping[0] : 0, + inherited ? actuator->biasprm[3] : 0, + inherited ? actuator->biasprm[4] : 0, + inherited ? actuator->biasprm[5] : 0}; + int input_mode = inherited ? (int)actuator->gainprm[9] : 0; + ReadAttr(elem, "motorconst", 2, motorconst, text, false, false); + ReadAttr(elem, "resistance", 1, &resistance, text); + ReadAttr(elem, "nominal", 3, nominal, text, false, false); + ReadAttr(elem, "saturation", 4, saturation, text, false, false); + ReadAttr(elem, "inductance", 2, inductance, text, false, false); + ReadAttr(elem, "cogging", 3, cogging, text, false, false); + ReadAttr(elem, "controller", 5, controller, text, false, false); + ReadAttr(elem, "thermal", 6, thermal, text, false, false); + ReadAttr(elem, "lugre", 6, lugre, text, false, false); + if (MapValue(elem, "input", &input_mode, dcmotorinput_map, dcmotorinput_sz)) { + // successfully parsed + } + err = mjs_setToDCMotor(actuator, motorconst, resistance, + nominal, saturation, inductance, + cogging, controller, thermal, lugre, input_mode); + } + else if (type == "plugin") { OnePlugin(elem, &actuator->plugin); int n; @@ -2962,7 +3032,8 @@ void mjXReader::Default(XMLElement* section, const mjsDefault* def, const mjVFS* name == "intvelocity" || name == "cylinder" || name == "muscle" || - name == "adhesion") { + name == "adhesion" || + name == "dcmotor") { OneActuator(elem, def->actuator); } diff --git a/src/xml/xml_native_reader.h b/src/xml/xml_native_reader.h index 4e0369ce6a..8c568b22dc 100644 --- a/src/xml/xml_native_reader.h +++ b/src/xml/xml_native_reader.h @@ -102,7 +102,7 @@ class mjXReader : public mjXBase { }; // MJCF schema -#define nMJCF 246 +#define nMJCF 248 extern std::vector MJCF[nMJCF]; #endif // MUJOCO_SRC_XML_XML_NATIVE_READER_H_ diff --git a/src/xml/xml_native_writer.cc b/src/xml/xml_native_writer.cc index 144ffe6521..e9aa9ea7b3 100644 --- a/src/xml/xml_native_writer.cc +++ b/src/xml/xml_native_writer.cc @@ -871,7 +871,7 @@ void mjXWriter::OneActuator(XMLElement* elem, const mjCActuator* actuator, mjCDe if (writingdefaults) { WriteAttrInt(elem, "actdim", actuator->actdim, def->Actuator().actdim); } else { - int default_actdim = actuator->dyntype == mjDYN_NONE ? 0 : 1; + int default_actdim = (actuator->dyntype != mjDYN_NONE && actuator->dyntype != mjDYN_DCMOTOR); WriteAttrInt(elem, "actdim", actuator->actdim, default_actdim); } WriteAttrKey(elem, "dyntype", dyn_map, dyn_sz, actuator->dyntype, def->Actuator().dyntype); diff --git a/test/engine/engine_derivative_test.cc b/test/engine/engine_derivative_test.cc index df8f863bbd..c32e6b1e34 100644 --- a/test/engine/engine_derivative_test.cc +++ b/test/engine/engine_derivative_test.cc @@ -91,6 +91,8 @@ static const char* const kDampedPendulumPath = "engine/testdata/derivative/damped_pendulum.xml"; static const char* const kLinearPath = "engine/testdata/derivative/linear.xml"; +static const char* const kDCMotorPath = + "engine/testdata/derivative/dcmotor.xml"; static const char* const kModelPath = "testdata/model.xml"; // compare analytic and finite-difference d_smooth/d_qvel @@ -99,9 +101,12 @@ TEST_F(DerivativeTest, SmoothDvel) { for (const char* local_path : {kEnergyConservingPendulumPath, kTumblingThinObjectPath, kDampedActuatorsPath, - kDamperActuatorsPath}) { + kDamperActuatorsPath, + kDCMotorPath}) { const std::string xml_path = GetTestDataFilePath(local_path); - mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); + char error[1024] = ""; + mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error)); + ASSERT_THAT(model, testing::NotNull()) << "Failed to load model: " << error; int nD = model->nD; mjData* data = mj_makeData(model); @@ -758,9 +763,12 @@ TEST_F(DerivativeTest, DenseSparseRneEquivalent) { for (const char* local_path : {kEnergyConservingPendulumPath, kTumblingThinObjectPath, kDampedActuatorsPath, - kDamperActuatorsPath}) { + kDamperActuatorsPath, + kDCMotorPath}) { const std::string xml_path = GetTestDataFilePath(local_path); - mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, nullptr, 0); + char error[1024] = ""; + mjModel* model = mj_loadXML(xml_path.c_str(), nullptr, error, sizeof(error)); + ASSERT_THAT(model, testing::NotNull()) << "Failed to load model: " << error; int nD = model->nD; mjtNum* qDeriv = (mjtNum*) mju_malloc(sizeof(mjtNum)*nD); mjData* data = mj_makeData(model); diff --git a/test/engine/engine_forward_test.cc b/test/engine/engine_forward_test.cc index cee67e297f..f3acf0aa59 100644 --- a/test/engine/engine_forward_test.cc +++ b/test/engine/engine_forward_test.cc @@ -1148,6 +1148,949 @@ TEST_F(ActuatorTest, DampRatioTendon) { mj_deleteModel(model); } +// ----------------------- DC motor actuators ---------------------------------- + +using DCMotorTest = MujocoTest; + +TEST_F(DCMotorTest, IntVelocityEquivalence) { + static constexpr char xml[] = R"( + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + // Apply a time-varying velocity command + while (data->time < 1.0) { + data->ctrl[0] = mju_sin(20 * data->time); + data->ctrl[1] = mju_sin(20 * data->time); + mj_step(model, data); + + // Both actuators should integrate identical states + EXPECT_MJTNUM_EQ(data->act[0], data->act[1]); + + // Both bodies should move identically + EXPECT_NEAR(data->qpos[0], data->qpos[1], MjTol(1e-14, 1e-7)); + EXPECT_NEAR(data->qvel[0], data->qvel[1], MjTol(1e-14, 1e-7)); + EXPECT_NEAR(data->qacc[0], data->qacc[1], MjTol(1e-14, 1e-6)); + + // Both actuators should produce identical force + EXPECT_NEAR(data->actuator_force[0], data->actuator_force[1], + MjTol(1e-14, 1e-6)); + } + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, StatelessSteadyState) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + double K = 0.05; + double R = 2.0; + double V = 12.0; + double omega = 3.0; + + data->ctrl[0] = V; + data->qvel[0] = omega; + mj_forward(model, data); + + double expected_force = K / R * (V - K * omega); + EXPECT_NEAR(data->actuator_force[0], expected_force, MjTol(1e-12, 1e-5)); + EXPECT_EQ(model->actuator_actnum[0], 0); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, CurrentFilterConverges) { + static constexpr char xml[] = R"( + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + ASSERT_EQ(model->actuator_actnum[0], 1); + + double K = 0.05; + double R = 2.0; + double V = 12.0; + + data->ctrl[0] = V; + for (int i = 0; i < 10000; i++) { + mj_step(model, data); + } + + double omega = data->qvel[0]; + double i_ss = V / R - K / R * omega; + double expected_force = K * i_ss; + + EXPECT_NEAR(data->act[0], i_ss, MjTol(1e-6, 1e-4)); + EXPECT_NEAR(data->actuator_force[0], expected_force, MjTol(1e-6, 1e-4)); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, CurrentFilterExactIntegration) { + static constexpr char xml[] = R"( + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + double R = 2.0; + double te = 0.01 / R; + double V = 12.0; + + data->ctrl[0] = V; + mj_step(model, data); + + double h = model->opt.timestep; + double exact_current = V / R * (1 - mju_exp(-h / te)); + EXPECT_NEAR(data->act[0], exact_current, MjTol(1e-10, 1e-4)); + + double euler_current = V / R * h / te; + EXPECT_GT(std::abs(data->act[0] - euler_current), + std::abs(data->act[0] - exact_current)); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, CoggingTorque) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + double A = 0.1, Np = 6, phi = 0; + double K = 0.05, R = 2.0; + double V = 5.0; + double pos = 1.0; + + data->ctrl[0] = V; + data->qpos[0] = pos; + mj_forward(model, data); + + double electrical_force = K / R * V; + double cogging = A * mju_sin(Np * pos + phi); + EXPECT_NEAR(data->actuator_force[0], electrical_force + cogging, + MjTol(1e-12, 1e-5)); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, CoggingBypassesSaturation) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + double A = 0.1, Np = 6, phi = 0; + double pos = 1.0; + + data->ctrl[0] = 100.0; + data->qpos[0] = pos; + mj_forward(model, data); + + double cogging = A * mju_sin(Np * pos + phi); + EXPECT_NEAR(model->actuator_forcerange[1], 0.001, MjTol(1e-12, 1e-5)); + EXPECT_GT(mju_abs(data->actuator_force[0]), 0.001); + EXPECT_NEAR(data->actuator_force[0], 0.001 + cogging, MjTol(1e-12, 1e-5)); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, LuGreViscousFriction) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + ASSERT_EQ(model->actuator_actnum[0], 1); + + double sigma1 = 1, sigma2 = 0.01; + double K = 0.05, R = 2.0; + double omega = 2.0; + + data->ctrl[0] = 0; + data->qvel[0] = omega; + mj_forward(model, data); + + EXPECT_MJTNUM_EQ(model->actuator_damping[0], sigma2); + double electrical_force = K / R * (0 - K * omega); + double z = data->act[model->actuator_actadr[0]]; + double z_dot = data->act_dot[model->actuator_actadr[0]]; + double lugre_force = 100 * z + sigma1 * z_dot; + EXPECT_NEAR(data->actuator_force[0], electrical_force - lugre_force, + MjTol(1e-12, 1e-5)); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, ThermalRiseAndFall) { + static constexpr char xml[] = R"( + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + int adr = model->actuator_actadr[0]; + ASSERT_EQ(model->actuator_actnum[0], 1); + EXPECT_EQ(data->act[adr], 0); + + double R = 2.0, V = 10.0; + double RT = 10.0, C = 5.0; + double h = model->opt.timestep; + double P = V * V / R; + + data->ctrl[0] = V; + + mj_step(model, data); + double dT1 = h * P / C; + EXPECT_NEAR(data->act[adr], dT1, MjTol(1e-11, 1e-4)); + + mj_step(model, data); + double dT2 = dT1 + h * (P - dT1 / RT) / C; + EXPECT_NEAR(data->act[adr], dT2, MjTol(1e-11, 1e-4)); + + data->ctrl[0] = 0; + mj_step(model, data); + double dT3 = dT2 + h * (0 - dT2 / RT) / C; + EXPECT_NEAR(data->act[adr], dT3, MjTol(1e-11, 1e-4)); + EXPECT_LT(data->act[adr], dT2); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, ThermalSteadyState) { + static constexpr char xml[] = R"( + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + double R = 2.0, V = 10.0; + double RT = 0.1; + double dT_ss = RT * V * V / R; + + data->ctrl[0] = V; + for (int i = 0; i < 10000; i++) { + mj_step(model, data); + } + + int adr = model->actuator_actadr[0]; + EXPECT_NEAR(data->act[adr], dT_ss, 1e-4); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, ThermalAffectsForce) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + double K = 0.05, R = 2.0, V = 10.0; + double alpha = 0.004; + int adr = model->actuator_actadr[0]; + + data->ctrl[0] = V; + data->act[adr] = 0; + mj_forward(model, data); + double force_cold = data->actuator_force[0]; + EXPECT_NEAR(force_cold, K / R * V, MjTol(1e-12, 1e-5)); + + double dT = 50; + data->act[adr] = dT; + mj_forward(model, data); + double R_hot = R * (1 + alpha * dT); + double force_hot = data->actuator_force[0]; + EXPECT_NEAR(force_hot, K / R_hot * V, MjTol(1e-12, 1e-5)); + EXPECT_LT(force_hot, force_cold); + + mj_deleteData(data); + mj_deleteModel(model); +} + +// Temperature slot must be correctly offset past slew and integral states. +TEST_F(DCMotorTest, ThermalAffectsForceWithController) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + // slot order: slew(0), integral(1), temperature(2) + ASSERT_EQ(model->actuator_actnum[0], 3); + int adr = model->actuator_actadr[0]; + int temp_adr = adr + 2; // temperature is slot 2 + + double K = 0.05, R = 2.0, alpha = 0.004; + double dT = 50; + data->act[adr] = 1.0; // slew state = ctrl: no rate-limiting applied + data->act[adr + 1] = 0.0; // integral state x_I = 0 + data->act[temp_adr] = dT; // temperature rise above ambient + data->ctrl[0] = 1.0; // position setpoint = 1.0, qpos = 0, error = 1.0 + mj_forward(model, data); + + // u_eff = ctrl = 1.0 (no slew applied since act[slew] == ctrl) + // V = kp*(u_eff - length) + ki*x_I - kd*omega = 1.0*1.0 + 1.0*0.0 - 0*0 = 1.0 + // R(T) = 2.0 * (1 + 0.004 * 50) = 2.4 + // stateless (no te): force = K/R(T) * V = 0.05/2.4 * 1.0 + double R_hot = R * (1 + alpha * dT); + EXPECT_NEAR(data->actuator_force[0], K / R_hot * 1.0, MjTol(1e-12, 1e-5)); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, StatelessPositionMode) { + static constexpr char xml[] = R"( + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + // Position target 5.0, current pos 0.0, current vel 0.0 + data->ctrl[0] = 5.0; + mj_forward(model, data); + + // V = Kp * (u - theta) = 2.0 * 5.0 = 10.0 + // force = K / R * V + bias = (0.05 / 2.0) * 10.0 + 0 = 0.25 + EXPECT_NEAR(data->actuator_force[0], 0.25, MjTol(1e-12, 1e-5)); + + // Velocity penalty + data->qvel[0] = 2.0; + mj_forward(model, data); + // V = 10.0 - Kd * omega = 10.0 - (0.5 * 2.0) = 9.0 + // bias = - K^2 / R * omega = -0.0025 / 2.0 * 2.0 = -0.0025 + // force = K / R * V + bias = 0.225 - 0.0025 = 0.2225 + EXPECT_NEAR(data->actuator_force[0], 0.2225, MjTol(1e-12, 1e-5)); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, StatelessVelocityMode) { + static constexpr char xml[] = R"( + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + // Velocity target 4.0, current vel 1.0 + data->ctrl[0] = 4.0; + data->qvel[0] = 1.0; + mj_forward(model, data); + + // V = Kp * (u - omega) = 3.0 * (4.0 - 1.0) = 9.0 + // bias = - K^2 / R * omega = -0.0025 / 2.0 * 1.0 = -0.00125 + // force = K / R * V + bias = (0.05 / 2.0) * 9.0 - 0.00125 = 0.22375 + EXPECT_NEAR(data->actuator_force[0], 0.22375, MjTol(1e-12, 1e-5)); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, StatefulPositionMode) { + static constexpr char xml[] = R"( + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + // Controller states: 1 for slew, 1 for ki -> actnum = 2 + ASSERT_EQ(model->actuator_actnum[0], 2); + int adr = model->actuator_actadr[0]; + + // Current states + double u_prev = 1.0; + double x_I = 2.0; + data->act[adr] = u_prev; + data->act[adr+1] = x_I; + + // target 5.0 position, current 0.0 + data->ctrl[0] = 5.0; + data->qvel[0] = 0.5; + mj_forward(model, data); + + // slew bounding: s = 10.0, dt = 0.001. max_change = 0.01 + // Target = 5.0. It is upper bounded by u_prev + 0.01 = 1.01 + EXPECT_NEAR(data->act_dot[adr], 10.0, MjTol(1e-12, 1e-5)); + + // PI error: error = u_eff - length = 1.01 - 0.0 = 1.01 + EXPECT_NEAR(data->act_dot[adr+1], 1.01, MjTol(1e-12, 1e-5)); + + // V = Kp(u_eff - length) + Ki * x_I - Kd * omega + // V = 2.0 * 1.01 + 0.5 * 2.0 - 0.1 * 0.5 = 2.97 + // bias = - K^2/R * omega = -(0.05)^2 / 2.0 * 0.5 = -0.000625 + // force = K/R * V + bias = 0.025 * 2.97 - 0.000625 = 0.073625 + EXPECT_NEAR(data->actuator_force[0], 0.073625, MjTol(1e-12, 1e-5)); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, StatefulPositionWithCurrentMode) { + static constexpr char xml[] = R"( + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + // Controller states: slew (0), ki (1), current (2). actnum = 3 + ASSERT_EQ(model->actuator_actnum[0], 3); + int adr = model->actuator_actadr[0]; + + double u_prev = 1.0; + double x_I = 2.0; + double current = 0.5; + data->act[adr] = u_prev; + data->act[adr+1] = x_I; + data->act[adr+2] = current; + + // Target 5.0 position, velocity 0.5 + data->ctrl[0] = 5.0; + data->qvel[0] = 0.5; + mj_forward(model, data); + + // Slew bounding: max_change = 0.01, u_eff = 1.01 + EXPECT_NEAR(data->act_dot[adr], 10.0, MjTol(1e-12, 1e-5)); + + // PI error: error = u_eff - length = 1.01 + EXPECT_NEAR(data->act_dot[adr+1], 1.01, MjTol(1e-12, 1e-5)); + + // Voltage computation: + // V = Kp(u_eff - length) + Ki * x_I - Kd * omega + // V = 2.0 * 1.01 + 0.5 * 2.0 - 0.1 * 0.5 = 2.97 + + // Current filter: + // t_e = L / R = 1.0 / 2.0 = 0.5 + // di/dt = (V/R - K/R * omega - i) / t_e + // di/dt = (2.97/2.0 - 0.05/2.0 * 0.5 - 0.5) / 0.5 + // di/dt = (1.485 - 0.0125 - 0.5) / 0.5 = 0.9725 / 0.5 = 1.945 + EXPECT_NEAR(data->act_dot[adr+2], 1.945, MjTol(1e-12, 1e-5)); + + // Force is just K * current since current is stateful + EXPECT_NEAR(data->actuator_force[0], 0.05 * 0.5, MjTol(1e-12, 1e-5)); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, StatefulVelocityMode) { + static constexpr char xml[] = R"( + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + // Controller states: 1 for ki (no slew) + ASSERT_EQ(model->actuator_actnum[0], 1); + int adr = model->actuator_actadr[0]; + + double x_I = 2.0; // Exactly at Imax limit (Imax = 2.0) + data->act[adr] = x_I; + + // target vel 4.0, current vel 1.0 + data->ctrl[0] = 4.0; + data->qvel[0] = 1.0; + mj_forward(model, data); + + // integrate command directly: error = target = 4.0 + // since x_I == Imax (2.0) and error (4.0) > 0, act_dot should be clamped to 0 + EXPECT_NEAR(data->act_dot[adr], 0.0, MjTol(1e-12, 1e-5)); + + // V = Kp * (u_eff - omega) + Ki * (x_I - length) + // V = 3.0 * (4.0 - 1.0) + 1.0 * (2.0 - 0.0) = 9.0 + 2.0 = 11.0 + // bias = - K^2/R * omega = -(0.05)^2 / 2.0 * 1.0 = -0.00125 + // force = K/R * V + bias = 0.025 * 11.0 - 0.00125 = 0.275 - 0.00125 = 0.27375 + EXPECT_NEAR(data->actuator_force[0], 0.27375, MjTol(1e-12, 1e-5)); + + // repeat with non-zero joint position + data->qpos[0] = 1.5; + mj_forward(model, data); + + // V = 3.0 * (4.0 - 1.0) + 1.0 * (2.0 - 1.5) = 9.0 + 0.5 = 9.5 + // force = K/R * V + bias = 0.025 * 9.5 - 0.00125 = 0.2375 - 0.00125 = 0.23625 + EXPECT_NEAR(data->actuator_force[0], 0.23625, MjTol(1e-12, 1e-5)); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, CurrentPlusThermal) { + static constexpr char xml[] = R"( + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + ASSERT_EQ(model->actuator_actnum[0], 2); + int adr = model->actuator_actadr[0]; + + double K = 0.05, R = 2.0, V = 12.0; + double te = 0.01 / R; + double RT = 10.0, C = 5.0; + + double current = 3.0; + double dT = 10.0; + data->act[adr] = dT; + data->act[adr+1] = current; + data->ctrl[0] = V; + mj_forward(model, data); + + EXPECT_NEAR(data->actuator_force[0], K * current, MjTol(1e-12, 1e-5)); + + double R_hot = R * (1 + 0.004 * dT); + double T_dot = (R_hot * current * current - dT / RT) / C; + EXPECT_NEAR(data->act_dot[adr], T_dot, MjTol(1e-10, 1e-4)); + + double omega = data->qvel[0]; + double i_dot = (V/R_hot - K/R_hot*omega - current) / te; + EXPECT_NEAR(data->act_dot[adr+1], i_dot, MjTol(1e-10, 1e-3)); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, CurrentRateLimit) { + // Verifies that saturation:current_rate clamps di/dt. + static constexpr char xml[] = R"( + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + ASSERT_EQ(model->actuator_actnum[0], 1); + int adr = model->actuator_actadr[0]; + + double V = 12.0; + double dimax = 100.0; // A/s rate limit + + // unclamped: i_dot = (V/R - 0 - 0) / te = 6 / 0.005 = 1200 A/s >> dimax + data->act[adr] = 0; // current = 0 + data->ctrl[0] = V; + mj_forward(model, data); + + // i_dot should be clipped to +dimax + EXPECT_NEAR(data->act_dot[adr], dimax, MjTol(1e-12, 1e-5)); + + // reverse: large negative drive + data->ctrl[0] = -V; + mj_forward(model, data); + + // i_dot should be clipped to -dimax + EXPECT_NEAR(data->act_dot[adr], -dimax, MjTol(1e-12, 1e-5)); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, LuGreExactIntegration) { + static constexpr char xml[] = R"( + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + ASSERT_EQ(model->actuator_actnum[0], 1); + int adr = model->actuator_actadr[0]; + + double sigma0 = 100, F_C = 0.5, F_S = 0.7, v_S = 10; + double z0 = 0.002; + double v = 0.5; + double h = model->opt.timestep; + + data->act[adr] = z0; + data->qvel[0] = v; + + double ratio = v / v_S; + double g_v = F_C + (F_S - F_C) * mju_exp(-ratio*ratio); + double a = -sigma0 * std::abs(v) / g_v; + double exp_ah = mju_exp(a * h); + double int_h = (exp_ah - 1) / a; + double z_new = exp_ah * z0 + int_h * v; + + mj_step(model, data); + EXPECT_NEAR(data->act[adr], z_new, MjTol(1e-12, 1e-5)); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, LuGreSteadyState) { + static constexpr char xml[] = R"( + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + int adr = model->actuator_actadr[0]; + + double sigma0 = 100, sigma2 = 0.01; + double F_C = 0.5, F_S = 0.7, v_S = 10; + double K = 0.05, R = 2.0; + double v = 0.5; + + data->qvel[0] = v; + data->ctrl[0] = 0; + for (int i = 0; i < 10000; i++) { + mj_step(model, data); + } + + double ratio = v / v_S; + double g_v = F_C + (F_S - F_C) * mju_exp(-ratio*ratio); + double z_ss = g_v / sigma0; + EXPECT_NEAR(data->act[adr], z_ss, 1e-4); + + EXPECT_MJTNUM_EQ(model->actuator_damping[0], sigma2); + double back_emf = K * K / R * data->qvel[0]; + double lugre_ss = g_v; + EXPECT_NEAR(data->actuator_force[0], -back_emf - lugre_ss, 1e-3); + + mj_deleteData(data); + mj_deleteModel(model); +} + +TEST_F(DCMotorTest, LuGreBristleSpring) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + char error[1024]; + mjModel* model = LoadModelFromString(xml, error, sizeof(error)); + ASSERT_THAT(model, NotNull()) << error; + mjData* data = mj_makeData(model); + + int adr = model->actuator_actadr[0]; + double sigma0 = 100; + double X = 0.01; + + data->act[adr] = X; + data->ctrl[0] = 0; + mj_forward(model, data); + + EXPECT_NEAR(data->actuator_force[0], -sigma0 * X, MjTol(1e-12, 1e-5)); + + mj_deleteData(data); + mj_deleteModel(model); +} + // ----------------------- filterexact actuators ------------------------------- using FilterExactTest = MujocoTest; diff --git a/test/engine/testdata/derivative/dcmotor.xml b/test/engine/testdata/derivative/dcmotor.xml new file mode 100644 index 0000000000..d3c4b0acad --- /dev/null +++ b/test/engine/testdata/derivative/dcmotor.xml @@ -0,0 +1,35 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/test/xml/xml_native_reader_test.cc b/test/xml/xml_native_reader_test.cc index 45ae2393de..bd1b517bc3 100644 --- a/test/xml/xml_native_reader_test.cc +++ b/test/xml/xml_native_reader_test.cc @@ -3003,6 +3003,325 @@ TEST_F(ActuatorParseTest, AdhesionInheritsFromGeneral) { mj_deleteModel(model); } +TEST_F(ActuatorParseTest, DCMotorBasicParsing) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + std::array error; + mjModel* model = LoadModelFromString(xml, error.data(), error.size()); + ASSERT_THAT(model, NotNull()) << error.data(); + EXPECT_EQ(model->actuator_dyntype[0], mjDYN_DCMOTOR); + EXPECT_EQ(model->actuator_gaintype[0], mjGAIN_DCMOTOR); + EXPECT_EQ(model->actuator_biastype[0], mjBIAS_DCMOTOR); + EXPECT_MJTNUM_EQ(model->actuator_gainprm[0], 2.0); + EXPECT_MJTNUM_EQ(model->actuator_gainprm[1], 0.05); + EXPECT_MJTNUM_EQ(model->actuator_damping[0], 1.0); + EXPECT_MJTNUM_EQ(model->actuator_dampingpoly[0], 2.0); + EXPECT_MJTNUM_EQ(model->actuator_dampingpoly[1], 3.0); + EXPECT_MJTNUM_EQ(model->actuator_armature[0], 0.1); + mj_deleteModel(model); +} + +TEST_F(ActuatorParseTest, DCMotorNominalDerivation) { + static constexpr char xml[] = R"( + + + + + + + + + + + + + + + + + )"; + std::array error; + mjModel* model = LoadModelFromString(xml, error.data(), error.size()); + ASSERT_THAT(model, NotNull()) << error.data(); + + // actuator 0: B = 0, Ke = vn/omega0 + { + double K = 12.0 / 600.0; + double R = K * 12.0 / 0.6; + EXPECT_MJTNUM_EQ(model->actuator_gainprm[0*mjNGAIN + 0], R); + EXPECT_MJTNUM_EQ(model->actuator_gainprm[0*mjNGAIN + 1], K); + } + + // actuator 1: B > 0, R given, quadratic Ke^2*omega0 - Ke*vn + R*B*omega0 = 0 + { + double B = 0.0001, R = 0.4, vn = 12.0, omega0 = 600.0; + double disc = vn*vn - 4*R*B*omega0*omega0; + double Ke = (vn + sqrt(disc)) / (2*omega0); + EXPECT_MJTNUM_EQ(model->actuator_gainprm[1*mjNGAIN + 0], R); + EXPECT_MJTNUM_EQ(model->actuator_gainprm[1*mjNGAIN + 1], Ke); + } + + // actuator 2: B > 0, R from nominal, Ke = vn/omega0 - vn*B/tau0 + { + double B = 0.0001, vn = 12.0, tau0 = 0.6, omega0 = 600.0; + double Ke = vn / omega0 - vn*B / tau0; + double R = Ke * vn / tau0; + EXPECT_MJTNUM_EQ(model->actuator_gainprm[2*mjNGAIN + 0], R); + EXPECT_MJTNUM_EQ(model->actuator_gainprm[2*mjNGAIN + 1], Ke); + } + + mj_deleteModel(model); +} + +TEST_F(ActuatorParseTest, DCMotorSaturation) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + std::array error; + mjModel* model = LoadModelFromString(xml, error.data(), error.size()); + ASSERT_THAT(model, NotNull()) << error.data(); + EXPECT_EQ(model->actuator_forcelimited[0], 1); + EXPECT_MJTNUM_EQ(model->actuator_forcerange[0], -1.5); + EXPECT_MJTNUM_EQ(model->actuator_forcerange[1], 1.5); + mj_deleteModel(model); +} + +TEST_F(ActuatorParseTest, DCMotorLuGreRemapping) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + std::array error; + mjModel* model = LoadModelFromString(xml, error.data(), error.size()); + ASSERT_THAT(model, NotNull()) << error.data(); + EXPECT_MJTNUM_EQ(model->actuator_dynprm[5], 100); + EXPECT_MJTNUM_EQ(model->actuator_dynprm[6], 1); + EXPECT_MJTNUM_EQ(model->actuator_damping[0], 0.01); + EXPECT_MJTNUM_EQ(model->actuator_biasprm[3], 0.5); + EXPECT_MJTNUM_EQ(model->actuator_biasprm[4], 0.7); + EXPECT_MJTNUM_EQ(model->actuator_biasprm[5], 10); + mj_deleteModel(model); +} + +TEST_F(ActuatorParseTest, DCMotorActdimStateless) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + std::array error; + mjModel* model = LoadModelFromString(xml, error.data(), error.size()); + ASSERT_THAT(model, NotNull()) << error.data(); + EXPECT_EQ(model->actuator_actnum[0], 0); + EXPECT_EQ(model->actuator_actadr[0], -1); + mj_deleteModel(model); +} + +TEST_F(ActuatorParseTest, DCMotorActdimCurrentOnly) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + std::array error; + mjModel* model = LoadModelFromString(xml, error.data(), error.size()); + ASSERT_THAT(model, NotNull()) << error.data(); + EXPECT_EQ(model->actuator_actnum[0], 1); + EXPECT_MJTNUM_EQ(model->actuator_dynprm[0], 0.001 / 2.0); + mj_deleteModel(model); +} + +TEST_F(ActuatorParseTest, DCMotorActdimThermalOnly) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + std::array error; + mjModel* model = LoadModelFromString(xml, error.data(), error.size()); + ASSERT_THAT(model, NotNull()) << error.data(); + EXPECT_EQ(model->actuator_actnum[0], 1); + EXPECT_MJTNUM_EQ(model->actuator_dynprm[2], 10); + EXPECT_MJTNUM_EQ(model->actuator_dynprm[3], 5); + EXPECT_MJTNUM_EQ(model->actuator_dynprm[4], 25); + mj_deleteModel(model); +} + +TEST_F(ActuatorParseTest, DCMotorActdimLuGreOnly) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + std::array error; + mjModel* model = LoadModelFromString(xml, error.data(), error.size()); + ASSERT_THAT(model, NotNull()) << error.data(); + EXPECT_EQ(model->actuator_actnum[0], 1); + EXPECT_MJTNUM_EQ(model->actuator_dynprm[5], 100); + mj_deleteModel(model); +} + +TEST_F(ActuatorParseTest, DCMotorActdimAllThree) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + std::array error; + mjModel* model = LoadModelFromString(xml, error.data(), error.size()); + ASSERT_THAT(model, NotNull()) << error.data(); + EXPECT_EQ(model->actuator_actnum[0], 3); + mj_deleteModel(model); +} + +TEST_F(ActuatorParseTest, DCMotorMissingKError) { + static constexpr char xml[] = R"( + + + + + + + + + + + + )"; + std::array error; + mjModel* model = LoadModelFromString(xml, error.data(), error.size()); + ASSERT_THAT(model, IsNull()); + EXPECT_THAT(error.data(), HasSubstr("motor constant K must be positive")); +} + +TEST_F(ActuatorParseTest, DCMotorDefaultsPropagate) { + static constexpr char xml[] = R"( + + + + + + + + + + + + + + + )"; + std::array error; + mjModel* model = LoadModelFromString(xml, error.data(), error.size()); + ASSERT_THAT(model, NotNull()) << error.data(); + EXPECT_MJTNUM_EQ(model->actuator_gainprm[0], 1.5); + EXPECT_MJTNUM_EQ(model->actuator_gainprm[1], 0.03); + mj_deleteModel(model); +} + +TEST_F(ActuatorParseTest, DCMotorMotorconstGeometricMean) { + static constexpr char xml[] = R"( + + + + + + + + + + + + + )"; + std::array error; + mjModel* model = LoadModelFromString(xml, error.data(), error.size()); + ASSERT_THAT(model, NotNull()) << error.data(); + double K = std::sqrt(0.03 * 0.05); + EXPECT_MJTNUM_EQ(model->actuator_gainprm[0], 2.0); + EXPECT_MJTNUM_EQ(model->actuator_gainprm[1], K); + EXPECT_MJTNUM_EQ(model->actuator_gainprm[mjNGAIN + 1], 0.03); + mj_deleteModel(model); +} + TEST_F(ActuatorParseTest, ActdimDefaultsPropagate) { static constexpr char xml[] = R"( diff --git a/unity/Runtime/Bindings/MjBindings.cs b/unity/Runtime/Bindings/MjBindings.cs index ea8ae869c2..1e6168a9de 100644 --- a/unity/Runtime/Bindings/MjBindings.cs +++ b/unity/Runtime/Bindings/MjBindings.cs @@ -269,19 +269,22 @@ public enum mjtDyn : int{ mjDYN_FILTER = 2, mjDYN_FILTEREXACT = 3, mjDYN_MUSCLE = 4, - mjDYN_USER = 5, + mjDYN_DCMOTOR = 5, + mjDYN_USER = 6, } public enum mjtGain : int{ mjGAIN_FIXED = 0, mjGAIN_AFFINE = 1, mjGAIN_MUSCLE = 2, - mjGAIN_USER = 3, + mjGAIN_DCMOTOR = 3, + mjGAIN_USER = 4, } public enum mjtBias : int{ mjBIAS_NONE = 0, mjBIAS_AFFINE = 1, mjBIAS_MUSCLE = 2, - mjBIAS_USER = 3, + mjBIAS_DCMOTOR = 3, + mjBIAS_USER = 4, } public enum mjtObj : int{ mjOBJ_UNKNOWN = 0, diff --git a/wasm/codegen/generated/bindings.cc b/wasm/codegen/generated/bindings.cc index 53013ccd7f..cfa83b4068 100644 --- a/wasm/codegen/generated/bindings.cc +++ b/wasm/codegen/generated/bindings.cc @@ -9876,6 +9876,18 @@ std::string mjs_setToCylinder_wrapper(MjsActuator& actuator, double timeconst, d return std::string(mjs_setToCylinder(actuator.get(), timeconst, bias, area, diameter)); } +std::string mjs_setToDCMotor_wrapper(MjsActuator& actuator, const val& motorconst, double resistance, const val& nominal, const val& saturation, const val& inductance, const val& cogging, const val& controller, const val& thermal, const val& lugre, int input_mode) { + UNPACK_VALUE(double, motorconst); + UNPACK_VALUE(double, nominal); + UNPACK_VALUE(double, saturation); + UNPACK_VALUE(double, inductance); + UNPACK_VALUE(double, cogging); + UNPACK_VALUE(double, controller); + UNPACK_VALUE(double, thermal); + UNPACK_VALUE(double, lugre); + return std::string(mjs_setToDCMotor(actuator.get(), motorconst_.data(), resistance, nominal_.data(), saturation_.data(), inductance_.data(), cogging_.data(), controller_.data(), thermal_.data(), lugre_.data(), input_mode)); +} + std::string mjs_setToDamper_wrapper(MjsActuator& actuator, double kv) { return std::string(mjs_setToDamper(actuator.get(), kv)); } @@ -10812,6 +10824,7 @@ EMSCRIPTEN_BINDINGS(mujoco_bindings) { .value("mjBIAS_NONE", mjBIAS_NONE) .value("mjBIAS_AFFINE", mjBIAS_AFFINE) .value("mjBIAS_MUSCLE", mjBIAS_MUSCLE) + .value("mjBIAS_DCMOTOR", mjBIAS_DCMOTOR) .value("mjBIAS_USER", mjBIAS_USER); enum_("mjtBuiltin") .value("mjBUILTIN_NONE", mjBUILTIN_NONE) @@ -10912,6 +10925,7 @@ EMSCRIPTEN_BINDINGS(mujoco_bindings) { .value("mjDYN_FILTER", mjDYN_FILTER) .value("mjDYN_FILTEREXACT", mjDYN_FILTEREXACT) .value("mjDYN_MUSCLE", mjDYN_MUSCLE) + .value("mjDYN_DCMOTOR", mjDYN_DCMOTOR) .value("mjDYN_USER", mjDYN_USER); enum_("mjtEnableBit") .value("mjENBL_OVERRIDE", mjENBL_OVERRIDE) @@ -10974,6 +10988,7 @@ EMSCRIPTEN_BINDINGS(mujoco_bindings) { .value("mjGAIN_FIXED", mjGAIN_FIXED) .value("mjGAIN_AFFINE", mjGAIN_AFFINE) .value("mjGAIN_MUSCLE", mjGAIN_MUSCLE) + .value("mjGAIN_DCMOTOR", mjGAIN_DCMOTOR) .value("mjGAIN_USER", mjGAIN_USER); enum_("mjtGeom") .value("mjGEOM_PLANE", mjGEOM_PLANE) @@ -13295,6 +13310,7 @@ EMSCRIPTEN_BINDINGS(mujoco_bindings) { function("mjs_setName", &mjs_setName_wrapper); function("mjs_setToAdhesion", &mjs_setToAdhesion_wrapper); function("mjs_setToCylinder", &mjs_setToCylinder_wrapper); + function("mjs_setToDCMotor", &mjs_setToDCMotor_wrapper); function("mjs_setToDamper", &mjs_setToDamper_wrapper); function("mjs_setToIntVelocity", &mjs_setToIntVelocity_wrapper); function("mjs_setToMotor", &mjs_setToMotor_wrapper); From b3b0bd676cad7ef44165aad4ee6d7f44d3ce69d0 Mon Sep 17 00:00:00 2001 From: Taylor Howell Date: Wed, 1 Apr 2026 09:32:47 -0700 Subject: [PATCH 19/20] Import google-deepmind/mujoco_warp from GitHub. PiperOrigin-RevId: 892971818 Change-Id: Ibce0c41294a4fcf2825a246a9533e8927fdc7e82 --- .../mjx/third_party/mujoco_warp/__init__.py | 2 + .../mjx/third_party/mujoco_warp/_src/bvh.py | 596 +-- .../mujoco_warp/_src/collision_convex.py | 27 +- .../mujoco_warp/_src/collision_core.py | 213 +- .../mujoco_warp/_src/collision_driver.py | 31 +- .../mujoco_warp/_src/collision_flex.py | 834 +++++ .../mujoco_warp/_src/collision_gjk.py | 31 +- .../mujoco_warp/_src/collision_primitive.py | 38 +- .../_src/collision_primitive_core.py | 504 +++ .../mujoco_warp/_src/collision_sdf.py | 441 +-- .../mujoco_warp/_src/constraint.py | 3276 +++++++++-------- .../mujoco_warp/_src/derivative.py | 193 +- .../third_party/mujoco_warp/_src/forward.py | 419 +-- .../mjx/third_party/mujoco_warp/_src/io.py | 878 +++-- .../third_party/mujoco_warp/_src/island.py | 33 +- .../mjx/third_party/mujoco_warp/_src/math.py | 29 + .../third_party/mujoco_warp/_src/passive.py | 141 +- .../mjx/third_party/mujoco_warp/_src/ray.py | 22 +- .../third_party/mujoco_warp/_src/render.py | 384 +- .../mujoco_warp/_src/render_util.py | 38 + .../third_party/mujoco_warp/_src/sensor.py | 272 +- .../third_party/mujoco_warp/_src/smooth.py | 1358 ++++--- .../third_party/mujoco_warp/_src/solver.py | 1180 +++--- .../third_party/mujoco_warp/_src/support.py | 34 + .../mjx/third_party/mujoco_warp/_src/types.py | 281 +- .../third_party/mujoco_warp/_src/util_pkg.py | 20 +- .../third_party/mujoco_warp/_src/warp_util.py | 4 +- .../third_party/mujoco_warp/pyproject.toml | 4 +- .../mjx/third_party/mujoco_warp/viewer.py | 5 +- mjx/mujoco/mjx/warp/bvh.py | 31 +- mjx/mujoco/mjx/warp/collision_driver.py | 113 +- mjx/mujoco/mjx/warp/forward.py | 290 +- mjx/mujoco/mjx/warp/forward_test.py | 11 +- mjx/mujoco/mjx/warp/render.py | 16 +- mjx/mujoco/mjx/warp/smooth.py | 23 +- mjx/mujoco/mjx/warp/types.py | 82 +- 36 files changed, 7240 insertions(+), 4614 deletions(-) create mode 100644 mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_flex.py diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/__init__.py b/mjx/mujoco/mjx/third_party/mujoco_warp/__init__.py index 1ff05ff6a6..40653b62dc 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/__init__.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/__init__.py @@ -64,6 +64,7 @@ from mujoco.mjx.third_party.mujoco_warp._src.render import render as render from mujoco.mjx.third_party.mujoco_warp._src.render_util import get_depth as get_depth from mujoco.mjx.third_party.mujoco_warp._src.render_util import get_rgb as get_rgb +from mujoco.mjx.third_party.mujoco_warp._src.render_util import get_segmentation as get_segmentation from mujoco.mjx.third_party.mujoco_warp._src.sensor import energy_pos as energy_pos from mujoco.mjx.third_party.mujoco_warp._src.sensor import energy_vel as energy_vel from mujoco.mjx.third_party.mujoco_warp._src.sensor import sensor_acc as sensor_acc @@ -92,6 +93,7 @@ from mujoco.mjx.third_party.mujoco_warp._src.types import BiasType as BiasType from mujoco.mjx.third_party.mujoco_warp._src.types import BroadphaseFilter as BroadphaseFilter from mujoco.mjx.third_party.mujoco_warp._src.types import BroadphaseType as BroadphaseType +from mujoco.mjx.third_party.mujoco_warp._src.types import Callback as Callback from mujoco.mjx.third_party.mujoco_warp._src.types import ConeType as ConeType from mujoco.mjx.third_party.mujoco_warp._src.types import Constraint as Constraint from mujoco.mjx.third_party.mujoco_warp._src.types import Contact as Contact diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/bvh.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/bvh.py index c40fcfc98f..58f7b2213a 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/bvh.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/bvh.py @@ -189,12 +189,12 @@ def _compute_bvh_bounds( upper_out: wp.array(dtype=wp.vec3), group_out: wp.array(dtype=int), ): - world_id, geom_local_id = wp.tid() + worldid, geom_local_id = wp.tid() geom_id = enabled_geom_ids[geom_local_id] - pos = geom_xpos_in[world_id, geom_id] - rot = geom_xmat_in[world_id, geom_id] - size = geom_size[world_id % geom_size.shape[0], geom_id] + pos = geom_xpos_in[worldid, geom_id] + rot = geom_xmat_in[worldid, geom_id] + size = geom_size[worldid % geom_size.shape[0], geom_id] type = geom_type[geom_id] # TODO: Investigate branch elimination with static loop unrolling @@ -218,9 +218,9 @@ def _compute_bvh_bounds( hfield_center = pos + rot[:, 2] * size[2] lower_bound, upper_bound = _compute_box_bounds(hfield_center, rot, size) - lower_out[world_id * bvh_ngeom + geom_local_id] = lower_bound - upper_out[world_id * bvh_ngeom + geom_local_id] = upper_bound - group_out[world_id * bvh_ngeom + geom_local_id] = world_id + lower_out[worldid * bvh_ngeom + geom_local_id] = lower_bound + upper_out[worldid * bvh_ngeom + geom_local_id] = upper_bound + group_out[worldid * bvh_ngeom + geom_local_id] = worldid @wp.kernel @@ -235,14 +235,70 @@ def compute_bvh_group_roots( group_root_out[tid] = root +@wp.kernel +def _compute_flex_bvh_bounds( + # Model: + flex_vertadr: wp.array(dtype=int), + flex_vertnum: wp.array(dtype=int), + flex_edge: wp.array(dtype=wp.vec2i), + flex_radius: wp.array(dtype=float), + # Data in: + flexvert_xpos_in: wp.array2d(dtype=wp.vec3), + # In: + flex_geom_flexid: wp.array(dtype=int), + flex_geom_edgeid: wp.array(dtype=int), + bvh_ngeom: int, + total_bvh_size: int, + # Out: + lower_out: wp.array(dtype=wp.vec3), + upper_out: wp.array(dtype=wp.vec3), + group_out: wp.array(dtype=int), +): + worldid, flexlocalid = wp.tid() + + flex_id = flex_geom_flexid[flexlocalid] + edge_id = flex_geom_edgeid[flexlocalid] + out_idx = worldid * total_bvh_size + bvh_ngeom + flexlocalid + radius = flex_radius[flex_id] + inflate = wp.vec3(radius, radius, radius) + + if edge_id >= 0: # capsule (1D edge) + edge = flex_edge[edge_id] + vert_adr = flex_vertadr[flex_id] + v0 = flexvert_xpos_in[worldid, vert_adr + edge[0]] + v1 = flexvert_xpos_in[worldid, vert_adr + edge[1]] + lower_out[out_idx] = wp.min(v0, v1) - inflate + upper_out[out_idx] = wp.max(v0, v1) + inflate + else: # mesh (2D/3D) + vert_adr = flex_vertadr[flex_id] + nvert = flex_vertnum[flex_id] + min_bound = wp.vec3(MJ_MAXVAL, MJ_MAXVAL, MJ_MAXVAL) + max_bound = wp.vec3(-MJ_MAXVAL, -MJ_MAXVAL, -MJ_MAXVAL) + for i in range(nvert): + v = flexvert_xpos_in[worldid, vert_adr + i] + min_bound = wp.min(min_bound, v) + max_bound = wp.max(max_bound, v) + lower_out[out_idx] = min_bound - inflate + upper_out[out_idx] = max_bound + inflate + + group_out[out_idx] = worldid + + def build_scene_bvh(mjm: mujoco.MjModel, mjd: mujoco.MjData, rc: RenderContext, nworld: int): """Build a global BVH for all geometries in all worlds.""" + total_bvh_size = rc.bvh_ngeom + rc.bvh_nflexgeom + geom_type = wp.array(mjm.geom_type, dtype=int) geom_dataid = wp.array(mjm.geom_dataid, dtype=int) geom_size = wp.array(np.tile(mjm.geom_size[np.newaxis, :, :], (nworld, 1, 1)), dtype=wp.vec3) geom_xpos = wp.array(np.tile(mjd.geom_xpos[np.newaxis, :, :], (nworld, 1, 1)), dtype=wp.vec3) geom_xmat = wp.array(np.tile(mjd.geom_xmat.reshape(mjm.ngeom, 3, 3)[np.newaxis, :, :, :], (nworld, 1, 1, 1)), dtype=wp.mat33) + flex_vertadr = wp.array(mjm.flex_vertadr, dtype=int) + flex_vertnum = wp.array(mjm.flex_vertnum, dtype=int) + flex_edge = wp.array(mjm.flex_edge, dtype=wp.vec2i) + flex_radius = wp.array(mjm.flex_radius, dtype=float) + wp.launch( kernel=_compute_bvh_bounds, dim=(nworld, rc.bvh_ngeom), @@ -252,7 +308,7 @@ def build_scene_bvh(mjm: mujoco.MjModel, mjd: mujoco.MjData, rc: RenderContext, geom_size, geom_xpos, geom_xmat, - rc.bvh_ngeom, + total_bvh_size, rc.enabled_geom_ids, rc.mesh_bounds_size, rc.hfield_bounds_size, @@ -262,6 +318,26 @@ def build_scene_bvh(mjm: mujoco.MjModel, mjd: mujoco.MjData, rc: RenderContext, ], ) + flexvert_xpos = wp.array(np.tile(mjd.flexvert_xpos[np.newaxis, :, :], (nworld, 1, 1)), dtype=wp.vec3) + wp.launch( + kernel=_compute_flex_bvh_bounds, + dim=(nworld, rc.bvh_nflexgeom), + inputs=[ + flex_vertadr, + flex_vertnum, + flex_edge, + flex_radius, + flexvert_xpos, + rc.flex_geom_flexid, + rc.flex_geom_edgeid, + rc.bvh_ngeom, + total_bvh_size, + rc.lower, + rc.upper, + rc.group, + ], + ) + bvh = wp.Bvh(rc.lower, rc.upper, groups=rc.group, constructor="sah") # BVH handle must be stored to avoid garbage collection @@ -277,6 +353,8 @@ def build_scene_bvh(mjm: mujoco.MjModel, mjd: mujoco.MjData, rc: RenderContext, def refit_scene_bvh(m: Model, d: Data, rc: RenderContext): + total_bvh_size = rc.bvh_ngeom + rc.bvh_nflexgeom + wp.launch( kernel=_compute_bvh_bounds, dim=(d.nworld, rc.bvh_ngeom), @@ -286,7 +364,7 @@ def refit_scene_bvh(m: Model, d: Data, rc: RenderContext): m.geom_size, d.geom_xpos, d.geom_xmat, - rc.bvh_ngeom, + total_bvh_size, rc.enabled_geom_ids, rc.mesh_bounds_size, rc.hfield_bounds_size, @@ -296,6 +374,26 @@ def refit_scene_bvh(m: Model, d: Data, rc: RenderContext): ], ) + if rc.bvh_nflexgeom > 0: + wp.launch( + kernel=_compute_flex_bvh_bounds, + dim=(d.nworld, rc.bvh_nflexgeom), + inputs=[ + m.flex_vertadr, + m.flex_vertnum, + m.flex_edge, + m.flex_radius, + d.flexvert_xpos, + rc.flex_geom_flexid, + rc.flex_geom_edgeid, + rc.bvh_ngeom, + total_bvh_size, + rc.lower, + rc.upper, + rc.group, + ], + ) + rc.bvh.refit() @@ -500,6 +598,12 @@ def build_hfield_bvh( @wp.kernel def accumulate_flex_vertex_normals( # Model: + nflex: int, + flex_dim: wp.array(dtype=int), + flex_vertadr: wp.array(dtype=int), + flex_elemadr: wp.array(dtype=int), + flex_elemnum: wp.array(dtype=int), + flex_elemdataadr: wp.array(dtype=int), flex_elem: wp.array(dtype=int), # Data in: flexvert_xpos_in: wp.array2d(dtype=wp.vec3), @@ -509,10 +613,22 @@ def accumulate_flex_vertex_normals( """Accumulate per-vertex normals by summing adjacent face normals.""" worldid, elemid = wp.tid() - elem_base = elemid * 3 - i0 = flex_elem[elem_base + 0] - i1 = flex_elem[elem_base + 1] - i2 = flex_elem[elem_base + 2] + for i in range(nflex): + locid = elemid - flex_elemadr[i] + if locid >= 0 and locid < flex_elemnum[i]: + f = i + break + + if flex_dim[f] == 1 or flex_dim[f] == 3: + return + + local_elemid = elemid - flex_elemadr[f] + elem_adr = flex_elemdataadr[f] + vert_adr = flex_vertadr[f] + elem_base = elem_adr + local_elemid * 3 + i0 = vert_adr + flex_elem[elem_base + 0] + i1 = vert_adr + flex_elem[elem_base + 1] + i2 = vert_adr + flex_elem[elem_base + 2] v0 = flexvert_xpos_in[worldid, i0] v1 = flexvert_xpos_in[worldid, i1] @@ -611,11 +727,12 @@ def _build_flex_2d_elements( @wp.kernel def _build_flex_2d_sides( + # Model: + flex_shell: wp.array(dtype=int), # Data in: flexvert_xpos_in: wp.array2d(dtype=wp.vec3), # In: flexvert_norm_in: wp.array2d(dtype=wp.vec3), - flex_shell_in: wp.array(dtype=int), shell_adr: int, vert_adr: int, face_offset: int, @@ -635,8 +752,8 @@ def _build_flex_2d_sides( worldid, shellid = wp.tid() base = shell_adr + 2 * shellid - i0 = vert_adr + flex_shell_in[base + 0] - i1 = vert_adr + flex_shell_in[base + 1] + i0 = vert_adr + flex_shell[base + 0] + i1 = vert_adr + flex_shell[base + 1] v0 = flexvert_xpos_in[worldid, i0] v1 = flexvert_xpos_in[worldid, i1] @@ -672,10 +789,11 @@ def _build_flex_2d_sides( @wp.kernel def _build_flex_3d_shells( + # Model: + flex_shell: wp.array(dtype=int), # Data in: flexvert_xpos_in: wp.array2d(dtype=wp.vec3), # In: - flex_shell_in: wp.array(dtype=int), shell_adr: int, vert_adr: int, face_offset: int, @@ -693,9 +811,9 @@ def _build_flex_3d_shells( worldid, shellid = wp.tid() base = shell_adr + shellid * 3 - i0 = vert_adr + flex_shell_in[base + 0] - i1 = vert_adr + flex_shell_in[base + 1] - i2 = vert_adr + flex_shell_in[base + 2] + i0 = vert_adr + flex_shell[base + 0] + i1 = vert_adr + flex_shell[base + 1] + i2 = vert_adr + flex_shell[base + 2] face_id = worldid * nface + face_offset + shellid base = face_id * 3 @@ -716,163 +834,163 @@ def _build_flex_3d_shells( @wp.kernel -def _update_flex_face_points( +def _update_flex_2d_face_points( # Model: - nflex: int, - flex_dim: wp.array(dtype=int), flex_vertadr: wp.array(dtype=int), flex_elemnum: wp.array(dtype=int), + flex_elemdataadr: wp.array(dtype=int), + flex_shelldataadr: wp.array(dtype=int), flex_elem: wp.array(dtype=int), + flex_shell: wp.array(dtype=int), + flex_radius: wp.array(dtype=float), # Data in: flexvert_xpos_in: wp.array2d(dtype=wp.vec3), # In: - flex_shell_in: wp.array(dtype=int), flexvert_norm_in: wp.array2d(dtype=wp.vec3), - flex_elemdataadr: wp.array(dtype=int), - flex_shelldataadr: wp.array(dtype=int), - flex_faceadr: wp.array(dtype=int), - flex_radius: wp.array(dtype=float), - flex_workadr: wp.array(dtype=int), - flex_worknum: wp.array(dtype=int), - nfaces: int, + flex_id: int, + nface: int, smooth: bool, # Out: face_point_out: wp.array(dtype=wp.vec3), ): worldid, workid = wp.tid() - # identify which flex this work item belongs to - f = int(0) - locid = int(0) - for i in range(nflex): - locid = workid - flex_workadr[i] - if locid >= 0 and locid < flex_worknum[i]: - f = i - break - - dim = flex_dim[f] - face_offset = flex_faceadr[f] - world_face_offset = worldid * nfaces - vert_adr = flex_vertadr[f] + elem_adr = flex_elemdataadr[flex_id] + vert_adr = flex_vertadr[flex_id] + radius = flex_radius[flex_id] + nelem = flex_elemnum[flex_id] + world_face_offset = worldid * nface - if dim == 2: - radius = flex_radius[f] - elem_count = flex_elemnum[f] - - if locid < elem_count: - # 2D element faces - elemid = locid - elem_adr = flex_elemdataadr[f] - ebase = elem_adr + elemid * 3 - i0 = vert_adr + flex_elem[ebase + 0] - i1 = vert_adr + flex_elem[ebase + 1] - i2 = vert_adr + flex_elem[ebase + 2] - - v0 = flexvert_xpos_in[worldid, i0] - v1 = flexvert_xpos_in[worldid, i1] - v2 = flexvert_xpos_in[worldid, i2] - - # TODO: Use static conditional - if smooth: - n0 = flexvert_norm_in[worldid, i0] - n1 = flexvert_norm_in[worldid, i1] - n2 = flexvert_norm_in[worldid, i2] - else: - face_nrm = wp.cross(v1 - v0, v2 - v0) - face_nrm = wp.normalize(face_nrm) - n0 = face_nrm - n1 = face_nrm - n2 = face_nrm - - p0_pos = v0 + radius * n0 - p1_pos = v1 + radius * n1 - p2_pos = v2 + radius * n2 - - p0_neg = v0 - radius * n0 - p1_neg = v1 - radius * n1 - p2_neg = v2 - radius * n2 - - face_id0 = world_face_offset + face_offset + (2 * elemid) - base0 = face_id0 * 3 - face_point_out[base0 + 0] = p0_pos - face_point_out[base0 + 1] = p1_pos - face_point_out[base0 + 2] = p2_pos - - face_id1 = world_face_offset + face_offset + (2 * elemid + 1) - base1 = face_id1 * 3 - face_point_out[base1 + 0] = p0_neg - face_point_out[base1 + 1] = p1_neg - face_point_out[base1 + 2] = p2_neg - else: - # 2D shell faces - shellid = locid - elem_count - shell_adr = flex_shelldataadr[f] - sbase = shell_adr + 2 * shellid - i0 = vert_adr + flex_shell_in[sbase + 0] - i1 = vert_adr + flex_shell_in[sbase + 1] + if workid < nelem: + # 2D element faces + elemid = workid + ebase = elem_adr + elemid * 3 + i0 = vert_adr + flex_elem[ebase + 0] + i1 = vert_adr + flex_elem[ebase + 1] + i2 = vert_adr + flex_elem[ebase + 2] - v0 = flexvert_xpos_in[worldid, i0] - v1 = flexvert_xpos_in[worldid, i1] + v0 = flexvert_xpos_in[worldid, i0] + v1 = flexvert_xpos_in[worldid, i1] + v2 = flexvert_xpos_in[worldid, i2] + # TODO: Use static conditional + if smooth: n0 = flexvert_norm_in[worldid, i0] n1 = flexvert_norm_in[worldid, i1] - - shell_face_offset = face_offset + (2 * elem_count) - face_id0 = world_face_offset + shell_face_offset + (2 * shellid) - base0 = face_id0 * 3 - face_point_out[base0 + 0] = v0 + radius * n0 - face_point_out[base0 + 1] = v1 - radius * n1 - face_point_out[base0 + 2] = v1 + radius * n1 - - face_id1 = world_face_offset + shell_face_offset + (2 * shellid + 1) - base1 = face_id1 * 3 - face_point_out[base1 + 0] = v1 - radius * n1 - face_point_out[base1 + 1] = v0 + radius * n0 - face_point_out[base1 + 2] = v0 - radius * n0 + n2 = flexvert_norm_in[worldid, i2] + else: + face_nrm = wp.cross(v1 - v0, v2 - v0) + face_nrm = wp.normalize(face_nrm) + n0 = face_nrm + n1 = face_nrm + n2 = face_nrm + + p0_pos = v0 + radius * n0 + p1_pos = v1 + radius * n1 + p2_pos = v2 + radius * n2 + + p0_neg = v0 - radius * n0 + p1_neg = v1 - radius * n1 + p2_neg = v2 - radius * n2 + + face_id0 = world_face_offset + (2 * elemid) + base0 = face_id0 * 3 + face_point_out[base0 + 0] = p0_pos + face_point_out[base0 + 1] = p1_pos + face_point_out[base0 + 2] = p2_pos + + face_id1 = world_face_offset + (2 * elemid + 1) + base1 = face_id1 * 3 + face_point_out[base1 + 0] = p0_neg + face_point_out[base1 + 1] = p1_neg + face_point_out[base1 + 2] = p2_neg else: - # 3D shell faces - shellid = locid - shell_adr = flex_shelldataadr[f] - sbase = shell_adr + shellid * 3 - i0 = vert_adr + flex_shell_in[sbase + 0] - i1 = vert_adr + flex_shell_in[sbase + 1] - i2 = vert_adr + flex_shell_in[sbase + 2] + # 2D shell faces + shell_adr = flex_shelldataadr[flex_id] + shellid = workid - nelem + sbase = shell_adr + 2 * shellid + i0 = vert_adr + flex_shell[sbase + 0] + i1 = vert_adr + flex_shell[sbase + 1] v0 = flexvert_xpos_in[worldid, i0] v1 = flexvert_xpos_in[worldid, i1] - v2 = flexvert_xpos_in[worldid, i2] - face_id = world_face_offset + face_offset + shellid - fbase = face_id * 3 + n0 = flexvert_norm_in[worldid, i0] + n1 = flexvert_norm_in[worldid, i1] - face_point_out[fbase + 0] = v0 - face_point_out[fbase + 1] = v1 - face_point_out[fbase + 2] = v2 + shell_face_offset = 2 * nelem + face_id0 = world_face_offset + shell_face_offset + (2 * shellid) + base0 = face_id0 * 3 + face_point_out[base0 + 0] = v0 + radius * n0 + face_point_out[base0 + 1] = v1 - radius * n1 + face_point_out[base0 + 2] = v1 + radius * n1 + face_id1 = world_face_offset + shell_face_offset + (2 * shellid + 1) + base1 = face_id1 * 3 + face_point_out[base1 + 0] = v1 - radius * n1 + face_point_out[base1 + 1] = v0 + radius * n0 + face_point_out[base1 + 2] = v0 - radius * n0 -def build_flex_bvh( - mjm: mujoco.MjModel, mjd: mujoco.MjData, nworld: int, constructor: str = "sah", leaf_size: int = 2 -) -> tuple[wp.Mesh, wp.array, wp.array, wp.array, wp.array, wp.array, int]: - """Create a Warp mesh BVH from flex data.""" - if (mjm.flex_dim == 1).any(): - raise ValueError("1D Flex objects are not currently supported.") - nflex = mjm.nflex +@wp.kernel +def _update_flex_3d_face_points( + # Model: + flex_vertadr: wp.array(dtype=int), + flex_shelldataadr: wp.array(dtype=int), + flex_shell: wp.array(dtype=int), + # Data in: + flexvert_xpos_in: wp.array2d(dtype=wp.vec3), + # In: + flex_id: int, + nface: int, + # Out: + face_point_out: wp.array(dtype=wp.vec3), +): + worldid, shellid = wp.tid() + + shell_adr = flex_shelldataadr[flex_id] + vert_adr = flex_vertadr[flex_id] + + face_id = worldid * nface + shellid + fbase = face_id * 3 + + sbase = shell_adr + shellid * 3 + i0 = vert_adr + flex_shell[sbase + 0] + i1 = vert_adr + flex_shell[sbase + 1] + i2 = vert_adr + flex_shell[sbase + 2] + + face_point_out[fbase + 0] = flexvert_xpos_in[worldid, i0] + face_point_out[fbase + 1] = flexvert_xpos_in[worldid, i1] + face_point_out[fbase + 2] = flexvert_xpos_in[worldid, i2] + + +def build_flex_bvh( + mjm: mujoco.MjModel, + mjd: mujoco.MjData, + nworld: int, + flex_id: int, + constructor: str = "sah", + leaf_size: int = 2, +) -> tuple[wp.Mesh, wp.array, wp.array, wp.array, int]: + """Create a Warp mesh BVH for a single 2D or 3D flex.""" nflexvert = mjm.nflexvert - nflexelemdata = len(mjm.flex_elem) + flex_dim = wp.array(mjm.flex_dim, dtype=int) + flex_elemadr = wp.array(mjm.flex_elemadr, dtype=int) + flex_elemnum = wp.array(mjm.flex_elemnum, dtype=int) flex_elem = wp.array(mjm.flex_elem, dtype=int) + flex_elemdataadr = wp.array(mjm.flex_elemdataadr, dtype=int) + flex_vertadr = wp.array(mjm.flex_vertadr, dtype=int) flexvert_xpos = wp.array(np.tile(mjd.flexvert_xpos[np.newaxis, :, :], (nworld, 1, 1)), dtype=wp.vec3) - flex_faceadr = [0] - for f in range(nflex): - if mjm.flex_dim[f] == 2: - flex_faceadr.append(flex_faceadr[-1] + 2 * mjm.flex_elemnum[f] + 2 * mjm.flex_shellnum[f]) - elif mjm.flex_dim[f] == 3: - flex_faceadr.append(flex_faceadr[-1] + mjm.flex_shellnum[f]) + dim = int(mjm.flex_dim[flex_id]) + nelem = int(mjm.flex_elemnum[flex_id]) + nshell = int(mjm.flex_shellnum[flex_id]) - nface = int(flex_faceadr[-1]) - flex_faceadr = flex_faceadr[:-1] + if dim == 2: + nface = 2 * nelem + 2 * nshell + else: + nface = nshell face_point = wp.empty(nface * 3 * nworld, dtype=wp.vec3) face_index = wp.empty(nface * 3 * nworld, dtype=wp.int32) @@ -883,8 +1001,8 @@ def build_flex_bvh( wp.launch( kernel=accumulate_flex_vertex_normals, - dim=(nworld, nflexelemdata // 3), - inputs=[flex_elem, flexvert_xpos], + dim=(nworld, mjm.nflexelem), + inputs=[mjm.nflex, flex_dim, flex_vertadr, flex_elemadr, flex_elemnum, flex_elemdataadr, flex_elem, flexvert_xpos], outputs=[flexvert_norm], ) @@ -894,60 +1012,56 @@ def build_flex_bvh( inputs=[flexvert_norm], ) - for f in range(nflex): - dim = mjm.flex_dim[f] - elem_adr = mjm.flex_elemdataadr[f] - nelem = mjm.flex_elemnum[f] - shell_adr = mjm.flex_shelldataadr[f] - nshell = mjm.flex_shellnum[f] - vert_adr = mjm.flex_vertadr[f] - - if dim == 2: - wp.launch( - kernel=_build_flex_2d_elements, - dim=(nworld, nelem), - inputs=[ - flex_elem, - flexvert_xpos, - flexvert_norm, - elem_adr, - vert_adr, - flex_faceadr[f], - mjm.flex_radius[f], - nface, - ], - outputs=[face_point, face_index, group], - ) + elem_adr = mjm.flex_elemdataadr[flex_id] + shell_adr = mjm.flex_shelldataadr[flex_id] + vert_adr = mjm.flex_vertadr[flex_id] - wp.launch( - kernel=_build_flex_2d_sides, - dim=(nworld, nshell), - inputs=[ - flexvert_xpos, - flexvert_norm, - flex_shell, - shell_adr, - vert_adr, - flex_faceadr[f] + 2 * nelem, - mjm.flex_radius[f], - nface, - ], - outputs=[face_point, face_index, group], - ) - elif dim == 3: - wp.launch( - kernel=_build_flex_3d_shells, - dim=(nworld, nshell), - inputs=[ - flexvert_xpos, - flex_shell, - shell_adr, - vert_adr, - flex_faceadr[f], - nface, - ], - outputs=[face_point, face_index, group], - ) + if dim == 2: + wp.launch( + kernel=_build_flex_2d_elements, + dim=(nworld, nelem), + inputs=[ + flex_elem, + flexvert_xpos, + flexvert_norm, + elem_adr, + vert_adr, + 0, # face_offset + mjm.flex_radius[flex_id], + nface, + ], + outputs=[face_point, face_index, group], + ) + + wp.launch( + kernel=_build_flex_2d_sides, + dim=(nworld, nshell), + inputs=[ + flex_shell, + flexvert_xpos, + flexvert_norm, + shell_adr, + vert_adr, + 2 * nelem, # face_offset + mjm.flex_radius[flex_id], + nface, + ], + outputs=[face_point, face_index, group], + ) + elif dim == 3: + wp.launch( + kernel=_build_flex_3d_shells, + dim=(nworld, nshell), + inputs=[ + flex_shell, + flexvert_xpos, + shell_adr, + vert_adr, + 0, # face_offset + nface, + ], + outputs=[face_point, face_index, group], + ) flex_mesh = wp.Mesh( points=face_point, @@ -965,24 +1079,23 @@ def build_flex_bvh( outputs=[group_root], ) - return ( - flex_mesh, - face_point, - group_root, - flex_shell, - flex_faceadr, - nface, - ) + return flex_mesh, group_root def refit_flex_bvh(m: Model, d: Data, rc: RenderContext): - """Refit the flex BVH.""" + """Refit per-flex BVHs.""" flexvert_norm = wp.zeros(d.flexvert_xpos.shape, dtype=wp.vec3) wp.launch( kernel=accumulate_flex_vertex_normals, - dim=(d.nworld, m.nflexelemdata // 3), + dim=(d.nworld, m.nflexelem), inputs=[ + m.nflex, + m.flex_dim, + m.flex_vertadr, + m.flex_elemadr, + m.flex_elemnum, + m.flex_elemdataadr, m.flex_elem, d.flexvert_xpos, ], @@ -991,32 +1104,49 @@ def refit_flex_bvh(m: Model, d: Data, rc: RenderContext): wp.launch( kernel=normalize_vertex_normals, - dim=(d.nworld, m.nflexvert), + dim=(d.nworld, d.flexvert_xpos.shape[1]), inputs=[flexvert_norm], ) - wp.launch( - kernel=_update_flex_face_points, - dim=(d.nworld, rc.flex_nwork), - inputs=[ - m.nflex, - m.flex_dim, - m.flex_vertadr, - m.flex_elemnum, - m.flex_elem, - d.flexvert_xpos, - rc.flex_shell, - flexvert_norm, - rc.flex_elemdataadr, - rc.flex_shelldataadr, - rc.flex_faceadr, - rc.flex_radius, - rc.flex_workadr, - rc.flex_worknum, - rc.flex_nface, - rc.flex_render_smooth, - ], - outputs=[rc.flex_face_point], - ) + for i in range(m.nflex): + if rc.flex_dim_np[i] == 1: + continue + mesh = rc.flex_mesh_registry[i] + nface = mesh.points.shape[0] // (3 * d.nworld) + + if rc.flex_dim_np[i] == 2: + wp.launch( + kernel=_update_flex_2d_face_points, + dim=(d.nworld, nface // 2), + inputs=[ + m.flex_vertadr, + m.flex_elemnum, + m.flex_elemdataadr, + m.flex_shelldataadr, + m.flex_elem, + m.flex_shell, + m.flex_radius, + d.flexvert_xpos, + flexvert_norm, + i, + nface, + rc.flex_render_smooth, + ], + outputs=[mesh.points], + ) + else: + wp.launch( + kernel=_update_flex_3d_face_points, + dim=(d.nworld, nface), + inputs=[ + m.flex_vertadr, + m.flex_shelldataadr, + m.flex_shell, + d.flexvert_xpos, + i, + nface, + ], + outputs=[mesh.points], + ) - rc.flex_mesh.refit() + mesh.refit() diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_convex.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_convex.py index 69ea9cbe3d..12d9824a44 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_convex.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_convex.py @@ -15,34 +15,35 @@ from typing import Tuple +import warp as wp + from mujoco.mjx.third_party.mujoco_warp._src.collision_core import CollisionContext -from mujoco.mjx.third_party.mujoco_warp._src.collision_core import contact_params from mujoco.mjx.third_party.mujoco_warp._src.collision_core import Geom +from mujoco.mjx.third_party.mujoco_warp._src.collision_core import contact_params from mujoco.mjx.third_party.mujoco_warp._src.collision_core import geom_collision_pair from mujoco.mjx.third_party.mujoco_warp._src.collision_core import write_contact from mujoco.mjx.third_party.mujoco_warp._src.collision_gjk import ccd from mujoco.mjx.third_party.mujoco_warp._src.collision_gjk import multicontact from mujoco.mjx.third_party.mujoco_warp._src.collision_gjk import support -from mujoco.mjx.third_party.mujoco_warp._src.collision_primitive import contact_params from mujoco.mjx.third_party.mujoco_warp._src.collision_primitive import Geom +from mujoco.mjx.third_party.mujoco_warp._src.collision_primitive import contact_params from mujoco.mjx.third_party.mujoco_warp._src.collision_primitive import geom_collision_pair from mujoco.mjx.third_party.mujoco_warp._src.collision_primitive import write_contact from mujoco.mjx.third_party.mujoco_warp._src.math import make_frame from mujoco.mjx.third_party.mujoco_warp._src.math import upper_trid_index -from mujoco.mjx.third_party.mujoco_warp._src.types import Data -from mujoco.mjx.third_party.mujoco_warp._src.types import EnableBit -from mujoco.mjx.third_party.mujoco_warp._src.types import GeomType -from mujoco.mjx.third_party.mujoco_warp._src.types import mat43 -from mujoco.mjx.third_party.mujoco_warp._src.types import mat63 from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MAX_EPAFACES from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MAX_EPAHORIZON from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MAXCONPAIR from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MAXVAL +from mujoco.mjx.third_party.mujoco_warp._src.types import Data +from mujoco.mjx.third_party.mujoco_warp._src.types import EnableBit +from mujoco.mjx.third_party.mujoco_warp._src.types import GeomType from mujoco.mjx.third_party.mujoco_warp._src.types import Model +from mujoco.mjx.third_party.mujoco_warp._src.types import mat43 +from mujoco.mjx.third_party.mujoco_warp._src.types import mat63 from mujoco.mjx.third_party.mujoco_warp._src.types import vec5 from mujoco.mjx.third_party.mujoco_warp._src.warp_util import cache_kernel from mujoco.mjx.third_party.mujoco_warp._src.warp_util import event_scope -import warp as wp # TODO(team): improve compile time to enable backward pass wp.set_module_options({"enable_backward": False}) @@ -233,6 +234,7 @@ def ccd_hfield_kernel( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -516,6 +518,7 @@ def ccd_hfield_kernel( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -572,6 +575,7 @@ def ccd_hfield_kernel( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -626,6 +630,7 @@ def ccd_hfield_kernel( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -681,6 +686,7 @@ def ccd_hfield_kernel( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -751,6 +757,7 @@ def eval_ccd_write_contact( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -871,6 +878,7 @@ def eval_ccd_write_contact( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -956,6 +964,7 @@ def ccd_kernel( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -1070,6 +1079,7 @@ def ccd_kernel( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -1156,6 +1166,7 @@ def _pair_count(p1: int, p2: int) -> Tuple[int, int]: d.contact.solimp, d.contact.dim, d.contact.geom, + d.contact.efc_address, d.contact.worldid, d.contact.type, d.contact.geomcollisionid, diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_core.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_core.py index f8294f65da..b7affa7ddc 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_core.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_core.py @@ -18,14 +18,15 @@ import dataclasses from typing import Tuple +import warp as wp + from mujoco.mjx.third_party.mujoco_warp._src.math import safe_div +from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MINMU +from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MINVAL from mujoco.mjx.third_party.mujoco_warp._src.types import ContactType from mujoco.mjx.third_party.mujoco_warp._src.types import GeomType from mujoco.mjx.third_party.mujoco_warp._src.types import mat63 -from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MINMU -from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MINVAL from mujoco.mjx.third_party.mujoco_warp._src.types import vec5 -import warp as wp wp.set_module_options({"enable_backward": False}) @@ -63,30 +64,30 @@ class Geom: @wp.func def geom_collision_pair( - # Model: - geom_type: wp.array(dtype=int), - geom_dataid: wp.array(dtype=int), - geom_size: wp.array2d(dtype=wp.vec3), - mesh_vertadr: wp.array(dtype=int), - mesh_vertnum: wp.array(dtype=int), - mesh_graphadr: wp.array(dtype=int), - mesh_vert: wp.array(dtype=wp.vec3), - mesh_graph: wp.array(dtype=int), - mesh_polynum: wp.array(dtype=int), - mesh_polyadr: wp.array(dtype=int), - mesh_polynormal: wp.array(dtype=wp.vec3), - mesh_polyvertadr: wp.array(dtype=int), - mesh_polyvertnum: wp.array(dtype=int), - mesh_polyvert: wp.array(dtype=int), - mesh_polymapadr: wp.array(dtype=int), - mesh_polymapnum: wp.array(dtype=int), - mesh_polymap: wp.array(dtype=int), - # Data in: - geom_xpos_in: wp.array2d(dtype=wp.vec3), - geom_xmat_in: wp.array2d(dtype=wp.mat33), - # In: - geoms: wp.vec2i, - worldid: int, + # Model: + geom_type: wp.array(dtype=int), + geom_dataid: wp.array(dtype=int), + geom_size: wp.array2d(dtype=wp.vec3), + mesh_vertadr: wp.array(dtype=int), + mesh_vertnum: wp.array(dtype=int), + mesh_graphadr: wp.array(dtype=int), + mesh_vert: wp.array(dtype=wp.vec3), + mesh_graph: wp.array(dtype=int), + mesh_polynum: wp.array(dtype=int), + mesh_polyadr: wp.array(dtype=int), + mesh_polynormal: wp.array(dtype=wp.vec3), + mesh_polyvertadr: wp.array(dtype=int), + mesh_polyvertnum: wp.array(dtype=int), + mesh_polyvert: wp.array(dtype=int), + mesh_polymapadr: wp.array(dtype=int), + mesh_polymapnum: wp.array(dtype=int), + mesh_polymap: wp.array(dtype=int), + # Data in: + geom_xpos_in: wp.array2d(dtype=wp.vec3), + geom_xmat_in: wp.array2d(dtype=wp.mat33), + # In: + geoms: wp.vec2i, + worldid: int, ) -> Tuple[Geom, Geom]: geom1 = Geom() geom2 = Geom() @@ -155,38 +156,39 @@ def geom_collision_pair( @wp.func def write_contact( - # Data in: - naconmax_in: int, - # In: - id_: int, - dist_in: float, - pos_in: wp.vec3, - frame_in: wp.mat33, - margin_in: float, - gap_in: float, - condim_in: int, - friction_in: vec5, - solref_in: wp.vec2, - solreffriction_in: wp.vec2, - solimp_in: vec5, - geoms_in: wp.vec2i, - pairid_in: wp.vec2i, - worldid_in: int, - # Data out: - contact_dist_out: wp.array(dtype=float), - contact_pos_out: wp.array(dtype=wp.vec3), - contact_frame_out: wp.array(dtype=wp.mat33), - contact_includemargin_out: wp.array(dtype=float), - contact_friction_out: wp.array(dtype=vec5), - contact_solref_out: wp.array(dtype=wp.vec2), - contact_solreffriction_out: wp.array(dtype=wp.vec2), - contact_solimp_out: wp.array(dtype=vec5), - contact_dim_out: wp.array(dtype=int), - contact_geom_out: wp.array(dtype=wp.vec2i), - contact_worldid_out: wp.array(dtype=int), - contact_type_out: wp.array(dtype=int), - contact_geomcollisionid_out: wp.array(dtype=int), - nacon_out: wp.array(dtype=int), + # Data in: + naconmax_in: int, + # In: + id_: int, + dist_in: float, + pos_in: wp.vec3, + frame_in: wp.mat33, + margin_in: float, + gap_in: float, + condim_in: int, + friction_in: vec5, + solref_in: wp.vec2, + solreffriction_in: wp.vec2, + solimp_in: vec5, + geoms_in: wp.vec2i, + pairid_in: wp.vec2i, + worldid_in: int, + # Data out: + contact_dist_out: wp.array(dtype=float), + contact_pos_out: wp.array(dtype=wp.vec3), + contact_frame_out: wp.array(dtype=wp.mat33), + contact_includemargin_out: wp.array(dtype=float), + contact_friction_out: wp.array(dtype=vec5), + contact_solref_out: wp.array(dtype=wp.vec2), + contact_solreffriction_out: wp.array(dtype=wp.vec2), + contact_solimp_out: wp.array(dtype=vec5), + contact_dim_out: wp.array(dtype=int), + contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), + contact_worldid_out: wp.array(dtype=int), + contact_type_out: wp.array(dtype=int), + contact_geomcollisionid_out: wp.array(dtype=int), + nacon_out: wp.array(dtype=int), ) -> int: """Atomically write a detected contact into the contact output arrays. @@ -222,33 +224,35 @@ def write_contact( contact_solimp_out[cid] = solimp_in contact_type_out[cid] = contact_type contact_geomcollisionid_out[cid] = id_ + for i in range(contact_efc_address_out.shape[1]): + contact_efc_address_out[cid, i] = -1 return int(active) return 0 @wp.func def contact_params( - # Model: - geom_condim: wp.array(dtype=int), - geom_priority: wp.array(dtype=int), - geom_solmix: wp.array2d(dtype=float), - geom_solref: wp.array2d(dtype=wp.vec2), - geom_solimp: wp.array2d(dtype=vec5), - geom_friction: wp.array2d(dtype=wp.vec3), - geom_margin: wp.array2d(dtype=float), - geom_gap: wp.array2d(dtype=float), - pair_dim: wp.array(dtype=int), - pair_solref: wp.array2d(dtype=wp.vec2), - pair_solreffriction: wp.array2d(dtype=wp.vec2), - pair_solimp: wp.array2d(dtype=vec5), - pair_margin: wp.array2d(dtype=float), - pair_gap: wp.array2d(dtype=float), - pair_friction: wp.array2d(dtype=vec5), - # In: - collision_pair_in: wp.array(dtype=wp.vec2i), - collision_pairid_in: wp.array(dtype=wp.vec2i), - cid: int, - worldid: int, + # Model: + geom_condim: wp.array(dtype=int), + geom_priority: wp.array(dtype=int), + geom_solmix: wp.array2d(dtype=float), + geom_solref: wp.array2d(dtype=wp.vec2), + geom_solimp: wp.array2d(dtype=vec5), + geom_friction: wp.array2d(dtype=wp.vec3), + geom_margin: wp.array2d(dtype=float), + geom_gap: wp.array2d(dtype=float), + pair_dim: wp.array(dtype=int), + pair_solref: wp.array2d(dtype=wp.vec2), + pair_solreffriction: wp.array2d(dtype=wp.vec2), + pair_solimp: wp.array2d(dtype=vec5), + pair_margin: wp.array2d(dtype=float), + pair_gap: wp.array2d(dtype=float), + pair_friction: wp.array2d(dtype=vec5), + # In: + collision_pair_in: wp.array(dtype=wp.vec2i), + collision_pairid_in: wp.array(dtype=wp.vec2i), + cid: int, + worldid: int, ): """Resolve contact parameters for a collision pair. @@ -267,9 +271,7 @@ def contact_params( condim = pair_dim[pairid] friction = pair_friction[worldid % pair_friction.shape[0], pairid] solref = pair_solref[worldid % pair_solref.shape[0], pairid] - solreffriction = pair_solreffriction[ - worldid % pair_solreffriction.shape[0], pairid - ] + solreffriction = pair_solreffriction[worldid % pair_solreffriction.shape[0], pairid] solimp = pair_solimp[worldid % pair_solimp.shape[0], pairid] else: g1 = geoms[0] @@ -305,44 +307,33 @@ def contact_params( 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) - max_geom_friction = wp.max( - geom_friction[friction_id, g1], geom_friction[friction_id, g2] - ) + max_geom_friction = wp.max(geom_friction[friction_id, g1], geom_friction[friction_id, g2]) friction = vec5( - max_geom_friction[0], - max_geom_friction[0], - max_geom_friction[1], - max_geom_friction[2], - max_geom_friction[2], + max_geom_friction[0], + max_geom_friction[0], + max_geom_friction[1], + max_geom_friction[2], + max_geom_friction[2], ) - if ( - geom_solref[solref_id, g1][0] > 0.0 - and geom_solref[solref_id, g2][0] > 0.0 - ): - solref = ( - mix * geom_solref[solref_id, g1] - + (1.0 - mix) * geom_solref[solref_id, g2] - ) + if geom_solref[solref_id, g1][0] > 0.0 and geom_solref[solref_id, g2][0] > 0.0: + solref = mix * geom_solref[solref_id, g1] + (1.0 - mix) * geom_solref[solref_id, g2] else: solref = wp.min(geom_solref[solref_id, g1], geom_solref[solref_id, g2]) solreffriction = wp.vec2(0.0, 0.0) - solimp = ( - mix * geom_solimp[solimp_id, g1] - + (1.0 - mix) * geom_solimp[solimp_id, g2] - ) + solimp = mix * geom_solimp[solimp_id, g1] + (1.0 - mix) * geom_solimp[solimp_id, g2] # geom priority is ignored margin = geom_margin[margin_id, g1] + geom_margin[margin_id, g2] gap = geom_gap[gap_id, g1] + geom_gap[gap_id, g2] friction = vec5( - wp.max(MJ_MINMU, friction[0]), - wp.max(MJ_MINMU, friction[1]), - wp.max(MJ_MINMU, friction[2]), - wp.max(MJ_MINMU, friction[3]), - wp.max(MJ_MINMU, friction[4]), + wp.max(MJ_MINMU, friction[0]), + wp.max(MJ_MINMU, friction[1]), + wp.max(MJ_MINMU, friction[2]), + wp.max(MJ_MINMU, friction[3]), + wp.max(MJ_MINMU, friction[4]), ) return geoms, margin, gap, condim, friction, solref, solreffriction, solimp @@ -366,7 +357,7 @@ class CollisionContext: def create_collision_context(naconmax: int) -> CollisionContext: """Create a CollisionContext with allocated arrays.""" return CollisionContext( - collision_pair=wp.empty(naconmax, dtype=wp.vec2i), - collision_pairid=wp.empty(naconmax, dtype=wp.vec2i), - collision_worldid=wp.empty(naconmax, dtype=int), + collision_pair=wp.empty(naconmax, dtype=wp.vec2i), + collision_pairid=wp.empty(naconmax, dtype=wp.vec2i), + collision_worldid=wp.empty(naconmax, dtype=int), ) diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_driver.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_driver.py index 36cdaea16d..786ee9b888 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_driver.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_driver.py @@ -15,25 +15,27 @@ from typing import Any +import warp as wp + from mujoco.mjx.third_party.mujoco_warp._src.collision_convex import convex_narrowphase from mujoco.mjx.third_party.mujoco_warp._src.collision_core import CollisionContext from mujoco.mjx.third_party.mujoco_warp._src.collision_core import create_collision_context +from mujoco.mjx.third_party.mujoco_warp._src.collision_flex import flex_narrowphase from mujoco.mjx.third_party.mujoco_warp._src.collision_primitive import primitive_narrowphase from mujoco.mjx.third_party.mujoco_warp._src.collision_sdf import sdf_narrowphase from mujoco.mjx.third_party.mujoco_warp._src.math import upper_tri_index +from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MAXVAL from mujoco.mjx.third_party.mujoco_warp._src.types import BroadphaseFilter from mujoco.mjx.third_party.mujoco_warp._src.types import BroadphaseType from mujoco.mjx.third_party.mujoco_warp._src.types import CollisionType from mujoco.mjx.third_party.mujoco_warp._src.types import Data from mujoco.mjx.third_party.mujoco_warp._src.types import DisableBit from mujoco.mjx.third_party.mujoco_warp._src.types import GeomType +from mujoco.mjx.third_party.mujoco_warp._src.types import Model from mujoco.mjx.third_party.mujoco_warp._src.types import mat23 from mujoco.mjx.third_party.mujoco_warp._src.types import mat63 -from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MAXVAL -from mujoco.mjx.third_party.mujoco_warp._src.types import Model from mujoco.mjx.third_party.mujoco_warp._src.warp_util import cache_kernel from mujoco.mjx.third_party.mujoco_warp._src.warp_util import event_scope -import warp as wp wp.set_module_options({"enable_backward": False}) @@ -290,25 +292,13 @@ def func( # 8: obb aabb_id = worldid % ngeom_aabb if wp.static(ngeom_aabb > 1) else 0 - center1, center2 = ( - geom_aabb[aabb_id, geom1, 0], - geom_aabb[aabb_id, geom2, 0], - ) # kernel_analyzer: ignore - size1, size2 = ( - geom_aabb[aabb_id, geom1, 1], - geom_aabb[aabb_id, geom2, 1], - ) # kernel_analyzer: ignore + center1, center2 = geom_aabb[aabb_id, geom1, 0], geom_aabb[aabb_id, geom2, 0] # kernel_analyzer: ignore + size1, size2 = geom_aabb[aabb_id, geom1, 1], geom_aabb[aabb_id, geom2, 1] # kernel_analyzer: ignore rbound_id = worldid % ngeom_rbound if wp.static(ngeom_rbound > 1) else 0 - rbound1, rbound2 = ( - geom_rbound[rbound_id, geom1], - geom_rbound[rbound_id, geom2], - ) # kernel_analyzer: ignore + rbound1, rbound2 = geom_rbound[rbound_id, geom1], geom_rbound[rbound_id, geom2] # kernel_analyzer: ignore margin_id = worldid % ngeom_margin if wp.static(ngeom_margin > 1) else 0 - margin1, margin2 = ( - geom_margin[margin_id, geom1], - geom_margin[margin_id, geom2], - ) # kernel_analyzer: ignore + margin1, margin2 = geom_margin[margin_id, geom1], geom_margin[margin_id, geom2] # kernel_analyzer: ignore xpos1, xpos2 = geom_xpos_in[worldid, geom1], geom_xpos_in[worldid, geom2] xmat1, xmat2 = geom_xmat_in[worldid, geom1], geom_xmat_in[worldid, geom2] @@ -757,6 +747,9 @@ def _narrowphase(m: Model, d: Data, ctx: CollisionContext): if m.has_sdf_geom: sdf_narrowphase(m, d, ctx) + if m.nflex > 0: + flex_narrowphase(m, d) + @event_scope def collision(m: Model, d: Data): diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_flex.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_flex.py new file mode 100644 index 0000000000..215423e991 --- /dev/null +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_flex.py @@ -0,0 +1,834 @@ +# Copyright 2026 The Newton Developers +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +"""Flex collision detection (geom vs flex triangles).""" + +import warp as wp + +from mujoco.mjx.third_party.mujoco_warp._src import collision_primitive_core +from mujoco.mjx.third_party.mujoco_warp._src.math import make_frame +from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MAXVAL +from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MINMU +from mujoco.mjx.third_party.mujoco_warp._src.types import Data +from mujoco.mjx.third_party.mujoco_warp._src.types import GeomType +from mujoco.mjx.third_party.mujoco_warp._src.types import Model +from mujoco.mjx.third_party.mujoco_warp._src.types import vec5 +from mujoco.mjx.third_party.mujoco_warp._src.warp_util import event_scope + +wp.set_module_options({"enable_backward": False}) + + +@wp.func +def _write_flex_contact( + # Data in: + naconmax_in: int, + # In: + dist: float, + pos: wp.vec3, + frame: wp.mat33, + margin: float, + condim: int, + friction: vec5, + solref: wp.vec2, + solimp: vec5, + geom: int, + flexid: int, + vertid: int, + worldid: int, + # Data out: + contact_dist_out: wp.array(dtype=float), + contact_pos_out: wp.array(dtype=wp.vec3), + contact_frame_out: wp.array(dtype=wp.mat33), + contact_includemargin_out: wp.array(dtype=float), + contact_friction_out: wp.array(dtype=vec5), + contact_solref_out: wp.array(dtype=wp.vec2), + contact_solreffriction_out: wp.array(dtype=wp.vec2), + contact_solimp_out: wp.array(dtype=vec5), + contact_dim_out: wp.array(dtype=int), + contact_geom_out: wp.array(dtype=wp.vec2i), + contact_flex_out: wp.array(dtype=wp.vec2i), + contact_vert_out: wp.array(dtype=wp.vec2i), + contact_worldid_out: wp.array(dtype=int), + contact_type_out: wp.array(dtype=int), + contact_geomcollisionid_out: wp.array(dtype=int), + nacon_out: wp.array(dtype=int), +): + if dist >= margin or dist >= MJ_MAXVAL: + return + + id_ = wp.atomic_add(nacon_out, 0, 1) + if id_ >= naconmax_in: + return + + contact_dist_out[id_] = dist + contact_pos_out[id_] = pos + contact_frame_out[id_] = frame + contact_includemargin_out[id_] = margin + contact_friction_out[id_] = friction + contact_solref_out[id_] = solref + contact_solreffriction_out[id_] = wp.vec2(0.0, 0.0) + contact_solimp_out[id_] = solimp + contact_dim_out[id_] = condim + contact_geom_out[id_] = wp.vec2i(geom, -1) + contact_flex_out[id_] = wp.vec2i(-1, flexid) + contact_vert_out[id_] = wp.vec2i(-1, vertid) + contact_worldid_out[id_] = worldid + contact_type_out[id_] = 1 + contact_geomcollisionid_out[id_] = 0 + + +@wp.func +def _collide_geom_triangle( + # Data in: + naconmax_in: int, + # In: + gtype: int, + pos: wp.vec3, + rot: wp.mat33, + size_val: wp.vec3, + t1: wp.vec3, + t2: wp.vec3, + t3: wp.vec3, + tri_radius: float, + margin: float, + condim: int, + friction: vec5, + solref: wp.vec2, + solimp: vec5, + geomid: int, + flexid: int, + vertex_id: int, + worldid: int, + # Data out: + contact_dist_out: wp.array(dtype=float), + contact_pos_out: wp.array(dtype=wp.vec3), + contact_frame_out: wp.array(dtype=wp.mat33), + contact_includemargin_out: wp.array(dtype=float), + contact_friction_out: wp.array(dtype=vec5), + contact_solref_out: wp.array(dtype=wp.vec2), + contact_solreffriction_out: wp.array(dtype=wp.vec2), + contact_solimp_out: wp.array(dtype=vec5), + contact_dim_out: wp.array(dtype=int), + contact_geom_out: wp.array(dtype=wp.vec2i), + contact_flex_out: wp.array(dtype=wp.vec2i), + contact_vert_out: wp.array(dtype=wp.vec2i), + contact_worldid_out: wp.array(dtype=int), + contact_type_out: wp.array(dtype=int), + contact_geomcollisionid_out: wp.array(dtype=int), + nacon_out: wp.array(dtype=int), +): + if gtype == int(GeomType.SPHERE): + sphere_radius = size_val[0] + dist, contact_pos, nrm = collision_primitive_core.sphere_triangle(pos, sphere_radius, t1, t2, t3, tri_radius) + if dist < margin: + _write_flex_contact( + naconmax_in, + dist, + contact_pos, + make_frame(nrm), + margin, + condim, + friction, + solref, + solimp, + geomid, + flexid, + vertex_id, + worldid, + contact_dist_out, + contact_pos_out, + contact_frame_out, + contact_includemargin_out, + contact_friction_out, + contact_solref_out, + contact_solreffriction_out, + contact_solimp_out, + contact_dim_out, + contact_geom_out, + contact_flex_out, + contact_vert_out, + contact_worldid_out, + contact_type_out, + contact_geomcollisionid_out, + nacon_out, + ) + return + + # Capsule, box, cylinder all return up to 2 contacts - compute then share writing code + dists = wp.vec2(collision_primitive_core.MJ_MAXVAL, collision_primitive_core.MJ_MAXVAL) + poss = collision_primitive_core.mat23f(0.0, 0.0, 0.0, 0.0, 0.0, 0.0) + nrms = collision_primitive_core.mat23f(0.0, 0.0, 0.0, 0.0, 0.0, 0.0) + + if gtype == int(GeomType.CAPSULE): + cap_radius = size_val[0] + cap_half_len = size_val[1] + cap_axis = wp.vec3(rot[0, 2], rot[1, 2], rot[2, 2]) + dists, poss, nrms = collision_primitive_core.capsule_triangle( + pos, cap_axis, cap_radius, cap_half_len, t1, t2, t3, tri_radius + ) + elif gtype == int(GeomType.BOX): + dists, poss, nrms = collision_primitive_core.box_triangle(pos, rot, size_val, t1, t2, t3, tri_radius) + elif gtype == int(GeomType.CYLINDER): + cyl_radius = size_val[0] + cyl_half_height = size_val[1] + cyl_axis = wp.vec3(rot[0, 2], rot[1, 2], rot[2, 2]) + dists, poss, nrms = collision_primitive_core.cylinder_triangle( + pos, cyl_axis, cyl_radius, cyl_half_height, t1, t2, t3, tri_radius + ) + + # Write up to 2 contacts (shared code for capsule/box/cylinder) + if dists[0] < margin: + p1 = wp.vec3(poss[0, 0], poss[0, 1], poss[0, 2]) + n1 = wp.vec3(nrms[0, 0], nrms[0, 1], nrms[0, 2]) + _write_flex_contact( + naconmax_in, + dists[0], + p1, + make_frame(n1), + margin, + condim, + friction, + solref, + solimp, + geomid, + flexid, + vertex_id, + worldid, + contact_dist_out, + contact_pos_out, + contact_frame_out, + contact_includemargin_out, + contact_friction_out, + contact_solref_out, + contact_solreffriction_out, + contact_solimp_out, + contact_dim_out, + contact_geom_out, + contact_flex_out, + contact_vert_out, + contact_worldid_out, + contact_type_out, + contact_geomcollisionid_out, + nacon_out, + ) + if dists[1] < margin: + p2 = wp.vec3(poss[1, 0], poss[1, 1], poss[1, 2]) + n2 = wp.vec3(nrms[1, 0], nrms[1, 1], nrms[1, 2]) + _write_flex_contact( + naconmax_in, + dists[1], + p2, + make_frame(n2), + margin, + condim, + friction, + solref, + solimp, + geomid, + flexid, + vertex_id, + worldid, + contact_dist_out, + contact_pos_out, + contact_frame_out, + contact_includemargin_out, + contact_friction_out, + contact_solref_out, + contact_solreffriction_out, + contact_solimp_out, + contact_dim_out, + contact_geom_out, + contact_flex_out, + contact_vert_out, + contact_worldid_out, + contact_type_out, + contact_geomcollisionid_out, + nacon_out, + ) + + +@wp.kernel +def _flex_plane_narrowphase( + # Model: + ngeom: int, + nflexvert: int, + geom_type: wp.array(dtype=int), + geom_condim: wp.array(dtype=int), + geom_solref: wp.array2d(dtype=wp.vec2), + geom_solimp: wp.array2d(dtype=vec5), + geom_friction: wp.array2d(dtype=wp.vec3), + geom_margin: wp.array2d(dtype=float), + flex_condim: wp.array(dtype=int), + flex_friction: wp.array(dtype=wp.vec3), + flex_margin: wp.array(dtype=float), + flex_vertadr: wp.array(dtype=int), + flex_radius: wp.array(dtype=float), + flex_vertflexid: wp.array(dtype=int), + # Data in: + geom_xpos_in: wp.array2d(dtype=wp.vec3), + geom_xmat_in: wp.array2d(dtype=wp.mat33), + flexvert_xpos_in: wp.array2d(dtype=wp.vec3), + nworld_in: int, + naconmax_in: int, + # Data out: + contact_dist_out: wp.array(dtype=float), + contact_pos_out: wp.array(dtype=wp.vec3), + contact_frame_out: wp.array(dtype=wp.mat33), + contact_includemargin_out: wp.array(dtype=float), + contact_friction_out: wp.array(dtype=vec5), + contact_solref_out: wp.array(dtype=wp.vec2), + contact_solreffriction_out: wp.array(dtype=wp.vec2), + contact_solimp_out: wp.array(dtype=vec5), + contact_dim_out: wp.array(dtype=int), + contact_geom_out: wp.array(dtype=wp.vec2i), + contact_flex_out: wp.array(dtype=wp.vec2i), + contact_vert_out: wp.array(dtype=wp.vec2i), + contact_worldid_out: wp.array(dtype=int), + contact_type_out: wp.array(dtype=int), + contact_geomcollisionid_out: wp.array(dtype=int), + nacon_out: wp.array(dtype=int), +): + worldid, vertid = wp.tid() + + flexid = flex_vertflexid[vertid] + radius = flex_radius[flexid] + flex_margin_val = flex_margin[flexid] + flex_condim_val = flex_condim[flexid] + flex_fric = flex_friction[flexid] + # Convert global vertid to local vertex index within this flex + local_vertid = vertid - flex_vertadr[flexid] + + vert = flexvert_xpos_in[worldid, vertid] + + # TODO: Add a broadphase + for geomid in range(ngeom): + gtype = geom_type[geomid] + if gtype != int(GeomType.PLANE): + continue + + plane_pos = geom_xpos_in[worldid, geomid] + plane_rot = geom_xmat_in[worldid, geomid] + plane_normal = wp.vec3(plane_rot[0, 2], plane_rot[1, 2], plane_rot[2, 2]) + + margin = geom_margin[worldid % geom_margin.shape[0], geomid] + flex_margin_val + + diff = vert - plane_pos + signed_dist = wp.dot(diff, plane_normal) + dist = signed_dist - radius + + if dist < margin: + geom_condim_val = geom_condim[geomid] + condim = wp.max(geom_condim_val, flex_condim_val) + solref = geom_solref[worldid % geom_solref.shape[0], geomid] + solimp = geom_solimp[worldid % geom_solimp.shape[0], geomid] + geom_fric = geom_friction[worldid % geom_friction.shape[0], geomid] + fric0 = wp.max(geom_fric[0], flex_fric[0]) + fric1 = wp.max(geom_fric[1], flex_fric[1]) + fric2 = wp.max(geom_fric[2], flex_fric[2]) + friction = vec5( + wp.max(MJ_MINMU, fric0), + wp.max(MJ_MINMU, fric0), + wp.max(MJ_MINMU, fric1), + wp.max(MJ_MINMU, fric2), + wp.max(MJ_MINMU, fric2), + ) + + contact_pos = vert - plane_normal * (dist * 0.5 + radius) + _write_flex_contact( + naconmax_in, + dist, + contact_pos, + make_frame(plane_normal), + margin, + condim, + friction, + solref, + solimp, + geomid, + flexid, + local_vertid, + worldid, + contact_dist_out, + contact_pos_out, + contact_frame_out, + contact_includemargin_out, + contact_friction_out, + contact_solref_out, + contact_solreffriction_out, + contact_solimp_out, + contact_dim_out, + contact_geom_out, + contact_flex_out, + contact_vert_out, + contact_worldid_out, + contact_type_out, + contact_geomcollisionid_out, + nacon_out, + ) + + +@wp.kernel +def _flex_narrowphase_dim2( + # Model: + ngeom: int, + nflex: int, + geom_type: wp.array(dtype=int), + geom_contype: wp.array(dtype=int), + geom_conaffinity: wp.array(dtype=int), + geom_condim: wp.array(dtype=int), + geom_solref: wp.array2d(dtype=wp.vec2), + geom_solimp: wp.array2d(dtype=vec5), + geom_size: wp.array2d(dtype=wp.vec3), + geom_friction: wp.array2d(dtype=wp.vec3), + geom_margin: wp.array2d(dtype=float), + flex_contype: wp.array(dtype=int), + flex_conaffinity: wp.array(dtype=int), + flex_margin: wp.array(dtype=float), + flex_dim: wp.array(dtype=int), + flex_vertadr: wp.array(dtype=int), + flex_elemadr: wp.array(dtype=int), + flex_elemnum: wp.array(dtype=int), + flex_elemdataadr: wp.array(dtype=int), + flex_elem: wp.array(dtype=int), + flex_radius: wp.array(dtype=float), + # Data in: + geom_xpos_in: wp.array2d(dtype=wp.vec3), + geom_xmat_in: wp.array2d(dtype=wp.mat33), + flexvert_xpos_in: wp.array2d(dtype=wp.vec3), + nworld_in: int, + naconmax_in: int, + # Data out: + contact_dist_out: wp.array(dtype=float), + contact_pos_out: wp.array(dtype=wp.vec3), + contact_frame_out: wp.array(dtype=wp.mat33), + contact_includemargin_out: wp.array(dtype=float), + contact_friction_out: wp.array(dtype=vec5), + contact_solref_out: wp.array(dtype=wp.vec2), + contact_solreffriction_out: wp.array(dtype=wp.vec2), + contact_solimp_out: wp.array(dtype=vec5), + contact_dim_out: wp.array(dtype=int), + contact_geom_out: wp.array(dtype=wp.vec2i), + contact_flex_out: wp.array(dtype=wp.vec2i), + contact_vert_out: wp.array(dtype=wp.vec2i), + contact_worldid_out: wp.array(dtype=int), + contact_type_out: wp.array(dtype=int), + contact_geomcollisionid_out: wp.array(dtype=int), + nacon_out: wp.array(dtype=int), +): + worldid, elemid = wp.tid() + + flexid = int(-1) + for i in range(nflex): + if flex_dim[i] != 2: + continue + elem_adr = flex_elemadr[i] + elem_num = flex_elemnum[i] + if elemid >= elem_adr and elemid < elem_adr + elem_num: + flexid = i + break + + if flexid < 0: + return + + vert_adr = flex_vertadr[flexid] + tri_radius = flex_radius[flexid] + tri_margin = flex_margin[flexid] + + elem_data_idx = flex_elemdataadr[flexid] + (elemid - flex_elemadr[flexid]) * 3 + v0_local = flex_elem[elem_data_idx] + v1_local = flex_elem[elem_data_idx + 1] + v2_local = flex_elem[elem_data_idx + 2] + + t1 = flexvert_xpos_in[worldid, vert_adr + v0_local] + t2 = flexvert_xpos_in[worldid, vert_adr + v1_local] + t3 = flexvert_xpos_in[worldid, vert_adr + v2_local] + + # TODO: Add a broadphase + for geomid in range(ngeom): + gtype = geom_type[geomid] + if ( + gtype != int(GeomType.SPHERE) + and gtype != int(GeomType.CAPSULE) + and gtype != int(GeomType.BOX) + and gtype != int(GeomType.CYLINDER) + ): + continue + + g_contype = geom_contype[geomid] + g_conaffinity = geom_conaffinity[geomid] + f_contype = flex_contype[flexid] + f_conaffinity = flex_conaffinity[flexid] + if not ((g_contype & f_conaffinity) or (f_contype & g_conaffinity)): + continue + + geom_margin_val = geom_margin[worldid % geom_margin.shape[0], geomid] + margin = geom_margin_val + tri_margin + + geom_pos = geom_xpos_in[worldid, geomid] + geom_rot = geom_xmat_in[worldid, geomid] + geom_size_val = geom_size[worldid % geom_size.shape[0], geomid] + + condim = geom_condim[geomid] + gf = geom_friction[worldid % geom_friction.shape[0], geomid] + friction = vec5( + wp.max(MJ_MINMU, gf[0]), + wp.max(MJ_MINMU, gf[0]), + wp.max(MJ_MINMU, gf[1]), + wp.max(MJ_MINMU, gf[2]), + wp.max(MJ_MINMU, gf[2]), + ) + solref = geom_solref[worldid % geom_solref.shape[0], geomid] + solimp = geom_solimp[worldid % geom_solimp.shape[0], geomid] + + _collide_geom_triangle( + naconmax_in, + gtype, + geom_pos, + geom_rot, + geom_size_val, + t1, + t2, + t3, + tri_radius, + margin, + condim, + friction, + solref, + solimp, + geomid, + flexid, + v0_local, + worldid, + contact_dist_out, + contact_pos_out, + contact_frame_out, + contact_includemargin_out, + contact_friction_out, + contact_solref_out, + contact_solreffriction_out, + contact_solimp_out, + contact_dim_out, + contact_geom_out, + contact_flex_out, + contact_vert_out, + contact_worldid_out, + contact_type_out, + contact_geomcollisionid_out, + nacon_out, + ) + + +@wp.kernel +def _flex_narrowphase_dim3( + # Model: + ngeom: int, + nflex: int, + geom_type: wp.array(dtype=int), + geom_contype: wp.array(dtype=int), + geom_conaffinity: wp.array(dtype=int), + geom_condim: wp.array(dtype=int), + geom_solref: wp.array2d(dtype=wp.vec2), + geom_solimp: wp.array2d(dtype=vec5), + geom_size: wp.array2d(dtype=wp.vec3), + geom_friction: wp.array2d(dtype=wp.vec3), + geom_margin: wp.array2d(dtype=float), + flex_contype: wp.array(dtype=int), + flex_conaffinity: wp.array(dtype=int), + flex_margin: wp.array(dtype=float), + flex_dim: wp.array(dtype=int), + flex_vertadr: wp.array(dtype=int), + flex_shellnum: wp.array(dtype=int), + flex_shelldataadr: wp.array(dtype=int), + flex_shell: wp.array(dtype=int), + flex_radius: wp.array(dtype=float), + # Data in: + geom_xpos_in: wp.array2d(dtype=wp.vec3), + geom_xmat_in: wp.array2d(dtype=wp.mat33), + flexvert_xpos_in: wp.array2d(dtype=wp.vec3), + nworld_in: int, + naconmax_in: int, + # Data out: + contact_dist_out: wp.array(dtype=float), + contact_pos_out: wp.array(dtype=wp.vec3), + contact_frame_out: wp.array(dtype=wp.mat33), + contact_includemargin_out: wp.array(dtype=float), + contact_friction_out: wp.array(dtype=vec5), + contact_solref_out: wp.array(dtype=wp.vec2), + contact_solreffriction_out: wp.array(dtype=wp.vec2), + contact_solimp_out: wp.array(dtype=vec5), + contact_dim_out: wp.array(dtype=int), + contact_geom_out: wp.array(dtype=wp.vec2i), + contact_flex_out: wp.array(dtype=wp.vec2i), + contact_vert_out: wp.array(dtype=wp.vec2i), + contact_worldid_out: wp.array(dtype=int), + contact_type_out: wp.array(dtype=int), + contact_geomcollisionid_out: wp.array(dtype=int), + nacon_out: wp.array(dtype=int), +): + worldid, shellid = wp.tid() + + flexid = int(-1) + shell_offset = int(0) + for i in range(nflex): + if flex_dim[i] != 3: + continue + shell_num = flex_shellnum[i] + if shellid >= shell_offset and shellid < shell_offset + shell_num: + flexid = i + break + shell_offset += shell_num + + if flexid < 0: + return + + vert_adr = flex_vertadr[flexid] + tri_radius = flex_radius[flexid] + tri_margin = flex_margin[flexid] + + shell_adr = flex_shelldataadr[flexid] + local_shellid = shellid - shell_offset + shell_data_idx = shell_adr + local_shellid * 3 + + v0_local = flex_shell[shell_data_idx] + v1_local = flex_shell[shell_data_idx + 1] + v2_local = flex_shell[shell_data_idx + 2] + + t1 = flexvert_xpos_in[worldid, vert_adr + v0_local] + t2 = flexvert_xpos_in[worldid, vert_adr + v1_local] + t3 = flexvert_xpos_in[worldid, vert_adr + v2_local] + + # TODO: Add a broadphase + for geomid in range(ngeom): + gtype = geom_type[geomid] + if ( + gtype != int(GeomType.SPHERE) + and gtype != int(GeomType.CAPSULE) + and gtype != int(GeomType.BOX) + and gtype != int(GeomType.CYLINDER) + ): + continue + + g_contype = geom_contype[geomid] + g_conaffinity = geom_conaffinity[geomid] + f_contype = flex_contype[flexid] + f_conaffinity = flex_conaffinity[flexid] + if not ((g_contype & f_conaffinity) or (f_contype & g_conaffinity)): + continue + + geom_margin_val = geom_margin[worldid % geom_margin.shape[0], geomid] + margin = geom_margin_val + tri_margin + + geom_pos = geom_xpos_in[worldid, geomid] + geom_rot = geom_xmat_in[worldid, geomid] + geom_size_val = geom_size[worldid % geom_size.shape[0], geomid] + + condim = geom_condim[geomid] + gf = geom_friction[worldid % geom_friction.shape[0], geomid] + friction = vec5( + wp.max(MJ_MINMU, gf[0]), + wp.max(MJ_MINMU, gf[0]), + wp.max(MJ_MINMU, gf[1]), + wp.max(MJ_MINMU, gf[2]), + wp.max(MJ_MINMU, gf[2]), + ) + solref = geom_solref[worldid % geom_solref.shape[0], geomid] + solimp = geom_solimp[worldid % geom_solimp.shape[0], geomid] + + _collide_geom_triangle( + naconmax_in, + gtype, + geom_pos, + geom_rot, + geom_size_val, + t1, + t2, + t3, + tri_radius, + margin, + condim, + friction, + solref, + solimp, + geomid, + flexid, + v0_local, + worldid, + contact_dist_out, + contact_pos_out, + contact_frame_out, + contact_includemargin_out, + contact_friction_out, + contact_solref_out, + contact_solreffriction_out, + contact_solimp_out, + contact_dim_out, + contact_geom_out, + contact_flex_out, + contact_vert_out, + contact_worldid_out, + contact_type_out, + contact_geomcollisionid_out, + nacon_out, + ) + + +@event_scope +def flex_narrowphase(m: Model, d: Data): + """Runs collision detection between geoms and flex elements.""" + if m.nflex == 0: + return + + wp.launch( + _flex_narrowphase_dim2, + dim=(d.nworld, m.nflexelem), + inputs=[ + m.ngeom, + m.nflex, + m.geom_type, + m.geom_contype, + m.geom_conaffinity, + m.geom_condim, + m.geom_solref, + m.geom_solimp, + m.geom_size, + m.geom_friction, + m.geom_margin, + m.flex_contype, + m.flex_conaffinity, + m.flex_margin, + m.flex_dim, + m.flex_vertadr, + m.flex_elemadr, + m.flex_elemnum, + m.flex_elemdataadr, + m.flex_elem, + m.flex_radius, + d.geom_xpos, + d.geom_xmat, + d.flexvert_xpos, + d.nworld, + d.naconmax, + ], + outputs=[ + d.contact.dist, + d.contact.pos, + d.contact.frame, + d.contact.includemargin, + d.contact.friction, + d.contact.solref, + d.contact.solreffriction, + d.contact.solimp, + d.contact.dim, + d.contact.geom, + d.contact.flex, + d.contact.vert, + d.contact.worldid, + d.contact.type, + d.contact.geomcollisionid, + d.nacon, + ], + ) + + wp.launch( + _flex_narrowphase_dim3, + dim=(d.nworld, m.nflexshelldata // 3), + inputs=[ + m.ngeom, + m.nflex, + m.geom_type, + m.geom_contype, + m.geom_conaffinity, + m.geom_condim, + m.geom_solref, + m.geom_solimp, + m.geom_size, + m.geom_friction, + m.geom_margin, + m.flex_contype, + m.flex_conaffinity, + m.flex_margin, + m.flex_dim, + m.flex_vertadr, + m.flex_shellnum, + m.flex_shelldataadr, + m.flex_shell, + m.flex_radius, + d.geom_xpos, + d.geom_xmat, + d.flexvert_xpos, + d.nworld, + d.naconmax, + ], + outputs=[ + d.contact.dist, + d.contact.pos, + d.contact.frame, + d.contact.includemargin, + d.contact.friction, + d.contact.solref, + d.contact.solreffriction, + d.contact.solimp, + d.contact.dim, + d.contact.geom, + d.contact.flex, + d.contact.vert, + d.contact.worldid, + d.contact.type, + d.contact.geomcollisionid, + d.nacon, + ], + ) + + wp.launch( + _flex_plane_narrowphase, + dim=(d.nworld, m.nflexvert), + inputs=[ + m.ngeom, + m.nflexvert, + m.geom_type, + m.geom_condim, + m.geom_solref, + m.geom_solimp, + m.geom_friction, + m.geom_margin, + m.flex_condim, + m.flex_friction, + m.flex_margin, + m.flex_vertadr, + m.flex_radius, + m.flex_vertflexid, + d.geom_xpos, + d.geom_xmat, + d.flexvert_xpos, + d.nworld, + d.naconmax, + ], + outputs=[ + d.contact.dist, + d.contact.pos, + d.contact.frame, + d.contact.includemargin, + d.contact.friction, + d.contact.solref, + d.contact.solreffriction, + d.contact.solimp, + d.contact.dim, + d.contact.geom, + d.contact.flex, + d.contact.vert, + d.contact.worldid, + d.contact.type, + d.contact.geomcollisionid, + d.nacon, + ], + ) diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_gjk.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_gjk.py index 7e4948ed1a..fe1c4445d3 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_gjk.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_gjk.py @@ -16,11 +16,12 @@ import math from typing import Tuple +import warp as wp + from mujoco.mjx.third_party.mujoco_warp._src.collision_core import Geom from mujoco.mjx.third_party.mujoco_warp._src.types import GeomType from mujoco.mjx.third_party.mujoco_warp._src.types import mat43 from mujoco.mjx.third_party.mujoco_warp._src.types import mat63 -import warp as wp # TODO(team): improve compile time to enable backward pass wp.set_module_options({"enable_backward": False}) @@ -581,16 +582,19 @@ def gjk( simplex_index2 = wp.vec4i() n = int(0) coordinates = wp.vec4() # barycentric coordinates - epsilon = wp.where(is_discrete, 0.0, 0.5 * tolerance * tolerance) + tol2 = tolerance * tolerance + epsilon = wp.where(is_discrete, 0.0, 0.5 * tol2) # set initial guess x_k = x1_0 - x2_0 + xnorm_old = FLOAT_MAX - for k in range(gjk_iterations): + for _ in range(gjk_iterations): xnorm = wp.dot(x_k, x_k) # TODO(kbayes): determine new constant here - if xnorm < 1e-12: + if xnorm < tol2 or wp.abs(xnorm_old - xnorm) < tol2: break + xnorm_old = xnorm dir_neg = x_k / wp.sqrt(xnorm) # compute kth support point in geom1 @@ -663,13 +667,6 @@ def gjk( if n == 4: break - if k == gjk_iterations - 1: - wp.printf( - "Warning: opt.ccd_iterations, currently set to %d, needs to be" - " increased.\n", - gjk_iterations, - ) - result = GJKResult() # compute the approximate witness points @@ -1205,7 +1202,6 @@ def _is_invalid_face(face: int) -> bool: def _epa( # In: tolerance: float, - gjk_iterations: int, epa_iterations: int, pt: Polytope, geom1: Geom, @@ -1226,7 +1222,7 @@ def _epa( # so iterations must be cap to limit the number of generated vertices # (one new vertex per iteration) epa_iterations = wp.min(epa_iterations, 1000) - for k in range(epa_iterations): + for _ in range(epa_iterations): pidx = idx idx = int(-1) lower2 = float(FLOAT_MAX) @@ -1325,13 +1321,6 @@ def _epa( # clear horizon pt.nhorizon = 0 - if k == epa_iterations - 1: - wp.printf( - "Warning: opt.ccd_iterations, currently set to %d, needs to be" - " increased.\n", - gjk_iterations, - ) - # return from valid face if idx > -1: x1, x2, dist = _epa_witness(pt, geom1, geom2, geomtype1, geomtype2, idx) @@ -2347,7 +2336,7 @@ def ccd( if pt.status: return result.dist, 1, result.x1, result.x2, -1 - dist, x1, x2, idx = _epa(tolerance, gjk_iterations, epa_iterations, pt, geom1, geom2, geomtype1, geomtype2, is_discrete) + dist, x1, x2, idx = _epa(tolerance, epa_iterations, pt, geom1, geom2, geomtype1, geomtype2, is_discrete) if idx == -1: return FLOAT_MAX, 0, wp.vec3(), wp.vec3(), -1 diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_primitive.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_primitive.py index c7a4051439..f1829de404 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_primitive.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_primitive.py @@ -15,9 +15,11 @@ from typing import Tuple +import warp as wp + from mujoco.mjx.third_party.mujoco_warp._src.collision_core import CollisionContext -from mujoco.mjx.third_party.mujoco_warp._src.collision_core import contact_params from mujoco.mjx.third_party.mujoco_warp._src.collision_core import Geom +from mujoco.mjx.third_party.mujoco_warp._src.collision_core import contact_params from mujoco.mjx.third_party.mujoco_warp._src.collision_core import geom_collision_pair from mujoco.mjx.third_party.mujoco_warp._src.collision_core import write_contact from mujoco.mjx.third_party.mujoco_warp._src.collision_primitive_core import box_box @@ -34,15 +36,14 @@ from mujoco.mjx.third_party.mujoco_warp._src.collision_primitive_core import sphere_sphere from mujoco.mjx.third_party.mujoco_warp._src.math import make_frame from mujoco.mjx.third_party.mujoco_warp._src.math import upper_trid_index +from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MAXVAL from mujoco.mjx.third_party.mujoco_warp._src.types import Data from mujoco.mjx.third_party.mujoco_warp._src.types import GeomType -from mujoco.mjx.third_party.mujoco_warp._src.types import mat43 -from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MAXVAL from mujoco.mjx.third_party.mujoco_warp._src.types import Model +from mujoco.mjx.third_party.mujoco_warp._src.types import mat43 from mujoco.mjx.third_party.mujoco_warp._src.types import vec5 from mujoco.mjx.third_party.mujoco_warp._src.warp_util import cache_kernel from mujoco.mjx.third_party.mujoco_warp._src.warp_util import event_scope -import warp as wp wp.set_module_options({"enable_backward": False}) @@ -304,6 +305,7 @@ def plane_sphere_wrapper( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -339,6 +341,7 @@ def plane_sphere_wrapper( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -374,6 +377,7 @@ def sphere_sphere_wrapper( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -408,6 +412,7 @@ def sphere_sphere_wrapper( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -443,6 +448,7 @@ def sphere_capsule_wrapper( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -480,6 +486,7 @@ def sphere_capsule_wrapper( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -515,6 +522,7 @@ def capsule_capsule_wrapper( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -564,6 +572,7 @@ def capsule_capsule_wrapper( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -599,6 +608,7 @@ def plane_capsule_wrapper( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -644,6 +654,7 @@ def plane_capsule_wrapper( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -679,6 +690,7 @@ def plane_ellipsoid_wrapper( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -713,6 +725,7 @@ def plane_ellipsoid_wrapper( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -748,6 +761,7 @@ def plane_box_wrapper( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -784,6 +798,7 @@ def plane_box_wrapper( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -819,6 +834,7 @@ def plane_convex_wrapper( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -855,6 +871,7 @@ def plane_convex_wrapper( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -890,6 +907,7 @@ def sphere_cylinder_wrapper( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -934,6 +952,7 @@ def sphere_cylinder_wrapper( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -969,6 +988,7 @@ def plane_cylinder_wrapper( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -1015,6 +1035,7 @@ def plane_cylinder_wrapper( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -1050,6 +1071,7 @@ def sphere_box_wrapper( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -1083,6 +1105,7 @@ def sphere_box_wrapper( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -1118,6 +1141,7 @@ def capsule_box_wrapper( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -1166,6 +1190,7 @@ def capsule_box_wrapper( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -1201,6 +1226,7 @@ def box_box_wrapper( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -1245,6 +1271,7 @@ def box_box_wrapper( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -1327,6 +1354,7 @@ def primitive_narrowphase( contact_solimp_out: wp.array(dtype=vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), contact_geomcollisionid_out: wp.array(dtype=int), @@ -1416,6 +1444,7 @@ def primitive_narrowphase( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -1511,6 +1540,7 @@ def primitive_narrowphase(m: Model, d: Data, ctx: CollisionContext, collision_ta d.contact.solimp, d.contact.dim, d.contact.geom, + d.contact.efc_address, d.contact.worldid, d.contact.type, d.contact.geomcollisionid, diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_primitive_core.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_primitive_core.py index 306a301e58..8a85d2412f 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_primitive_core.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_primitive_core.py @@ -1489,3 +1489,507 @@ def capsule_box( mat23f(pos1[0], pos1[1], pos1[2], pos2[0], pos2[1], pos2[2]), mat23f(normal1[0], normal1[1], normal1[2], normal2[0], normal2[1], normal2[2]), ) + + +@wp.func +def _tri_area_sign(p1: wp.vec2, p2: wp.vec2, p3: wp.vec2) -> float: + """Sign of (signed) area of planar triangle.""" + return wp.sign((p1[0] - p3[0]) * (p2[1] - p3[1]) - (p2[0] - p3[0]) * (p1[1] - p3[1])) + + +@wp.func +def _tri_point_segment(p: wp.vec2, u: wp.vec2, v: wp.vec2) -> wp.vec2: + """Find nearest point to p within line segment (u, v).""" + uv = v - u + up = p - u + + denom = wp.max(MJ_MINVAL, wp.dot(uv, uv)) + a = wp.dot(uv, up) / denom + + if a <= 0.0: + return u + elif a >= 1.0: + return v + else: + return u + a * uv + + +@wp.func +def sphere_triangle( + sphere_pos: wp.vec3, + sphere_radius: float, + t1: wp.vec3, + t2: wp.vec3, + t3: wp.vec3, + tri_radius: float, +) -> Tuple[float, wp.vec3, wp.vec3]: + """Core contact geometry calculation for sphere-triangle collision. + + Port of mjraw_SphereTriangle from engine_collision_primitive.c + + Args: + sphere_pos: Center position of the sphere. + sphere_radius: Radius of the sphere. + t1: Triangle vertex positions. + t2: Triangle vertex positions. + t3: Triangle vertex positions. + tri_radius: Triangle (flex element) radius. + + Returns: + - Contact distance (MJ_MAXVAL if no collision). + - Contact position. + - Contact normal vector. + """ + S = sphere_pos - t1 + A = t2 - t1 + B = t3 - t1 + + N = wp.normalize(wp.cross(A, B)) + + dstS = wp.dot(N, S) + + P = S - dstS * N + + V1 = wp.normalize(A) + lenA = wp.length(A) + V2 = wp.normalize(wp.cross(N, A)) + + o = wp.vec2(0.0, 0.0) + a = wp.vec2(lenA, 0.0) + b = wp.vec2(wp.dot(V1, B), wp.dot(V2, B)) + p = wp.vec2(wp.dot(V1, P), wp.dot(V2, P)) + + sign1 = _tri_area_sign(p, o, a) + sign2 = _tri_area_sign(p, a, b) + sign3 = _tri_area_sign(p, b, o) + + X = wp.vec3(0.0) + if sign1 == sign2 and sign2 == sign3: + X = P + else: + x0 = _tri_point_segment(p, o, a) + x1 = _tri_point_segment(p, a, b) + x2 = _tri_point_segment(p, b, o) + + d0 = wp.length(p - x0) + d1 = wp.length(p - x1) + d2 = wp.length(p - x2) + + if d0 < d1 and d0 < d2: + X = x0[0] * V1 + x0[1] * V2 + elif d1 < d2: + X = x1[0] * V1 + x1[1] * V2 + else: + X = x2[0] * V1 + x2[1] * V2 + + nrm = X - S + dst = wp.length(nrm) + + if dst > MJ_MINVAL: + nrm = nrm / dst + else: + nrm = N + + dist = dst - sphere_radius - tri_radius + pos = sphere_pos + nrm * (sphere_radius + 0.5 * dist) + + return dist, pos, nrm + + +@wp.func +def box_triangle( + box_pos: wp.vec3, + box_rot: wp.mat33, + box_size: wp.vec3, + t1: wp.vec3, + t2: wp.vec3, + t3: wp.vec3, + tri_radius: float, +) -> Tuple[wp.vec2, mat23f, mat23f]: + """Core contact geometry calculation for box-triangle collision. + + Port of mjraw_BoxTriangle from engine_collision_primitive.c + + Args: + box_pos: Center position of the box. + box_rot: Orientation matrix of the box. + box_size: Half-sizes of the box. + t1: Triangle vertex positions. + t2: Triangle vertex positions. + t3: Triangle vertex positions. + tri_radius: Triangle (flex element) radius. + + Returns: + - wp.vec2 of distances for up to 2 contacts (MJ_MAXVAL if no collision). + - mat23f of contact positions (2 x vec3). + - mat23f of contact normals (2 x vec3). + """ + dist1 = MJ_MAXVAL + dist2 = MJ_MAXVAL + pos1 = wp.vec3(0.0) + pos2 = wp.vec3(0.0) + nrm1 = wp.vec3(0.0) + nrm2 = wp.vec3(0.0) + cnt = 0 + + box_rotT = wp.transpose(box_rot) + + for vi in range(3): + vert = wp.vec3(0.0) + if vi == 0: + vert = t1 + elif vi == 1: + vert = t2 + else: + vert = t3 + + diff = vert - box_pos + local = box_rotT @ diff + + maxaxis = 0 + maxval = wp.abs(local[0]) - box_size[0] + for j in range(1, 3): + val = wp.abs(local[j]) - box_size[j] + if val > maxval: + maxval = val + maxaxis = j + + inside = True + for j in range(3): + if wp.abs(local[j]) > box_size[j] + tri_radius: + inside = False + + if inside and cnt < 2: + nrm_local = wp.vec3(0.0) + if maxaxis == 0: + nrm_local = wp.vec3(wp.sign(local[0]), 0.0, 0.0) + elif maxaxis == 1: + nrm_local = wp.vec3(0.0, wp.sign(local[1]), 0.0) + else: + nrm_local = wp.vec3(0.0, 0.0, wp.sign(local[2])) + + nrm_global = box_rot @ nrm_local + d = maxval - tri_radius + offset = tri_radius + d * 0.5 + p = vert - nrm_global * offset + + if cnt == 0: + dist1 = d + pos1 = p + nrm1 = nrm_global + else: + dist2 = d + pos2 = p + nrm2 = nrm_global + cnt += 1 + + for i in range(8): + if cnt >= 2: + break + + vec = wp.vec3( + wp.where(i & 1, box_size[0], -box_size[0]), + wp.where(i & 2, box_size[1], -box_size[1]), + wp.where(i & 4, box_size[2], -box_size[2]), + ) + corner = box_rot @ vec + box_pos + + d, p, n = sphere_triangle(corner, 0.0, t1, t2, t3, tri_radius) + if d < MJ_MAXVAL: + if cnt == 0: + dist1 = d + pos1 = p + nrm1 = n + elif cnt == 1: + dist2 = d + pos2 = p + nrm2 = n + cnt += 1 + + return ( + wp.vec2(dist1, dist2), + mat23f(pos1[0], pos1[1], pos1[2], pos2[0], pos2[1], pos2[2]), + mat23f(nrm1[0], nrm1[1], nrm1[2], nrm2[0], nrm2[1], nrm2[2]), + ) + + +@wp.func +def capsule_triangle( + capsule_pos: wp.vec3, + capsule_axis: wp.vec3, + capsule_radius: float, + capsule_half_length: float, + t1: wp.vec3, + t2: wp.vec3, + t3: wp.vec3, + tri_radius: float, +) -> Tuple[wp.vec2, mat23f, mat23f]: + """Core contact geometry calculation for capsule-triangle collision. + + Port of mjraw_CapsuleTriangle from engine_collision_primitive.c + + Args: + capsule_pos: Center position of the capsule. + capsule_axis: Unit axis direction of the capsule. + capsule_radius: Radius of the capsule. + capsule_half_length: Half-length of the capsule cylinder. + t1: Triangle vertex positions. + t2: Triangle vertex positions. + t3: Triangle vertex positions. + tri_radius: Triangle (flex element) radius. + + Returns: + - wp.vec2 of distances for up to 2 contacts (MJ_MAXVAL if no collision). + - mat23f of contact positions (2 x vec3). + - mat23f of contact normals (2 x vec3). + """ + dist1 = MJ_MAXVAL + dist2 = MJ_MAXVAL + pos1 = wp.vec3(0.0) + pos2 = wp.vec3(0.0) + nrm1 = wp.vec3(0.0) + nrm2 = wp.vec3(0.0) + cnt = 0 + + p1 = capsule_pos - capsule_axis * capsule_half_length + p2 = capsule_pos + capsule_axis * capsule_half_length + + d, p, n = sphere_triangle(p1, capsule_radius, t1, t2, t3, tri_radius) + if d < MJ_MAXVAL: + dist1 = d + pos1 = p + nrm1 = n + cnt = 1 + + d, p, n = sphere_triangle(p2, capsule_radius, t1, t2, t3, tri_radius) + if d < MJ_MAXVAL and cnt < 2: + if cnt == 0: + dist1 = d + pos1 = p + nrm1 = n + else: + dist2 = d + pos2 = p + nrm2 = n + cnt += 1 + + ab = p2 - p1 + ab_len_sq = 4.0 * capsule_half_length * capsule_half_length + + for vi in range(3): + if cnt >= 2: + break + + vert = wp.vec3(0.0) + if vi == 0: + vert = t1 + elif vi == 1: + vert = t2 + else: + vert = t3 + + vec = vert - p1 + t_param = wp.dot(vec, ab) / wp.max(MJ_MINVAL, ab_len_sq) + + if t_param > MJ_MINVAL and t_param < 1.0 - MJ_MINVAL: + closest = p1 + ab * t_param + diff = vert - closest + dist_raw = wp.length(diff) + + if dist_raw > MJ_MINVAL: + nrm = diff / dist_raw + d = dist_raw - capsule_radius - tri_radius + p = (closest + vert + nrm * (capsule_radius - tri_radius)) * 0.5 + + if cnt == 0: + dist1 = d + pos1 = p + nrm1 = nrm + else: + dist2 = d + pos2 = p + nrm2 = nrm + cnt += 1 + + return ( + wp.vec2(dist1, dist2), + mat23f(pos1[0], pos1[1], pos1[2], pos2[0], pos2[1], pos2[2]), + mat23f(nrm1[0], nrm1[1], nrm1[2], nrm2[0], nrm2[1], nrm2[2]), + ) + + +@wp.func +def cylinder_triangle( + cylinder_pos: wp.vec3, + cylinder_axis: wp.vec3, + cylinder_radius: float, + cylinder_half_height: float, + t1: wp.vec3, + t2: wp.vec3, + t3: wp.vec3, + tri_radius: float, +) -> Tuple[wp.vec2, mat23f, mat23f]: + """Core contact geometry calculation for cylinder-triangle collision. + + Args: + cylinder_pos: Center position of the cylinder. + cylinder_axis: Unit axis direction of the cylinder. + cylinder_radius: Radius of the cylinder. + cylinder_half_height: Half-height of the cylinder. + t1: Triangle vertex positions. + t2: Triangle vertex positions. + t3: Triangle vertex positions. + tri_radius: Triangle (flex element) radius. + + Returns: + - wp.vec2 of distances for up to 2 contacts (MJ_MAXVAL if no collision). + - mat23f of contact positions (2 x vec3). + - mat23f of contact normals (2 x vec3). + """ + dist1 = MJ_MAXVAL + dist2 = MJ_MAXVAL + pos1 = wp.vec3(0.0) + pos2 = wp.vec3(0.0) + nrm1 = wp.vec3(0.0) + nrm2 = wp.vec3(0.0) + cnt = int(0) + + p1 = cylinder_pos - cylinder_axis * cylinder_half_height + p2 = cylinder_pos + cylinder_axis * cylinder_half_height + + ab = p2 - p1 + ab_len_sq = 4.0 * cylinder_half_height * cylinder_half_height + + for vi in range(3): + if cnt >= 2: + break + + vert = wp.vec3(0.0) + if vi == 0: + vert = t1 + elif vi == 1: + vert = t2 + else: + vert = t3 + + vec = vert - p1 + t_param = wp.dot(vec, ab) / wp.max(MJ_MINVAL, ab_len_sq) + + if t_param > MJ_MINVAL and t_param < 1.0 - MJ_MINVAL: + closest = p1 + ab * t_param + diff = vert - closest + dist_raw = wp.length(diff) + + if dist_raw < cylinder_radius + tri_radius: + if dist_raw > MJ_MINVAL: + nrm = diff / dist_raw + d = dist_raw - cylinder_radius - tri_radius + p = (closest + vert + nrm * (cylinder_radius - tri_radius)) * 0.5 + else: + dist_to_side = cylinder_radius + dist_to_p2 = (1.0 - t_param) * wp.sqrt(ab_len_sq) + dist_to_p1 = t_param * wp.sqrt(ab_len_sq) + + if dist_to_p2 < dist_to_side and dist_to_p2 < dist_to_p1: + nrm = cylinder_axis + d = -dist_to_p2 - tri_radius + p = vert + elif dist_to_p1 < dist_to_side: + nrm = -cylinder_axis + d = -dist_to_p1 - tri_radius + p = vert + else: + tri_normal = wp.normalize(wp.cross(t2 - t1, t3 - t1)) + nrm = tri_normal + d = -cylinder_radius - tri_radius + p = closest + + if cnt == 0: + dist1 = d + pos1 = p + nrm1 = nrm + else: + dist2 = d + pos2 = p + nrm2 = nrm + cnt += 1 + elif t_param <= MJ_MINVAL: + diff = vert - p1 + signed_dist = wp.dot(diff, cylinder_axis) + perp = diff - cylinder_axis * signed_dist + perp_len = wp.length(perp) + + if perp_len < cylinder_radius: + d = -signed_dist - tri_radius + nrm = -cylinder_axis + p = vert - nrm * (tri_radius + d * 0.5) + if cnt == 0: + dist1 = d + pos1 = p + nrm1 = nrm + else: + dist2 = d + pos2 = p + nrm2 = nrm + cnt += 1 + elif perp_len < cylinder_radius + tri_radius: + edge_dir = perp / perp_len + edge_point = p1 + edge_dir * cylinder_radius + diff_to_edge = vert - edge_point + dist_raw = wp.length(diff_to_edge) + if dist_raw > MJ_MINVAL: + nrm = diff_to_edge / dist_raw + d = dist_raw - tri_radius + p = vert - nrm * (tri_radius + d * 0.5) + if cnt == 0: + dist1 = d + pos1 = p + nrm1 = nrm + else: + dist2 = d + pos2 = p + nrm2 = nrm + cnt += 1 + else: + diff = vert - p2 + signed_dist = wp.dot(diff, cylinder_axis) + perp = diff - cylinder_axis * signed_dist + perp_len = wp.length(perp) + + if perp_len < cylinder_radius: + d = signed_dist - tri_radius + nrm = cylinder_axis + p = vert - nrm * (tri_radius + d * 0.5) + if cnt == 0: + dist1 = d + pos1 = p + nrm1 = nrm + else: + dist2 = d + pos2 = p + nrm2 = nrm + cnt += 1 + elif perp_len < cylinder_radius + tri_radius: + edge_dir = perp / perp_len + edge_point = p2 + edge_dir * cylinder_radius + diff_to_edge = vert - edge_point + dist_raw = wp.length(diff_to_edge) + if dist_raw > MJ_MINVAL: + nrm = diff_to_edge / dist_raw + d = dist_raw - tri_radius + p = vert - nrm * (tri_radius + d * 0.5) + if cnt == 0: + dist1 = d + pos1 = p + nrm1 = nrm + else: + dist2 = d + pos2 = p + nrm2 = nrm + cnt += 1 + + return ( + wp.vec2(dist1, dist2), + mat23f(pos1[0], pos1[1], pos1[2], pos2[0], pos2[1], pos2[2]), + mat23f(nrm1[0], nrm1[1], nrm1[2], nrm2[0], nrm2[1], nrm2[2]), + ) diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_sdf.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_sdf.py index c84b67c820..4decf33c99 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_sdf.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/collision_sdf.py @@ -15,6 +15,8 @@ from typing import Tuple +import warp as wp + from mujoco.mjx.third_party.mujoco_warp._src.collision_core import CollisionContext from mujoco.mjx.third_party.mujoco_warp._src.collision_core import contact_params from mujoco.mjx.third_party.mujoco_warp._src.collision_core import geom_collision_pair @@ -27,9 +29,9 @@ from mujoco.mjx.third_party.mujoco_warp._src.types import vec5 from mujoco.mjx.third_party.mujoco_warp._src.types import vec8 from mujoco.mjx.third_party.mujoco_warp._src.types import vec8i +from mujoco.mjx.third_party.mujoco_warp._src.types import vec_pluginattr from mujoco.mjx.third_party.mujoco_warp._src.util_misc import halton from mujoco.mjx.third_party.mujoco_warp._src.warp_util import event_scope -import warp as wp wp.set_module_options({"enable_backward": False}) @@ -38,8 +40,8 @@ class OptimizationParams: rel_mat: wp.mat33 rel_pos: wp.vec3 - attr1: wp.vec3 - attr2: wp.vec3 + attr1: vec_pluginattr + attr2: vec_pluginattr @wp.struct @@ -77,20 +79,24 @@ class MeshData: @wp.func def get_sdf_params( - # Model: - oct_child: wp.array(dtype=vec8i), - oct_aabb: wp.array2d(dtype=wp.vec3), - oct_coeff: wp.array(dtype=vec8), - mesh_octadr: wp.array(dtype=int), - plugin: wp.array(dtype=int), - plugin_attr: wp.array(dtype=wp.vec3f), - # In: - g_type: int, - g_size: wp.vec3, - plugin_id: int, - mesh_id: int, -) -> Tuple[wp.vec3, int, VolumeData, MeshData]: - attributes = g_size + # Model: + oct_child: wp.array(dtype=vec8i), + oct_aabb: wp.array2d(dtype=wp.vec3), + oct_coeff: wp.array(dtype=vec8), + mesh_octadr: wp.array(dtype=int), + plugin: wp.array(dtype=int), + plugin_attr: wp.array(dtype=vec_pluginattr), + # In: + g_type: int, + g_size: wp.vec3, + plugin_id: int, + mesh_id: int, +) -> Tuple[vec_pluginattr, int, VolumeData, MeshData]: + # default attributes from geom size, first 3 values copied + attributes = vec_pluginattr() + attributes[0] = g_size[0] + attributes[1] = g_size[1] + attributes[2] = g_size[2] plugin_index = -1 volume_data = VolumeData() @@ -108,6 +114,16 @@ def get_sdf_params( volume_data.oct_coeff = oct_coeff volume_data.valid = True + elif g_type == GeomType.MESH and mesh_id != -1 and mesh_octadr[mesh_id] != -1: + octadr = mesh_octadr[mesh_id] + volume_data.center = oct_aabb[octadr, 0] + volume_data.half_size = oct_aabb[octadr, 1] + volume_data.root = octadr + volume_data.oct_aabb = oct_aabb + volume_data.oct_child = oct_child + volume_data.oct_coeff = oct_coeff + volume_data.valid = True + return attributes, plugin_index, volume_data, MeshData() @@ -215,24 +231,28 @@ def grad_ellipsoid(p: wp.vec3, size: wp.vec3) -> wp.vec3: @wp.func -def user_sdf(p: wp.vec3, attr: wp.vec3, sdf_type: int) -> float: +def user_sdf(p: wp.vec3, attr: vec_pluginattr, sdf_type: int) -> float: + """User-defined SDF function. + + Access attributes via attr[i] where i is the attribute index (0 to _NPLUGINATTR-1). + """ wp.printf("ERROR: user_sdf function must be implemented by user code\n") return 0.0 @wp.func -def user_sdf_grad(p: wp.vec3, attr: wp.vec3, sdf_type: int) -> wp.vec3: +def user_sdf_grad(p: wp.vec3, attr: vec_pluginattr, sdf_type: int) -> wp.vec3: + """User-defined SDF gradient function. + + Access attributes via attr[i] where i is the attribute index (0 to _NPLUGINATTR-1). + """ wp.printf("ERROR: user_sdf_grad function must be implemented by user code\n") return wp.vec3(0.0) @wp.func def find_oct( - oct_child: wp.array(dtype=vec8i), - oct_aabb: wp.array2d(dtype=wp.vec3), - p: wp.vec3, - grad: bool, - root: int, + oct_child: wp.array(dtype=vec8i), oct_aabb: wp.array2d(dtype=wp.vec3), p: wp.vec3, grad: bool, root: int ) -> Tuple[int, Tuple[vec8, vec8, vec8]]: stack = root niter = int(100) @@ -268,14 +288,14 @@ def find_oct( # child indices are relative to root (mesh_octadr offset) child0 = oct_child[node][0] if ( - child0 == -1 - and oct_child[node][1] == -1 - and oct_child[node][2] == -1 - and oct_child[node][3] == -1 - and oct_child[node][4] == -1 - and oct_child[node][5] == -1 - and oct_child[node][6] == -1 - and oct_child[node][7] == -1 + child0 == -1 + and oct_child[node][1] == -1 + and oct_child[node][2] == -1 + and oct_child[node][3] == -1 + and oct_child[node][4] == -1 + and oct_child[node][5] == -1 + and oct_child[node][6] == -1 + and oct_child[node][7] == -1 ): for j in range(8): if not grad: @@ -342,13 +362,7 @@ def box_project(center: wp.vec3, half_size: wp.vec3, xyz: wp.vec3) -> Tuple[floa @wp.func def sample_volume_sdf(xyz: wp.vec3, volume_data: VolumeData) -> float: dist0, point = box_project(volume_data.center, volume_data.half_size, xyz) - node, weights = find_oct( - volume_data.oct_child, - volume_data.oct_aabb, - point, - grad=False, - root=volume_data.root, - ) + node, weights = find_oct(volume_data.oct_child, volume_data.oct_aabb, point, grad=False, root=volume_data.root) return dist0 + wp.dot(weights[0], volume_data.oct_coeff[node]) @@ -365,13 +379,7 @@ def sample_volume_grad(xyz: wp.vec3, volume_data: VolumeData) -> wp.vec3: grad_y = (sample_volume_sdf(xyz + dy, volume_data) - f) / h grad_z = (sample_volume_sdf(xyz + dz, volume_data) - f) / h return wp.vec3(grad_x, grad_y, grad_z) - node, weights = find_oct( - volume_data.oct_child, - volume_data.oct_aabb, - point, - grad=True, - root=volume_data.root, - ) + node, weights = find_oct(volume_data.oct_child, volume_data.oct_aabb, point, grad=True, root=volume_data.root) grad_x = wp.dot(weights[0], volume_data.oct_coeff[node]) grad_y = wp.dot(weights[1], volume_data.oct_coeff[node]) grad_z = wp.dot(weights[2], volume_data.oct_coeff[node]) @@ -379,15 +387,17 @@ def sample_volume_grad(xyz: wp.vec3, volume_data: VolumeData) -> wp.vec3: @wp.func -def sdf(type: int, p: wp.vec3, attr: wp.vec3, sdf_type: int, volume_data: VolumeData, mesh_data: MeshData) -> float: +def sdf(type: int, p: wp.vec3, attr: vec_pluginattr, sdf_type: int, volume_data: VolumeData, mesh_data: MeshData) -> float: + # extract first 3 elements as vec3 for primitive sdf functions + attr_vec3 = wp.vec3(attr[0], attr[1], attr[2]) if type == GeomType.PLANE: return p[2] elif type == GeomType.SPHERE: - return sphere(p, attr) + return sphere(p, attr_vec3) elif type == GeomType.BOX: - return box(p, attr) + return box(p, attr_vec3) elif type == GeomType.ELLIPSOID: - return ellipsoid(p, attr) + return ellipsoid(p, attr_vec3) elif type == GeomType.MESH and mesh_data.valid: mesh_data.pnt = p mesh_data.vec = -wp.normalize(p) @@ -425,21 +435,27 @@ def sdf(type: int, p: wp.vec3, attr: wp.vec3, sdf_type: int, volume_data: Volume return sample_volume_sdf(p, volume_data) else: return user_sdf(p, attr, sdf_type) + elif type == GeomType.MESH and volume_data.valid: + return sample_volume_sdf(p, volume_data) wp.printf("ERROR: SDF type not implemented\n") return 0.0 @wp.func -def sdf_grad(type: int, p: wp.vec3, attr: wp.vec3, sdf_type: int, volume_data: VolumeData, mesh_data: MeshData) -> wp.vec3: +def sdf_grad( + type: int, p: wp.vec3, attr: vec_pluginattr, sdf_type: int, volume_data: VolumeData, mesh_data: MeshData +) -> wp.vec3: + # extract first 3 elements as vec3 for primitive sdf functions + attr_vec3 = wp.vec3(attr[0], attr[1], attr[2]) if type == GeomType.PLANE: grad = wp.vec3(0.0, 0.0, 1.0) return grad elif type == GeomType.SPHERE: return grad_sphere(p) elif type == GeomType.BOX: - return grad_box(p, attr) + return grad_box(p, attr_vec3) elif type == GeomType.ELLIPSOID: - return grad_ellipsoid(p, attr) + return grad_ellipsoid(p, attr_vec3) elif type == GeomType.MESH and mesh_data.valid: mesh_data.pnt = p mesh_data.vec = -wp.normalize(p) @@ -466,6 +482,8 @@ def sdf_grad(type: int, p: wp.vec3, attr: wp.vec3, sdf_type: int, volume_data: V return sample_volume_grad(p, volume_data) else: return user_sdf_grad(p, attr, sdf_type) + elif type == GeomType.MESH and volume_data.valid: + return sample_volume_grad(p, volume_data) wp.printf("ERROR: SDF grad type not implemented\n") return wp.vec3(0.0) @@ -476,8 +494,8 @@ def clearance( type1: int, p1: wp.vec3, p2: wp.vec3, - s1: wp.vec3, - s2: wp.vec3, + s1: vec_pluginattr, + s2: vec_pluginattr, sdf_type1: int, sdf_type2: int, sfd_intersection: bool, @@ -606,8 +624,8 @@ def gradient_descent( # In: type1: int, x0_initial: wp.vec3, - attr1: wp.vec3, - attr2: wp.vec3, + attr1: vec_pluginattr, + attr2: vec_pluginattr, pos1: wp.vec3, rot1: wp.mat33, pos2: wp.vec3, @@ -645,76 +663,77 @@ def gradient_descent( @wp.kernel def _sdf_narrowphase( - # Model: - nmeshface: int, - oct_child: wp.array(dtype=vec8i), - oct_aabb: wp.array2d(dtype=wp.vec3), - oct_coeff: wp.array(dtype=vec8), - geom_type: wp.array(dtype=int), - geom_condim: wp.array(dtype=int), - geom_dataid: wp.array(dtype=int), - geom_priority: wp.array(dtype=int), - geom_solmix: wp.array2d(dtype=float), - geom_solref: wp.array2d(dtype=wp.vec2), - geom_solimp: wp.array2d(dtype=vec5), - geom_size: wp.array2d(dtype=wp.vec3), - geom_aabb: wp.array3d(dtype=wp.vec3), - geom_friction: wp.array2d(dtype=wp.vec3), - geom_margin: wp.array2d(dtype=float), - geom_gap: wp.array2d(dtype=float), - mesh_vertadr: wp.array(dtype=int), - mesh_vertnum: wp.array(dtype=int), - mesh_faceadr: wp.array(dtype=int), - mesh_octadr: wp.array(dtype=int), - mesh_graphadr: wp.array(dtype=int), - mesh_vert: wp.array(dtype=wp.vec3), - mesh_face: wp.array(dtype=wp.vec3i), - mesh_graph: wp.array(dtype=int), - mesh_polynum: wp.array(dtype=int), - mesh_polyadr: wp.array(dtype=int), - mesh_polynormal: wp.array(dtype=wp.vec3), - mesh_polyvertadr: wp.array(dtype=int), - mesh_polyvertnum: wp.array(dtype=int), - mesh_polyvert: wp.array(dtype=int), - mesh_polymapadr: wp.array(dtype=int), - mesh_polymapnum: wp.array(dtype=int), - mesh_polymap: wp.array(dtype=int), - pair_dim: wp.array(dtype=int), - pair_solref: wp.array2d(dtype=wp.vec2), - pair_solreffriction: wp.array2d(dtype=wp.vec2), - pair_solimp: wp.array2d(dtype=vec5), - pair_margin: wp.array2d(dtype=float), - pair_gap: wp.array2d(dtype=float), - pair_friction: wp.array2d(dtype=vec5), - plugin: wp.array(dtype=int), - plugin_attr: wp.array(dtype=wp.vec3f), - geom_plugin_index: wp.array(dtype=int), - # Data in: - geom_xpos_in: wp.array2d(dtype=wp.vec3), - geom_xmat_in: wp.array2d(dtype=wp.mat33), - naconmax_in: int, - ncollision_in: wp.array(dtype=int), - # In: - collision_pair_in: wp.array(dtype=wp.vec2i), - collision_pairid_in: wp.array(dtype=wp.vec2i), - collision_worldid_in: wp.array(dtype=int), - sdf_initpoints: int, - sdf_iterations: int, - # Data out: - contact_dist_out: wp.array(dtype=float), - contact_pos_out: wp.array(dtype=wp.vec3), - contact_frame_out: wp.array(dtype=wp.mat33), - contact_includemargin_out: wp.array(dtype=float), - contact_friction_out: wp.array(dtype=vec5), - contact_solref_out: wp.array(dtype=wp.vec2), - contact_solreffriction_out: wp.array(dtype=wp.vec2), - contact_solimp_out: wp.array(dtype=vec5), - contact_dim_out: wp.array(dtype=int), - contact_geom_out: wp.array(dtype=wp.vec2i), - contact_worldid_out: wp.array(dtype=int), - contact_type_out: wp.array(dtype=int), - contact_geomcollisionid_out: wp.array(dtype=int), - nacon_out: wp.array(dtype=int), + # Model: + nmeshface: int, + oct_child: wp.array(dtype=vec8i), + oct_aabb: wp.array2d(dtype=wp.vec3), + oct_coeff: wp.array(dtype=vec8), + geom_type: wp.array(dtype=int), + geom_condim: wp.array(dtype=int), + geom_dataid: wp.array(dtype=int), + geom_priority: wp.array(dtype=int), + geom_solmix: wp.array2d(dtype=float), + geom_solref: wp.array2d(dtype=wp.vec2), + geom_solimp: wp.array2d(dtype=vec5), + geom_size: wp.array2d(dtype=wp.vec3), + geom_aabb: wp.array3d(dtype=wp.vec3), + geom_friction: wp.array2d(dtype=wp.vec3), + geom_margin: wp.array2d(dtype=float), + geom_gap: wp.array2d(dtype=float), + mesh_vertadr: wp.array(dtype=int), + mesh_vertnum: wp.array(dtype=int), + mesh_faceadr: wp.array(dtype=int), + mesh_octadr: wp.array(dtype=int), + mesh_graphadr: wp.array(dtype=int), + mesh_vert: wp.array(dtype=wp.vec3), + mesh_face: wp.array(dtype=wp.vec3i), + mesh_graph: wp.array(dtype=int), + mesh_polynum: wp.array(dtype=int), + mesh_polyadr: wp.array(dtype=int), + mesh_polynormal: wp.array(dtype=wp.vec3), + mesh_polyvertadr: wp.array(dtype=int), + mesh_polyvertnum: wp.array(dtype=int), + mesh_polyvert: wp.array(dtype=int), + mesh_polymapadr: wp.array(dtype=int), + mesh_polymapnum: wp.array(dtype=int), + mesh_polymap: wp.array(dtype=int), + pair_dim: wp.array(dtype=int), + pair_solref: wp.array2d(dtype=wp.vec2), + pair_solreffriction: wp.array2d(dtype=wp.vec2), + pair_solimp: wp.array2d(dtype=vec5), + pair_margin: wp.array2d(dtype=float), + pair_gap: wp.array2d(dtype=float), + pair_friction: wp.array2d(dtype=vec5), + plugin: wp.array(dtype=int), + plugin_attr: wp.array(dtype=vec_pluginattr), + geom_plugin_index: wp.array(dtype=int), + # Data in: + geom_xpos_in: wp.array2d(dtype=wp.vec3), + geom_xmat_in: wp.array2d(dtype=wp.mat33), + naconmax_in: int, + ncollision_in: wp.array(dtype=int), + # In: + collision_pair_in: wp.array(dtype=wp.vec2i), + collision_pairid_in: wp.array(dtype=wp.vec2i), + collision_worldid_in: wp.array(dtype=int), + sdf_initpoints: int, + sdf_iterations: int, + # Data out: + contact_dist_out: wp.array(dtype=float), + contact_pos_out: wp.array(dtype=wp.vec3), + contact_frame_out: wp.array(dtype=wp.mat33), + contact_includemargin_out: wp.array(dtype=float), + contact_friction_out: wp.array(dtype=vec5), + contact_solref_out: wp.array(dtype=wp.vec2), + contact_solreffriction_out: wp.array(dtype=wp.vec2), + contact_solimp_out: wp.array(dtype=vec5), + contact_dim_out: wp.array(dtype=int), + contact_geom_out: wp.array(dtype=wp.vec2i), + contact_efc_address_out: wp.array2d(dtype=int), + contact_worldid_out: wp.array(dtype=int), + contact_type_out: wp.array(dtype=int), + contact_geomcollisionid_out: wp.array(dtype=int), + nacon_out: wp.array(dtype=int), ): i, contact_tid = wp.tid() if i >= sdf_initpoints: @@ -799,29 +818,11 @@ def _sdf_narrowphase( rot1 = geom1.rot attr1, g1_plugin_id, volume_data1, mesh_data1 = get_sdf_params( - oct_child, - oct_aabb, - oct_coeff, - mesh_octadr, - plugin, - plugin_attr, - type1, - geom1.size, - g1_plugin, - geom_dataid[g1], + oct_child, oct_aabb, oct_coeff, mesh_octadr, plugin, plugin_attr, type1, geom1.size, g1_plugin, geom_dataid[g1] ) attr2, g2_plugin_id, volume_data2, mesh_data2 = get_sdf_params( - oct_child, - oct_aabb, - oct_coeff, - mesh_octadr, - plugin, - plugin_attr, - type2, - geom2.size, - g2_plugin, - geom_dataid[g2], + oct_child, oct_aabb, oct_coeff, mesh_octadr, plugin, plugin_attr, type2, geom2.size, g2_plugin, geom_dataid[g2] ) mesh_data1.nmeshface = nmeshface @@ -900,6 +901,7 @@ def _sdf_narrowphase( contact_solimp_out, contact_dim_out, contact_geom_out, + contact_efc_address_out, contact_worldid_out, contact_type_out, contact_geomcollisionid_out, @@ -910,76 +912,77 @@ def _sdf_narrowphase( @event_scope def sdf_narrowphase(m: Model, d: Data, ctx: CollisionContext): wp.launch( - _sdf_narrowphase, - dim=(m.opt.sdf_initpoints, d.naconmax), - inputs=[ - m.nmeshface, - m.oct_child, - m.oct_aabb, - m.oct_coeff, - m.geom_type, - m.geom_condim, - m.geom_dataid, - m.geom_priority, - m.geom_solmix, - m.geom_solref, - m.geom_solimp, - m.geom_size, - m.geom_aabb, - m.geom_friction, - m.geom_margin, - m.geom_gap, - m.mesh_vertadr, - m.mesh_vertnum, - m.mesh_faceadr, - m.mesh_octadr, - m.mesh_graphadr, - m.mesh_vert, - m.mesh_face, - m.mesh_graph, - m.mesh_polynum, - m.mesh_polyadr, - m.mesh_polynormal, - m.mesh_polyvertadr, - m.mesh_polyvertnum, - m.mesh_polyvert, - m.mesh_polymapadr, - m.mesh_polymapnum, - m.mesh_polymap, - m.pair_dim, - m.pair_solref, - m.pair_solreffriction, - m.pair_solimp, - m.pair_margin, - m.pair_gap, - m.pair_friction, - m.plugin, - m.plugin_attr, - m.geom_plugin_index, - d.geom_xpos, - d.geom_xmat, - d.naconmax, - d.ncollision, - ctx.collision_pair, - ctx.collision_pairid, - ctx.collision_worldid, - m.opt.sdf_initpoints, - m.opt.sdf_iterations, - ], - outputs=[ - d.contact.dist, - d.contact.pos, - d.contact.frame, - d.contact.includemargin, - d.contact.friction, - d.contact.solref, - d.contact.solreffriction, - d.contact.solimp, - d.contact.dim, - d.contact.geom, - d.contact.worldid, - d.contact.type, - d.contact.geomcollisionid, - d.nacon, - ], + _sdf_narrowphase, + dim=(m.opt.sdf_initpoints, d.naconmax), + inputs=[ + m.nmeshface, + m.oct_child, + m.oct_aabb, + m.oct_coeff, + m.geom_type, + m.geom_condim, + m.geom_dataid, + m.geom_priority, + m.geom_solmix, + m.geom_solref, + m.geom_solimp, + m.geom_size, + m.geom_aabb, + m.geom_friction, + m.geom_margin, + m.geom_gap, + m.mesh_vertadr, + m.mesh_vertnum, + m.mesh_faceadr, + m.mesh_octadr, + m.mesh_graphadr, + m.mesh_vert, + m.mesh_face, + m.mesh_graph, + m.mesh_polynum, + m.mesh_polyadr, + m.mesh_polynormal, + m.mesh_polyvertadr, + m.mesh_polyvertnum, + m.mesh_polyvert, + m.mesh_polymapadr, + m.mesh_polymapnum, + m.mesh_polymap, + m.pair_dim, + m.pair_solref, + m.pair_solreffriction, + m.pair_solimp, + m.pair_margin, + m.pair_gap, + m.pair_friction, + m.plugin, + m.plugin_attr, + m.geom_plugin_index, + d.geom_xpos, + d.geom_xmat, + d.naconmax, + d.ncollision, + ctx.collision_pair, + ctx.collision_pairid, + ctx.collision_worldid, + m.opt.sdf_initpoints, + m.opt.sdf_iterations, + ], + outputs=[ + d.contact.dist, + d.contact.pos, + d.contact.frame, + d.contact.includemargin, + d.contact.friction, + d.contact.solref, + d.contact.solreffriction, + d.contact.solimp, + d.contact.dim, + d.contact.geom, + d.contact.efc_address, + d.contact.worldid, + d.contact.type, + d.contact.geomcollisionid, + d.nacon, + ], ) diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/constraint.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/constraint.py index 228006e834..eec47583ad 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/constraint.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/constraint.py @@ -13,18 +13,18 @@ # limitations under the License. # ============================================================================== +import warp as wp + from mujoco.mjx.third_party.mujoco_warp._src import math from mujoco.mjx.third_party.mujoco_warp._src import support from mujoco.mjx.third_party.mujoco_warp._src import types from mujoco.mjx.third_party.mujoco_warp._src.types import ConstraintType from mujoco.mjx.third_party.mujoco_warp._src.types import ContactType from mujoco.mjx.third_party.mujoco_warp._src.types import DisableBit -from mujoco.mjx.third_party.mujoco_warp._src.types import SPARSE_CONSTRAINT_JACOBIAN -from mujoco.mjx.third_party.mujoco_warp._src.types import vec11 from mujoco.mjx.third_party.mujoco_warp._src.types import vec5 +from mujoco.mjx.third_party.mujoco_warp._src.types import vec11 from mujoco.mjx.third_party.mujoco_warp._src.warp_util import cache_kernel from mujoco.mjx.third_party.mujoco_warp._src.warp_util import event_scope -import warp as wp wp.set_module_options({"enable_backward": False}) @@ -36,6 +36,8 @@ def _zero_constraint_counts( nf_out: wp.array(dtype=int), nl_out: wp.array(dtype=int), nefc_out: wp.array(dtype=int), + # Out: + efc_nnz_out: wp.array(dtype=int), ): worldid = wp.tid() @@ -44,35 +46,36 @@ def _zero_constraint_counts( nf_out[worldid] = 0 nl_out[worldid] = 0 nefc_out[worldid] = 0 + efc_nnz_out[worldid] = 0 @wp.func def _efc_row( - # Model: - opt_disableflags: int, - # In: - worldid: int, - timestep: float, - efcid: int, - pos_aref: float, - pos_imp: float, - invweight: float, - solref: wp.vec2, - solimp: vec5, - margin: float, - vel: float, - frictionloss: float, - type: int, - id: int, - # Out: - type_out: wp.array2d(dtype=int), - id_out: wp.array2d(dtype=int), - pos_out: wp.array2d(dtype=float), - margin_out: wp.array2d(dtype=float), - D_out: wp.array2d(dtype=float), - vel_out: wp.array2d(dtype=float), - aref_out: wp.array2d(dtype=float), - frictionloss_out: wp.array2d(dtype=float), + # Model: + opt_disableflags: int, + # In: + worldid: int, + timestep: float, + efcid: int, + pos_aref: float, + pos_imp: float, + invweight: float, + solref: wp.vec2, + solimp: vec5, + margin: float, + vel: float, + frictionloss: float, + type: int, + id: int, + # Out: + type_out: wp.array2d(dtype=int), + id_out: wp.array2d(dtype=int), + pos_out: wp.array2d(dtype=float), + margin_out: wp.array2d(dtype=float), + D_out: wp.array2d(dtype=float), + vel_out: wp.array2d(dtype=float), + aref_out: wp.array2d(dtype=float), + frictionloss_out: wp.array2d(dtype=float), ): # calculate kbi timeconst = solref[0] @@ -108,9 +111,7 @@ def _efc_row( imp = wp.where(imp_x > 1.0, dmax, imp) # set outputs - D_out[worldid, efcid] = 1.0 / wp.max( - invweight * (1.0 - imp) / imp, types.MJ_MINVAL - ) + D_out[worldid, efcid] = 1.0 / wp.max(invweight * (1.0 - imp) / imp, types.MJ_MINVAL) vel_out[worldid, efcid] = vel aref_out[worldid, efcid] = -k * imp * pos_aref - b * vel pos_out[worldid, efcid] = pos_aref + margin @@ -122,52 +123,55 @@ def _efc_row( @wp.kernel def _equality_connect( - # Model: - nv: int, - nsite: int, - opt_timestep: wp.array(dtype=float), - opt_disableflags: int, - body_parentid: wp.array(dtype=int), - body_rootid: wp.array(dtype=int), - body_weldid: wp.array(dtype=int), - body_dofnum: wp.array(dtype=int), - body_dofadr: wp.array(dtype=int), - body_invweight0: wp.array2d(dtype=wp.vec2), - dof_bodyid: wp.array(dtype=int), - dof_parentid: wp.array(dtype=int), - site_bodyid: wp.array(dtype=int), - eq_obj1id: wp.array(dtype=int), - eq_obj2id: wp.array(dtype=int), - eq_objtype: wp.array(dtype=int), - eq_solref: wp.array2d(dtype=wp.vec2), - eq_solimp: wp.array2d(dtype=vec5), - eq_data: wp.array2d(dtype=vec11), - is_sparse: bool, - eq_connect_adr: wp.array(dtype=int), - # Data in: - qvel_in: wp.array2d(dtype=float), - eq_active_in: wp.array2d(dtype=bool), - xpos_in: wp.array2d(dtype=wp.vec3), - xmat_in: wp.array2d(dtype=wp.mat33), - site_xpos_in: wp.array2d(dtype=wp.vec3), - subtree_com_in: wp.array2d(dtype=wp.vec3), - cdof_in: wp.array2d(dtype=wp.spatial_vector), - njmax_in: int, - # Data out: - ne_out: wp.array(dtype=int), - nefc_out: wp.array(dtype=int), - efc_type_out: wp.array2d(dtype=int), - efc_id_out: wp.array2d(dtype=int), - efc_J_rownnz_out: wp.array2d(dtype=int), - efc_J_rowadr_out: wp.array2d(dtype=int), - efc_J_colind_out: wp.array3d(dtype=int), - efc_J_out: wp.array3d(dtype=float), - efc_pos_out: wp.array2d(dtype=float), - efc_margin_out: wp.array2d(dtype=float), - efc_D_out: wp.array2d(dtype=float), - efc_vel_out: wp.array2d(dtype=float), - efc_aref_out: wp.array2d(dtype=float), - efc_frictionloss_out: wp.array2d(dtype=float), + # Model: + nv: int, + nsite: int, + opt_timestep: wp.array(dtype=float), + opt_disableflags: int, + body_parentid: wp.array(dtype=int), + body_rootid: wp.array(dtype=int), + body_weldid: wp.array(dtype=int), + body_dofnum: wp.array(dtype=int), + body_dofadr: wp.array(dtype=int), + body_invweight0: wp.array2d(dtype=wp.vec2), + dof_bodyid: wp.array(dtype=int), + dof_parentid: wp.array(dtype=int), + site_bodyid: wp.array(dtype=int), + eq_obj1id: wp.array(dtype=int), + eq_obj2id: wp.array(dtype=int), + eq_objtype: wp.array(dtype=int), + eq_solref: wp.array2d(dtype=wp.vec2), + eq_solimp: wp.array2d(dtype=vec5), + eq_data: wp.array2d(dtype=vec11), + is_sparse: bool, + eq_connect_adr: wp.array(dtype=int), + # Data in: + qvel_in: wp.array2d(dtype=float), + eq_active_in: wp.array2d(dtype=bool), + xpos_in: wp.array2d(dtype=wp.vec3), + xmat_in: wp.array2d(dtype=wp.mat33), + site_xpos_in: wp.array2d(dtype=wp.vec3), + subtree_com_in: wp.array2d(dtype=wp.vec3), + cdof_in: wp.array2d(dtype=wp.spatial_vector), + njmax_in: int, + njmax_nnz_in: int, + # Data out: + ne_out: wp.array(dtype=int), + nefc_out: wp.array(dtype=int), + efc_type_out: wp.array2d(dtype=int), + efc_id_out: wp.array2d(dtype=int), + efc_J_rownnz_out: wp.array2d(dtype=int), + efc_J_rowadr_out: wp.array2d(dtype=int), + efc_J_colind_out: wp.array3d(dtype=int), + efc_J_out: wp.array3d(dtype=float), + efc_pos_out: wp.array2d(dtype=float), + efc_margin_out: wp.array2d(dtype=float), + efc_D_out: wp.array2d(dtype=float), + efc_vel_out: wp.array2d(dtype=float), + efc_aref_out: wp.array2d(dtype=float), + efc_frictionloss_out: wp.array2d(dtype=float), + # Out: + efc_nnz_out: wp.array(dtype=int), ): """Calculates constraint rows for connect equality constraints.""" worldid, eqconnectid = wp.tid() @@ -182,6 +186,10 @@ def _equality_connect( if efcid >= njmax_in - 3: return + efcid0 = efcid + 0 + efcid1 = efcid + 1 + efcid2 = efcid + 2 + data = eq_data[worldid % eq_data.shape[0], eqid] anchor1 = wp.vec3f(data[0], data[1], data[2]) anchor2 = wp.vec3f(data[3], data[4], data[5]) @@ -207,26 +215,39 @@ def _equality_connect( Jqvel = wp.vec3f(0.0, 0.0, 0.0) if is_sparse: + # TODO(team): pre-compute number of non-zeros body1 = body_weldid[body1] body2 = body_weldid[body2] da1 = int(body_dofadr[body1] + body_dofnum[body1] - 1) da2 = int(body_dofadr[body2] + body_dofnum[body2] - 1) - efcid0 = efcid + 0 - efcid1 = efcid + 1 - efcid2 = efcid + 2 - - rowadr0 = efcid0 * nv - rowadr1 = efcid1 * nv - rowadr2 = efcid2 * nv + # count non-zeros + pda1 = da1 + pda2 = da2 + rownnz = int(0) + while pda1 >= 0 or pda2 >= 0: + da = wp.max(pda1, pda2) + if pda1 == da: + pda1 = dof_parentid[pda1] + if pda2 == da: + pda2 = dof_parentid[pda2] + rownnz += 1 - efc_J_rowadr_out[worldid, efcid0] = rowadr0 - efc_J_rowadr_out[worldid, efcid1] = rowadr1 - efc_J_rowadr_out[worldid, efcid2] = rowadr2 + # get rowadr + rowadr = wp.atomic_add(efc_nnz_out, worldid, 3 * rownnz) + if rowadr + 3 * rownnz > njmax_nnz_in: + return + efc_J_rowadr_out[worldid, efcid0] = rowadr + efc_J_rowadr_out[worldid, efcid1] = rowadr + rownnz + efc_J_rowadr_out[worldid, efcid2] = rowadr + 2 * rownnz - rownnz = int(0) + efc_J_rownnz_out[worldid, efcid0] = rownnz + efc_J_rownnz_out[worldid, efcid1] = rownnz + efc_J_rownnz_out[worldid, efcid2] = rownnz + # compute J and colind + nnz = int(0) while da1 >= 0 or da2 >= 0: da = wp.max(da1, da2) if da1 == da: @@ -235,32 +256,32 @@ def _equality_connect( da2 = dof_parentid[da2] jacp1, _ = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - pos1, - body1, - da, - worldid, + body_parentid, + body_rootid, + dof_bodyid, + subtree_com_in, + cdof_in, + pos1, + body1, + da, + worldid, ) jacp2, _ = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - pos2, - body2, - da, - worldid, + body_parentid, + body_rootid, + dof_bodyid, + subtree_com_in, + cdof_in, + pos2, + body2, + da, + worldid, ) j1mj2 = jacp1 - jacp2 - sparseid0 = rowadr0 + rownnz - sparseid1 = rowadr1 + rownnz - sparseid2 = rowadr2 + rownnz + sparseid0 = rowadr + nnz + sparseid1 = rowadr + rownnz + nnz + sparseid2 = rowadr + 2 * rownnz + nnz efc_J_colind_out[worldid, 0, sparseid0] = da efc_J_colind_out[worldid, 0, sparseid1] = da @@ -272,49 +293,42 @@ def _equality_connect( Jqvel += j1mj2 * qvel_in[worldid, da] - rownnz += 1 - - efc_J_rownnz_out[worldid, efcid0] = rownnz - efc_J_rownnz_out[worldid, efcid1] = rownnz - efc_J_rownnz_out[worldid, efcid2] = rownnz + nnz += 1 else: # TODO(team): dof tree traversal for dofid in range(nv): jacp1, _ = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - pos1, - body1, - dofid, - worldid, + body_parentid, + body_rootid, + dof_bodyid, + subtree_com_in, + cdof_in, + pos1, + body1, + dofid, + worldid, ) jacp2, _ = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - pos2, - body2, - dofid, - worldid, + body_parentid, + body_rootid, + dof_bodyid, + subtree_com_in, + cdof_in, + pos2, + body2, + dofid, + worldid, ) j1mj2 = jacp1 - jacp2 - efc_J_out[worldid, efcid + 0, dofid] = j1mj2[0] - efc_J_out[worldid, efcid + 1, dofid] = j1mj2[1] - efc_J_out[worldid, efcid + 2, dofid] = j1mj2[2] + efc_J_out[worldid, efcid0, dofid] = j1mj2[0] + efc_J_out[worldid, efcid1, dofid] = j1mj2[1] + efc_J_out[worldid, efcid2, dofid] = j1mj2[2] Jqvel += j1mj2 * qvel_in[worldid, dofid] body_invweight0_id = worldid % body_invweight0.shape[0] - invweight = ( - body_invweight0[body_invweight0_id, body1][0] - + body_invweight0[body_invweight0_id, body2][0] - ) + invweight = body_invweight0[body_invweight0_id, body1][0] + body_invweight0[body_invweight0_id, body2][0] pos_imp = wp.length(pos) solref = eq_solref[worldid % eq_solref.shape[0], eqid] @@ -325,68 +339,71 @@ def _equality_connect( efcidi = efcid + i _efc_row( - opt_disableflags, - worldid, - timestep, - efcidi, - pos[i], - pos_imp, - invweight, - solref, - solimp, - 0.0, - Jqvel[i], - 0.0, - ConstraintType.EQUALITY, - eqid, - efc_type_out, - efc_id_out, - efc_pos_out, - efc_margin_out, - efc_D_out, - efc_vel_out, - efc_aref_out, - efc_frictionloss_out, + opt_disableflags, + worldid, + timestep, + efcidi, + pos[i], + pos_imp, + invweight, + solref, + solimp, + 0.0, + Jqvel[i], + 0.0, + ConstraintType.EQUALITY, + eqid, + efc_type_out, + efc_id_out, + efc_pos_out, + efc_margin_out, + efc_D_out, + efc_vel_out, + efc_aref_out, + efc_frictionloss_out, ) @wp.kernel def _equality_joint( - # Model: - nv: int, - opt_timestep: wp.array(dtype=float), - opt_disableflags: int, - qpos0: wp.array2d(dtype=float), - jnt_qposadr: wp.array(dtype=int), - jnt_dofadr: wp.array(dtype=int), - dof_invweight0: wp.array2d(dtype=float), - eq_obj1id: wp.array(dtype=int), - eq_obj2id: wp.array(dtype=int), - eq_solref: wp.array2d(dtype=wp.vec2), - eq_solimp: wp.array2d(dtype=vec5), - eq_data: wp.array2d(dtype=vec11), - is_sparse: bool, - eq_jnt_adr: wp.array(dtype=int), - # Data in: - qpos_in: wp.array2d(dtype=float), - qvel_in: wp.array2d(dtype=float), - eq_active_in: wp.array2d(dtype=bool), - njmax_in: int, - # Data out: - ne_out: wp.array(dtype=int), - nefc_out: wp.array(dtype=int), - efc_type_out: wp.array2d(dtype=int), - efc_id_out: wp.array2d(dtype=int), - efc_J_rownnz_out: wp.array2d(dtype=int), - efc_J_rowadr_out: wp.array2d(dtype=int), - efc_J_colind_out: wp.array3d(dtype=int), - efc_J_out: wp.array3d(dtype=float), - efc_pos_out: wp.array2d(dtype=float), - efc_margin_out: wp.array2d(dtype=float), - efc_D_out: wp.array2d(dtype=float), - efc_vel_out: wp.array2d(dtype=float), - efc_aref_out: wp.array2d(dtype=float), - efc_frictionloss_out: wp.array2d(dtype=float), + # Model: + nv: int, + opt_timestep: wp.array(dtype=float), + opt_disableflags: int, + qpos0: wp.array2d(dtype=float), + jnt_qposadr: wp.array(dtype=int), + jnt_dofadr: wp.array(dtype=int), + dof_invweight0: wp.array2d(dtype=float), + eq_obj1id: wp.array(dtype=int), + eq_obj2id: wp.array(dtype=int), + eq_solref: wp.array2d(dtype=wp.vec2), + eq_solimp: wp.array2d(dtype=vec5), + eq_data: wp.array2d(dtype=vec11), + is_sparse: bool, + eq_jnt_adr: wp.array(dtype=int), + # Data in: + qpos_in: wp.array2d(dtype=float), + qvel_in: wp.array2d(dtype=float), + eq_active_in: wp.array2d(dtype=bool), + njmax_in: int, + njmax_nnz_in: int, + # Data out: + ne_out: wp.array(dtype=int), + nefc_out: wp.array(dtype=int), + efc_type_out: wp.array2d(dtype=int), + efc_id_out: wp.array2d(dtype=int), + efc_J_rownnz_out: wp.array2d(dtype=int), + efc_J_rowadr_out: wp.array2d(dtype=int), + efc_J_colind_out: wp.array3d(dtype=int), + efc_J_out: wp.array3d(dtype=float), + efc_pos_out: wp.array2d(dtype=float), + efc_margin_out: wp.array2d(dtype=float), + efc_D_out: wp.array2d(dtype=float), + efc_vel_out: wp.array2d(dtype=float), + efc_aref_out: wp.array2d(dtype=float), + efc_frictionloss_out: wp.array2d(dtype=float), + # Out: + efc_nnz_out: wp.array(dtype=int), ): worldid, eqjntid = wp.tid() eqid = eq_jnt_adr[eqjntid] @@ -414,7 +431,9 @@ def _equality_joint( else: rownnz = 1 efc_J_rownnz_out[worldid, efcid] = rownnz - rowadr = efcid * nv + rowadr = wp.atomic_add(efc_nnz_out, worldid, rownnz) + if rowadr + rownnz > njmax_nnz_in: + return efc_J_rowadr_out[worldid, efcid] = rowadr efc_J_colind_out[worldid, 0, rowadr] = dofadr1 efc_J_out[worldid, 0, rowadr] = 1.0 @@ -430,19 +449,12 @@ def _equality_joint( dif = qpos_in[worldid, qposadr2] - qpos0[qpos0_id, qposadr2] # Horner's method for polynomials - rhs = data[0] + dif * ( - data[1] + dif * (data[2] + dif * (data[3] + dif * data[4])) - ) - deriv_2 = data[1] + dif * ( - 2.0 * data[2] + dif * (3.0 * data[3] + dif * 4.0 * data[4]) - ) + rhs = data[0] + dif * (data[1] + dif * (data[2] + dif * (data[3] + dif * data[4]))) + deriv_2 = data[1] + dif * (2.0 * data[2] + dif * (3.0 * data[3] + dif * 4.0 * data[4])) pos = qpos_in[worldid, qposadr1] - qpos0[qpos0_id, qposadr1] - rhs Jqvel = qvel_in[worldid, dofadr1] - qvel_in[worldid, dofadr2] * deriv_2 - invweight = ( - dof_invweight0[dof_invweight0_id, dofadr1] - + dof_invweight0[dof_invweight0_id, dofadr2] - ) + invweight = dof_invweight0[dof_invweight0_id, dofadr1] + dof_invweight0[dof_invweight0_id, dofadr2] if is_sparse: sparseid = rowadr + 1 @@ -458,67 +470,73 @@ def _equality_joint( # Update constraint parameters _efc_row( - opt_disableflags, - worldid, - opt_timestep[worldid % opt_timestep.shape[0]], - efcid, - pos, - pos, - invweight, - eq_solref[worldid % eq_solref.shape[0], eqid], - eq_solimp[worldid % eq_solimp.shape[0], eqid], - 0.0, - Jqvel, - 0.0, - ConstraintType.EQUALITY, - eqid, - efc_type_out, - efc_id_out, - efc_pos_out, - efc_margin_out, - efc_D_out, - efc_vel_out, - efc_aref_out, - efc_frictionloss_out, + opt_disableflags, + worldid, + opt_timestep[worldid % opt_timestep.shape[0]], + efcid, + pos, + pos, + invweight, + eq_solref[worldid % eq_solref.shape[0], eqid], + eq_solimp[worldid % eq_solimp.shape[0], eqid], + 0.0, + Jqvel, + 0.0, + ConstraintType.EQUALITY, + eqid, + efc_type_out, + efc_id_out, + efc_pos_out, + efc_margin_out, + efc_D_out, + efc_vel_out, + efc_aref_out, + efc_frictionloss_out, ) @wp.kernel def _equality_tendon( - # Model: - nv: int, - opt_timestep: wp.array(dtype=float), - opt_disableflags: int, - eq_obj1id: wp.array(dtype=int), - eq_obj2id: wp.array(dtype=int), - eq_solref: wp.array2d(dtype=wp.vec2), - eq_solimp: wp.array2d(dtype=vec5), - eq_data: wp.array2d(dtype=vec11), - tendon_length0: wp.array2d(dtype=float), - tendon_invweight0: wp.array2d(dtype=float), - is_sparse: bool, - eq_ten_adr: wp.array(dtype=int), - # Data in: - qvel_in: wp.array2d(dtype=float), - eq_active_in: wp.array2d(dtype=bool), - ten_J_in: wp.array3d(dtype=float), - ten_length_in: wp.array2d(dtype=float), - njmax_in: int, - # Data out: - ne_out: wp.array(dtype=int), - nefc_out: wp.array(dtype=int), - efc_type_out: wp.array2d(dtype=int), - efc_id_out: wp.array2d(dtype=int), - efc_J_rownnz_out: wp.array2d(dtype=int), - efc_J_rowadr_out: wp.array2d(dtype=int), - efc_J_colind_out: wp.array3d(dtype=int), - efc_J_out: wp.array3d(dtype=float), - efc_pos_out: wp.array2d(dtype=float), - efc_margin_out: wp.array2d(dtype=float), - efc_D_out: wp.array2d(dtype=float), - efc_vel_out: wp.array2d(dtype=float), - efc_aref_out: wp.array2d(dtype=float), - efc_frictionloss_out: wp.array2d(dtype=float), + # Model: + nv: int, + opt_timestep: wp.array(dtype=float), + opt_disableflags: int, + eq_obj1id: wp.array(dtype=int), + eq_obj2id: wp.array(dtype=int), + eq_solref: wp.array2d(dtype=wp.vec2), + eq_solimp: wp.array2d(dtype=vec5), + eq_data: wp.array2d(dtype=vec11), + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), + tendon_length0: wp.array2d(dtype=float), + tendon_invweight0: wp.array2d(dtype=float), + is_sparse: bool, + eq_ten_adr: wp.array(dtype=int), + # Data in: + qvel_in: wp.array2d(dtype=float), + eq_active_in: wp.array2d(dtype=bool), + ten_J_in: wp.array2d(dtype=float), + ten_length_in: wp.array2d(dtype=float), + njmax_in: int, + njmax_nnz_in: int, + # Data out: + ne_out: wp.array(dtype=int), + nefc_out: wp.array(dtype=int), + efc_type_out: wp.array2d(dtype=int), + efc_id_out: wp.array2d(dtype=int), + efc_J_rownnz_out: wp.array2d(dtype=int), + efc_J_rowadr_out: wp.array2d(dtype=int), + efc_J_colind_out: wp.array3d(dtype=int), + efc_J_out: wp.array3d(dtype=float), + efc_pos_out: wp.array2d(dtype=float), + efc_margin_out: wp.array2d(dtype=float), + efc_D_out: wp.array2d(dtype=float), + efc_vel_out: wp.array2d(dtype=float), + efc_aref_out: wp.array2d(dtype=float), + efc_frictionloss_out: wp.array2d(dtype=float), + # Out: + efc_nnz_out: wp.array(dtype=int), ): worldid, eqtenid = wp.tid() eqid = eq_ten_adr[eqtenid] @@ -540,89 +558,118 @@ def _equality_tendon( solimp = eq_solimp[worldid % eq_solimp.shape[0], eqid] tendon_length0_id = worldid % tendon_length0.shape[0] tendon_invweight0_id = worldid % tendon_invweight0.shape[0] - pos1 = ( - ten_length_in[worldid, obj1id] - tendon_length0[tendon_length0_id, obj1id] - ) - jac1 = ten_J_in[worldid, obj1id] + pos1 = ten_length_in[worldid, obj1id] - tendon_length0[tendon_length0_id, obj1id] if obj2id > -1: - invweight = ( - tendon_invweight0[tendon_invweight0_id, obj1id] - + tendon_invweight0[tendon_invweight0_id, obj2id] - ) + invweight = tendon_invweight0[tendon_invweight0_id, obj1id] + tendon_invweight0[tendon_invweight0_id, obj2id] - pos2 = ( - ten_length_in[worldid, obj2id] - - tendon_length0[tendon_length0_id, obj2id] - ) - jac2 = ten_J_in[worldid, obj2id] + pos2 = ten_length_in[worldid, obj2id] - tendon_length0[tendon_length0_id, obj2id] dif = pos2 dif2 = dif * dif dif3 = dif2 * dif dif4 = dif3 * dif - pos = pos1 - ( - data[0] - + data[1] * dif - + data[2] * dif2 - + data[3] * dif3 - + data[4] * dif4 - ) - deriv = ( - data[1] - + 2.0 * data[2] * dif - + 3.0 * data[3] * dif2 - + 4.0 * data[4] * dif3 - ) + pos = pos1 - (data[0] + data[1] * dif + data[2] * dif2 + data[3] * dif3 + data[4] * dif4) + deriv = data[1] + 2.0 * data[2] * dif + 3.0 * data[3] * dif2 + 4.0 * data[4] * dif3 else: invweight = tendon_invweight0[tendon_invweight0_id, obj1id] pos = pos1 - data[0] deriv = 0.0 - Jqvel = float(0.0) + rownnz1 = ten_J_rownnz[obj1id] + rowadr1 = ten_J_rowadr[obj1id] + rownnz2 = 0 + rowadr2 = 0 + + if deriv != 0.0: + rownnz2 = ten_J_rownnz[obj2id] + rowadr2 = ten_J_rowadr[obj2id] - # TODO(team): sparse tendon jacobian if is_sparse: - rowadr = efcid * nv - efc_J_rownnz_out[worldid, efcid] = nv + # TODO(team): pre-compute rownnz + # count unique dofs + p1, p2 = int(0), int(0) + rownnz = int(0) + while p1 < rownnz1 or p2 < rownnz2: + col1 = nv + col2 = nv + if p1 < rownnz1: + col1 = ten_J_colind[rowadr1 + p1] + if p2 < rownnz2: + col2 = ten_J_colind[rowadr2 + p2] + if col1 <= col2: + p1 += 1 + if col2 <= col1: + p2 += 1 + rownnz += 1 + + rowadr = wp.atomic_add(efc_nnz_out, worldid, rownnz) + if rowadr + rownnz > njmax_nnz_in: + return efc_J_rowadr_out[worldid, efcid] = rowadr + ptr1 = int(0) + ptr2 = int(0) + + Jqvel = float(0.0) + + nnz = int(0) for i in range(nv): + J1 = float(0.0) + if ptr1 < rownnz1: + sparseid1 = rowadr1 + ptr1 + if ten_J_colind[sparseid1] == i: + J1 = ten_J_in[worldid, sparseid1] + ptr1 += 1 + + J = J1 if deriv != 0.0: - J = jac1[i] + jac2[i] * -deriv - else: - J = jac1[i] + J2 = float(0.0) + if ptr2 < rownnz2: + sparseid2 = rowadr2 + ptr2 + if ten_J_colind[sparseid2] == i: + J2 = ten_J_in[worldid, sparseid2] + ptr2 += 1 + J += J2 * -deriv + if is_sparse: - efc_J_colind_out[worldid, 0, rowadr + i] = i - efc_J_out[worldid, 0, rowadr + i] = J + if J != 0.0: + sparseid = rowadr + nnz + efc_J_colind_out[worldid, 0, sparseid] = i + efc_J_out[worldid, 0, sparseid] = J + nnz += 1 else: efc_J_out[worldid, efcid, i] = J + Jqvel += J * qvel_in[worldid, i] + if is_sparse: + efc_J_rownnz_out[worldid, efcid] = nnz + _efc_row( - opt_disableflags, - worldid, - opt_timestep[worldid % opt_timestep.shape[0]], - efcid, - pos, - pos, - invweight, - solref, - solimp, - 0.0, - Jqvel, - 0.0, - ConstraintType.EQUALITY, - eqid, - efc_type_out, - efc_id_out, - efc_pos_out, - efc_margin_out, - efc_D_out, - efc_vel_out, - efc_aref_out, - efc_frictionloss_out, + opt_disableflags, + worldid, + opt_timestep[worldid % opt_timestep.shape[0]], + efcid, + pos, + pos, + invweight, + solref, + solimp, + 0.0, + Jqvel, + 0.0, + ConstraintType.EQUALITY, + eqid, + efc_type_out, + efc_id_out, + efc_pos_out, + efc_margin_out, + efc_D_out, + efc_vel_out, + efc_aref_out, + efc_frictionloss_out, ) @@ -630,41 +677,50 @@ def _equality_tendon( def _equality_flex(is_sparse: bool): @wp.kernel(module="unique", enable_backward=False) def kernel( - # Model: - nv: int, - opt_timestep: wp.array(dtype=float), - opt_disableflags: int, - flexedge_length0: wp.array(dtype=float), - flexedge_invweight0: wp.array(dtype=float), - flexedge_J_rownnz: wp.array(dtype=int), - flexedge_J_rowadr: wp.array(dtype=int), - flexedge_J_colind: wp.array(dtype=int), - eq_solref: wp.array2d(dtype=wp.vec2), - eq_solimp: wp.array2d(dtype=vec5), - eq_flex_adr: wp.array(dtype=int), - # Data in: - qvel_in: wp.array2d(dtype=float), - flexedge_J_in: wp.array2d(dtype=float), - flexedge_length_in: wp.array2d(dtype=float), - njmax_in: int, - # Data out: - ne_out: wp.array(dtype=int), - nefc_out: wp.array(dtype=int), - efc_type_out: wp.array2d(dtype=int), - efc_id_out: wp.array2d(dtype=int), - efc_J_rownnz_out: wp.array2d(dtype=int), - efc_J_rowadr_out: wp.array2d(dtype=int), - efc_J_colind_out: wp.array3d(dtype=int), - efc_J_out: wp.array3d(dtype=float), - efc_pos_out: wp.array2d(dtype=float), - efc_margin_out: wp.array2d(dtype=float), - efc_D_out: wp.array2d(dtype=float), - efc_vel_out: wp.array2d(dtype=float), - efc_aref_out: wp.array2d(dtype=float), - efc_frictionloss_out: wp.array2d(dtype=float), + # Model: + nv: int, + opt_timestep: wp.array(dtype=float), + opt_disableflags: int, + flex_edgeadr: wp.array(dtype=int), + flex_edgenum: wp.array(dtype=int), + flexedge_length0: wp.array(dtype=float), + flexedge_invweight0: wp.array(dtype=float), + flexedge_J_rownnz: wp.array(dtype=int), + flexedge_J_rowadr: wp.array(dtype=int), + flexedge_J_colind: wp.array(dtype=int), + eq_obj1id: wp.array(dtype=int), + eq_solref: wp.array2d(dtype=wp.vec2), + eq_solimp: wp.array2d(dtype=vec5), + eq_flex_adr: wp.array(dtype=int), + # Data in: + qvel_in: wp.array2d(dtype=float), + flexedge_J_in: wp.array2d(dtype=float), + flexedge_length_in: wp.array2d(dtype=float), + njmax_in: int, + njmax_nnz_in: int, + # Data out: + ne_out: wp.array(dtype=int), + nefc_out: wp.array(dtype=int), + efc_type_out: wp.array2d(dtype=int), + efc_id_out: wp.array2d(dtype=int), + efc_J_rownnz_out: wp.array2d(dtype=int), + efc_J_rowadr_out: wp.array2d(dtype=int), + efc_J_colind_out: wp.array3d(dtype=int), + efc_J_out: wp.array3d(dtype=float), + efc_pos_out: wp.array2d(dtype=float), + efc_margin_out: wp.array2d(dtype=float), + efc_D_out: wp.array2d(dtype=float), + efc_vel_out: wp.array2d(dtype=float), + efc_aref_out: wp.array2d(dtype=float), + efc_frictionloss_out: wp.array2d(dtype=float), + # Out: + efc_nnz_out: wp.array(dtype=int), ): worldid, eqflexid, edgeid = wp.tid() eqid = eq_flex_adr[eqflexid] + flexid = eq_obj1id[eqid] + if edgeid < flex_edgeadr[flexid] or edgeid >= flex_edgeadr[flexid] + flex_edgenum[flexid]: + return wp.atomic_add(ne_out, worldid, 1) efcid = wp.atomic_add(nefc_out, worldid, 1) @@ -683,7 +739,9 @@ def kernel( if wp.static(is_sparse): efc_J_rownnz_out[worldid, efcid] = rownnz - efc_rowadr = efcid * nv + efc_rowadr = wp.atomic_add(efc_nnz_out, worldid, rownnz) + if efc_rowadr + rownnz > njmax_nnz_in: + return efc_J_rowadr_out[worldid, efcid] = efc_rowadr for i in range(rownnz): flex_sparseid = flex_rowadr + i @@ -704,83 +762,86 @@ def kernel( Jqvel += J * qvel_in[worldid, colind] _efc_row( - opt_disableflags, - worldid, - opt_timestep[worldid % opt_timestep.shape[0]], - efcid, - pos, - pos, - flexedge_invweight0[edgeid], - solref, - solimp, - 0.0, - Jqvel, - 0.0, - ConstraintType.EQUALITY, - eqid, - efc_type_out, - efc_id_out, - efc_pos_out, - efc_margin_out, - efc_D_out, - efc_vel_out, - efc_aref_out, - efc_frictionloss_out, - ) - - return kernel + opt_disableflags, + worldid, + opt_timestep[worldid % opt_timestep.shape[0]], + efcid, + pos, + pos, + flexedge_invweight0[edgeid], + solref, + solimp, + 0.0, + Jqvel, + 0.0, + ConstraintType.EQUALITY, + eqid, + efc_type_out, + efc_id_out, + efc_pos_out, + efc_margin_out, + efc_D_out, + efc_vel_out, + efc_aref_out, + efc_frictionloss_out, + ) + + return kernel @wp.kernel def _equality_weld( - # Model: - nv: int, - nsite: int, - opt_timestep: wp.array(dtype=float), - opt_disableflags: int, - body_parentid: wp.array(dtype=int), - body_rootid: wp.array(dtype=int), - body_weldid: wp.array(dtype=int), - body_dofnum: wp.array(dtype=int), - body_dofadr: wp.array(dtype=int), - body_invweight0: wp.array2d(dtype=wp.vec2), - dof_bodyid: wp.array(dtype=int), - dof_parentid: wp.array(dtype=int), - site_bodyid: wp.array(dtype=int), - site_quat: wp.array2d(dtype=wp.quat), - eq_obj1id: wp.array(dtype=int), - eq_obj2id: wp.array(dtype=int), - eq_objtype: wp.array(dtype=int), - eq_solref: wp.array2d(dtype=wp.vec2), - eq_solimp: wp.array2d(dtype=vec5), - eq_data: wp.array2d(dtype=vec11), - is_sparse: bool, - eq_wld_adr: wp.array(dtype=int), - # Data in: - qvel_in: wp.array2d(dtype=float), - eq_active_in: wp.array2d(dtype=bool), - xpos_in: wp.array2d(dtype=wp.vec3), - xquat_in: wp.array2d(dtype=wp.quat), - xmat_in: wp.array2d(dtype=wp.mat33), - site_xpos_in: wp.array2d(dtype=wp.vec3), - subtree_com_in: wp.array2d(dtype=wp.vec3), - cdof_in: wp.array2d(dtype=wp.spatial_vector), - njmax_in: int, - # Data out: - ne_out: wp.array(dtype=int), - nefc_out: wp.array(dtype=int), - efc_type_out: wp.array2d(dtype=int), - efc_id_out: wp.array2d(dtype=int), - efc_J_rownnz_out: wp.array2d(dtype=int), - efc_J_rowadr_out: wp.array2d(dtype=int), - efc_J_colind_out: wp.array3d(dtype=int), - efc_J_out: wp.array3d(dtype=float), - efc_pos_out: wp.array2d(dtype=float), - efc_margin_out: wp.array2d(dtype=float), - efc_D_out: wp.array2d(dtype=float), - efc_vel_out: wp.array2d(dtype=float), - efc_aref_out: wp.array2d(dtype=float), - efc_frictionloss_out: wp.array2d(dtype=float), + # Model: + nv: int, + nsite: int, + opt_timestep: wp.array(dtype=float), + opt_disableflags: int, + body_parentid: wp.array(dtype=int), + body_rootid: wp.array(dtype=int), + body_weldid: wp.array(dtype=int), + body_dofnum: wp.array(dtype=int), + body_dofadr: wp.array(dtype=int), + body_invweight0: wp.array2d(dtype=wp.vec2), + dof_bodyid: wp.array(dtype=int), + dof_parentid: wp.array(dtype=int), + site_bodyid: wp.array(dtype=int), + site_quat: wp.array2d(dtype=wp.quat), + eq_obj1id: wp.array(dtype=int), + eq_obj2id: wp.array(dtype=int), + eq_objtype: wp.array(dtype=int), + eq_solref: wp.array2d(dtype=wp.vec2), + eq_solimp: wp.array2d(dtype=vec5), + eq_data: wp.array2d(dtype=vec11), + is_sparse: bool, + eq_wld_adr: wp.array(dtype=int), + # Data in: + qvel_in: wp.array2d(dtype=float), + eq_active_in: wp.array2d(dtype=bool), + xpos_in: wp.array2d(dtype=wp.vec3), + xquat_in: wp.array2d(dtype=wp.quat), + xmat_in: wp.array2d(dtype=wp.mat33), + site_xpos_in: wp.array2d(dtype=wp.vec3), + subtree_com_in: wp.array2d(dtype=wp.vec3), + cdof_in: wp.array2d(dtype=wp.spatial_vector), + njmax_in: int, + njmax_nnz_in: int, + # Data out: + ne_out: wp.array(dtype=int), + nefc_out: wp.array(dtype=int), + efc_type_out: wp.array2d(dtype=int), + efc_id_out: wp.array2d(dtype=int), + efc_J_rownnz_out: wp.array2d(dtype=int), + efc_J_rowadr_out: wp.array2d(dtype=int), + efc_J_colind_out: wp.array3d(dtype=int), + efc_J_out: wp.array3d(dtype=float), + efc_pos_out: wp.array2d(dtype=float), + efc_margin_out: wp.array2d(dtype=float), + efc_D_out: wp.array2d(dtype=float), + efc_vel_out: wp.array2d(dtype=float), + efc_aref_out: wp.array2d(dtype=float), + efc_frictionloss_out: wp.array2d(dtype=float), + # Out: + efc_nnz_out: wp.array(dtype=int), ): worldid, eqweldid = wp.tid() eqid = eq_wld_adr[eqweldid] @@ -794,6 +855,13 @@ def _equality_weld( if efcid >= njmax_in - 6: return + efcid0 = efcid + 0 + efcid1 = efcid + 1 + efcid2 = efcid + 2 + efcid3 = efcid + 3 + efcid4 = efcid + 4 + efcid5 = efcid + 5 + is_site = eq_objtype[eqid] == types.ObjType.SITE and nsite > 0 obj1id = eq_obj1id[eqid] @@ -812,12 +880,8 @@ def _equality_weld( pos2 = site_xpos_in[worldid, obj2id] site_quat_id = worldid % site_quat.shape[0] - quat = math.mul_quat( - xquat_in[worldid, body1], site_quat[site_quat_id, obj1id] - ) - quat1 = math.quat_inv( - math.mul_quat(xquat_in[worldid, body2], site_quat[site_quat_id, obj2id]) - ) + quat = math.mul_quat(xquat_in[worldid, body1], site_quat[site_quat_id, obj1id]) + quat1 = math.quat_inv(math.mul_quat(xquat_in[worldid, body2], site_quat[site_quat_id, obj2id])) else: body1 = obj1id @@ -833,35 +897,45 @@ def _equality_weld( Jqvelr = wp.vec3f(0.0, 0.0, 0.0) if is_sparse: + # TODO(team): pre-compute number of non-zeros body1 = body_weldid[body1] body2 = body_weldid[body2] da1 = int(body_dofadr[body1] + body_dofnum[body1] - 1) da2 = int(body_dofadr[body2] + body_dofnum[body2] - 1) - efcid0 = efcid + 0 - efcid1 = efcid + 1 - efcid2 = efcid + 2 - efcid3 = efcid + 3 - efcid4 = efcid + 4 - efcid5 = efcid + 5 - - rowadr0 = efcid0 * nv - rowadr1 = efcid1 * nv - rowadr2 = efcid2 * nv - rowadr3 = efcid3 * nv - rowadr4 = efcid4 * nv - rowadr5 = efcid5 * nv - - efc_J_rowadr_out[worldid, efcid0] = rowadr0 - efc_J_rowadr_out[worldid, efcid1] = rowadr1 - efc_J_rowadr_out[worldid, efcid2] = rowadr2 - efc_J_rowadr_out[worldid, efcid3] = rowadr3 - efc_J_rowadr_out[worldid, efcid4] = rowadr4 - efc_J_rowadr_out[worldid, efcid5] = rowadr5 - + # count non-zeros + pda1 = da1 + pda2 = da2 rownnz = int(0) + while pda1 >= 0 or pda2 >= 0: + da = wp.max(pda1, pda2) + if pda1 == da: + pda1 = dof_parentid[da] + if pda2 == da: + pda2 = dof_parentid[da] + rownnz += 1 + + # get rowadr + rowadr = wp.atomic_add(efc_nnz_out, worldid, 6 * rownnz) + if rowadr + 6 * rownnz > njmax_nnz_in: + return + efc_J_rowadr_out[worldid, efcid0] = rowadr + efc_J_rowadr_out[worldid, efcid1] = rowadr + rownnz + efc_J_rowadr_out[worldid, efcid2] = rowadr + 2 * rownnz + efc_J_rowadr_out[worldid, efcid3] = rowadr + 3 * rownnz + efc_J_rowadr_out[worldid, efcid4] = rowadr + 4 * rownnz + efc_J_rowadr_out[worldid, efcid5] = rowadr + 5 * rownnz + + efc_J_rownnz_out[worldid, efcid0] = rownnz + efc_J_rownnz_out[worldid, efcid1] = rownnz + efc_J_rownnz_out[worldid, efcid2] = rownnz + efc_J_rownnz_out[worldid, efcid3] = rownnz + efc_J_rownnz_out[worldid, efcid4] = rownnz + efc_J_rownnz_out[worldid, efcid5] = rownnz + # compute J and colind + nnz = int(0) while da1 >= 0 or da2 >= 0: da = wp.max(da1, da2) if da1 == da: @@ -870,26 +944,26 @@ def _equality_weld( da2 = dof_parentid[da] jacp1, jacr1 = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - pos1, - body1, - da, - worldid, + body_parentid, + body_rootid, + dof_bodyid, + subtree_com_in, + cdof_in, + pos1, + body1, + da, + worldid, ) jacp2, jacr2 = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - pos2, - body2, - da, - worldid, + body_parentid, + body_rootid, + dof_bodyid, + subtree_com_in, + cdof_in, + pos2, + body2, + da, + worldid, ) jacdifp = jacp1 - jacp2 @@ -898,12 +972,12 @@ def _equality_weld( jacdifrq = math.mul_quat(math.quat_mul_axis(quat1, jacdifr), quat) jacdifr = 0.5 * wp.vec3(jacdifrq[1], jacdifrq[2], jacdifrq[3]) - sparseid0 = rowadr0 + rownnz - sparseid1 = rowadr1 + rownnz - sparseid2 = rowadr2 + rownnz - sparseid3 = rowadr3 + rownnz - sparseid4 = rowadr4 + rownnz - sparseid5 = rowadr5 + rownnz + sparseid0 = rowadr + nnz + sparseid1 = rowadr + rownnz + nnz + sparseid2 = rowadr + 2 * rownnz + nnz + sparseid3 = rowadr + 3 * rownnz + nnz + sparseid4 = rowadr + 4 * rownnz + nnz + sparseid5 = rowadr + 5 * rownnz + nnz efc_J_colind_out[worldid, 0, sparseid0] = da efc_J_colind_out[worldid, 0, sparseid1] = da @@ -922,50 +996,45 @@ def _equality_weld( Jqvelp += jacdifp * qvel_in[worldid, da] Jqvelr += jacdifr * qvel_in[worldid, da] - rownnz += 1 - - efc_J_rownnz_out[worldid, efcid0] = rownnz - efc_J_rownnz_out[worldid, efcid1] = rownnz - efc_J_rownnz_out[worldid, efcid2] = rownnz - efc_J_rownnz_out[worldid, efcid3] = rownnz - efc_J_rownnz_out[worldid, efcid4] = rownnz - efc_J_rownnz_out[worldid, efcid5] = rownnz + nnz += 1 else: for dofid in range(nv): jacp1, jacr1 = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - pos1, - body1, - dofid, - worldid, + body_parentid, + body_rootid, + dof_bodyid, + subtree_com_in, + cdof_in, + pos1, + body1, + dofid, + worldid, ) jacp2, jacr2 = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - pos2, - body2, - dofid, - worldid, + body_parentid, + body_rootid, + dof_bodyid, + subtree_com_in, + cdof_in, + pos2, + body2, + dofid, + worldid, ) jacdifp = jacp1 - jacp2 - for i in range(3): - efc_J_out[worldid, efcid + i, dofid] = jacdifp[i] + efc_J_out[worldid, efcid0, dofid] = jacdifp[0] + efc_J_out[worldid, efcid1, dofid] = jacdifp[1] + efc_J_out[worldid, efcid2, dofid] = jacdifp[2] jacdifr = (jacr1 - jacr2) * torquescale jacdifrq = math.mul_quat(math.quat_mul_axis(quat1, jacdifr), quat) jacdifr = 0.5 * wp.vec3(jacdifrq[1], jacdifrq[2], jacdifrq[3]) - for i in range(3): - efc_J_out[worldid, efcid + 3 + i, dofid] = jacdifr[i] + efc_J_out[worldid, efcid3, dofid] = jacdifr[0] + efc_J_out[worldid, efcid4, dofid] = jacdifr[1] + efc_J_out[worldid, efcid5, dofid] = jacdifr[2] Jqvelp += jacdifp * qvel_in[worldid, dofid] Jqvelr += jacdifr * qvel_in[worldid, dofid] @@ -977,10 +1046,7 @@ def _equality_weld( crot = wp.vec3(crotq[1], crotq[2], crotq[3]) * torquescale body_invweight0_id = worldid % body_invweight0.shape[0] - invweight_t = ( - body_invweight0[body_invweight0_id, body1][0] - + body_invweight0[body_invweight0_id, body2][0] - ) + invweight_t = body_invweight0[body_invweight0_id, body1][0] + body_invweight0[body_invweight0_id, body2][0] pos_imp = wp.sqrt(wp.length_sq(cpos) + wp.length_sq(crot)) @@ -991,91 +1057,91 @@ def _equality_weld( for i in range(3): _efc_row( - opt_disableflags, - worldid, - timestep, - efcid + i, - cpos[i], - pos_imp, - invweight_t, - solref, - solimp, - 0.0, - Jqvelp[i], - 0.0, - ConstraintType.EQUALITY, - eqid, - efc_type_out, - efc_id_out, - efc_pos_out, - efc_margin_out, - efc_D_out, - efc_vel_out, - efc_aref_out, - efc_frictionloss_out, + opt_disableflags, + worldid, + timestep, + efcid + i, + cpos[i], + pos_imp, + invweight_t, + solref, + solimp, + 0.0, + Jqvelp[i], + 0.0, + ConstraintType.EQUALITY, + eqid, + efc_type_out, + efc_id_out, + efc_pos_out, + efc_margin_out, + efc_D_out, + efc_vel_out, + efc_aref_out, + efc_frictionloss_out, ) - invweight_r = ( - body_invweight0[body_invweight0_id, body1][1] - + body_invweight0[body_invweight0_id, body2][1] - ) + invweight_r = body_invweight0[body_invweight0_id, body1][1] + body_invweight0[body_invweight0_id, body2][1] for i in range(3): _efc_row( - opt_disableflags, - worldid, - timestep, - efcid + 3 + i, - crot[i], - pos_imp, - invweight_r, - solref, - solimp, - 0.0, - Jqvelr[i], - 0.0, - ConstraintType.EQUALITY, - eqid, - efc_type_out, - efc_id_out, - efc_pos_out, - efc_margin_out, - efc_D_out, - efc_vel_out, - efc_aref_out, - efc_frictionloss_out, + opt_disableflags, + worldid, + timestep, + efcid + 3 + i, + crot[i], + pos_imp, + invweight_r, + solref, + solimp, + 0.0, + Jqvelr[i], + 0.0, + ConstraintType.EQUALITY, + eqid, + efc_type_out, + efc_id_out, + efc_pos_out, + efc_margin_out, + efc_D_out, + efc_vel_out, + efc_aref_out, + efc_frictionloss_out, ) @wp.kernel def _friction_dof( - # Model: - nv: int, - opt_timestep: wp.array(dtype=float), - opt_disableflags: int, - dof_solref: wp.array2d(dtype=wp.vec2), - dof_solimp: wp.array2d(dtype=vec5), - dof_frictionloss: wp.array2d(dtype=float), - dof_invweight0: wp.array2d(dtype=float), - is_sparse: bool, - # Data in: - qvel_in: wp.array2d(dtype=float), - njmax_in: int, - # Data out: - nf_out: wp.array(dtype=int), - nefc_out: wp.array(dtype=int), - efc_type_out: wp.array2d(dtype=int), - efc_id_out: wp.array2d(dtype=int), - efc_J_rownnz_out: wp.array2d(dtype=int), - efc_J_rowadr_out: wp.array2d(dtype=int), - efc_J_colind_out: wp.array3d(dtype=int), - efc_J_out: wp.array3d(dtype=float), - efc_pos_out: wp.array2d(dtype=float), - efc_margin_out: wp.array2d(dtype=float), - efc_D_out: wp.array2d(dtype=float), - efc_vel_out: wp.array2d(dtype=float), - efc_aref_out: wp.array2d(dtype=float), - efc_frictionloss_out: wp.array2d(dtype=float), + # Model: + nv: int, + opt_timestep: wp.array(dtype=float), + opt_disableflags: int, + dof_solref: wp.array2d(dtype=wp.vec2), + dof_solimp: wp.array2d(dtype=vec5), + dof_frictionloss: wp.array2d(dtype=float), + dof_invweight0: wp.array2d(dtype=float), + is_sparse: bool, + # Data in: + qvel_in: wp.array2d(dtype=float), + njmax_in: int, + njmax_nnz_in: int, + # Data out: + nf_out: wp.array(dtype=int), + nefc_out: wp.array(dtype=int), + efc_type_out: wp.array2d(dtype=int), + efc_id_out: wp.array2d(dtype=int), + efc_J_rownnz_out: wp.array2d(dtype=int), + efc_J_rowadr_out: wp.array2d(dtype=int), + efc_J_colind_out: wp.array3d(dtype=int), + efc_J_out: wp.array3d(dtype=float), + efc_pos_out: wp.array2d(dtype=float), + efc_margin_out: wp.array2d(dtype=float), + efc_D_out: wp.array2d(dtype=float), + efc_vel_out: wp.array2d(dtype=float), + efc_aref_out: wp.array2d(dtype=float), + efc_frictionloss_out: wp.array2d(dtype=float), + # Out: + efc_nnz_out: wp.array(dtype=int), ): worldid, dofid = wp.tid() @@ -1092,7 +1158,9 @@ def _friction_dof( if is_sparse: efc_J_rownnz_out[worldid, efcid] = 1 - rowadr = efcid * nv + rowadr = wp.atomic_add(efc_nnz_out, worldid, 1) + if rowadr + 1 > njmax_nnz_in: + return efc_J_rowadr_out[worldid, efcid] = rowadr efc_J_colind_out[worldid, 0, rowadr] = dofid efc_J_out[worldid, 0, rowadr] = 1.0 @@ -1107,61 +1175,67 @@ def _friction_dof( dof_solref_id = worldid % dof_solref.shape[0] dof_solimp_id = worldid % dof_solimp.shape[0] _efc_row( - opt_disableflags, - worldid, - opt_timestep[worldid % opt_timestep.shape[0]], - efcid, - 0.0, - 0.0, - dof_invweight0[dof_invweight0_id, dofid], - dof_solref[dof_solref_id, dofid], - dof_solimp[dof_solimp_id, dofid], - 0.0, - Jqvel, - dof_frictionloss[dof_frictionloss_id, dofid], - ConstraintType.FRICTION_DOF, - dofid, - efc_type_out, - efc_id_out, - efc_pos_out, - efc_margin_out, - efc_D_out, - efc_vel_out, - efc_aref_out, - efc_frictionloss_out, + opt_disableflags, + worldid, + opt_timestep[worldid % opt_timestep.shape[0]], + efcid, + 0.0, + 0.0, + dof_invweight0[dof_invweight0_id, dofid], + dof_solref[dof_solref_id, dofid], + dof_solimp[dof_solimp_id, dofid], + 0.0, + Jqvel, + dof_frictionloss[dof_frictionloss_id, dofid], + ConstraintType.FRICTION_DOF, + dofid, + efc_type_out, + efc_id_out, + efc_pos_out, + efc_margin_out, + efc_D_out, + efc_vel_out, + efc_aref_out, + efc_frictionloss_out, ) @wp.kernel def _friction_tendon( - # Model: - nv: int, - opt_timestep: wp.array(dtype=float), - opt_disableflags: int, - tendon_solref_fri: wp.array2d(dtype=wp.vec2), - tendon_solimp_fri: wp.array2d(dtype=vec5), - tendon_frictionloss: wp.array2d(dtype=float), - tendon_invweight0: wp.array2d(dtype=float), - is_sparse: bool, - # Data in: - qvel_in: wp.array2d(dtype=float), - ten_J_in: wp.array3d(dtype=float), - njmax_in: int, - # Data out: - nf_out: wp.array(dtype=int), - nefc_out: wp.array(dtype=int), - efc_type_out: wp.array2d(dtype=int), - efc_id_out: wp.array2d(dtype=int), - efc_J_rownnz_out: wp.array2d(dtype=int), - efc_J_rowadr_out: wp.array2d(dtype=int), - efc_J_colind_out: wp.array3d(dtype=int), - efc_J_out: wp.array3d(dtype=float), - efc_pos_out: wp.array2d(dtype=float), - efc_margin_out: wp.array2d(dtype=float), - efc_D_out: wp.array2d(dtype=float), - efc_vel_out: wp.array2d(dtype=float), - efc_aref_out: wp.array2d(dtype=float), - efc_frictionloss_out: wp.array2d(dtype=float), + # Model: + nv: int, + opt_timestep: wp.array(dtype=float), + opt_disableflags: int, + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), + tendon_solref_fri: wp.array2d(dtype=wp.vec2), + tendon_solimp_fri: wp.array2d(dtype=vec5), + tendon_frictionloss: wp.array2d(dtype=float), + tendon_invweight0: wp.array2d(dtype=float), + is_sparse: bool, + # Data in: + qvel_in: wp.array2d(dtype=float), + ten_J_in: wp.array2d(dtype=float), + njmax_in: int, + njmax_nnz_in: int, + # Data out: + nf_out: wp.array(dtype=int), + nefc_out: wp.array(dtype=int), + efc_type_out: wp.array2d(dtype=int), + efc_id_out: wp.array2d(dtype=int), + efc_J_rownnz_out: wp.array2d(dtype=int), + efc_J_rowadr_out: wp.array2d(dtype=int), + efc_J_colind_out: wp.array3d(dtype=int), + efc_J_out: wp.array3d(dtype=float), + efc_pos_out: wp.array2d(dtype=float), + efc_margin_out: wp.array2d(dtype=float), + efc_D_out: wp.array2d(dtype=float), + efc_vel_out: wp.array2d(dtype=float), + efc_aref_out: wp.array2d(dtype=float), + efc_frictionloss_out: wp.array2d(dtype=float), + # Out: + efc_nnz_out: wp.array(dtype=int), ): worldid, tenid = wp.tid() @@ -1179,86 +1253,103 @@ def _friction_tendon( Jqvel = float(0.0) - # TODO(team): sparse tendon jacobian + rownnz_tenJ = ten_J_rownnz[tenid] + rowadr_tenJ = ten_J_rowadr[tenid] if is_sparse: - rowadr = efcid * nv - efc_J_rownnz_out[worldid, efcid] = nv - efc_J_rowadr_out[worldid, efcid] = rowadr - - for i in range(nv): - # TODO(team): sparse ten_J - J = ten_J_in[worldid, tenid, i] - if is_sparse: - efc_J_colind_out[worldid, 0, rowadr + i] = i - efc_J_out[worldid, 0, rowadr + i] = J - else: - efc_J_out[worldid, efcid, i] = J - - Jqvel += J * qvel_in[worldid, i] + efc_J_rownnz_out[worldid, efcid] = rownnz_tenJ + rowadr_efc = wp.atomic_add(efc_nnz_out, worldid, rownnz_tenJ) + if rowadr_efc + rownnz_tenJ > njmax_nnz_in: + return + efc_J_rowadr_out[worldid, efcid] = rowadr_efc + + for i in range(rownnz_tenJ): + sparseid_ten = rowadr_tenJ + i + sparseid_efc = rowadr_efc + i + colind = ten_J_colind[sparseid_ten] + J = ten_J_in[worldid, sparseid_ten] + efc_J_colind_out[worldid, 0, sparseid_efc] = colind + efc_J_out[worldid, 0, sparseid_efc] = J + Jqvel += J * qvel_in[worldid, colind] + else: + nnz = int(0) + colind = ten_J_colind[rowadr_tenJ] + for i in range(nv): + if nnz < rownnz_tenJ and i == colind: + J = ten_J_in[worldid, rowadr_tenJ + nnz] + efc_J_out[worldid, efcid, i] = J + Jqvel += J * qvel_in[worldid, i] + nnz += 1 + if nnz < rownnz_tenJ: + colind = ten_J_colind[rowadr_tenJ + nnz] + else: + efc_J_out[worldid, efcid, i] = 0.0 tendon_invweight0_id = worldid % tendon_invweight0.shape[0] tendon_solref_fri_id = worldid % tendon_solref_fri.shape[0] tendon_solimp_fri_id = worldid % tendon_solimp_fri.shape[0] _efc_row( - opt_disableflags, - worldid, - opt_timestep[worldid % opt_timestep.shape[0]], - efcid, - 0.0, - 0.0, - tendon_invweight0[tendon_invweight0_id, tenid], - tendon_solref_fri[tendon_solref_fri_id, tenid], - tendon_solimp_fri[tendon_solimp_fri_id, tenid], - 0.0, - Jqvel, - frictionloss, - ConstraintType.FRICTION_TENDON, - tenid, - efc_type_out, - efc_id_out, - efc_pos_out, - efc_margin_out, - efc_D_out, - efc_vel_out, - efc_aref_out, - efc_frictionloss_out, + opt_disableflags, + worldid, + opt_timestep[worldid % opt_timestep.shape[0]], + efcid, + 0.0, + 0.0, + tendon_invweight0[tendon_invweight0_id, tenid], + tendon_solref_fri[tendon_solref_fri_id, tenid], + tendon_solimp_fri[tendon_solimp_fri_id, tenid], + 0.0, + Jqvel, + frictionloss, + ConstraintType.FRICTION_TENDON, + tenid, + efc_type_out, + efc_id_out, + efc_pos_out, + efc_margin_out, + efc_D_out, + efc_vel_out, + efc_aref_out, + efc_frictionloss_out, ) @wp.kernel def _limit_slide_hinge( - # Model: - nv: int, - opt_timestep: wp.array(dtype=float), - opt_disableflags: int, - jnt_qposadr: wp.array(dtype=int), - jnt_dofadr: wp.array(dtype=int), - jnt_solref: wp.array2d(dtype=wp.vec2), - jnt_solimp: wp.array2d(dtype=vec5), - jnt_range: wp.array2d(dtype=wp.vec2), - jnt_margin: wp.array2d(dtype=float), - dof_invweight0: wp.array2d(dtype=float), - is_sparse: bool, - jnt_limited_slide_hinge_adr: wp.array(dtype=int), - # Data in: - qpos_in: wp.array2d(dtype=float), - qvel_in: wp.array2d(dtype=float), - njmax_in: int, - # Data out: - nl_out: wp.array(dtype=int), - nefc_out: wp.array(dtype=int), - efc_type_out: wp.array2d(dtype=int), - efc_id_out: wp.array2d(dtype=int), - efc_J_rownnz_out: wp.array2d(dtype=int), - efc_J_rowadr_out: wp.array2d(dtype=int), - efc_J_colind_out: wp.array3d(dtype=int), - efc_J_out: wp.array3d(dtype=float), - efc_pos_out: wp.array2d(dtype=float), - efc_margin_out: wp.array2d(dtype=float), - efc_D_out: wp.array2d(dtype=float), - efc_vel_out: wp.array2d(dtype=float), - efc_aref_out: wp.array2d(dtype=float), - efc_frictionloss_out: wp.array2d(dtype=float), + # Model: + nv: int, + opt_timestep: wp.array(dtype=float), + opt_disableflags: int, + jnt_qposadr: wp.array(dtype=int), + jnt_dofadr: wp.array(dtype=int), + jnt_solref: wp.array2d(dtype=wp.vec2), + jnt_solimp: wp.array2d(dtype=vec5), + jnt_range: wp.array2d(dtype=wp.vec2), + jnt_margin: wp.array2d(dtype=float), + dof_invweight0: wp.array2d(dtype=float), + is_sparse: bool, + jnt_limited_slide_hinge_adr: wp.array(dtype=int), + # Data in: + qpos_in: wp.array2d(dtype=float), + qvel_in: wp.array2d(dtype=float), + njmax_in: int, + njmax_nnz_in: int, + # Data out: + nl_out: wp.array(dtype=int), + nefc_out: wp.array(dtype=int), + efc_type_out: wp.array2d(dtype=int), + efc_id_out: wp.array2d(dtype=int), + efc_J_rownnz_out: wp.array2d(dtype=int), + efc_J_rowadr_out: wp.array2d(dtype=int), + efc_J_colind_out: wp.array3d(dtype=int), + efc_J_out: wp.array3d(dtype=float), + efc_pos_out: wp.array2d(dtype=float), + efc_margin_out: wp.array2d(dtype=float), + efc_D_out: wp.array2d(dtype=float), + efc_vel_out: wp.array2d(dtype=float), + efc_aref_out: wp.array2d(dtype=float), + efc_frictionloss_out: wp.array2d(dtype=float), + # Out: + efc_nnz_out: wp.array(dtype=int), ): worldid, jntlimitedid = wp.tid() jntid = jnt_limited_slide_hinge_adr[jntlimitedid] @@ -1285,7 +1376,9 @@ def _limit_slide_hinge( if is_sparse: efc_J_rownnz_out[worldid, efcid] = 1 - rowadr = efcid * nv + rowadr = wp.atomic_add(efc_nnz_out, worldid, 1) + if rowadr + 1 > njmax_nnz_in: + return efc_J_rowadr_out[worldid, efcid] = rowadr efc_J_colind_out[worldid, 0, rowadr] = dofadr efc_J_out[worldid, 0, rowadr] = J @@ -1300,65 +1393,68 @@ def _limit_slide_hinge( jnt_solref_id = worldid % jnt_solref.shape[0] jnt_solimp_id = worldid % jnt_solimp.shape[0] _efc_row( - opt_disableflags, - worldid, - opt_timestep[worldid % opt_timestep.shape[0]], - efcid, - pos, - pos, - dof_invweight0[dof_invweight0_id, dofadr], - jnt_solref[jnt_solref_id, jntid], - jnt_solimp[jnt_solimp_id, jntid], - jntmargin, - Jqvel, - 0.0, - ConstraintType.LIMIT_JOINT, - jntid, - efc_type_out, - efc_id_out, - efc_pos_out, - efc_margin_out, - efc_D_out, - efc_vel_out, - efc_aref_out, - efc_frictionloss_out, - ) - - -@wp.kernel -def _limit_ball( - # Model: - nv: int, - opt_timestep: wp.array(dtype=float), - opt_disableflags: int, - jnt_qposadr: wp.array(dtype=int), - jnt_dofadr: wp.array(dtype=int), - jnt_solref: wp.array2d(dtype=wp.vec2), - jnt_solimp: wp.array2d(dtype=vec5), - jnt_range: wp.array2d(dtype=wp.vec2), - jnt_margin: wp.array2d(dtype=float), - dof_invweight0: wp.array2d(dtype=float), - is_sparse: bool, - jnt_limited_ball_adr: wp.array(dtype=int), - # Data in: - qpos_in: wp.array2d(dtype=float), - qvel_in: wp.array2d(dtype=float), - njmax_in: int, - # Data out: - nl_out: wp.array(dtype=int), - nefc_out: wp.array(dtype=int), - efc_type_out: wp.array2d(dtype=int), - efc_id_out: wp.array2d(dtype=int), - efc_J_rownnz_out: wp.array2d(dtype=int), - efc_J_rowadr_out: wp.array2d(dtype=int), - efc_J_colind_out: wp.array3d(dtype=int), - efc_J_out: wp.array3d(dtype=float), - efc_pos_out: wp.array2d(dtype=float), - efc_margin_out: wp.array2d(dtype=float), - efc_D_out: wp.array2d(dtype=float), - efc_vel_out: wp.array2d(dtype=float), - efc_aref_out: wp.array2d(dtype=float), - efc_frictionloss_out: wp.array2d(dtype=float), + opt_disableflags, + worldid, + opt_timestep[worldid % opt_timestep.shape[0]], + efcid, + pos, + pos, + dof_invweight0[dof_invweight0_id, dofadr], + jnt_solref[jnt_solref_id, jntid], + jnt_solimp[jnt_solimp_id, jntid], + jntmargin, + Jqvel, + 0.0, + ConstraintType.LIMIT_JOINT, + jntid, + efc_type_out, + efc_id_out, + efc_pos_out, + efc_margin_out, + efc_D_out, + efc_vel_out, + efc_aref_out, + efc_frictionloss_out, + ) + + +@wp.kernel +def _limit_ball( + # Model: + nv: int, + opt_timestep: wp.array(dtype=float), + opt_disableflags: int, + jnt_qposadr: wp.array(dtype=int), + jnt_dofadr: wp.array(dtype=int), + jnt_solref: wp.array2d(dtype=wp.vec2), + jnt_solimp: wp.array2d(dtype=vec5), + jnt_range: wp.array2d(dtype=wp.vec2), + jnt_margin: wp.array2d(dtype=float), + dof_invweight0: wp.array2d(dtype=float), + is_sparse: bool, + jnt_limited_ball_adr: wp.array(dtype=int), + # Data in: + qpos_in: wp.array2d(dtype=float), + qvel_in: wp.array2d(dtype=float), + njmax_in: int, + njmax_nnz_in: int, + # Data out: + nl_out: wp.array(dtype=int), + nefc_out: wp.array(dtype=int), + efc_type_out: wp.array2d(dtype=int), + efc_id_out: wp.array2d(dtype=int), + efc_J_rownnz_out: wp.array2d(dtype=int), + efc_J_rowadr_out: wp.array2d(dtype=int), + efc_J_colind_out: wp.array3d(dtype=int), + efc_J_out: wp.array3d(dtype=float), + efc_pos_out: wp.array2d(dtype=float), + efc_margin_out: wp.array2d(dtype=float), + efc_D_out: wp.array2d(dtype=float), + efc_vel_out: wp.array2d(dtype=float), + efc_aref_out: wp.array2d(dtype=float), + efc_frictionloss_out: wp.array2d(dtype=float), + # Out: + efc_nnz_out: wp.array(dtype=int), ): worldid, jntlimitedid = wp.tid() jntid = jnt_limited_ball_adr[jntlimitedid] @@ -1391,7 +1487,9 @@ def _limit_ball( if is_sparse: efc_J_rownnz_out[worldid, efcid] = 3 - rowadr = efcid * nv + rowadr = wp.atomic_add(efc_nnz_out, worldid, 3) + if rowadr + 3 > njmax_nnz_in: + return efc_J_rowadr_out[worldid, efcid] = rowadr sparseid0 = rowadr + 0 @@ -1420,69 +1518,70 @@ def _limit_ball( jnt_solref_id = worldid % jnt_solref.shape[0] jnt_solimp_id = worldid % jnt_solimp.shape[0] _efc_row( - opt_disableflags, - worldid, - opt_timestep[worldid % opt_timestep.shape[0]], - efcid, - pos, - pos, - dof_invweight0[dof_invweight0_id, dofadr], - jnt_solref[jnt_solref_id, jntid], - jnt_solimp[jnt_solimp_id, jntid], - jntmargin, - Jqvel, - 0.0, - ConstraintType.LIMIT_JOINT, - jntid, - efc_type_out, - efc_id_out, - efc_pos_out, - efc_margin_out, - efc_D_out, - efc_vel_out, - efc_aref_out, - efc_frictionloss_out, + opt_disableflags, + worldid, + opt_timestep[worldid % opt_timestep.shape[0]], + efcid, + pos, + pos, + dof_invweight0[dof_invweight0_id, dofadr], + jnt_solref[jnt_solref_id, jntid], + jnt_solimp[jnt_solimp_id, jntid], + jntmargin, + Jqvel, + 0.0, + ConstraintType.LIMIT_JOINT, + jntid, + efc_type_out, + efc_id_out, + efc_pos_out, + efc_margin_out, + efc_D_out, + efc_vel_out, + efc_aref_out, + efc_frictionloss_out, ) @wp.kernel def _limit_tendon( - # Model: - nv: int, - opt_timestep: wp.array(dtype=float), - opt_disableflags: int, - jnt_dofadr: wp.array(dtype=int), - tendon_adr: wp.array(dtype=int), - tendon_num: wp.array(dtype=int), - tendon_solref_lim: wp.array2d(dtype=wp.vec2), - tendon_solimp_lim: wp.array2d(dtype=vec5), - tendon_range: wp.array2d(dtype=wp.vec2), - tendon_margin: wp.array2d(dtype=float), - tendon_invweight0: wp.array2d(dtype=float), - wrap_type: wp.array(dtype=int), - wrap_objid: wp.array(dtype=int), - is_sparse: bool, - tendon_limited_adr: wp.array(dtype=int), - # Data in: - qvel_in: wp.array2d(dtype=float), - ten_J_in: wp.array3d(dtype=float), - ten_length_in: wp.array2d(dtype=float), - njmax_in: int, - # Data out: - nl_out: wp.array(dtype=int), - nefc_out: wp.array(dtype=int), - efc_type_out: wp.array2d(dtype=int), - efc_id_out: wp.array2d(dtype=int), - efc_J_rownnz_out: wp.array2d(dtype=int), - efc_J_rowadr_out: wp.array2d(dtype=int), - efc_J_colind_out: wp.array3d(dtype=int), - efc_J_out: wp.array3d(dtype=float), - efc_pos_out: wp.array2d(dtype=float), - efc_margin_out: wp.array2d(dtype=float), - efc_D_out: wp.array2d(dtype=float), - efc_vel_out: wp.array2d(dtype=float), - efc_aref_out: wp.array2d(dtype=float), - efc_frictionloss_out: wp.array2d(dtype=float), + # Model: + nv: int, + opt_timestep: wp.array(dtype=float), + opt_disableflags: int, + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), + tendon_solref_lim: wp.array2d(dtype=wp.vec2), + tendon_solimp_lim: wp.array2d(dtype=vec5), + tendon_range: wp.array2d(dtype=wp.vec2), + tendon_margin: wp.array2d(dtype=float), + tendon_invweight0: wp.array2d(dtype=float), + is_sparse: bool, + tendon_limited_adr: wp.array(dtype=int), + # Data in: + qvel_in: wp.array2d(dtype=float), + ten_J_in: wp.array2d(dtype=float), + ten_length_in: wp.array2d(dtype=float), + njmax_in: int, + njmax_nnz_in: int, + # Data out: + nl_out: wp.array(dtype=int), + nefc_out: wp.array(dtype=int), + efc_type_out: wp.array2d(dtype=int), + efc_id_out: wp.array2d(dtype=int), + efc_J_rownnz_out: wp.array2d(dtype=int), + efc_J_rowadr_out: wp.array2d(dtype=int), + efc_J_colind_out: wp.array3d(dtype=int), + efc_J_out: wp.array3d(dtype=float), + efc_pos_out: wp.array2d(dtype=float), + efc_margin_out: wp.array2d(dtype=float), + efc_D_out: wp.array2d(dtype=float), + efc_vel_out: wp.array2d(dtype=float), + efc_aref_out: wp.array2d(dtype=float), + efc_frictionloss_out: wp.array2d(dtype=float), + # Out: + efc_nnz_out: wp.array(dtype=int), ): worldid, tenlimitedid = wp.tid() tenid = tendon_limited_adr[tenlimitedid] @@ -1506,122 +1605,123 @@ def _limit_tendon( Jqvel = float(0.0) scl = float(dist_min < dist_max) * 2.0 - 1.0 - # TODO(team): sparse tendon jacobian + rownnz_tenJ = ten_J_rownnz[tenid] + rowadr_tenJ = ten_J_rowadr[tenid] if is_sparse: - rowadr = efcid * nv - efc_J_rownnz_out[worldid, efcid] = nv - efc_J_rowadr_out[worldid, efcid] = rowadr - for i in range(nv): - efc_J_colind_out[worldid, 0, rowadr + i] = i - efc_J_out[worldid, 0, rowadr + i] = 0.0 - - adr = tendon_adr[tenid] - if wrap_type[adr] == types.WrapType.JOINT: - if not is_sparse: - for i in range(nv): - efc_J_out[worldid, efcid, i] = 0.0 - - ten_num = tendon_num[tenid] - for i in range(ten_num): - dofadr = jnt_dofadr[wrap_objid[adr + i]] - J = scl * ten_J_in[worldid, tenid, dofadr] - - if is_sparse: - efc_J_out[worldid, 0, rowadr + dofadr] = J - else: - efc_J_out[worldid, efcid, dofadr] = J - - Jqvel += J * qvel_in[worldid, dofadr] + efc_J_rownnz_out[worldid, efcid] = rownnz_tenJ + rowadr_efc = wp.atomic_add(efc_nnz_out, worldid, rownnz_tenJ) + if rowadr_efc + rownnz_tenJ > njmax_nnz_in: + return + efc_J_rowadr_out[worldid, efcid] = rowadr_efc + + for i in range(rownnz_tenJ): + sparseid_ten = rowadr_tenJ + i + sparseid_efc = rowadr_efc + i + colind = ten_J_colind[sparseid_ten] + J = scl * ten_J_in[worldid, sparseid_ten] + efc_J_colind_out[worldid, 0, sparseid_efc] = colind + efc_J_out[worldid, 0, sparseid_efc] = J + Jqvel += J * qvel_in[worldid, colind] else: + nnz = int(0) + colind = ten_J_colind[rowadr_tenJ] for i in range(nv): - J = scl * ten_J_in[worldid, tenid, i] - - if is_sparse: - efc_J_out[worldid, 0, rowadr + i] = J - else: + if nnz < rownnz_tenJ and i == colind: + J = scl * ten_J_in[worldid, rowadr_tenJ + nnz] efc_J_out[worldid, efcid, i] = J - - Jqvel += J * qvel_in[worldid, i] + Jqvel += J * qvel_in[worldid, i] + nnz += 1 + if nnz < rownnz_tenJ: + colind = ten_J_colind[rowadr_tenJ + nnz] + else: + efc_J_out[worldid, efcid, i] = 0.0 tendon_invweight0_id = worldid % tendon_invweight0.shape[0] tendon_solref_lim_id = worldid % tendon_solref_lim.shape[0] tendon_solimp_lim_id = worldid % tendon_solimp_lim.shape[0] _efc_row( - opt_disableflags, - worldid, - opt_timestep[worldid % opt_timestep.shape[0]], - efcid, - pos, - pos, - tendon_invweight0[tendon_invweight0_id, tenid], - tendon_solref_lim[tendon_solref_lim_id, tenid], - tendon_solimp_lim[tendon_solimp_lim_id, tenid], - tenmargin, - Jqvel, - 0.0, - ConstraintType.LIMIT_TENDON, - tenid, - efc_type_out, - efc_id_out, - efc_pos_out, - efc_margin_out, - efc_D_out, - efc_vel_out, - efc_aref_out, - efc_frictionloss_out, + opt_disableflags, + worldid, + opt_timestep[worldid % opt_timestep.shape[0]], + efcid, + pos, + pos, + tendon_invweight0[tendon_invweight0_id, tenid], + tendon_solref_lim[tendon_solref_lim_id, tenid], + tendon_solimp_lim[tendon_solimp_lim_id, tenid], + tenmargin, + Jqvel, + 0.0, + ConstraintType.LIMIT_TENDON, + tenid, + efc_type_out, + efc_id_out, + efc_pos_out, + efc_margin_out, + efc_D_out, + efc_vel_out, + efc_aref_out, + efc_frictionloss_out, ) @wp.kernel def _contact_pyramidal( - # Model: - nv: int, - opt_timestep: wp.array(dtype=float), - opt_disableflags: int, - opt_impratio_invsqrt: wp.array(dtype=float), - body_parentid: wp.array(dtype=int), - body_rootid: wp.array(dtype=int), - body_weldid: wp.array(dtype=int), - body_dofnum: wp.array(dtype=int), - body_dofadr: wp.array(dtype=int), - body_invweight0: wp.array2d(dtype=wp.vec2), - dof_bodyid: wp.array(dtype=int), - dof_parentid: wp.array(dtype=int), - geom_bodyid: wp.array(dtype=int), - is_sparse: bool, - # Data in: - qvel_in: wp.array2d(dtype=float), - subtree_com_in: wp.array2d(dtype=wp.vec3), - cdof_in: wp.array2d(dtype=wp.spatial_vector), - njmax_in: int, - nacon_in: wp.array(dtype=int), - # In: - dist_in: wp.array(dtype=float), - condim_in: wp.array(dtype=int), - includemargin_in: wp.array(dtype=float), - worldid_in: wp.array(dtype=int), - geom_in: wp.array(dtype=wp.vec2i), - pos_in: wp.array(dtype=wp.vec3), - frame_in: wp.array(dtype=wp.mat33), - friction_in: wp.array(dtype=vec5), - solref_in: wp.array(dtype=wp.vec2), - solimp_in: wp.array(dtype=vec5), - type_in: wp.array(dtype=int), - # Data out: - nefc_out: wp.array(dtype=int), - contact_efc_address_out: wp.array2d(dtype=int), - efc_type_out: wp.array2d(dtype=int), - efc_id_out: wp.array2d(dtype=int), - efc_J_rownnz_out: wp.array2d(dtype=int), - efc_J_rowadr_out: wp.array2d(dtype=int), - efc_J_colind_out: wp.array3d(dtype=int), - efc_J_out: wp.array3d(dtype=float), - efc_pos_out: wp.array2d(dtype=float), - efc_margin_out: wp.array2d(dtype=float), - efc_D_out: wp.array2d(dtype=float), - efc_vel_out: wp.array2d(dtype=float), - efc_aref_out: wp.array2d(dtype=float), - efc_frictionloss_out: wp.array2d(dtype=float), + # Model: + nv: int, + opt_timestep: wp.array(dtype=float), + opt_disableflags: int, + opt_impratio_invsqrt: wp.array(dtype=float), + body_parentid: wp.array(dtype=int), + body_rootid: wp.array(dtype=int), + body_weldid: wp.array(dtype=int), + body_dofnum: wp.array(dtype=int), + body_dofadr: wp.array(dtype=int), + body_invweight0: wp.array2d(dtype=wp.vec2), + dof_bodyid: wp.array(dtype=int), + dof_parentid: wp.array(dtype=int), + geom_bodyid: wp.array(dtype=int), + flex_vertadr: wp.array(dtype=int), + flex_vertbodyid: wp.array(dtype=int), + is_sparse: bool, + # Data in: + qvel_in: wp.array2d(dtype=float), + subtree_com_in: wp.array2d(dtype=wp.vec3), + cdof_in: wp.array2d(dtype=wp.spatial_vector), + njmax_in: int, + njmax_nnz_in: int, + nacon_in: wp.array(dtype=int), + # In: + dist_in: wp.array(dtype=float), + condim_in: wp.array(dtype=int), + includemargin_in: wp.array(dtype=float), + worldid_in: wp.array(dtype=int), + geom_in: wp.array(dtype=wp.vec2i), + flex_in: wp.array(dtype=wp.vec2i), + vert_in: wp.array(dtype=wp.vec2i), + pos_in: wp.array(dtype=wp.vec3), + frame_in: wp.array(dtype=wp.mat33), + friction_in: wp.array(dtype=vec5), + solref_in: wp.array(dtype=wp.vec2), + solimp_in: wp.array(dtype=vec5), + type_in: wp.array(dtype=int), + # Data out: + nefc_out: wp.array(dtype=int), + contact_efc_address_out: wp.array2d(dtype=int), + efc_type_out: wp.array2d(dtype=int), + efc_id_out: wp.array2d(dtype=int), + efc_J_rownnz_out: wp.array2d(dtype=int), + efc_J_rowadr_out: wp.array2d(dtype=int), + efc_J_colind_out: wp.array3d(dtype=int), + efc_J_out: wp.array3d(dtype=float), + efc_pos_out: wp.array2d(dtype=float), + efc_margin_out: wp.array2d(dtype=float), + efc_D_out: wp.array2d(dtype=float), + efc_vel_out: wp.array2d(dtype=float), + efc_aref_out: wp.array2d(dtype=float), + efc_frictionloss_out: wp.array2d(dtype=float), + # Out: + efc_nnz_out: wp.array(dtype=int), ): conid, dimid = wp.tid() @@ -1655,8 +1755,20 @@ def _contact_pyramidal( contact_efc_address_out[conid, dimid] = efcid geom = geom_in[conid] - body1 = geom_bodyid[geom[0]] - body2 = geom_bodyid[geom[1]] + + if geom[0] >= 0: + body1 = geom_bodyid[geom[0]] + else: + flex = flex_in[conid] + vert = vert_in[conid] + body1 = flex_vertbodyid[flex_vertadr[flex[0]] + vert[0]] + + if geom[1] >= 0: + body2 = geom_bodyid[geom[1]] + else: + flex = flex_in[conid] + vert = vert_in[conid] + body2 = flex_vertbodyid[flex_vertadr[flex[1]] + vert[1]] con_pos = pos_in[conid] frame = frame_in[conid] @@ -1674,29 +1786,48 @@ def _contact_pyramidal( invweight = invweight + fri0 * fri0 * invweight invweight = invweight * 2.0 * fri0 * fri0 * impratio_invsqrt * impratio_invsqrt - if is_sparse: - rowadr = efcid * nv - efc_J_rowadr_out[worldid, efcid] = rowadr - Jqvel = float(0.0) # skip fixed bodies body1 = body_weldid[body1] body2 = body_weldid[body2] - da1 = body_dofadr[body1] + body_dofnum[body1] - 1 - da2 = body_dofadr[body2] + body_dofnum[body2] - 1 - da = wp.max(da1, da2) + da1 = int(body_dofadr[body1] + body_dofnum[body1] - 1) + da2 = int(body_dofadr[body2] + body_dofnum[body2] - 1) if is_sparse: + pda1 = da1 + pda2 = da2 rownnz = int(0) + while pda1 >= 0 or pda2 >= 0: + da = wp.max(pda1, pda2) + # skip common dofs + if pda1 == da and pda2 == da: + break + if pda1 == da: + pda1 = dof_parentid[pda1] + if pda2 == da: + pda2 = dof_parentid[pda2] + rownnz += 1 + + # get rowadr + rowadr = wp.atomic_add(efc_nnz_out, worldid, rownnz) + if rowadr + rownnz > njmax_nnz_in: + return + efc_J_rowadr_out[worldid, efcid] = rowadr + efc_J_rownnz_out[worldid, efcid] = rownnz + + da = wp.max(da1, da2) + + if is_sparse: + nnz = int(0) dofid = int(da) else: dofid = int(nv - 1) while True: if is_sparse: - if da1 < 0 and da2 < 0: + if nnz >= rownnz: break else: if dofid < 0: @@ -1749,13 +1880,15 @@ def _contact_pyramidal( J -= Ji * frii if is_sparse: - sparseid = rowadr + rownnz + sparseid = rowadr + nnz efc_J_colind_out[worldid, 0, sparseid] = dofid efc_J_out[worldid, 0, sparseid] = J - rownnz += 1 + nnz += 1 else: efc_J_out[worldid, efcid, dofid] = J Jqvel += J * qvel_in[worldid, dofid] + if is_sparse and nnz >= rownnz: + break # Advance tree pointers and recompute da for next iteration if da1 == da: @@ -1772,91 +1905,95 @@ def _contact_pyramidal( efc_J_out[worldid, efcid, dofid] = 0.0 dofid -= 1 - if is_sparse: - efc_J_rownnz_out[worldid, efcid] = rownnz - if condim == 1: efc_type = ConstraintType.CONTACT_FRICTIONLESS else: efc_type = ConstraintType.CONTACT_PYRAMIDAL _efc_row( - opt_disableflags, - worldid, - timestep, - efcid, - pos, - pos, - invweight, - solref_in[conid], - solimp_in[conid], - includemargin, - Jqvel, - 0.0, - efc_type, - conid, - efc_type_out, - efc_id_out, - efc_pos_out, - efc_margin_out, - efc_D_out, - efc_vel_out, - efc_aref_out, - efc_frictionloss_out, + opt_disableflags, + worldid, + timestep, + efcid, + pos, + pos, + invweight, + solref_in[conid], + solimp_in[conid], + includemargin, + Jqvel, + 0.0, + efc_type, + conid, + efc_type_out, + efc_id_out, + efc_pos_out, + efc_margin_out, + efc_D_out, + efc_vel_out, + efc_aref_out, + efc_frictionloss_out, ) @wp.kernel def _contact_elliptic( - # Model: - nv: int, - opt_timestep: wp.array(dtype=float), - opt_disableflags: int, - opt_impratio_invsqrt: wp.array(dtype=float), - body_parentid: wp.array(dtype=int), - body_rootid: wp.array(dtype=int), - body_weldid: wp.array(dtype=int), - body_dofnum: wp.array(dtype=int), - body_dofadr: wp.array(dtype=int), - body_invweight0: wp.array2d(dtype=wp.vec2), - dof_bodyid: wp.array(dtype=int), - dof_parentid: wp.array(dtype=int), - geom_bodyid: wp.array(dtype=int), - is_sparse: bool, - # Data in: - qvel_in: wp.array2d(dtype=float), - subtree_com_in: wp.array2d(dtype=wp.vec3), - cdof_in: wp.array2d(dtype=wp.spatial_vector), - njmax_in: int, - nacon_in: wp.array(dtype=int), - # In: - dist_in: wp.array(dtype=float), - condim_in: wp.array(dtype=int), - includemargin_in: wp.array(dtype=float), - worldid_in: wp.array(dtype=int), - geom_in: wp.array(dtype=wp.vec2i), - pos_in: wp.array(dtype=wp.vec3), - frame_in: wp.array(dtype=wp.mat33), - friction_in: wp.array(dtype=vec5), - solref_in: wp.array(dtype=wp.vec2), - solreffriction_in: wp.array(dtype=wp.vec2), - solimp_in: wp.array(dtype=vec5), - type_in: wp.array(dtype=int), - # Data out: - nefc_out: wp.array(dtype=int), - contact_efc_address_out: wp.array2d(dtype=int), - efc_type_out: wp.array2d(dtype=int), - efc_id_out: wp.array2d(dtype=int), - efc_J_rownnz_out: wp.array2d(dtype=int), - efc_J_rowadr_out: wp.array2d(dtype=int), - efc_J_colind_out: wp.array3d(dtype=int), - efc_J_out: wp.array3d(dtype=float), - efc_pos_out: wp.array2d(dtype=float), - efc_margin_out: wp.array2d(dtype=float), - efc_D_out: wp.array2d(dtype=float), - efc_vel_out: wp.array2d(dtype=float), - efc_aref_out: wp.array2d(dtype=float), - efc_frictionloss_out: wp.array2d(dtype=float), + # Model: + nv: int, + opt_timestep: wp.array(dtype=float), + opt_disableflags: int, + opt_impratio_invsqrt: wp.array(dtype=float), + body_parentid: wp.array(dtype=int), + body_rootid: wp.array(dtype=int), + body_weldid: wp.array(dtype=int), + body_dofnum: wp.array(dtype=int), + body_dofadr: wp.array(dtype=int), + body_invweight0: wp.array2d(dtype=wp.vec2), + dof_bodyid: wp.array(dtype=int), + dof_parentid: wp.array(dtype=int), + geom_bodyid: wp.array(dtype=int), + flex_vertadr: wp.array(dtype=int), + flex_vertbodyid: wp.array(dtype=int), + is_sparse: bool, + # Data in: + qvel_in: wp.array2d(dtype=float), + subtree_com_in: wp.array2d(dtype=wp.vec3), + cdof_in: wp.array2d(dtype=wp.spatial_vector), + njmax_in: int, + njmax_nnz_in: int, + nacon_in: wp.array(dtype=int), + # In: + dist_in: wp.array(dtype=float), + condim_in: wp.array(dtype=int), + includemargin_in: wp.array(dtype=float), + worldid_in: wp.array(dtype=int), + geom_in: wp.array(dtype=wp.vec2i), + flex_in: wp.array(dtype=wp.vec2i), + vert_in: wp.array(dtype=wp.vec2i), + pos_in: wp.array(dtype=wp.vec3), + frame_in: wp.array(dtype=wp.mat33), + friction_in: wp.array(dtype=vec5), + solref_in: wp.array(dtype=wp.vec2), + solreffriction_in: wp.array(dtype=wp.vec2), + solimp_in: wp.array(dtype=vec5), + type_in: wp.array(dtype=int), + # Data out: + nefc_out: wp.array(dtype=int), + contact_efc_address_out: wp.array2d(dtype=int), + efc_type_out: wp.array2d(dtype=int), + efc_id_out: wp.array2d(dtype=int), + efc_J_rownnz_out: wp.array2d(dtype=int), + efc_J_rowadr_out: wp.array2d(dtype=int), + efc_J_colind_out: wp.array3d(dtype=int), + efc_J_out: wp.array3d(dtype=float), + efc_pos_out: wp.array2d(dtype=float), + efc_margin_out: wp.array2d(dtype=float), + efc_D_out: wp.array2d(dtype=float), + efc_vel_out: wp.array2d(dtype=float), + efc_aref_out: wp.array2d(dtype=float), + efc_frictionloss_out: wp.array2d(dtype=float), + # Out: + efc_nnz_out: wp.array(dtype=int), ): conid, dimid = wp.tid() @@ -1888,35 +2025,67 @@ def _contact_elliptic( contact_efc_address_out[conid, dimid] = efcid geom = geom_in[conid] - body1 = geom_bodyid[geom[0]] - body2 = geom_bodyid[geom[1]] + + if geom[0] >= 0: + body1 = geom_bodyid[geom[0]] + else: + flex = flex_in[conid] + vert = vert_in[conid] + body1 = flex_vertbodyid[flex_vertadr[flex[0]] + vert[0]] + + if geom[1] >= 0: + body2 = geom_bodyid[geom[1]] + else: + flex = flex_in[conid] + vert = vert_in[conid] + body2 = flex_vertbodyid[flex_vertadr[flex[1]] + vert[1]] con_pos = pos_in[conid] frame = frame_in[conid] - if is_sparse: - rowadr = efcid * nv - efc_J_rowadr_out[worldid, efcid] = rowadr - Jqvel = float(0.0) # skip fixed bodies body1 = body_weldid[body1] body2 = body_weldid[body2] - da1 = body_dofadr[body1] + body_dofnum[body1] - 1 - da2 = body_dofadr[body2] + body_dofnum[body2] - 1 - da = wp.max(da1, da2) + da1 = int(body_dofadr[body1] + body_dofnum[body1] - 1) + da2 = int(body_dofadr[body2] + body_dofnum[body2] - 1) if is_sparse: + # count non-zeros + pda1 = da1 + pda2 = da2 rownnz = int(0) + while pda1 >= 0 or pda2 >= 0: + da = wp.max(pda1, pda2) + # skip common dofs + if pda1 == da and pda2 == da: + break + if pda1 == da: + pda1 = dof_parentid[pda1] + if pda2 == da: + pda2 = dof_parentid[pda2] + rownnz += 1 + + # get rowadr + rowadr = wp.atomic_add(efc_nnz_out, worldid, rownnz) + if rowadr + rownnz > njmax_nnz_in: + return + efc_J_rowadr_out[worldid, efcid] = rowadr + efc_J_rownnz_out[worldid, efcid] = rownnz + + da = wp.max(da1, da2) + + if is_sparse: + nnz = int(0) dofid = int(da) else: dofid = int(nv - 1) while True: if is_sparse: - if da1 < 0 and da2 < 0: + if nnz >= rownnz: break else: if dofid < 0: @@ -1957,13 +2126,15 @@ def _contact_elliptic( J += frame[dimid - 3, xyz] * jac_dif if is_sparse: - sparseid = rowadr + rownnz + sparseid = rowadr + nnz efc_J_colind_out[worldid, 0, sparseid] = dofid efc_J_out[worldid, 0, sparseid] = J - rownnz += 1 + nnz += 1 else: efc_J_out[worldid, efcid, dofid] = J Jqvel += J * qvel_in[worldid, dofid] + if is_sparse and nnz >= rownnz: + break # Advance tree pointers and recompute da for next iteration if da1 == da: @@ -1980,9 +2151,6 @@ def _contact_elliptic( efc_J_out[worldid, efcid, dofid] = 0.0 dofid -= 1 - if is_sparse: - efc_J_rownnz_out[worldid, efcid] = rownnz - body_invweight0_id = worldid % body_invweight0.shape[0] invweight = body_invweight0[body_invweight0_id, body1][0] + body_invweight0[body_invweight0_id, body2][0] @@ -2013,561 +2181,599 @@ def _contact_elliptic( efc_type = ConstraintType.CONTACT_ELLIPTIC _efc_row( - opt_disableflags, - worldid, - timestep, - efcid, - pos_aref, - pos, - invweight, - ref, - solimp_in[conid], - includemargin, - Jqvel, - 0.0, - efc_type, - conid, - efc_type_out, - efc_id_out, - efc_pos_out, - efc_margin_out, - efc_D_out, - efc_vel_out, - efc_aref_out, - efc_frictionloss_out, + opt_disableflags, + worldid, + timestep, + efcid, + pos_aref, + pos, + invweight, + ref, + solimp_in[conid], + includemargin, + Jqvel, + 0.0, + efc_type, + conid, + efc_type_out, + efc_id_out, + efc_pos_out, + efc_margin_out, + efc_D_out, + efc_vel_out, + efc_aref_out, + efc_frictionloss_out, ) @event_scope def make_constraint(m: types.Model, d: types.Data): """Creates constraint jacobians and other supporting data.""" + efc_nnz = wp.empty((d.nworld,), dtype=int) + wp.launch( _zero_constraint_counts, dim=d.nworld, - inputs=[d.ne, d.nf, d.nl, d.nefc], + inputs=[d.ne, d.nf, d.nl, d.nefc, efc_nnz], ) - if types.SPARSE_CONSTRAINT_JACOBIAN: - d.contact.efc_address.fill_(-1) - if not (m.opt.disableflags & types.DisableBit.CONSTRAINT): if not (m.opt.disableflags & types.DisableBit.EQUALITY): wp.launch( - _equality_connect, - dim=(d.nworld, m.eq_connect_adr.size), - inputs=[ - m.nv, - m.nsite, - m.opt.timestep, - m.opt.disableflags, - m.body_parentid, - m.body_rootid, - m.body_weldid, - m.body_dofnum, - m.body_dofadr, - m.body_invweight0, - m.dof_bodyid, - m.dof_parentid, - m.site_bodyid, - m.eq_obj1id, - m.eq_obj2id, - m.eq_objtype, - m.eq_solref, - m.eq_solimp, - m.eq_data, - SPARSE_CONSTRAINT_JACOBIAN, - m.eq_connect_adr, - d.qvel, - d.eq_active, - d.xpos, - d.xmat, - d.site_xpos, - d.subtree_com, - d.cdof, - d.njmax, - ], - outputs=[ - d.ne, - d.nefc, - d.efc.type, - d.efc.id, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.pos, - d.efc.margin, - d.efc.D, - d.efc.vel, - d.efc.aref, - d.efc.frictionloss, - ], + _equality_connect, + dim=(d.nworld, m.eq_connect_adr.size), + inputs=[ + m.nv, + m.nsite, + m.opt.timestep, + m.opt.disableflags, + m.body_parentid, + m.body_rootid, + m.body_weldid, + m.body_dofnum, + m.body_dofadr, + m.body_invweight0, + m.dof_bodyid, + m.dof_parentid, + m.site_bodyid, + m.eq_obj1id, + m.eq_obj2id, + m.eq_objtype, + m.eq_solref, + m.eq_solimp, + m.eq_data, + m.is_sparse, + m.eq_connect_adr, + d.qvel, + d.eq_active, + d.xpos, + d.xmat, + d.site_xpos, + d.subtree_com, + d.cdof, + d.njmax, + d.njmax_nnz, + ], + outputs=[ + d.ne, + d.nefc, + d.efc.type, + d.efc.id, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.efc.pos, + d.efc.margin, + d.efc.D, + d.efc.vel, + d.efc.aref, + d.efc.frictionloss, + efc_nnz, + ], ) wp.launch( - _equality_weld, - dim=(d.nworld, m.eq_wld_adr.size), - inputs=[ - m.nv, - m.nsite, - m.opt.timestep, - m.opt.disableflags, - m.body_parentid, - m.body_rootid, - m.body_weldid, - m.body_dofnum, - m.body_dofadr, - m.body_invweight0, - m.dof_bodyid, - m.dof_parentid, - m.site_bodyid, - m.site_quat, - m.eq_obj1id, - m.eq_obj2id, - m.eq_objtype, - m.eq_solref, - m.eq_solimp, - m.eq_data, - SPARSE_CONSTRAINT_JACOBIAN, - m.eq_wld_adr, - d.qvel, - d.eq_active, - d.xpos, - d.xquat, - d.xmat, - d.site_xpos, - d.subtree_com, - d.cdof, - d.njmax, - ], - outputs=[ - d.ne, - d.nefc, - d.efc.type, - d.efc.id, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.pos, - d.efc.margin, - d.efc.D, - d.efc.vel, - d.efc.aref, - d.efc.frictionloss, - ], + _equality_weld, + dim=(d.nworld, m.eq_wld_adr.size), + inputs=[ + m.nv, + m.nsite, + m.opt.timestep, + m.opt.disableflags, + m.body_parentid, + m.body_rootid, + m.body_weldid, + m.body_dofnum, + m.body_dofadr, + m.body_invweight0, + m.dof_bodyid, + m.dof_parentid, + m.site_bodyid, + m.site_quat, + m.eq_obj1id, + m.eq_obj2id, + m.eq_objtype, + m.eq_solref, + m.eq_solimp, + m.eq_data, + m.is_sparse, + m.eq_wld_adr, + d.qvel, + d.eq_active, + d.xpos, + d.xquat, + d.xmat, + d.site_xpos, + d.subtree_com, + d.cdof, + d.njmax, + d.njmax_nnz, + ], + outputs=[ + d.ne, + d.nefc, + d.efc.type, + d.efc.id, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.efc.pos, + d.efc.margin, + d.efc.D, + d.efc.vel, + d.efc.aref, + d.efc.frictionloss, + efc_nnz, + ], ) wp.launch( - _equality_joint, - dim=(d.nworld, m.eq_jnt_adr.size), - inputs=[ - m.nv, - m.opt.timestep, - m.opt.disableflags, - m.qpos0, - m.jnt_qposadr, - m.jnt_dofadr, - m.dof_invweight0, - m.eq_obj1id, - m.eq_obj2id, - m.eq_solref, - m.eq_solimp, - m.eq_data, - SPARSE_CONSTRAINT_JACOBIAN, - m.eq_jnt_adr, - d.qpos, - d.qvel, - d.eq_active, - d.njmax, - ], - outputs=[ - d.ne, - d.nefc, - d.efc.type, - d.efc.id, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.pos, - d.efc.margin, - d.efc.D, - d.efc.vel, - d.efc.aref, - d.efc.frictionloss, - ], + _equality_joint, + dim=(d.nworld, m.eq_jnt_adr.size), + inputs=[ + m.nv, + m.opt.timestep, + m.opt.disableflags, + m.qpos0, + m.jnt_qposadr, + m.jnt_dofadr, + m.dof_invweight0, + m.eq_obj1id, + m.eq_obj2id, + m.eq_solref, + m.eq_solimp, + m.eq_data, + m.is_sparse, + m.eq_jnt_adr, + d.qpos, + d.qvel, + d.eq_active, + d.njmax, + d.njmax_nnz, + ], + outputs=[ + d.ne, + d.nefc, + d.efc.type, + d.efc.id, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.efc.pos, + d.efc.margin, + d.efc.D, + d.efc.vel, + d.efc.aref, + d.efc.frictionloss, + efc_nnz, + ], ) wp.launch( - _equality_tendon, - dim=(d.nworld, m.eq_ten_adr.size), - inputs=[ - m.nv, - m.opt.timestep, - m.opt.disableflags, - m.eq_obj1id, - m.eq_obj2id, - m.eq_solref, - m.eq_solimp, - m.eq_data, - m.tendon_length0, - m.tendon_invweight0, - SPARSE_CONSTRAINT_JACOBIAN, - m.eq_ten_adr, - d.qvel, - d.eq_active, - d.ten_J, - d.ten_length, - d.njmax, - ], - outputs=[ - d.ne, - d.nefc, - d.efc.type, - d.efc.id, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.pos, - d.efc.margin, - d.efc.D, - d.efc.vel, - d.efc.aref, - d.efc.frictionloss, - ], + _equality_tendon, + dim=(d.nworld, m.eq_ten_adr.size), + inputs=[ + m.nv, + m.opt.timestep, + m.opt.disableflags, + m.eq_obj1id, + m.eq_obj2id, + m.eq_solref, + m.eq_solimp, + m.eq_data, + m.ten_J_rownnz, + m.ten_J_rowadr, + m.ten_J_colind, + m.tendon_length0, + m.tendon_invweight0, + m.is_sparse, + m.eq_ten_adr, + d.qvel, + d.eq_active, + d.ten_J, + d.ten_length, + d.njmax, + d.njmax_nnz, + ], + outputs=[ + d.ne, + d.nefc, + d.efc.type, + d.efc.id, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.efc.pos, + d.efc.margin, + d.efc.D, + d.efc.vel, + d.efc.aref, + d.efc.frictionloss, + efc_nnz, + ], ) wp.launch( - _equality_flex(SPARSE_CONSTRAINT_JACOBIAN), - dim=(d.nworld, m.eq_flex_adr.size, m.nflexedge), - inputs=[ - m.nv, - m.opt.timestep, - m.opt.disableflags, - m.flexedge_length0, - m.flexedge_invweight0, - m.flexedge_J_rownnz, - m.flexedge_J_rowadr, - m.flexedge_J_colind, - m.eq_solref, - m.eq_solimp, - m.eq_flex_adr, - d.qvel, - d.flexedge_J, - d.flexedge_length, - d.njmax, - ], - outputs=[ - d.ne, - d.nefc, - d.efc.type, - d.efc.id, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.pos, - d.efc.margin, - d.efc.D, - d.efc.vel, - d.efc.aref, - d.efc.frictionloss, - ], + _equality_flex(m.is_sparse), + dim=(d.nworld, m.eq_flex_adr.size, m.nflexedge), + inputs=[ + m.nv, + m.opt.timestep, + m.opt.disableflags, + m.flex_edgeadr, + m.flex_edgenum, + m.flexedge_length0, + m.flexedge_invweight0, + m.flexedge_J_rownnz, + m.flexedge_J_rowadr, + m.flexedge_J_colind, + m.eq_obj1id, + m.eq_solref, + m.eq_solimp, + m.eq_flex_adr, + d.qvel, + d.flexedge_J, + d.flexedge_length, + d.njmax, + d.njmax_nnz, + ], + outputs=[ + d.ne, + d.nefc, + d.efc.type, + d.efc.id, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.efc.pos, + d.efc.margin, + d.efc.D, + d.efc.vel, + d.efc.aref, + d.efc.frictionloss, + efc_nnz, + ], ) if not (m.opt.disableflags & types.DisableBit.FRICTIONLOSS): wp.launch( - _friction_dof, - dim=(d.nworld, m.nv), - inputs=[ - m.nv, - m.opt.timestep, - m.opt.disableflags, - m.dof_solref, - m.dof_solimp, - m.dof_frictionloss, - m.dof_invweight0, - SPARSE_CONSTRAINT_JACOBIAN, - d.qvel, - d.njmax, - ], - outputs=[ - d.nf, - d.nefc, - d.efc.type, - d.efc.id, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.pos, - d.efc.margin, - d.efc.D, - d.efc.vel, - d.efc.aref, - d.efc.frictionloss, - ], + _friction_dof, + dim=(d.nworld, m.nv), + inputs=[ + m.nv, + m.opt.timestep, + m.opt.disableflags, + m.dof_solref, + m.dof_solimp, + m.dof_frictionloss, + m.dof_invweight0, + m.is_sparse, + d.qvel, + d.njmax, + d.njmax_nnz, + ], + outputs=[ + d.nf, + d.nefc, + d.efc.type, + d.efc.id, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.efc.pos, + d.efc.margin, + d.efc.D, + d.efc.vel, + d.efc.aref, + d.efc.frictionloss, + efc_nnz, + ], ) wp.launch( - _friction_tendon, - dim=(d.nworld, m.ntendon), - inputs=[ - m.nv, - m.opt.timestep, - m.opt.disableflags, - m.tendon_solref_fri, - m.tendon_solimp_fri, - m.tendon_frictionloss, - m.tendon_invweight0, - SPARSE_CONSTRAINT_JACOBIAN, - d.qvel, - d.ten_J, - d.njmax, - ], - outputs=[ - d.nf, - d.nefc, - d.efc.type, - d.efc.id, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.pos, - d.efc.margin, - d.efc.D, - d.efc.vel, - d.efc.aref, - d.efc.frictionloss, - ], + _friction_tendon, + dim=(d.nworld, m.ntendon), + inputs=[ + m.nv, + m.opt.timestep, + m.opt.disableflags, + m.ten_J_rownnz, + m.ten_J_rowadr, + m.ten_J_colind, + m.tendon_solref_fri, + m.tendon_solimp_fri, + m.tendon_frictionloss, + m.tendon_invweight0, + m.is_sparse, + d.qvel, + d.ten_J, + d.njmax, + d.njmax_nnz, + ], + outputs=[ + d.nf, + d.nefc, + d.efc.type, + d.efc.id, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.efc.pos, + d.efc.margin, + d.efc.D, + d.efc.vel, + d.efc.aref, + d.efc.frictionloss, + efc_nnz, + ], ) # limit if not (m.opt.disableflags & types.DisableBit.LIMIT): wp.launch( - _limit_ball, - dim=(d.nworld, m.jnt_limited_ball_adr.size), - inputs=[ - m.nv, - m.opt.timestep, - m.opt.disableflags, - m.jnt_qposadr, - m.jnt_dofadr, - m.jnt_solref, - m.jnt_solimp, - m.jnt_range, - m.jnt_margin, - m.dof_invweight0, - SPARSE_CONSTRAINT_JACOBIAN, - m.jnt_limited_ball_adr, - d.qpos, - d.qvel, - d.njmax, - ], - outputs=[ - d.nl, - d.nefc, - d.efc.type, - d.efc.id, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.pos, - d.efc.margin, - d.efc.D, - d.efc.vel, - d.efc.aref, - d.efc.frictionloss, - ], + _limit_ball, + dim=(d.nworld, m.jnt_limited_ball_adr.size), + inputs=[ + m.nv, + m.opt.timestep, + m.opt.disableflags, + m.jnt_qposadr, + m.jnt_dofadr, + m.jnt_solref, + m.jnt_solimp, + m.jnt_range, + m.jnt_margin, + m.dof_invweight0, + m.is_sparse, + m.jnt_limited_ball_adr, + d.qpos, + d.qvel, + d.njmax, + d.njmax_nnz, + ], + outputs=[ + d.nl, + d.nefc, + d.efc.type, + d.efc.id, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.efc.pos, + d.efc.margin, + d.efc.D, + d.efc.vel, + d.efc.aref, + d.efc.frictionloss, + efc_nnz, + ], ) wp.launch( - _limit_slide_hinge, - dim=(d.nworld, m.jnt_limited_slide_hinge_adr.size), - inputs=[ - m.nv, - m.opt.timestep, - m.opt.disableflags, - m.jnt_qposadr, - m.jnt_dofadr, - m.jnt_solref, - m.jnt_solimp, - m.jnt_range, - m.jnt_margin, - m.dof_invweight0, - SPARSE_CONSTRAINT_JACOBIAN, - m.jnt_limited_slide_hinge_adr, - d.qpos, - d.qvel, - d.njmax, - ], - outputs=[ - d.nl, - d.nefc, - d.efc.type, - d.efc.id, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.pos, - d.efc.margin, - d.efc.D, - d.efc.vel, - d.efc.aref, - d.efc.frictionloss, - ], + _limit_slide_hinge, + dim=(d.nworld, m.jnt_limited_slide_hinge_adr.size), + inputs=[ + m.nv, + m.opt.timestep, + m.opt.disableflags, + m.jnt_qposadr, + m.jnt_dofadr, + m.jnt_solref, + m.jnt_solimp, + m.jnt_range, + m.jnt_margin, + m.dof_invweight0, + m.is_sparse, + m.jnt_limited_slide_hinge_adr, + d.qpos, + d.qvel, + d.njmax, + d.njmax_nnz, + ], + outputs=[ + d.nl, + d.nefc, + d.efc.type, + d.efc.id, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.efc.pos, + d.efc.margin, + d.efc.D, + d.efc.vel, + d.efc.aref, + d.efc.frictionloss, + efc_nnz, + ], ) wp.launch( - _limit_tendon, - dim=(d.nworld, m.tendon_limited_adr.size), - inputs=[ - m.nv, - m.opt.timestep, - m.opt.disableflags, - m.jnt_dofadr, - m.tendon_adr, - m.tendon_num, - m.tendon_solref_lim, - m.tendon_solimp_lim, - m.tendon_range, - m.tendon_margin, - m.tendon_invweight0, - m.wrap_type, - m.wrap_objid, - SPARSE_CONSTRAINT_JACOBIAN, - m.tendon_limited_adr, - d.qvel, - d.ten_J, - d.ten_length, - d.njmax, - ], - outputs=[ - d.nl, - d.nefc, - d.efc.type, - d.efc.id, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.pos, - d.efc.margin, - d.efc.D, - d.efc.vel, - d.efc.aref, - d.efc.frictionloss, - ], + _limit_tendon, + dim=(d.nworld, m.tendon_limited_adr.size), + inputs=[ + m.nv, + m.opt.timestep, + m.opt.disableflags, + m.ten_J_rownnz, + m.ten_J_rowadr, + m.ten_J_colind, + m.tendon_solref_lim, + m.tendon_solimp_lim, + m.tendon_range, + m.tendon_margin, + m.tendon_invweight0, + m.is_sparse, + m.tendon_limited_adr, + d.qvel, + d.ten_J, + d.ten_length, + d.njmax, + d.njmax_nnz, + ], + outputs=[ + d.nl, + d.nefc, + d.efc.type, + d.efc.id, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.efc.pos, + d.efc.margin, + d.efc.D, + d.efc.vel, + d.efc.aref, + d.efc.frictionloss, + efc_nnz, + ], ) # contact if not (m.opt.disableflags & types.DisableBit.CONTACT): if m.opt.cone == types.ConeType.PYRAMIDAL: wp.launch( - _contact_pyramidal, - dim=(d.naconmax, m.nmaxpyramid), - inputs=[ - m.nv, - m.opt.timestep, - m.opt.disableflags, - m.opt.impratio_invsqrt, - m.body_parentid, - m.body_rootid, - m.body_weldid, - m.body_dofnum, - m.body_dofadr, - m.body_invweight0, - m.dof_bodyid, - m.dof_parentid, - m.geom_bodyid, - SPARSE_CONSTRAINT_JACOBIAN, - d.qvel, - d.subtree_com, - d.cdof, - d.njmax, - d.nacon, - d.contact.dist, - d.contact.dim, - d.contact.includemargin, - d.contact.worldid, - d.contact.geom, - d.contact.pos, - d.contact.frame, - d.contact.friction, - d.contact.solref, - d.contact.solimp, - d.contact.type, - ], - outputs=[ - d.nefc, - d.contact.efc_address, - d.efc.type, - d.efc.id, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.pos, - d.efc.margin, - d.efc.D, - d.efc.vel, - d.efc.aref, - d.efc.frictionloss, - ], + _contact_pyramidal, + dim=(d.naconmax, m.nmaxpyramid), + inputs=[ + m.nv, + m.opt.timestep, + m.opt.disableflags, + m.opt.impratio_invsqrt, + m.body_parentid, + m.body_rootid, + m.body_weldid, + m.body_dofnum, + m.body_dofadr, + m.body_invweight0, + m.dof_bodyid, + m.dof_parentid, + m.geom_bodyid, + m.flex_vertadr, + m.flex_vertbodyid, + m.is_sparse, + d.qvel, + d.subtree_com, + d.cdof, + d.njmax, + d.njmax_nnz, + d.nacon, + d.contact.dist, + d.contact.dim, + d.contact.includemargin, + d.contact.worldid, + d.contact.geom, + d.contact.flex, + d.contact.vert, + d.contact.pos, + d.contact.frame, + d.contact.friction, + d.contact.solref, + d.contact.solimp, + d.contact.type, + ], + outputs=[ + d.nefc, + d.contact.efc_address, + d.efc.type, + d.efc.id, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.efc.pos, + d.efc.margin, + d.efc.D, + d.efc.vel, + d.efc.aref, + d.efc.frictionloss, + efc_nnz, + ], ) elif m.opt.cone == types.ConeType.ELLIPTIC: wp.launch( - _contact_elliptic, - dim=(d.naconmax, m.nmaxcondim), - inputs=[ - m.nv, - m.opt.timestep, - m.opt.disableflags, - m.opt.impratio_invsqrt, - m.body_parentid, - m.body_rootid, - m.body_weldid, - m.body_dofnum, - m.body_dofadr, - m.body_invweight0, - m.dof_bodyid, - m.dof_parentid, - m.geom_bodyid, - SPARSE_CONSTRAINT_JACOBIAN, - d.qvel, - d.subtree_com, - d.cdof, - d.njmax, - d.nacon, - d.contact.dist, - d.contact.dim, - d.contact.includemargin, - d.contact.worldid, - d.contact.geom, - d.contact.pos, - d.contact.frame, - d.contact.friction, - d.contact.solref, - d.contact.solreffriction, - d.contact.solimp, - d.contact.type, - ], - outputs=[ - d.nefc, - d.contact.efc_address, - d.efc.type, - d.efc.id, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.pos, - d.efc.margin, - d.efc.D, - d.efc.vel, - d.efc.aref, - d.efc.frictionloss, - ], + _contact_elliptic, + dim=(d.naconmax, m.nmaxcondim), + inputs=[ + m.nv, + m.opt.timestep, + m.opt.disableflags, + m.opt.impratio_invsqrt, + m.body_parentid, + m.body_rootid, + m.body_weldid, + m.body_dofnum, + m.body_dofadr, + m.body_invweight0, + m.dof_bodyid, + m.dof_parentid, + m.geom_bodyid, + m.flex_vertadr, + m.flex_vertbodyid, + m.is_sparse, + d.qvel, + d.subtree_com, + d.cdof, + d.njmax, + d.njmax_nnz, + d.nacon, + d.contact.dist, + d.contact.dim, + d.contact.includemargin, + d.contact.worldid, + d.contact.geom, + d.contact.flex, + d.contact.vert, + d.contact.pos, + d.contact.frame, + d.contact.friction, + d.contact.solref, + d.contact.solreffriction, + d.contact.solimp, + d.contact.type, + ], + outputs=[ + d.nefc, + d.contact.efc_address, + d.efc.type, + d.efc.id, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.efc.pos, + d.efc.margin, + d.efc.D, + d.efc.vel, + d.efc.aref, + d.efc.frictionloss, + efc_nnz, + ], ) diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/derivative.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/derivative.py index 406c36c4aa..20da751ac1 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/derivative.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/derivative.py @@ -15,6 +15,7 @@ import warp as wp +from mujoco.mjx.third_party.mujoco_warp._src.support import next_act from mujoco.mjx.third_party.mujoco_warp._src.types import BiasType from mujoco.mjx.third_party.mujoco_warp._src.types import Data from mujoco.mjx.third_party.mujoco_warp._src.types import DisableBit @@ -30,18 +31,24 @@ @wp.kernel def _qderiv_actuator_passive_vel( # Model: + opt_timestep: wp.array(dtype=float), actuator_dyntype: wp.array(dtype=int), actuator_gaintype: wp.array(dtype=int), actuator_biastype: wp.array(dtype=int), actuator_actadr: wp.array(dtype=int), actuator_actnum: wp.array(dtype=int), actuator_forcelimited: wp.array(dtype=bool), + actuator_actlimited: wp.array(dtype=bool), + actuator_dynprm: wp.array2d(dtype=vec10f), actuator_gainprm: wp.array2d(dtype=vec10f), actuator_biasprm: wp.array2d(dtype=vec10f), + actuator_actearly: wp.array(dtype=bool), actuator_forcerange: wp.array2d(dtype=wp.vec2), + actuator_actrange: wp.array2d(dtype=wp.vec2), # Data in: act_in: wp.array2d(dtype=float), ctrl_in: wp.array2d(dtype=float), + act_dot_in: wp.array2d(dtype=float), actuator_force_in: wp.array2d(dtype=float), # Out: vel_out: wp.array2d(dtype=float), @@ -76,9 +83,24 @@ def _qderiv_actuator_passive_vel( vel = float(bias) if actuator_dyntype[actid] != DynType.NONE: if gain != 0.0: - act_first = actuator_actadr[actid] - act_last = act_first + actuator_actnum[actid] - 1 - vel += gain * act_in[worldid, act_last] + act_adr = actuator_actadr[actid] + actuator_actnum[actid] - 1 + + # use next activation if actearly is set (matching forward pass) + if actuator_actearly[actid]: + act = next_act( + opt_timestep[worldid % opt_timestep.shape[0]], + actuator_dyntype[actid], + actuator_dynprm[worldid % actuator_dynprm.shape[0], actid], + actuator_actrange[worldid % actuator_actrange.shape[0], actid], + act_in[worldid, act_adr], + act_dot_in[worldid, act_adr], + 1.0, + actuator_actlimited[actid], + ) + else: + act = act_in[worldid, act_adr] + + vel += gain * act else: if gain != 0.0: vel += gain * ctrl_in[worldid, actid] @@ -95,21 +117,20 @@ def _nonzero_mask(x: float) -> float: @wp.kernel -def _qderiv_actuator_passive_actuation_sparse( - # Model: - nu: int, - is_sparse: bool, - # Data in: - moment_rownnz_in: wp.array2d(dtype=int), - moment_rowadr_in: wp.array2d(dtype=int), - moment_colind_in: wp.array2d(dtype=int), - actuator_moment_in: wp.array2d(dtype=float), - # In: - vel_in: wp.array2d(dtype=float), - qMi: wp.array(dtype=int), - qMj: wp.array(dtype=int), - # Out: - qDeriv_out: wp.array3d(dtype=float), +def _qderiv_actuator_passive_actuation_dense( + # Model: + nu: int, + # Data in: + moment_rownnz_in: wp.array2d(dtype=int), + moment_rowadr_in: wp.array2d(dtype=int), + moment_colind_in: wp.array2d(dtype=int), + actuator_moment_in: wp.array2d(dtype=float), + # In: + vel_in: wp.array2d(dtype=float), + qMi: wp.array(dtype=int), + qMj: wp.array(dtype=int), + # Out: + qDeriv_out: wp.array3d(dtype=float), ): worldid, elemid = wp.tid() @@ -142,12 +163,63 @@ def _qderiv_actuator_passive_actuation_sparse( qderiv_contrib += moment_i * moment_j * vel - if is_sparse: - qDeriv_out[worldid, 0, elemid] = qderiv_contrib - else: - qDeriv_out[worldid, dofiid, dofjid] = qderiv_contrib - if dofiid != dofjid: - qDeriv_out[worldid, dofjid, dofiid] = qderiv_contrib + qDeriv_out[worldid, dofiid, dofjid] = qderiv_contrib + if dofiid != dofjid: + qDeriv_out[worldid, dofjid, dofiid] = qderiv_contrib + + +@wp.kernel +def _qderiv_actuator_passive_actuation_sparse( + # Model: + M_rownnz: wp.array(dtype=int), + M_rowadr: wp.array(dtype=int), + # Data in: + moment_rownnz_in: wp.array2d(dtype=int), + moment_rowadr_in: wp.array2d(dtype=int), + moment_colind_in: wp.array2d(dtype=int), + actuator_moment_in: wp.array2d(dtype=float), + # In: + vel_in: wp.array2d(dtype=float), + qMj: wp.array(dtype=int), + # Out: + qDeriv_out: wp.array3d(dtype=float), +): + worldid, actid = wp.tid() + + vel = vel_in[worldid, actid] + if vel == 0.0: + return + + rownnz = moment_rownnz_in[worldid, actid] + rowadr = moment_rowadr_in[worldid, actid] + + for i in range(rownnz): + rowadri = rowadr + i + moment_i = actuator_moment_in[worldid, rowadri] + if moment_i == 0.0: + continue + dofi = moment_colind_in[worldid, rowadri] + + for j in range(i + 1): + rowadrj = rowadr + j + moment_j = actuator_moment_in[worldid, rowadrj] + if moment_j == 0.0: + continue + dofj = moment_colind_in[worldid, rowadrj] + + contrib = moment_i * moment_j * vel + + # Search the corresponding elemid + # TODO: This could be precalculated for improved performance + row = dofi + col = dofj + row_startk = M_rowadr[row] - 1 + row_nnz = M_rownnz[row] + for k in range(row_nnz): + row_startk += 1 + if qMj[row_startk] == col: + wp.atomic_add(qDeriv_out[worldid, 0], row_startk, contrib) + break @wp.kernel @@ -176,7 +248,7 @@ def _qderiv_actuator_passive( else: qderiv = qDeriv_in[worldid, dofiid, dofjid] - if not opt_disableflags & DisableBit.DAMPER and dofiid == dofjid: + if not (opt_disableflags & DisableBit.DAMPER) and dofiid == dofjid: qderiv -= dof_damping[worldid % dof_damping.shape[0], dofiid] qderiv *= opt_timestep[worldid % opt_timestep.shape[0]] @@ -196,10 +268,13 @@ def _qderiv_tendon_damping( # Model: ntendon: int, opt_timestep: wp.array(dtype=float), + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), tendon_damping: wp.array2d(dtype=float), is_sparse: bool, # Data in: - ten_J_in: wp.array3d(dtype=float), + ten_J_in: wp.array2d(dtype=float), # In: qMi: wp.array(dtype=int), qMj: wp.array(dtype=int), @@ -213,7 +288,24 @@ def _qderiv_tendon_damping( qderiv = float(0.0) tendon_damping_id = worldid % tendon_damping.shape[0] for tenid in range(ntendon): - qderiv -= ten_J_in[worldid, tenid, dofiid] * ten_J_in[worldid, tenid, dofjid] * tendon_damping[tendon_damping_id, tenid] + damping = tendon_damping[tendon_damping_id, tenid] + if damping == 0.0: + continue + + rownnz = ten_J_rownnz[tenid] + rowadr = ten_J_rowadr[tenid] + Ji = float(0.0) + Jj = float(0.0) + for k in range(rownnz): + if Ji != 0.0 and Jj != 0.0: + break + sparseid = rowadr + k + colind = ten_J_colind[sparseid] + if colind == dofiid: + Ji = ten_J_in[worldid, sparseid] + if colind == dofjid: + Jj = ten_J_in[worldid, sparseid] + qderiv -= Ji * Jj * damping qderiv *= opt_timestep[worldid % opt_timestep.shape[0]] @@ -242,43 +334,47 @@ def deriv_smooth_vel(m: Model, d: Data, out: wp.array2d(dtype=float)): if ~(m.opt.disableflags & (DisableBit.ACTUATION | DisableBit.DAMPER)): # TODO(team): only clear elements not set by _qderiv_actuator_passive out.zero_() - if m.nu > 0 and not m.opt.disableflags & DisableBit.ACTUATION: + if m.nu > 0 and not (m.opt.disableflags & DisableBit.ACTUATION): vel = wp.empty((d.nworld, m.nu), dtype=float) wp.launch( _qderiv_actuator_passive_vel, dim=(d.nworld, m.nu), inputs=[ + m.opt.timestep, m.actuator_dyntype, m.actuator_gaintype, m.actuator_biastype, m.actuator_actadr, m.actuator_actnum, m.actuator_forcelimited, + m.actuator_actlimited, + m.actuator_dynprm, m.actuator_gainprm, m.actuator_biasprm, + m.actuator_actearly, m.actuator_forcerange, + m.actuator_actrange, d.act, d.ctrl, + d.act_dot, d.actuator_force, ], outputs=[vel], ) - wp.launch( + if m.is_sparse: + wp.launch( _qderiv_actuator_passive_actuation_sparse, + dim=(d.nworld, m.nu), + inputs=[m.M_rownnz, m.M_rowadr, d.moment_rownnz, d.moment_rowadr, d.moment_colind, d.actuator_moment, vel, qMj], + outputs=[out], + ) + else: + wp.launch( + _qderiv_actuator_passive_actuation_dense, dim=(d.nworld, qMi.size), - inputs=[ - m.nu, - m.is_sparse, - d.moment_rownnz, - d.moment_rowadr, - d.moment_colind, - d.actuator_moment, - vel, - qMi, - qMj, - ], + inputs=[m.nu, d.moment_rownnz, d.moment_rowadr, d.moment_colind, d.actuator_moment, vel, qMi, qMj], outputs=[out], - ) + ) wp.launch( _qderiv_actuator_passive, dim=(d.nworld, qMi.size), @@ -298,11 +394,22 @@ def deriv_smooth_vel(m: Model, d: Data, out: wp.array2d(dtype=float)): # TODO(team): directly utilize qM for these settings wp.copy(out, d.qM) - if not m.opt.disableflags & DisableBit.DAMPER: + if not (m.opt.disableflags & DisableBit.DAMPER): wp.launch( _qderiv_tendon_damping, dim=(d.nworld, qMi.size), - inputs=[m.ntendon, m.opt.timestep, m.tendon_damping, m.is_sparse, d.ten_J, qMi, qMj], + inputs=[ + m.ntendon, + m.opt.timestep, + m.ten_J_rownnz, + m.ten_J_rowadr, + m.ten_J_colind, + m.tendon_damping, + m.is_sparse, + d.ten_J, + qMi, + qMj, + ], outputs=[out], ) diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/forward.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/forward.py index 0dc3de14eb..64bdd91f5f 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/forward.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/forward.py @@ -15,6 +15,8 @@ from typing import Optional +import warp as wp + from mujoco.mjx.third_party.mujoco_warp._src import collision_driver from mujoco.mjx.third_party.mujoco_warp._src import constraint from mujoco.mjx.third_party.mujoco_warp._src import derivative @@ -25,7 +27,9 @@ from mujoco.mjx.third_party.mujoco_warp._src import smooth from mujoco.mjx.third_party.mujoco_warp._src import solver from mujoco.mjx.third_party.mujoco_warp._src import util_misc +from mujoco.mjx.third_party.mujoco_warp._src.support import next_act from mujoco.mjx.third_party.mujoco_warp._src.support import xfrc_accumulate +from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MINVAL from mujoco.mjx.third_party.mujoco_warp._src.types import BiasType from mujoco.mjx.third_party.mujoco_warp._src.types import Data from mujoco.mjx.third_party.mujoco_warp._src.types import DisableBit @@ -34,14 +38,12 @@ from mujoco.mjx.third_party.mujoco_warp._src.types import GainType from mujoco.mjx.third_party.mujoco_warp._src.types import IntegratorType from mujoco.mjx.third_party.mujoco_warp._src.types import JointType -from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MINVAL from mujoco.mjx.third_party.mujoco_warp._src.types import Model from mujoco.mjx.third_party.mujoco_warp._src.types import TileSet from mujoco.mjx.third_party.mujoco_warp._src.types import TrnType from mujoco.mjx.third_party.mujoco_warp._src.types import vec10f from mujoco.mjx.third_party.mujoco_warp._src.warp_util import cache_kernel from mujoco.mjx.third_party.mujoco_warp._src.warp_util import event_scope -import warp as wp wp.set_module_options({"enable_backward": False}) @@ -127,55 +129,24 @@ def _next_velocity( qvel_out[worldid, dofid] = qvel_in[worldid, dofid] + qacc_scale_in * qacc_in[worldid, dofid] * timestep -# TODO(team): kernel analyzer array slice? -@wp.func -def _next_act( +@wp.kernel +def _next_activation( # Model: - opt_timestep: float, # kernel_analyzer: ignore - actuator_dyntype: int, # kernel_analyzer: ignore - actuator_dynprm: vec10f, # kernel_analyzer: ignore - actuator_actrange: wp.vec2, # kernel_analyzer: ignore - # Data In: - act_in: float, # kernel_analyzer: ignore - act_dot_in: float, # kernel_analyzer: ignore + opt_timestep: wp.array(dtype=float), + actuator_dyntype: wp.array(dtype=int), + actuator_actadr: wp.array(dtype=int), + actuator_actnum: wp.array(dtype=int), + actuator_actlimited: wp.array(dtype=bool), + actuator_dynprm: wp.array2d(dtype=vec10f), + actuator_actrange: wp.array2d(dtype=wp.vec2), + # Data in: + act_in: wp.array2d(dtype=float), + act_dot_in: wp.array2d(dtype=float), # In: act_dot_scale: float, - clamp: bool, -) -> float: - # advance actuation - if actuator_dyntype == DynType.FILTEREXACT: - tau = wp.max(MJ_MINVAL, actuator_dynprm[0]) - act = act_in + act_dot_scale * act_dot_in * tau * (1.0 - wp.exp(-opt_timestep / tau)) - elif actuator_dyntype == DynType.USER: - return act_in - else: - act = act_in + act_dot_scale * act_dot_in * opt_timestep - - # clamp to actrange - if clamp: - act = wp.clamp(act, actuator_actrange[0], actuator_actrange[1]) - - return act - - -@wp.kernel -def _next_activation( - # Model: - opt_timestep: wp.array(dtype=float), - actuator_dyntype: wp.array(dtype=int), - actuator_actadr: wp.array(dtype=int), - actuator_actnum: wp.array(dtype=int), - actuator_actlimited: wp.array(dtype=bool), - actuator_dynprm: wp.array2d(dtype=vec10f), - actuator_actrange: wp.array2d(dtype=wp.vec2), - # Data in: - act_in: wp.array2d(dtype=float), - act_dot_in: wp.array2d(dtype=float), - # In: - act_dot_scale: float, - limit: bool, - # Data out: - act_out: wp.array2d(dtype=float), + limit: bool, + # Data out: + act_out: wp.array2d(dtype=float), ): worldid, uid = wp.tid() opt_timestep_id = worldid % opt_timestep.shape[0] @@ -184,15 +155,15 @@ def _next_activation( actadr = actuator_actadr[uid] actnum = actuator_actnum[uid] for j in range(actadr, actadr + actnum): - act = _next_act( - opt_timestep[opt_timestep_id], - actuator_dyntype[uid], - actuator_dynprm[actuator_dynprm_id, uid], - actuator_actrange[actuator_actrange_id, uid], - act_in[worldid, j], - act_dot_in[worldid, j], - act_dot_scale, - limit and actuator_actlimited[uid], + act = next_act( + opt_timestep[opt_timestep_id], + actuator_dyntype[uid], + actuator_dynprm[actuator_dynprm_id, uid], + actuator_actrange[actuator_actrange_id, uid], + act_in[worldid, j], + act_dot_in[worldid, j], + act_dot_scale, + limit and actuator_actlimited[uid], ) act_out[worldid, j] = act @@ -201,12 +172,16 @@ def _next_activation( def _next_time( # Model: opt_timestep: wp.array(dtype=float), + is_sparse: bool, # Data in: nefc_in: wp.array(dtype=int), time_in: wp.array(dtype=float), + efc_J_rownnz_in: wp.array2d(dtype=int), + efc_J_rowadr_in: wp.array2d(dtype=int), nworld_in: int, naconmax_in: int, njmax_in: int, + njmax_nnz_in: int, nacon_in: wp.array(dtype=int), ncollision_in: wp.array(dtype=int), # Data out: @@ -218,6 +193,11 @@ def _next_time( if nefc > njmax_in: wp.printf("nefc overflow - please increase njmax to %u\n", nefc) + elif nefc > 0 and is_sparse: + efcid = wp.min(nefc, njmax_in) - 1 + efc_nnz = efc_J_rowadr_in[worldid, efcid] + efc_J_rownnz_in[worldid, efcid] + if efc_nnz > njmax_nnz_in: + wp.printf("njmax_nnz overflow - please increase njmax_nnz to %u\n", efc_nnz) if worldid == 0: ncollision = ncollision_in[0] @@ -236,22 +216,22 @@ def _advance(m: Model, d: Data, qacc: wp.array, qvel: Optional[wp.array] = None) # advance activations wp.launch( - _next_activation, - dim=(d.nworld, m.nu), - inputs=[ - m.opt.timestep, - m.actuator_dyntype, - m.actuator_actadr, - m.actuator_actnum, - m.actuator_actlimited, - m.actuator_dynprm, - m.actuator_actrange, - d.act, - d.act_dot, - 1.0, - True, - ], - outputs=[d.act], + _next_activation, + dim=(d.nworld, m.nu), + inputs=[ + m.opt.timestep, + m.actuator_dyntype, + m.actuator_actadr, + m.actuator_actnum, + m.actuator_actlimited, + m.actuator_dynprm, + m.actuator_actrange, + d.act, + d.act_dot, + 1.0, + True, + ], + outputs=[d.act], ) wp.launch( @@ -274,7 +254,20 @@ def _advance(m: Model, d: Data, qacc: wp.array, qvel: Optional[wp.array] = None) wp.launch( _next_time, dim=d.nworld, - inputs=[m.opt.timestep, d.nefc, d.time, d.nworld, d.naconmax, d.njmax, d.nacon, d.ncollision], + inputs=[ + m.opt.timestep, + m.is_sparse, + d.nefc, + d.time, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.nworld, + d.naconmax, + d.njmax, + d.njmax_nnz, + d.nacon, + d.ncollision, + ], outputs=[d.time], ) @@ -294,9 +287,7 @@ def _euler_damp_qfrc_sparse( timestep = opt_timestep[worldid % opt_timestep.shape[0]] adr = dof_Madr[tid] - qM_integration_out[worldid, 0, adr] += ( - timestep * dof_damping[worldid % dof_damping.shape[0], tid] - ) + qM_integration_out[worldid, 0, adr] += timestep * dof_damping[worldid % dof_damping.shape[0], tid] @cache_kernel @@ -336,7 +327,7 @@ def euler_dense( def euler(m: Model, d: Data): """Euler integrator, semi-implicit in velocity.""" # integrate damping implicitly - if not m.opt.disableflags & (DisableBit.EULERDAMP | DisableBit.DAMPER): + if not (m.opt.disableflags & (DisableBit.EULERDAMP | DisableBit.DAMPER)): qacc = wp.empty((d.nworld, m.nv), dtype=float) if m.is_sparse: qM = wp.clone(d.qM) @@ -390,22 +381,22 @@ def _rk_perturb_state( # activation if m.na and act_t0 is not None: wp.launch( - _next_activation, - dim=(d.nworld, m.nu), - inputs=[ - m.opt.timestep, - m.actuator_dyntype, - m.actuator_actadr, - m.actuator_actnum, - m.actuator_actlimited, - m.actuator_dynprm, - m.actuator_actrange, - act_t0, - d.act_dot, - scale, - False, - ], - outputs=[d.act], + _next_activation, + dim=(d.nworld, m.nu), + inputs=[ + m.opt.timestep, + m.actuator_dyntype, + m.actuator_actadr, + m.actuator_actnum, + m.actuator_actlimited, + m.actuator_dynprm, + m.actuator_actrange, + act_t0, + d.act_dot, + scale, + False, + ], + outputs=[d.act], ) @@ -548,14 +539,14 @@ def fwd_position(m: Model, d: Data, factorize: bool = True): @wp.kernel def _actuator_velocity( - # Data in: - qvel_in: wp.array2d(dtype=float), - moment_rownnz_in: wp.array2d(dtype=int), - moment_rowadr_in: wp.array2d(dtype=int), - moment_colind_in: wp.array2d(dtype=int), - actuator_moment_in: wp.array2d(dtype=float), - # Data out: - actuator_velocity_out: wp.array2d(dtype=float), + # Data in: + qvel_in: wp.array2d(dtype=float), + moment_rownnz_in: wp.array2d(dtype=int), + moment_rowadr_in: wp.array2d(dtype=int), + moment_colind_in: wp.array2d(dtype=int), + actuator_moment_in: wp.array2d(dtype=float), + # Data out: + actuator_velocity_out: wp.array2d(dtype=float), ): worldid, actid = wp.tid() @@ -571,50 +562,49 @@ def _actuator_velocity( actuator_velocity_out[worldid, actid] = vel -@cache_kernel -def _tendon_velocity(nv: int): - @wp.kernel(module="unique", enable_backward=False) - def tendon_velocity( - # Data in: - qvel_in: wp.array2d(dtype=float), - ten_J_in: wp.array3d(dtype=float), - # Data out: - ten_velocity_out: wp.array2d(dtype=float), - ): - worldid, tenid = wp.tid() - ten_J_tile = wp.tile_load(ten_J_in[worldid, tenid], shape=wp.static(nv)) - qvel_tile = wp.tile_load(qvel_in[worldid], shape=wp.static(nv)) - ten_J_qvel_tile = wp.tile_map(wp.mul, ten_J_tile, qvel_tile) - ten_velocity_tile = wp.tile_reduce(wp.add, ten_J_qvel_tile) - ten_velocity_out[worldid, tenid] = ten_velocity_tile[0] +@wp.kernel +def _tendon_velocity( + # Model: + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), + # Data in: + qvel_in: wp.array2d(dtype=float), + ten_J_in: wp.array2d(dtype=float), + # Data out: + ten_velocity_out: wp.array2d(dtype=float), +): + worldid, tenid = wp.tid() - return tendon_velocity + velocity = float(0.0) + rownnz = ten_J_rownnz[tenid] + rowadr = ten_J_rowadr[tenid] + for i in range(rownnz): + sparseid = rowadr + i + J = ten_J_in[worldid, sparseid] + if J != 0.0: + colind = ten_J_colind[sparseid] + velocity += J * qvel_in[worldid, colind] + + ten_velocity_out[worldid, tenid] = velocity @event_scope def fwd_velocity(m: Model, d: Data): """Velocity-dependent computations.""" - wp.launch_tiled( - _actuator_velocity, - dim=(d.nworld, m.nu), - inputs=[ - d.qvel, - d.moment_rownnz, - d.moment_rowadr, - d.moment_colind, - d.actuator_moment, - ], - outputs=[d.actuator_velocity], - block_dim=m.block_dim.actuator_velocity, + wp.launch( + _actuator_velocity, + dim=(d.nworld, m.nu), + inputs=[d.qvel, d.moment_rownnz, d.moment_rowadr, d.moment_colind, d.actuator_moment], + outputs=[d.actuator_velocity], + block_dim=m.block_dim.actuator_velocity, ) - # TODO(team): sparse version - wp.launch_tiled( - _tendon_velocity(m.nv), + wp.launch( + _tendon_velocity, dim=(d.nworld, m.ntendon), - inputs=[d.qvel, d.ten_J], + inputs=[m.ten_J_rownnz, m.ten_J_rowadr, m.ten_J_colind, d.qvel, d.ten_J], outputs=[d.ten_velocity], - block_dim=m.block_dim.tendon_velocity, ) smooth.com_vel(m, d) @@ -625,36 +615,36 @@ def fwd_velocity(m: Model, d: Data): @wp.kernel def _actuator_force( - # Model: - na: int, - opt_timestep: wp.array(dtype=float), - actuator_dyntype: wp.array(dtype=int), - actuator_gaintype: wp.array(dtype=int), - actuator_biastype: wp.array(dtype=int), - actuator_actadr: wp.array(dtype=int), - actuator_actnum: wp.array(dtype=int), - actuator_ctrllimited: wp.array(dtype=bool), - actuator_forcelimited: wp.array(dtype=bool), - actuator_actlimited: wp.array(dtype=bool), - actuator_dynprm: wp.array2d(dtype=vec10f), - actuator_gainprm: wp.array2d(dtype=vec10f), - actuator_biasprm: wp.array2d(dtype=vec10f), - actuator_actearly: wp.array(dtype=bool), - actuator_ctrlrange: wp.array2d(dtype=wp.vec2), - actuator_forcerange: wp.array2d(dtype=wp.vec2), - actuator_actrange: wp.array2d(dtype=wp.vec2), - actuator_acc0: wp.array2d(dtype=float), - actuator_lengthrange: wp.array2d(dtype=wp.vec2), - # Data in: - act_in: wp.array2d(dtype=float), - ctrl_in: wp.array2d(dtype=float), - actuator_length_in: wp.array2d(dtype=float), - actuator_velocity_in: wp.array2d(dtype=float), - # In: - dsbl_clampctrl: int, - # Data out: - act_dot_out: wp.array2d(dtype=float), - actuator_force_out: wp.array2d(dtype=float), + # Model: + na: int, + opt_timestep: wp.array(dtype=float), + actuator_dyntype: wp.array(dtype=int), + actuator_gaintype: wp.array(dtype=int), + actuator_biastype: wp.array(dtype=int), + actuator_actadr: wp.array(dtype=int), + actuator_actnum: wp.array(dtype=int), + actuator_ctrllimited: wp.array(dtype=bool), + actuator_forcelimited: wp.array(dtype=bool), + actuator_actlimited: wp.array(dtype=bool), + actuator_dynprm: wp.array2d(dtype=vec10f), + actuator_gainprm: wp.array2d(dtype=vec10f), + actuator_biasprm: wp.array2d(dtype=vec10f), + actuator_actearly: wp.array(dtype=bool), + actuator_ctrlrange: wp.array2d(dtype=wp.vec2), + actuator_forcerange: wp.array2d(dtype=wp.vec2), + actuator_actrange: wp.array2d(dtype=wp.vec2), + actuator_acc0: wp.array2d(dtype=float), + actuator_lengthrange: wp.array2d(dtype=wp.vec2), + # Data in: + act_in: wp.array2d(dtype=float), + ctrl_in: wp.array2d(dtype=float), + actuator_length_in: wp.array2d(dtype=float), + actuator_velocity_in: wp.array2d(dtype=float), + # In: + dsbl_clampctrl: int, + # Data out: + act_dot_out: wp.array2d(dtype=float), + actuator_force_out: wp.array2d(dtype=float), ): worldid, uid = wp.tid() @@ -693,7 +683,7 @@ def _actuator_force( if dyntype == DynType.INTEGRATOR or dyntype == DynType.NONE: act = act_in[worldid, act_last] - ctrl_act = _next_act( + ctrl_act = next_act( opt_timestep[worldid % opt_timestep.shape[0]], dyntype, dynprm, @@ -720,9 +710,7 @@ def _actuator_force( gain = gainprm[0] + gainprm[1] * length + gainprm[2] * velocity elif gaintype == GainType.MUSCLE: acc0 = actuator_acc0[worldid % actuator_acc0.shape[0], uid] - lengthrange = actuator_lengthrange[ - worldid % actuator_lengthrange.shape[0], uid - ] + lengthrange = actuator_lengthrange[worldid % actuator_lengthrange.shape[0], uid] gain = util_misc.muscle_gain(length, velocity, lengthrange, acc0, gainprm) # GainType.USER: gain stays 0, modified by act_gain_callback @@ -735,9 +723,7 @@ def _actuator_force( bias = biasprm[0] + biasprm[1] * length + biasprm[2] * velocity elif biastype == BiasType.MUSCLE: acc0 = actuator_acc0[worldid % actuator_acc0.shape[0], uid] - lengthrange = actuator_lengthrange[ - worldid % actuator_lengthrange.shape[0], uid - ] + lengthrange = actuator_lengthrange[worldid % actuator_lengthrange.shape[0], uid] bias = util_misc.muscle_bias(length, lengthrange, acc0, biasprm) force = gain * ctrl_act + bias @@ -795,14 +781,14 @@ def _tendon_actuator_force_clamp( @wp.kernel def _qfrc_actuator( - # Data in: - moment_rownnz_in: wp.array2d(dtype=int), - moment_rowadr_in: wp.array2d(dtype=int), - moment_colind_in: wp.array2d(dtype=int), - actuator_moment_in: wp.array2d(dtype=float), - actuator_force_in: wp.array2d(dtype=float), - # Data out: - qfrc_actuator_out: wp.array2d(dtype=float), + # Data in: + moment_rownnz_in: wp.array2d(dtype=int), + moment_rowadr_in: wp.array2d(dtype=int), + moment_colind_in: wp.array2d(dtype=int), + actuator_moment_in: wp.array2d(dtype=float), + actuator_force_in: wp.array2d(dtype=float), + # Data out: + qfrc_actuator_out: wp.array2d(dtype=float), ): worldid, actid = wp.tid() @@ -812,26 +798,23 @@ def _qfrc_actuator( for i in range(rownnz): sparseid = rowadr + i colind = moment_colind_in[worldid, sparseid] - qfrc = ( - actuator_moment_in[worldid, sparseid] - * actuator_force_in[worldid, actid] - ) + qfrc = actuator_moment_in[worldid, sparseid] * actuator_force_in[worldid, actid] wp.atomic_add(qfrc_actuator_out[worldid], colind, qfrc) @wp.kernel def _qfrc_actuator_gravcomp_limits( - # Model: - ngravcomp: int, - jnt_actfrclimited: wp.array(dtype=bool), - jnt_actgravcomp: wp.array(dtype=int), - jnt_actfrcrange: wp.array2d(dtype=wp.vec2), - dof_jntid: wp.array(dtype=int), - # Data in: - qfrc_gravcomp_in: wp.array2d(dtype=float), - qfrc_actuator_in: wp.array2d(dtype=float), - # Data out: - qfrc_actuator_out: wp.array2d(dtype=float), + # Model: + ngravcomp: int, + jnt_actfrclimited: wp.array(dtype=bool), + jnt_actgravcomp: wp.array(dtype=int), + jnt_actfrcrange: wp.array2d(dtype=wp.vec2), + dof_jntid: wp.array(dtype=int), + # Data in: + qfrc_gravcomp_in: wp.array2d(dtype=float), + qfrc_actuator_in: wp.array2d(dtype=float), + # Data out: + qfrc_actuator_out: wp.array2d(dtype=float), ): worldid, dofid = wp.tid() jntid = dof_jntid[dofid] @@ -917,30 +900,30 @@ def fwd_actuation(m: Model, d: Data): # TODO(team): optimize performance d.qfrc_actuator.zero_() wp.launch( - _qfrc_actuator, - dim=(d.nworld, m.nu), - inputs=[ - d.moment_rownnz, - d.moment_rowadr, - d.moment_colind, - d.actuator_moment, - d.actuator_force, - ], - outputs=[d.qfrc_actuator], + _qfrc_actuator, + dim=(d.nworld, m.nu), + inputs=[ + d.moment_rownnz, + d.moment_rowadr, + d.moment_colind, + d.actuator_moment, + d.actuator_force, + ], + outputs=[d.qfrc_actuator], ) wp.launch( - _qfrc_actuator_gravcomp_limits, - dim=(d.nworld, m.nv), - inputs=[ - m.ngravcomp, - m.jnt_actfrclimited, - m.jnt_actgravcomp, - m.jnt_actfrcrange, - m.dof_jntid, - d.qfrc_gravcomp, - d.qfrc_actuator, - ], - outputs=[d.qfrc_actuator], + _qfrc_actuator_gravcomp_limits, + dim=(d.nworld, m.nv), + inputs=[ + m.ngravcomp, + m.jnt_actfrclimited, + m.jnt_actgravcomp, + m.jnt_actfrcrange, + m.dof_jntid, + d.qfrc_gravcomp, + d.qfrc_actuator, + ], + outputs=[d.qfrc_actuator], ) diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/io.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/io.py index e516739cb9..0b53094bd2 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/io.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/io.py @@ -14,24 +14,24 @@ # ============================================================================== import dataclasses -from typing import Any, Optional, Sequence import warnings +from typing import Any, Optional, Sequence import mujoco +import numpy as np +import warp as wp + from mujoco.mjx.third_party.mujoco_warp._src import bvh from mujoco.mjx.third_party.mujoco_warp._src import math as mjmath from mujoco.mjx.third_party.mujoco_warp._src import render_util from mujoco.mjx.third_party.mujoco_warp._src import smooth from mujoco.mjx.third_party.mujoco_warp._src import types from mujoco.mjx.third_party.mujoco_warp._src import warp_util -from mujoco.mjx.third_party.mujoco_warp._src.types import BiasType from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MINVAL -from mujoco.mjx.third_party.mujoco_warp._src.types import SPARSE_CONSTRAINT_JACOBIAN +from mujoco.mjx.third_party.mujoco_warp._src.types import BiasType from mujoco.mjx.third_party.mujoco_warp._src.types import TrnType from mujoco.mjx.third_party.mujoco_warp._src.types import vec10 from mujoco.mjx.third_party.mujoco_warp._src.util_pkg import check_version -import numpy as np -import warp as wp def _create_array(data: Any, spec: wp.array, sizes: dict[str, int]) -> wp.array | None: @@ -114,9 +114,6 @@ def put_model(mjm: mujoco.MjModel) -> types.Model: if unsupported: raise NotImplementedError(f"{mj_type(unsupported).name} is unsupported.") - if ((mjm.flex_contype != 0) | (mjm.flex_conaffinity != 0)).any(): - raise NotImplementedError("Flex collisions are not implemented.") - if mjm.opt.noslip_iterations > 0: raise NotImplementedError(f"noslip solver not implemented.") @@ -226,6 +223,8 @@ def _check_friction(name: str, id_: int, condim: int, friction, checks): m.is_sparse = is_sparse(mjm) m.has_fluid = mjm.opt.wind.any() or mjm.opt.density > 0 or mjm.opt.viscosity > 0 + m.max_ten_J_rownnz = int(mjm.ten_J_rownnz.max()) if mjm.ntendon else 0 + # body ids grouped by tree level (depth-based traversal) bodies, body_depth = {}, np.zeros(mjm.nbody, dtype=int) - 1 for i in range(mjm.nbody): @@ -364,6 +363,46 @@ def geom_trid_index(i, j): ) ) + # check for unsupported margin + multicontact / box-box CCD combinations + use_multiccd = mjm.opt.enableflags & types.EnableBit.MULTICCD + nativeccd_disabled = mjm.opt.disableflags & types.DisableBit.NATIVECCD + BOX = int(mujoco.mjtGeom.mjGEOM_BOX) + MESH = int(mujoco.mjtGeom.mjGEOM_MESH) + + has_boxbox = m.geom_pair_type_count[geom_trid_index(BOX, BOX)] > 0 + has_multiccd_pairs = has_boxbox or ( + use_multiccd + and (m.geom_pair_type_count[geom_trid_index(BOX, MESH)] > 0 or m.geom_pair_type_count[geom_trid_index(MESH, MESH)] > 0) + ) + + if has_multiccd_pairs: + + def _check_margin(name, t1, t2, margin): + if use_multiccd: + raise NotImplementedError( + f"{name} has non-zero margin ({margin}) with MULTICCD enabled. Set margin to 0 or disable MULTICCD." + ) + if t1 == BOX and t2 == BOX and not nativeccd_disabled: + raise NotImplementedError( + f"{name} has non-zero margin ({margin}) with NATIVECCD enabled. Set margin to 0 or disable NATIVECCD." + ) + + geom_name = lambda g: mujoco.mj_id2name(mjm, mujoco.mjtObj.mjOBJ_GEOM, g) or str(g) + + for idx in np.nonzero(nxn_include & (nxn_pairid_contact == -1))[0]: + g1, g2 = int(geom1[idx]), int(geom2[idx]) + t1, t2 = int(mjm.geom_type[g1]), int(mjm.geom_type[g2]) + m1, m2 = float(mjm.geom_margin[g1]), float(mjm.geom_margin[g2]) + if (m1 or m2) and t1 in (BOX, MESH) and t2 in (BOX, MESH): + _check_margin(f"geom pair ({geom_name(g1)}, {geom_name(g2)})", t1, t2, (m1, m2)) + + for pid in range(mjm.npair): + g1, g2 = int(mjm.pair_geom1[pid]), int(mjm.pair_geom2[pid]) + t1, t2 = int(mjm.geom_type[g1]), int(mjm.geom_type[g2]) + pm = float(mjm.pair_margin[pid]) + if pm and t1 in (BOX, MESH) and t2 in (BOX, MESH): + _check_margin(f"pair {pid} ({geom_name(g1)}, {geom_name(g2)})", t1, t2, pm) + m.nmaxpolygon = np.append(mjm.mesh_polyvertnum, 0).max() m.nmaxmeshdeg = np.append(mjm.mesh_polymapnum, 0).max() @@ -390,9 +429,11 @@ def geom_trid_index(i, j): current = [] else: current.append(v) - # Pad with zeros if less than 3 - attr_values += [0.0] * (3 - len(attr_values)) - m.plugin_attr.append(attr_values[:3]) + if len(attr_values) > types._NPLUGINATTR: + raise ValueError(f"Plugin has {len(attr_values)} attributes, which exceeds the maximum of {types._NPLUGINATTR}. ") + # pad with zeros to _NPLUGINATTR + attr_values += [0.0] * (types._NPLUGINATTR - len(attr_values)) + m.plugin_attr.append(attr_values[: types._NPLUGINATTR]) # equality constraint addresses m.eq_connect_adr = np.nonzero(mjm.eq_type == types.EqType.CONNECT)[0] @@ -542,6 +583,15 @@ def geom_trid_index(i, j): Madr_ki -= 1 m.qLD_updates = tuple(wp.array(qLD_updates[i], dtype=wp.vec3i) for i in sorted(qLD_updates)) + # Build concatenated updates for fused kernel + all_updates_flat = [] + level_offsets = [0] + for level in sorted(qLD_updates): + all_updates_flat.extend(qLD_updates[level]) + level_offsets.append(len(all_updates_flat)) + m.qLD_all_updates = all_updates_flat if all_updates_flat else [(0, 0, 0)] + m.qLD_level_offsets = level_offsets + # indices for sparse qM_fullm (used in solver) m.qM_fullm_i, m.qM_fullm_j = [], [] for i in range(mjm.nv): @@ -631,9 +681,168 @@ def _default_njmax(mjm: mujoco.MjModel, mjd: Optional[mujoco.MjData] = None) -> return int(valid_sizes[np.searchsorted(valid_sizes, njmax)]) -def _resolve_batch_size( - na: int | None, n: int | None, nworld: int, default: int -) -> int: +def _body_pair_nnz(mjm: mujoco.MjModel, body1: int, body2: int) -> int: + """Returns the number of unique DOFs in the kinematic tree union of two bodies.""" + body1 = mjm.body_weldid[body1] + body2 = mjm.body_weldid[body2] + da1 = mjm.body_dofadr[body1] + mjm.body_dofnum[body1] - 1 + da2 = mjm.body_dofadr[body2] + mjm.body_dofnum[body2] - 1 + nnz = 0 + while da1 >= 0 or da2 >= 0: + da = max(da1, da2) + if da1 == da: + da1 = mjm.dof_parentid[da1] + if da2 == da: + da2 = mjm.dof_parentid[da2] + nnz += 1 + return nnz + + +def _default_njmax_nnz(mjm: mujoco.MjModel, nconmax: int, njmax: int) -> int: + """Returns a heuristic estimate for the number of non-zeros in the sparse constraint Jacobian. + + Assumes all equality, friction, and limit constraints are active and computes + their non-zeros. For contacts, assumes njmax contact rows at the maximum + body-pair non-zeros from all enabled collision pairs. + + Args: + mjm: The model containing kinematic and dynamic information (host). + nconmax: Maximum number of contacts per world. + njmax: Maximum number of constraint rows per world. + + Returns: + Estimated number of non-zeros in the constraint Jacobian. + """ + total_nnz = 0 + + def _eq_bodies(i): + """Returns body pair for equality constraint i.""" + obj1id, obj2id = mjm.eq_obj1id[i], mjm.eq_obj2id[i] + if mjm.eq_objtype[i] == mujoco.mjtObj.mjOBJ_SITE: + return mjm.site_bodyid[obj1id], mjm.site_bodyid[obj2id] + return obj1id, obj2id + + # equality constraints (assume all active) + for i in range(mjm.neq): + eq_type = mjm.eq_type[i] + + if eq_type == mujoco.mjtEq.mjEQ_CONNECT: + total_nnz += 3 * _body_pair_nnz(mjm, *_eq_bodies(i)) + + elif eq_type == mujoco.mjtEq.mjEQ_WELD: + total_nnz += 6 * _body_pair_nnz(mjm, *_eq_bodies(i)) + + elif eq_type == mujoco.mjtEq.mjEQ_JOINT: + total_nnz += 2 if mjm.eq_obj2id[i] >= 0 else 1 + + elif eq_type == mujoco.mjtEq.mjEQ_TENDON: + obj1id = mjm.eq_obj1id[i] + obj2id = mjm.eq_obj2id[i] + rownnz1 = mjm.ten_J_rownnz[obj1id] if obj1id < mjm.ntendon else 0 + if obj2id >= 0 and obj2id < mjm.ntendon: + rowadr1 = mjm.ten_J_rowadr[obj1id] + rowadr2 = mjm.ten_J_rowadr[obj2id] + rownnz2 = mjm.ten_J_rownnz[obj2id] + cols = set() + for j in range(rownnz1): + cols.add(mjm.ten_J_colind[rowadr1 + j]) + for j in range(rownnz2): + cols.add(mjm.ten_J_colind[rowadr2 + j]) + total_nnz += len(cols) + else: + total_nnz += rownnz1 + + elif eq_type == mujoco.mjtEq.mjEQ_FLEX: + obj1id = mjm.eq_obj1id[i] + if obj1id < mjm.nflex: + edge_start = mjm.flex_edgeadr[obj1id] + edge_count = mjm.flex_edgenum[obj1id] + for e in range(edge_count): + total_nnz += mjm.flexedge_J_rownnz[edge_start + e] + + # friction constraints + total_nnz += (mjm.dof_frictionloss > 0).sum() + for i in range(mjm.ntendon): + if mjm.tendon_frictionloss[i] > 0: + total_nnz += mjm.ten_J_rownnz[i] + + # limit constraints (assume all active) + for i in range(mjm.njnt): + if mjm.jnt_limited[i]: + jnt_type = mjm.jnt_type[i] + if jnt_type == mujoco.mjtJoint.mjJNT_BALL: + total_nnz += 3 + elif jnt_type in (mujoco.mjtJoint.mjJNT_SLIDE, mujoco.mjtJoint.mjJNT_HINGE): + total_nnz += 1 + for i in range(mjm.ntendon): + if mjm.tendon_limited[i]: + total_nnz += mjm.ten_J_rownnz[i] + + # contact constraints: njmax rows at max body-pair non-zeros + max_contact_nnz = 0 + + # contact pairs + for i in range(mjm.npair): + g1, g2 = mjm.pair_geom1[i], mjm.pair_geom2[i] + b1, b2 = mjm.geom_bodyid[g1], mjm.geom_bodyid[g2] + max_contact_nnz = max(max_contact_nnz, _body_pair_nnz(mjm, b1, b2)) + + # filter geom-geom pairs (unique body pairs, filtered) + body_pair_seen = set() + for i in range(mjm.ngeom): + bi = mjm.geom_bodyid[i] + cti, cai = mjm.geom_contype[i], mjm.geom_conaffinity[i] + for j in range(i + 1, mjm.ngeom): + bj = mjm.geom_bodyid[j] + if bi == bj: + continue + if mjm.body_weldid[bi] == 0 and mjm.body_weldid[bj] == 0: + continue + bp = (min(bi, bj), max(bi, bj)) + if bp in body_pair_seen: + continue + ctj, caj = mjm.geom_contype[j], mjm.geom_conaffinity[j] + if not ((cti & caj) or (ctj & cai)): + continue + body_pair_seen.add(bp) + max_contact_nnz = max(max_contact_nnz, _body_pair_nnz(mjm, bi, bj)) + + # flex vertex contacts + for fi in range(mjm.nflex): + fct = mjm.flex_contype[fi] + fca = mjm.flex_conaffinity[fi] + + vert_start = mjm.flex_vertadr[fi] + vert_count = mjm.flex_vertnum[fi] + flex_bodies = {mjm.flex_vertbodyid[vert_start + v] for v in range(vert_count)} + + geom_bodies = set() + for g in range(mjm.ngeom): + ct, ca = mjm.geom_contype[g], mjm.geom_conaffinity[g] + if (fct & ca) or (ct & fca): + geom_bodies.add(mjm.geom_bodyid[g]) + + for fb in flex_bodies: + for gb in geom_bodies: + if fb != gb: + max_contact_nnz = max(max_contact_nnz, _body_pair_nnz(mjm, fb, gb)) + + # flex self-collision + if mjm.flex_selfcollide[fi]: + flex_body_list = sorted(flex_bodies) + for idx1 in range(len(flex_body_list)): + for idx2 in range(idx1 + 1, len(flex_body_list)): + max_contact_nnz = max( + max_contact_nnz, + _body_pair_nnz(mjm, flex_body_list[idx1], flex_body_list[idx2]), + ) + + total_nnz += njmax * max_contact_nnz + + return int(min(max(total_nnz, 1), njmax * mjm.nv)) + + +def _resolve_batch_size(na: int | None, n: int | None, nworld: int, default: int) -> int: if na is not None: return na if n is not None: @@ -647,6 +856,7 @@ def make_data( nconmax: Optional[int] = None, nccdmax: Optional[int] = None, njmax: Optional[int] = None, + njmax_nnz: Optional[int] = None, naconmax: Optional[int] = None, naccdmax: Optional[int] = None, ) -> types.Data: @@ -660,6 +870,7 @@ def make_data( nccdmax: Number of CCD contacts to allocate per world. Same semantics as nconmax. njmax: Number of constraints to allocate per world. Constraint arrays are batched by world: no world may have more than njmax constraints. + njmax_nnz: Number of non-zeros in constraint Jacobian (sparse). Defaults to njmax * nv. naconmax: Number of contacts to allocate for all worlds. Overrides nconmax. naccdmax: Maximum number of CCD contacts. Defaults to naconmax. @@ -709,20 +920,32 @@ def make_data( sizes["naconmax"] = naconmax sizes["njmax"] = njmax + if njmax_nnz is None: + if is_sparse(mjm): + njmax_nnz = _default_njmax_nnz(mjm, nconmax, njmax) + else: + njmax_nnz = njmax * mjm.nv + contact = types.Contact(**{f.name: _create_array(None, f.type, sizes) for f in dataclasses.fields(types.Contact)}) + contact.efc_address = wp.array(np.full((naconmax, sizes["nmaxpyramid"]), -1, dtype=int), dtype=int) efc = types.Constraint(**{f.name: _create_array(None, f.type, sizes) for f in dataclasses.fields(types.Constraint)}) - if SPARSE_CONSTRAINT_JACOBIAN: + if is_sparse(mjm): efc.J_rownnz = wp.zeros((nworld, njmax), dtype=int) efc.J_rowadr = wp.zeros((nworld, njmax), dtype=int) - efc.J_colind = wp.zeros((nworld, 1, njmax * mjm.nv), dtype=int) - efc.J = wp.zeros((nworld, 1, njmax * mjm.nv), dtype=float) + efc.J_colind = wp.zeros((nworld, 1, njmax_nnz), dtype=int) + efc.J = wp.zeros((nworld, 1, njmax_nnz), dtype=float) else: efc.J_rownnz = wp.zeros((nworld, 0), dtype=int) efc.J_rowadr = wp.zeros((nworld, 0), dtype=int) efc.J_colind = wp.zeros((nworld, 0, 0), dtype=int) efc.J = wp.zeros((nworld, sizes["njmax_pad"], sizes["nv_pad"]), dtype=float) + contact_kwargs = {} + for f in dataclasses.fields(types.Contact): + contact_kwargs[f.name] = _create_array(None, f.type, sizes) + contact = types.Contact(**contact_kwargs) + # world body and static geom (attached to the world) poses are precomputed # this speeds up scenes with many static geoms (e.g. terrains) # TODO(team): remove this when we introduce dof islands + sleeping @@ -734,65 +957,34 @@ def make_data( mocap_id = mjm.body_mocapid[mocap_body] d_kwargs = { - "qpos": wp.array( - np.tile(mjm.qpos0, nworld), shape=(nworld, mjm.nq), dtype=float - ), - "contact": contact, - "efc": efc, - "nworld": nworld, - "naconmax": naconmax, - "naccdmax": naccdmax, - "njmax": njmax, - "njmax_pad": sizes["njmax_pad"], - "qM": None, - "qLD": None, - # world body - "xquat": wp.array( - np.tile(mjd.xquat, (nworld, 1)), - shape=(nworld, mjm.nbody), - dtype=wp.quat, - ), - "xmat": wp.array( - np.tile(mjd.xmat, (nworld, 1)), - shape=(nworld, mjm.nbody), - dtype=wp.mat33, - ), - "ximat": wp.array( - np.tile(mjd.ximat, (nworld, 1)), - shape=(nworld, mjm.nbody), - dtype=wp.mat33, - ), - # static geoms - "geom_xpos": wp.array( - np.tile(mjd.geom_xpos, (nworld, 1)), - shape=(nworld, mjm.ngeom), - dtype=wp.vec3, - ), - "geom_xmat": wp.array( - np.tile(mjd.geom_xmat, (nworld, 1)), - shape=(nworld, mjm.ngeom), - dtype=wp.mat33, - ), - # mocap - "mocap_pos": wp.array( - np.tile(mjm.body_pos[mocap_body[mocap_id]], (nworld, 1)), - shape=(nworld, mjm.nmocap), - dtype=wp.vec3, - ), - "mocap_quat": wp.array( - np.tile(mjm.body_quat[mocap_body[mocap_id]], (nworld, 1)), - shape=(nworld, mjm.nmocap), - dtype=wp.quat, - ), - # equality constraints - "eq_active": wp.array( - np.tile(mjm.eq_active0.astype(bool), (nworld, 1)), - shape=(nworld, mjm.neq), - dtype=bool, - ), - # island arrays - "nisland": None, - "tree_island": None, + "qpos": wp.array(np.tile(mjm.qpos0, nworld), shape=(nworld, mjm.nq), dtype=float), + "contact": contact, + "efc": efc, + "nworld": nworld, + "naconmax": naconmax, + "naccdmax": naccdmax, + "njmax": njmax, + "njmax_pad": sizes["njmax_pad"], + "njmax_nnz": njmax_nnz, + "qM": None, + "qLD": None, + # world body + "xquat": wp.array(np.tile(mjd.xquat, (nworld, 1)), shape=(nworld, mjm.nbody), dtype=wp.quat), + "xmat": wp.array(np.tile(mjd.xmat, (nworld, 1)), shape=(nworld, mjm.nbody), dtype=wp.mat33), + "ximat": wp.array(np.tile(mjd.ximat, (nworld, 1)), shape=(nworld, mjm.nbody), dtype=wp.mat33), + # static geoms + "geom_xpos": wp.array(np.tile(mjd.geom_xpos, (nworld, 1)), shape=(nworld, mjm.ngeom), dtype=wp.vec3), + "geom_xmat": wp.array(np.tile(mjd.geom_xmat, (nworld, 1)), shape=(nworld, mjm.ngeom), dtype=wp.mat33), + # mocap + "mocap_pos": wp.array(np.tile(mjm.body_pos[mocap_body[mocap_id]], (nworld, 1)), shape=(nworld, mjm.nmocap), dtype=wp.vec3), + "mocap_quat": wp.array( + np.tile(mjm.body_quat[mocap_body[mocap_id]], (nworld, 1)), shape=(nworld, mjm.nmocap), dtype=wp.quat + ), + # equality constraints + "eq_active": wp.array(np.tile(mjm.eq_active0.astype(bool), (nworld, 1)), shape=(nworld, mjm.neq), dtype=bool), + # island arrays + "nisland": None, + "tree_island": None, } for f in dataclasses.fields(types.Data): if f.name in d_kwargs: @@ -822,6 +1014,7 @@ def put_data( nconmax: Optional[int] = None, nccdmax: Optional[int] = None, njmax: Optional[int] = None, + njmax_nnz: Optional[int] = None, naconmax: Optional[int] = None, naccdmax: Optional[int] = None, ) -> types.Data: @@ -836,6 +1029,7 @@ def put_data( nccdmax: Number of CCD contacts to allocate per world. Same semantics as nconmax. njmax: Number of constraints to allocate per world. Constraint arrays are batched by world: no world may have more than njmax constraints. + njmax_nnz: Number of non-zeros in constraint Jacobian (sparse). Defaults to njmax * nv. naconmax: Number of contacts to allocate for all worlds. Overrides nconmax. naccdmax: Maximum number of CCD contacts. Defaults to naconmax. @@ -898,6 +1092,12 @@ def put_data( sizes["naconmax"] = naconmax sizes["njmax"] = njmax + if njmax_nnz is None: + if is_sparse(mjm): + njmax_nnz = _default_njmax_nnz(mjm, nconmax, njmax) + else: + njmax_nnz = njmax * mjm.nv + # ensure static geom positions are computed # TODO: remove once MjData creation semantics are fixed mujoco.mj_kinematics(mjm, mjd) @@ -915,7 +1115,7 @@ def put_data( contact = types.Contact(**contact_kwargs) - contact.efc_address = np.zeros((naconmax, sizes["nmaxpyramid"]), dtype=int) + contact.efc_address = np.full((naconmax, sizes["nmaxpyramid"]), -1, dtype=int) for i in range(mjd.ncon): efc_address = mjd.contact.efc_address[i] if efc_address == -1: @@ -945,43 +1145,28 @@ def put_data( efc = types.Constraint(**efc_kwargs) - if SPARSE_CONSTRAINT_JACOBIAN: - # TODO(team): process efc_J sparsity structure for nv row shift - efc.J_rownnz = wp.array( - np.full((nworld, njmax), mjm.nv, dtype=int), dtype=int - ) - efc.J_rowadr = wp.array( - np.tile( - np.arange(0, njmax * mjm.nv, mjm.nv) - if mjm.nv - else np.zeros(njmax, dtype=int), - (nworld, 1), - ), - dtype=int, - ) - efc.J_colind = wp.array( - np.tile(np.arange(mjm.nv), (nworld, njmax)).reshape((nworld, 1, -1)), - dtype=int, - ) - - mj_efc_J = np.zeros((mjd.nefc, mjm.nv)) + if is_sparse(mjm): + J_rownnz = np.zeros(njmax, dtype=np.int32) + J_rowadr = np.zeros(njmax, dtype=np.int32) + J_colind = np.zeros(njmax_nnz, dtype=np.int32) + J = np.zeros(njmax_nnz, dtype=np.float64) if mjd.nefc: if mujoco.mj_isSparse(mjm): - mujoco.mju_sparse2dense( - mj_efc_J, - mjd.efc_J, - mjd.efc_J_rownnz, - mjd.efc_J_rowadr, - mjd.efc_J_colind, - ) + J_rownnz[: mjd.nefc] = mjd.efc_J_rownnz[: mjd.nefc] + J_rowadr[: mjd.nefc] = mjd.efc_J_rowadr[: mjd.nefc] + nnz = int(mjd.efc_J_rownnz[: mjd.nefc].sum()) + J_colind[:nnz] = mjd.efc_J_colind[:nnz] + J[:nnz] = mjd.efc_J[:nnz] else: - mj_efc_J = mjd.efc_J.reshape((mjd.nefc, mjm.nv)) - efc_J = np.zeros((njmax, mjm.nv), dtype=float) - efc_J[: mjd.nefc, : mjm.nv] = mj_efc_J - efc.J = wp.array( - np.tile(efc_J.reshape(-1), (nworld, 1, 1)).reshape((nworld, 1, -1)), - dtype=float, - ) + dense_J = mjd.efc_J.reshape((-1, mjm.nv))[: mjd.nefc] + mujoco.mju_dense2sparse( + J[: mjd.nefc * mjm.nv], dense_J, J_rownnz[: mjd.nefc], J_rowadr[: mjd.nefc], J_colind[: mjd.nefc * mjm.nv] + ) + + efc.J_rownnz = wp.array(np.tile(J_rownnz, (nworld, 1)), dtype=int) + efc.J_rowadr = wp.array(np.tile(J_rowadr, (nworld, 1)), dtype=int) + efc.J_colind = wp.array(np.tile(J_colind, (nworld, 1)).reshape((nworld, 1, -1)), dtype=int) + efc.J = wp.array(np.tile(J, (nworld, 1)).reshape((nworld, 1, -1)), dtype=float) else: efc.J_rownnz = wp.zeros((nworld, 0), dtype=int) efc.J_rowadr = wp.zeros((nworld, 0), dtype=int) @@ -990,13 +1175,7 @@ def put_data( mj_efc_J = np.zeros((mjd.nefc, mjm.nv)) if mjd.nefc: if mujoco.mj_isSparse(mjm): - mujoco.mju_sparse2dense( - mj_efc_J, - mjd.efc_J, - mjd.efc_J_rownnz, - mjd.efc_J_rowadr, - mjd.efc_J_colind, - ) + mujoco.mju_sparse2dense(mj_efc_J, mjd.efc_J, mjd.efc_J_rownnz, mjd.efc_J_rowadr, mjd.efc_J_colind) else: mj_efc_J = mjd.efc_J.reshape((mjd.nefc, mjm.nv)) efc_J = np.zeros((nworld, sizes["njmax_pad"], sizes["nv_pad"]), dtype=float) @@ -1005,22 +1184,22 @@ def put_data( # create data d_kwargs = { - "contact": contact, - "efc": efc, - "nworld": nworld, - "naconmax": naconmax, - "naccdmax": naccdmax, - "njmax": njmax, - "njmax_pad": sizes["njmax_pad"], - # fields set after initialization: - "solver_niter": None, - "qM": None, - "qLD": None, - "ten_J": None, - "nacon": None, - # island arrays - "nisland": None, - "tree_island": None, + "contact": contact, + "efc": efc, + "nworld": nworld, + "naconmax": naconmax, + "naccdmax": naccdmax, + "njmax": njmax, + "njmax_pad": sizes["njmax_pad"], + "njmax_nnz": njmax_nnz, + # fields set after initialization: + "solver_niter": None, + "qM": None, + "qLD": None, + "nacon": None, + # island arrays + "nisland": None, + "tree_island": None, } for f in dataclasses.fields(types.Data): if f.name in d_kwargs: @@ -1050,29 +1229,6 @@ def put_data( d.nisland = wp.array(np.full(nworld, mjd.nisland), dtype=int) d.tree_island = wp.array(np.tile(mjd.tree_island, (nworld, 1)), dtype=int) - ten_J = np.zeros((mjm.ntendon, mjm.nv)) - if mujoco.mj_isSparse(mjm) or check_version("mujoco>=3.5.1.dev872479828"): - if mjm.ntendon: - if check_version("mujoco>=3.5.1.dev875093374"): - mujoco.mju_sparse2dense( - ten_J, - mjd.ten_J.reshape(-1), - mjm.ten_J_rownnz, - mjm.ten_J_rowadr, - mjm.ten_J_colind.reshape(-1), - ) - else: - mujoco.mju_sparse2dense( - ten_J, - mjd.ten_J.reshape(-1), - mjd.ten_J_rownnz, - mjd.ten_J_rowadr, - mjd.ten_J_colind.reshape(-1), - ) - else: - ten_J = mjd.ten_J.reshape((mjm.ntendon, mjm.nv)) - d.ten_J = wp.array(np.full((nworld, mjm.ntendon, mjm.nv), ten_J), dtype=float) - d.nacon = wp.array([mjd.ncon * nworld], dtype=int) return d @@ -1233,14 +1389,14 @@ def get_data_into( mujoco.mj_factorM(mjm, result) if nefc > 0: - if SPARSE_CONSTRAINT_JACOBIAN: + if is_sparse(mjm): efc_J = np.zeros((nefc, mjm.nv)) mujoco.mju_sparse2dense( - efc_J, - d.efc.J.numpy()[world_id, 0], - d.efc.J_rownnz.numpy()[world_id, :nefc], - d.efc.J_rowadr.numpy()[world_id, :nefc], - d.efc.J_colind.numpy()[world_id, 0], + efc_J, + d.efc.J.numpy()[world_id, 0], + d.efc.J_rownnz.numpy()[world_id, :nefc], + d.efc.J_rowadr.numpy()[world_id, :nefc], + d.efc.J_colind.numpy()[world_id, 0], ) else: efc_J = d.efc.J.numpy()[world_id, :nefc, : mjm.nv] @@ -1248,11 +1404,11 @@ def get_data_into( # write to mujoco result (format depends on mj_isSparse) if mujoco.mj_isSparse(mjm): mujoco.mju_dense2sparse( - result.efc_J, - efc_J[efc_idx], - result.efc_J_rownnz, - result.efc_J_rowadr, - result.efc_J_colind, + result.efc_J, + efc_J[efc_idx], + result.efc_J_rownnz, + result.efc_J_rowadr, + result.efc_J_colind, ) else: result.efc_J[: nefc * mjm.nv] = efc_J[efc_idx].flatten() @@ -1276,24 +1432,7 @@ def get_data_into( # tendon result.ten_length[:] = d.ten_length.numpy()[world_id] - if check_version("mujoco>=3.5.1.dev869712136"): - ten_J = d.ten_J.numpy()[world_id] - if check_version("mujoco>=3.5.1.dev875093374"): - ten_J_rownnz = mjm.ten_J_rownnz - ten_J_rowadr = mjm.ten_J_rowadr - ten_J_colind = mjm.ten_J_colind.reshape(-1) - else: - ten_J_rownnz = result.ten_J_rownnz - ten_J_rowadr = result.ten_J_rowadr - ten_J_colind = result.ten_J_colind.reshape(-1) - mujoco.mju_dense2sparse( - result.ten_J, - ten_J, - ten_J_rownnz, - ten_J_rowadr, - ten_J_colind, - ) - else: + if mjm.ntendon > 0: result.ten_J[:] = d.ten_J.numpy()[world_id] result.ten_wrapadr[:] = d.ten_wrapadr.numpy()[world_id] result.ten_wrapnum[:] = d.ten_wrapnum.numpy()[world_id] @@ -1428,12 +1567,8 @@ def reset_mocap( mocapid = body_mocapid[bodyid] if mocapid >= 0: - mocap_pos_out[worldid, mocapid] = body_pos[ - worldid % body_pos.shape[0], bodyid - ] - mocap_quat_out[worldid, mocapid] = body_quat[ - worldid % body_quat.shape[0], bodyid - ] + mocap_pos_out[worldid, mocapid] = body_pos[worldid % body_pos.shape[0], bodyid] + mocap_quat_out[worldid, mocapid] = body_quat[worldid % body_quat.shape[0], bodyid] @wp.kernel(module="unique", enable_backward=False) def reset_contact( @@ -1453,6 +1588,8 @@ def reset_contact( contact_solimp_out: wp.array(dtype=types.vec5), contact_dim_out: wp.array(dtype=int), contact_geom_out: wp.array(dtype=wp.vec2i), + contact_flex_out: wp.array(dtype=wp.vec2i), + contact_vert_out: wp.array(dtype=wp.vec2i), contact_efc_address_out: wp.array2d(dtype=int), contact_worldid_out: wp.array(dtype=int), contact_type_out: wp.array(dtype=int), @@ -1479,8 +1616,10 @@ def reset_contact( contact_solimp_out[conid] = types.vec5(0.0, 0.0, 0.0, 0.0, 0.0) contact_dim_out[conid] = 0 contact_geom_out[conid] = wp.vec2i(0, 0) + contact_flex_out[conid] = wp.vec2i(0, 0) + contact_vert_out[conid] = wp.vec2i(0, 0) for i in range(nefcaddress): - contact_efc_address_out[conid, i] = 0 + contact_efc_address_out[conid, i] = -1 contact_worldid_out[conid] = 0 contact_type_out[conid] = 0 contact_geomcollisionid_out[conid] = 0 @@ -1519,6 +1658,8 @@ def reset_contact( d.contact.solimp, d.contact.dim, d.contact.geom, + d.contact.flex, + d.contact.vert, d.contact.efc_address, d.contact.worldid, d.contact.type, @@ -1812,28 +1953,45 @@ def _finalize_body_invweight0( @wp.kernel def _copy_tendon_jacobian( tenid_target: int, - ten_J_in: wp.array3d(dtype=float), + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), + ten_J_in: wp.array2d(dtype=float), ten_J_vec_out: wp.array2d(dtype=float), ): worldid = wp.tid() nv = ten_J_in.shape[2] - for i in range(nv): - ten_J_vec_out[worldid, i] = ten_J_in[worldid, tenid_target, i] + rownnz = ten_J_rownnz[tenid_target] + rowadr = ten_J_rowadr[tenid_target] + for i in range(rownnz): + colind = ten_J_colind[rowadr + i] + ten_J_vec_out[worldid, colind] = ten_J_in[worldid, rowadr + i] @wp.kernel def _compute_tendon_dot_product( + # Model: + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), + # In: tenid_target: int, - nv: int, - ten_J_in: wp.array3d(dtype=float), + ten_J_in: wp.array2d(dtype=float), result_vec_in: wp.array2d(dtype=float), + # Out: tendon_invweight0_out: wp.array2d(dtype=float), ): worldid = wp.tid() tendon_invweight0_id = worldid % tendon_invweight0_out.shape[0] dot_prod = float(0.0) - for i in range(nv): - dot_prod += ten_J_in[worldid, tenid_target, i] * result_vec_in[worldid, i] + + rownnz = ten_J_rownnz[tenid_target] + rowadr = ten_J_rowadr[tenid_target] + for i in range(rownnz): + sparseid = rowadr + i + colind = ten_J_colind[sparseid] + dot_prod += ten_J_in[worldid, sparseid] * result_vec_in[worldid, colind] + tendon_invweight0_out[tendon_invweight0_id, tenid_target] = dot_prod @@ -1891,12 +2049,12 @@ def _compute_light_pos0( @wp.kernel def _copy_actuator_moment( - actid_target: int, - moment_rownnz_in: wp.array2d(dtype=int), - moment_rowadr_in: wp.array2d(dtype=int), - moment_colind_in: wp.array2d(dtype=int), - actuator_moment_in: wp.array2d(dtype=float), - act_moment_vec_out: wp.array2d(dtype=float), + actid_target: int, + moment_rownnz_in: wp.array2d(dtype=int), + moment_rowadr_in: wp.array2d(dtype=int), + moment_colind_in: wp.array2d(dtype=int), + actuator_moment_in: wp.array2d(dtype=float), + act_moment_vec_out: wp.array2d(dtype=float), ): worldid = wp.tid() nv = act_moment_vec_out.shape[1] @@ -1912,10 +2070,10 @@ def _copy_actuator_moment( @wp.kernel def _compute_actuator_acc0( - actid_target: int, - nv: int, - result_vec_in: wp.array2d(dtype=float), - actuator_acc0_out: wp.array2d(dtype=float), + actid_target: int, + nv: int, + result_vec_in: wp.array2d(dtype=float), + actuator_acc0_out: wp.array2d(dtype=float), ): worldid = wp.tid() norm_sq = float(0.0) @@ -1926,11 +2084,11 @@ def _compute_actuator_acc0( @wp.kernel def _compute_dof_M0( - dof_bodyid: wp.array(dtype=int), - dof_armature: wp.array2d(dtype=float), - cdof_in: wp.array2d(dtype=wp.spatial_vector), - crb_in: wp.array2d(dtype=vec10), - dof_M0_out: wp.array2d(dtype=float), + dof_bodyid: wp.array(dtype=int), + dof_armature: wp.array2d(dtype=float), + cdof_in: wp.array2d(dtype=wp.spatial_vector), + crb_in: wp.array2d(dtype=vec10), + dof_M0_out: wp.array2d(dtype=float), ): worldid, dofid = wp.tid() bodyid = dof_bodyid[dofid] @@ -1941,15 +2099,15 @@ def _compute_dof_M0( @wp.kernel def _resolve_dampratio( - actuator_biastype: wp.array(dtype=int), - actuator_gainprm: wp.array2d(dtype=types.vec10f), - moment_rownnz_in: wp.array2d(dtype=int), - moment_rowadr_in: wp.array2d(dtype=int), - moment_colind_in: wp.array2d(dtype=int), - actuator_moment_in: wp.array2d(dtype=float), - dof_M0_in: wp.array2d(dtype=float), - nv: int, - actuator_biasprm: wp.array2d(dtype=types.vec10f), + actuator_biastype: wp.array(dtype=int), + actuator_gainprm: wp.array2d(dtype=types.vec10f), + moment_rownnz_in: wp.array2d(dtype=int), + moment_rowadr_in: wp.array2d(dtype=int), + moment_colind_in: wp.array2d(dtype=int), + actuator_moment_in: wp.array2d(dtype=float), + dof_M0_in: wp.array2d(dtype=float), + nv: int, + actuator_biasprm: wp.array2d(dtype=types.vec10f), ): worldid, actid = wp.tid() biastype = actuator_biastype[actid] @@ -1992,15 +2150,15 @@ def _resolve_dampratio( @wp.kernel def _set_length_range( - actuator_trntype: wp.array(dtype=int), - actuator_trnid: wp.array(dtype=wp.vec2i), - actuator_gear: wp.array2d(dtype=wp.spatial_vector), - jnt_limited: wp.array(dtype=int), - jnt_range: wp.array2d(dtype=wp.vec2), - tendon_limited: wp.array(dtype=int), - tendon_range: wp.array2d(dtype=wp.vec2), - ntendon: int, - actuator_lengthrange_out: wp.array2d(dtype=wp.vec2), + actuator_trntype: wp.array(dtype=int), + actuator_trnid: wp.array(dtype=wp.vec2i), + actuator_gear: wp.array2d(dtype=wp.spatial_vector), + jnt_limited: wp.array(dtype=int), + jnt_range: wp.array2d(dtype=wp.vec2), + tendon_limited: wp.array(dtype=int), + tendon_range: wp.array2d(dtype=wp.vec2), + ntendon: int, + actuator_lengthrange_out: wp.array2d(dtype=wp.vec2), ): worldid, actid = wp.tid() trntype = actuator_trntype[actid] @@ -2167,16 +2325,22 @@ def set_const_0(m: types.Model, d: types.Data): # tendon_invweight0[t] = J_t * inv(M) * J_t' if m.ntendon > 0: - ten_J_vec = wp.zeros((d.nworld, m.nv), dtype=float) - ten_result_vec = wp.zeros((d.nworld, m.nv), dtype=float) + ten_J_vec = wp.empty((d.nworld, m.nv), dtype=float) + ten_result_vec = wp.empty((d.nworld, m.nv), dtype=float) for tenid in range(m.ntendon): - wp.launch(_copy_tendon_jacobian, dim=d.nworld, inputs=[tenid, d.ten_J], outputs=[ten_J_vec]) + ten_J_vec.zero_() + wp.launch( + _copy_tendon_jacobian, + dim=d.nworld, + inputs=[tenid, m.ten_J_rownnz, m.ten_J_rowadr, m.ten_J_colind, d.ten_J], + outputs=[ten_J_vec], + ) smooth.solve_m(m, d, ten_result_vec, ten_J_vec) wp.launch( _compute_tendon_dot_product, dim=d.nworld, - inputs=[tenid, m.nv, d.ten_J, ten_result_vec], + inputs=[m.ten_J_rownnz, m.ten_J_rowadr, m.ten_J_colind, tenid, d.ten_J, ten_result_vec], outputs=[m.tendon_invweight0], ) @@ -2201,16 +2365,10 @@ def set_const_0(m: types.Model, d: types.Data): for actid in range(m.nu): wp.launch( - _copy_actuator_moment, - dim=d.nworld, - inputs=[ - actid, - d.moment_rownnz, - d.moment_rowadr, - d.moment_colind, - d.actuator_moment, - ], - outputs=[act_moment_vec], + _copy_actuator_moment, + dim=d.nworld, + inputs=[actid, d.moment_rownnz, d.moment_rowadr, d.moment_colind, d.actuator_moment], + outputs=[act_moment_vec], ) smooth.solve_m(m, d, act_result_vec, act_moment_vec) wp.launch(_compute_actuator_acc0, dim=d.nworld, inputs=[actid, m.nv, act_result_vec], outputs=[m.actuator_acc0]) @@ -2219,25 +2377,25 @@ def set_const_0(m: types.Model, d: types.Data): if m.nu > 0 and m.nv > 0: dof_M0 = wp.zeros((d.nworld, m.nv), dtype=float) wp.launch( - _compute_dof_M0, - dim=(d.nworld, m.nv), - inputs=[m.dof_bodyid, m.dof_armature, d.cdof, d.crb], - outputs=[dof_M0], + _compute_dof_M0, + dim=(d.nworld, m.nv), + inputs=[m.dof_bodyid, m.dof_armature, d.cdof, d.crb], + outputs=[dof_M0], ) wp.launch( - _resolve_dampratio, - dim=(d.nworld, m.nu), - inputs=[ - m.actuator_biastype, - m.actuator_gainprm, - d.moment_rownnz, - d.moment_rowadr, - d.moment_colind, - d.actuator_moment, - dof_M0, - m.nv, - ], - outputs=[m.actuator_biasprm], + _resolve_dampratio, + dim=(d.nworld, m.nu), + inputs=[ + m.actuator_biastype, + m.actuator_gainprm, + d.moment_rownnz, + d.moment_rowadr, + d.moment_colind, + d.actuator_moment, + dof_M0, + m.nv, + ], + outputs=[m.actuator_biasprm], ) wp.copy(d.qpos, qpos_saved) @@ -2255,16 +2413,12 @@ def set_const(m: types.Model, d: types.Data): Field | Notes ---------------------------------|---------------------------------------------- qpos0, qpos_spring | - body_mass, body_inertia, | Mass and inertia are usually scaled - together + body_mass, body_inertia, | Mass and inertia are usually scaled together body_ipos, body_iquat | since inertia is sum(m * r^2). - body_pos, body_quat | Unsafe for static bodies (invalidates - BVH). - body_gravcomp | If changing from 0 to >0 bodies, - required. + body_pos, body_quat | Unsafe for static bodies (invalidates BVH). + body_gravcomp | If changing from 0 to >0 bodies, required. dof_armature | - eq_data | For connect/weld, offsets computed if not - set. + eq_data | For connect/weld, offsets computed if not set. hfield_size | tendon_stiffness, tendon_damping | Only if changing from/to zero. actuator_gainprm, actuator_biasprm | For position actuators with dampratio. @@ -2319,19 +2473,19 @@ def set_length_range(m: types.Model, d: types.Data, index: int = -1): return wp.launch( - _set_length_range, - dim=(d.nworld, m.nu), - inputs=[ - m.actuator_trntype, - m.actuator_trnid, - m.actuator_gear, - m.jnt_limited, - m.jnt_range, - m.tendon_limited, - m.tendon_range, - m.ntendon, - ], - outputs=[m.actuator_lengthrange], + _set_length_range, + dim=(d.nworld, m.nu), + inputs=[ + m.actuator_trntype, + m.actuator_trnid, + m.actuator_gear, + m.jnt_limited, + m.jnt_range, + m.tendon_limited, + m.tendon_range, + m.ntendon, + ], + outputs=[m.actuator_lengthrange], ) @@ -2486,6 +2640,7 @@ def create_render_context( cam_res: list[tuple[int, int]] | tuple[int, int] | None = None, render_rgb: list[bool] | bool | None = None, render_depth: list[bool] | bool | None = None, + render_seg: list[bool] | bool | None = None, use_textures: bool = True, use_shadows: bool = False, enabled_geom_groups: list[int] = [0, 1, 2], @@ -2502,6 +2657,8 @@ def create_render_context( MuJoCo model values. render_rgb: Whether to render RGB images. If None, uses the MuJoCo model values. render_depth: Whether to render depth images. If None, uses the MuJoCo model values. + render_seg: Whether to render segmentation (per-pixel geom IDs). If None, + uses the MuJoCo model values. use_textures: Whether to use textures. use_shadows: Whether to use shadows. enabled_geom_groups: The geom groups to render. @@ -2517,10 +2674,13 @@ def create_render_context( mjd = mujoco.MjData(mjm) mujoco.mj_forward(mjm, mjd) - # TODO(team): remove after mjwarp depends on warp-lang >= 1.12 in pyproject.toml - if use_textures and not hasattr(wp, "Texture2D"): - warnings.warn("Textures require warp >= 1.12. Disabling textures.") - use_textures = False + constructor = "sah" + if check_version("warp>=1.13.0.dev20260325"): + # TODO: The cubql constructor and is_cubql_available exist only in + # recent Warp 1.13+ builds, modify this after warp is updated to 1.13+. + _cubql_avail = getattr(wp, "is_cubql_available", None) + if callable(_cubql_avail) and _cubql_avail(): + constructor = "cubql" # Mesh BVHs nmesh = mjm.nmesh @@ -2534,7 +2694,7 @@ def create_render_context( mesh_bounds_size = [wp.vec3(0.0, 0.0, 0.0) for _ in range(nmesh)] for mid in used_mesh_id: - mesh, half = bvh.build_mesh_bvh(mjm, mid) + mesh, half = bvh.build_mesh_bvh(mjm, mid, constructor=constructor) mesh_registry[mesh.id] = mesh mesh_bvh_id[mid] = mesh.id mesh_bounds_size[mid] = half @@ -2551,7 +2711,7 @@ def create_render_context( hfield_bounds_size = [wp.vec3(0.0, 0.0, 0.0) for _ in range(nhfield)] for hid in used_hfield_id: - hmesh, hhalf = bvh.build_hfield_bvh(mjm, hid) + hmesh, hhalf = bvh.build_hfield_bvh(mjm, hid, constructor=constructor) hfield_registry[hmesh.id] = hmesh hfield_bvh_id[hid] = hmesh.id hfield_bounds_size[hid] = hhalf @@ -2560,65 +2720,33 @@ def create_render_context( hfield_bounds_size_arr = wp.array(hfield_bounds_size, dtype=wp.vec3) # Flex BVHs - flex_bvh_id = wp.uint64(0) - flex_group_root = wp.zeros(nworld, dtype=int) - flex_mesh = None - flex_face_point = None - flex_elemdataadr = None - flex_shell = None - flex_shelldataadr = None - flex_faceadr = None - flex_nface = 0 - flex_radius = None - flex_workadr = None - flex_worknum = None - flex_nwork = 0 - - if mjm.nflex > 0: - ( - fmesh, - face_point, - flex_group_roots, - flex_shell_data, - flex_faceadr_data, - flex_nface, - ) = bvh.build_flex_bvh(mjm, mjd, nworld) - - flex_mesh = fmesh - flex_bvh_id = fmesh.id - flex_face_point = face_point - flex_group_root = flex_group_roots - flex_elemdataadr = wp.array(mjm.flex_elemdataadr, dtype=int) - flex_shell = flex_shell_data - flex_shelldataadr = wp.array(mjm.flex_shelldataadr, dtype=int) - flex_faceadr = wp.array(flex_faceadr_data, dtype=int) - flex_radius = wp.array(mjm.flex_radius, dtype=float) - - # precompute work item layout for unified refit kernel - nflex = mjm.nflex - workadr = np.zeros(nflex, dtype=np.int32) - worknum = np.zeros(nflex, dtype=np.int32) - cumsum = 0 - for f in range(nflex): - workadr[f] = cumsum - if mjm.flex_dim[f] == 2: - worknum[f] = mjm.flex_elemnum[f] + mjm.flex_shellnum[f] - else: - worknum[f] = mjm.flex_shellnum[f] - cumsum += worknum[f] - flex_workadr = wp.array(workadr, dtype=int) - flex_worknum = wp.array(worknum, dtype=int) - flex_nwork = int(cumsum) + nflex = mjm.nflex + flex_registry = {} + + # Scene BVH flex primitives: 1D → one capsule per edge, 2D/3D → one box per flex + flex_geom_flexid = [] + flex_geom_edgeid = [] + flex_bvh_id = np.full(nflex, 0, dtype=wp.uint64) + flex_group_root = np.zeros((nflex, nworld), dtype=int) + + for f in range(nflex): + if mjm.flex_dim[f] == 1: + edge_adr = mjm.flex_edgeadr[f] + flex_geom_flexid.extend([f] * mjm.flex_edgenum[f]) + flex_geom_edgeid.extend([edge_adr + e for e in range(mjm.flex_edgenum[f])]) + flex_group_root[f] = np.zeros(nworld, dtype=int) + else: + flex_geom_flexid.append(f) + flex_geom_edgeid.append(-1) + fmesh, group_root = bvh.build_flex_bvh(mjm, mjd, nworld, f) + flex_registry[f] = fmesh + flex_bvh_id[f] = fmesh.id + flex_group_root[f] = group_root.numpy() textures_registry = [] - # TODO: remove after mjwarp depends on warp-lang >= 1.12 in pyproject.toml - if hasattr(wp, "Texture2D"): - for i in range(mjm.ntex): - textures_registry.append(render_util.create_warp_texture(mjm, i)) - textures = wp.array(textures_registry, dtype=wp.Texture2D) - else: - # Dummy array when texture support isn't available (warp < 1.12) - textures = wp.zeros(1, dtype=int) + for i in range(mjm.ntex): + textures_registry.append(render_util.create_warp_texture(mjm, i)) + textures = wp.array(textures_registry, dtype=wp.Texture2D) # Filter active cameras if cam_active is not None: @@ -2642,31 +2770,31 @@ def create_render_context( cam_res_arr = wp.array(active_cam_res, dtype=wp.vec2i) if render_rgb is None: - render_rgb = [ - mjm.cam_output[i] & mujoco.mjtCamOutBit.mjCAMOUT_RGB - for i in active_cam_indices - ] + render_rgb = [mjm.cam_output[i] & mujoco.mjtCamOutBit.mjCAMOUT_RGB for i in active_cam_indices] elif isinstance(render_rgb, bool): render_rgb = [render_rgb] * ncam if render_depth is None: - render_depth = [ - mjm.cam_output[i] & mujoco.mjtCamOutBit.mjCAMOUT_DEPTH - for i in active_cam_indices - ] + render_depth = [mjm.cam_output[i] & mujoco.mjtCamOutBit.mjCAMOUT_DEPTH for i in active_cam_indices] if isinstance(render_depth, bool): render_depth = [render_depth] * ncam - assert len(render_rgb) == ncam and len(render_depth) == ncam, ( - "render_rgb and render_depth must be a bool or a list of bools with" - f" length {ncam}" + if render_seg is None: + render_seg = [mjm.cam_output[i] & mujoco.mjtCamOutBit.mjCAMOUT_SEG for i in active_cam_indices] + elif isinstance(render_seg, bool): + render_seg = [render_seg] * ncam + + assert len(render_rgb) == ncam and len(render_depth) == ncam and len(render_seg) == ncam, ( + f"render_rgb, render_depth, and render_seg must be a bool or a list of bools with length {ncam}" ) rgb_adr = -1 * np.ones(ncam, dtype=int) depth_adr = -1 * np.ones(ncam, dtype=int) + seg_adr = -1 * np.ones(ncam, dtype=int) cam_res_np = cam_res_arr.numpy() ri = 0 di = 0 + si = 0 total = 0 for idx in range(ncam): @@ -2676,6 +2804,9 @@ def create_render_context( if render_depth[idx]: depth_adr[idx] = di di += cam_res_np[idx][0] * cam_res_np[idx][1] + if render_seg[idx]: + seg_adr[idx] = si + si += cam_res_np[idx][0] * cam_res_np[idx][1] total += cam_res_np[idx][0] * cam_res_np[idx][1] @@ -2729,26 +2860,20 @@ def create_render_context( hfield_registry=hfield_registry, hfield_bvh_id=hfield_bvh_id_arr, hfield_bounds_size=hfield_bounds_size_arr, - flex_mesh=flex_mesh, + flex_mesh_registry=flex_registry, flex_rgba=wp.array(mjm.flex_rgba, dtype=wp.vec4), - flex_bvh_id=flex_bvh_id, - flex_face_point=flex_face_point, - flex_faceadr=flex_faceadr, - flex_nface=flex_nface, - flex_nwork=flex_nwork, - flex_group_root=flex_group_root, - flex_elemdataadr=flex_elemdataadr, - flex_shell=flex_shell, - flex_shelldataadr=flex_shelldataadr, - flex_radius=flex_radius, - flex_workadr=flex_workadr, - flex_worknum=flex_worknum, + flex_bvh_id=wp.array(flex_bvh_id, dtype=wp.uint64), + flex_group_root=wp.array(flex_group_root, dtype=int), flex_render_smooth=flex_render_smooth, + bvh_nflexgeom=len(flex_geom_flexid), + flex_dim_np=mjm.flex_dim, + flex_geom_flexid=wp.array(flex_geom_flexid, dtype=int), + flex_geom_edgeid=wp.array(flex_geom_edgeid, dtype=int), bvh=None, bvh_id=None, - lower=wp.zeros(nworld * bvh_ngeom, dtype=wp.vec3), - upper=wp.zeros(nworld * bvh_ngeom, dtype=wp.vec3), - group=wp.zeros(nworld * bvh_ngeom, dtype=int), + lower=wp.zeros(nworld * (bvh_ngeom + len(flex_geom_flexid)), dtype=wp.vec3), + upper=wp.zeros(nworld * (bvh_ngeom + len(flex_geom_flexid)), dtype=wp.vec3), + group=wp.zeros(nworld * (bvh_ngeom + len(flex_geom_flexid)), dtype=int), group_root=wp.zeros(nworld, dtype=int), ray=ray, rgb_data=wp.zeros((nworld, ri), dtype=wp.uint32), @@ -2757,6 +2882,9 @@ def create_render_context( depth_adr=wp.array(depth_adr, dtype=int), render_rgb=wp.array(render_rgb, dtype=bool), render_depth=wp.array(render_depth, dtype=bool), + seg_data=wp.zeros((nworld, max(si, 1)), dtype=int), + seg_adr=wp.array(seg_adr, dtype=int), + render_seg=wp.array(render_seg, dtype=bool), znear=znear, total_rays=int(total), ) diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/island.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/island.py index b5ae2846eb..c021db3f01 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/island.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/island.py @@ -13,12 +13,13 @@ # limitations under the License. # ============================================================================== +import warp as wp + from mujoco.mjx.third_party.mujoco_warp._src import types from mujoco.mjx.third_party.mujoco_warp._src.types import ConstraintType from mujoco.mjx.third_party.mujoco_warp._src.types import EqType from mujoco.mjx.third_party.mujoco_warp._src.types import ObjType from mujoco.mjx.third_party.mujoco_warp._src.warp_util import event_scope -import warp as wp @wp.kernel @@ -180,17 +181,17 @@ def tree_edges(m: types.Model, d: types.Data, tree_tree: wp.array3d(dtype=int)): @wp.kernel def _flood_fill( - # Model: - ntree: int, - # In: - tree_tree_in: wp.array3d(dtype=int), - labels_in: wp.array2d(dtype=int), - stack_in: wp.array2d(dtype=int), - # Data out: - nisland_out: wp.array(dtype=int), - tree_island_out: wp.array2d(dtype=int), - # Out: - stack_out: wp.array2d(dtype=int), + # Model: + ntree: int, + # In: + tree_tree_in: wp.array3d(dtype=int), + labels_in: wp.array2d(dtype=int), + stack_in: wp.array2d(dtype=int), + # Data out: + nisland_out: wp.array(dtype=int), + tree_island_out: wp.array2d(dtype=int), + # Out: + stack_out: wp.array2d(dtype=int), ): """DFS flood fill to discover islands using tree_tree matrix.""" worldid = wp.tid() @@ -257,8 +258,8 @@ def island(m: types.Model, d: types.Data): stack_scratch = wp.empty((d.nworld, m.ntree * m.ntree), dtype=int) wp.launch( - _flood_fill, - dim=d.nworld, - inputs=[m.ntree, tree_tree, d.tree_island, stack_scratch], - outputs=[d.nisland, d.tree_island, stack_scratch], + _flood_fill, + dim=d.nworld, + inputs=[m.ntree, tree_tree, d.tree_island, stack_scratch], + outputs=[d.nisland, d.tree_island, stack_scratch], ) diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/math.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/math.py index ec49041e58..3ce2d1c5d3 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/math.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/math.py @@ -83,6 +83,35 @@ def quat_to_mat(quat: wp.quat) -> wp.mat33: ) +@wp.func +def quat_z2vec(vec: wp.vec3) -> wp.quat: + """Compute quaternion performing rotation from z-axis to given vector.""" + quat = wp.quat(0.0, 0.0, 0.0, 1.0) + + # normalize vector; if too small, no rotation + norm = wp.length(vec) + if norm < types.MJ_MINVAL: + return quat + vec = vec / norm + + axis = wp.vec3(-vec[1], vec[0], 0.0) + a = wp.length(axis) + + # almost parallel + if a < types.MJ_MINVAL: + # opposite: 180 deg rotation around x axis + if vec[2] < 0.0: + quat = wp.quat(1.0, 0.0, 0.0, 0.0) + return quat + + # make quaternion from angle and axis + axis = axis / a + angle = wp.atan2(a, vec[2]) + quat = axis_angle_to_quat(axis, angle) + + return quat + + @wp.func def quat_inv(quat: wp.quat) -> wp.quat: return wp.quat(quat[0], -quat[1], -quat[2], -quat[3]) diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/passive.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/passive.py index 0bcd13af52..4abcff26b1 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/passive.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/passive.py @@ -89,8 +89,8 @@ def _spring_damper_dof_passive( stiffness = jnt_stiffness[worldid % jnt_stiffness.shape[0], jntid] damping = dof_damping[worldid % dof_damping.shape[0], dofid] - has_stiffness = stiffness != 0.0 and not opt_disableflags & DisableBit.SPRING - has_damping = damping != 0.0 and not opt_disableflags & DisableBit.DAMPER + has_stiffness = stiffness != 0.0 and not (opt_disableflags & DisableBit.SPRING) + has_damping = damping != 0.0 and not (opt_disableflags & DisableBit.DAMPER) if not has_stiffness: qfrc_spring_out[worldid, dofid] = 0.0 @@ -182,11 +182,14 @@ def _spring_damper_dof_passive( @wp.kernel def _spring_damper_tendon_passive( # Model: + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), tendon_stiffness: wp.array2d(dtype=float), tendon_damping: wp.array2d(dtype=float), tendon_lengthspring: wp.array2d(dtype=wp.vec2), # Data in: - ten_J_in: wp.array3d(dtype=float), + ten_J_in: wp.array2d(dtype=float), ten_length_in: wp.array2d(dtype=float), ten_velocity_in: wp.array2d(dtype=float), # In: @@ -196,7 +199,7 @@ def _spring_damper_tendon_passive( qfrc_spring_out: wp.array2d(dtype=float), qfrc_damper_out: wp.array2d(dtype=float), ): - worldid, tenid, dofid = wp.tid() + worldid, tenid, dofid_sparse = wp.tid() stiffness = tendon_stiffness[worldid % tendon_stiffness.shape[0], tenid] damping = tendon_damping[worldid % tendon_damping.shape[0], tenid] @@ -207,7 +210,13 @@ def _spring_damper_tendon_passive( if not has_stiffness and not has_damping: return - J = ten_J_in[worldid, tenid, dofid] + rownnz = ten_J_rownnz[tenid] + if dofid_sparse >= rownnz: + return + rowadr = ten_J_rowadr[tenid] + sparseid = rowadr + dofid_sparse + J = ten_J_in[worldid, sparseid] + dofid = ten_J_colind[sparseid] if has_stiffness: # compute spring force along tendon @@ -265,28 +274,28 @@ def _gravity_force( @wp.kernel def _fluid_force( - # Model: - opt_wind: wp.array(dtype=wp.vec3), - opt_density: wp.array(dtype=float), - opt_viscosity: wp.array(dtype=float), - body_rootid: wp.array(dtype=int), - body_geomnum: wp.array(dtype=int), - body_geomadr: wp.array(dtype=int), - body_mass: wp.array2d(dtype=float), - body_inertia: wp.array2d(dtype=wp.vec3), - geom_type: wp.array(dtype=int), - geom_size: wp.array2d(dtype=wp.vec3), - geom_fluid: wp.array2d(dtype=float), - body_fluid_ellipsoid: wp.array(dtype=bool), - # Data in: - xipos_in: wp.array2d(dtype=wp.vec3), - ximat_in: wp.array2d(dtype=wp.mat33), - geom_xpos_in: wp.array2d(dtype=wp.vec3), - geom_xmat_in: wp.array2d(dtype=wp.mat33), - subtree_com_in: wp.array2d(dtype=wp.vec3), - cvel_in: wp.array2d(dtype=wp.spatial_vector), - # Out: - fluid_applied_out: wp.array2d(dtype=wp.spatial_vector), + # Model: + opt_wind: wp.array(dtype=wp.vec3), + opt_density: wp.array(dtype=float), + opt_viscosity: wp.array(dtype=float), + body_rootid: wp.array(dtype=int), + body_geomnum: wp.array(dtype=int), + body_geomadr: wp.array(dtype=int), + body_mass: wp.array2d(dtype=float), + body_inertia: wp.array2d(dtype=wp.vec3), + geom_type: wp.array(dtype=int), + geom_size: wp.array2d(dtype=wp.vec3), + geom_fluid: wp.array2d(dtype=float), + body_fluid_ellipsoid: wp.array(dtype=bool), + # Data in: + xipos_in: wp.array2d(dtype=wp.vec3), + ximat_in: wp.array2d(dtype=wp.mat33), + geom_xpos_in: wp.array2d(dtype=wp.vec3), + geom_xmat_in: wp.array2d(dtype=wp.mat33), + subtree_com_in: wp.array2d(dtype=wp.vec3), + cvel_in: wp.array2d(dtype=wp.spatial_vector), + # Out: + fluid_applied_out: wp.array2d(dtype=wp.spatial_vector), ): """Computes body-space fluid forces for both inertia-box and ellipsoid models.""" worldid, bodyid = wp.tid() @@ -495,29 +504,29 @@ def _fluid(m: Model, d: Data): fluid_applied = wp.empty((d.nworld, m.nbody), dtype=wp.spatial_vector) wp.launch( - _fluid_force, - dim=(d.nworld, m.nbody), - inputs=[ - m.opt.wind, - m.opt.density, - m.opt.viscosity, - m.body_rootid, - m.body_geomnum, - m.body_geomadr, - m.body_mass, - m.body_inertia, - m.geom_type, - m.geom_size, - m.geom_fluid, - m.body_fluid_ellipsoid, - d.xipos, - d.ximat, - d.geom_xpos, - d.geom_xmat, - d.subtree_com, - d.cvel, - ], - outputs=[fluid_applied], + _fluid_force, + dim=(d.nworld, m.nbody), + inputs=[ + m.opt.wind, + m.opt.density, + m.opt.viscosity, + m.body_rootid, + m.body_geomnum, + m.body_geomadr, + m.body_mass, + m.body_inertia, + m.geom_type, + m.geom_size, + m.geom_fluid, + m.body_fluid_ellipsoid, + d.xipos, + d.ximat, + d.geom_xpos, + d.geom_xmat, + d.subtree_com, + d.cvel, + ], + outputs=[fluid_applied], ) support.apply_ft(m, d, fluid_applied, d.qfrc_fluid, False) @@ -565,6 +574,7 @@ def _flex_elasticity( flex_edgeadr: wp.array(dtype=int), flex_elemadr: wp.array(dtype=int), flex_elemnum: wp.array(dtype=int), + flex_elemdataadr: wp.array(dtype=int), flex_elemedgeadr: wp.array(dtype=int), flex_vertbodyid: wp.array(dtype=int), flex_elem: wp.array(dtype=int), @@ -590,32 +600,39 @@ def _flex_elasticity( f = i break + local_elemid = elemid - flex_elemadr[f] dim = flex_dim[f] nvert = dim + 1 nedge = nvert * (nvert - 1) / 2 edges = wp.where( - dim == 3, - wp.matrix(0, 1, 1, 2, 2, 0, 2, 3, 0, 3, 1, 3, shape=(6, 2), dtype=int), - wp.matrix(1, 2, 2, 0, 0, 1, 0, 0, 0, 0, 0, 0, shape=(6, 2), dtype=int), + dim == 1, + wp.matrix(0, 1, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, shape=(6, 2), dtype=int), + wp.where( + dim == 3, + wp.matrix(0, 1, 1, 2, 2, 0, 2, 3, 0, 3, 1, 3, shape=(6, 2), dtype=int), + wp.matrix(1, 2, 2, 0, 0, 1, 0, 0, 0, 0, 0, 0, shape=(6, 2), dtype=int), + ), ) if timestep > 0.0 and not dsbl_damper: kD = flex_damping[f] / timestep else: kD = 0.0 + elem_data_adr = flex_elemdataadr[f] + local_elemid * (dim + 1) + vbase = flex_vertadr[f] gradient = wp.matrix(0.0, shape=(6, 6)) for e in range(nedge): - vert0 = flex_elem[(dim + 1) * elemid + edges[e, 0]] - vert1 = flex_elem[(dim + 1) * elemid + edges[e, 1]] - xpos0 = flexvert_xpos_in[worldid, vert0] - xpos1 = flexvert_xpos_in[worldid, vert1] + vert0 = flex_elem[elem_data_adr + edges[e, 0]] + vert1 = flex_elem[elem_data_adr + edges[e, 1]] + xpos0 = flexvert_xpos_in[worldid, vbase + vert0] + xpos1 = flexvert_xpos_in[worldid, vbase + vert1] for i in range(3): gradient[e, 0 + i] = xpos0[i] - xpos1[i] gradient[e, 3 + i] = xpos1[i] - xpos0[i] elongation = wp.spatial_vectorf(0.0) for e in range(nedge): - idx = flex_elemedge[elemid * nedge + e] + idx = flex_elemedge[flex_elemedgeadr[f] + local_elemid * nedge + e] vel = flexedge_velocity_in[worldid, flex_edgeadr[f] + idx] deformed = flexedge_length_in[worldid, flex_edgeadr[f] + idx] reference = flexedge_length0[flex_edgeadr[f] + idx] @@ -638,7 +655,7 @@ def _flex_elasticity( force[edges[ed2, i], x] -= elongation[ed1] * gradient[ed2, 3 * i + x] * metric[ed1, ed2] for v in range(nvert): - vert = flex_elem[(dim + 1) * elemid + v] + vert = flex_elem[elem_data_adr + v] bodyid = flex_vertbodyid[flex_vertadr[f] + vert] for x in range(3): wp.atomic_add(qfrc_spring_out, worldid, body_dofadr[bodyid] + x, force[v, x]) @@ -742,8 +759,11 @@ def passive(m: Model, d: Data): if m.ntendon: wp.launch( _spring_damper_tendon_passive, - dim=(d.nworld, m.ntendon, m.nv), + dim=(d.nworld, m.ntendon, m.max_ten_J_rownnz), inputs=[ + m.ten_J_rownnz, + m.ten_J_rowadr, + m.ten_J_colind, m.tendon_stiffness, m.tendon_damping, m.tendon_lengthspring, @@ -772,6 +792,7 @@ def passive(m: Model, d: Data): m.flex_edgeadr, m.flex_elemadr, m.flex_elemnum, + m.flex_elemdataadr, m.flex_elemedgeadr, m.flex_vertbodyid, m.flex_elem, diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/ray.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/ray.py index 5eaea82124..57d6a5ba74 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/ray.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/ray.py @@ -752,7 +752,8 @@ def ray_mesh_with_bvh_anyhit( @wp.func def ray_flex_with_bvh( # In: - bvh_id: wp.uint64, + flex_bvh_id: wp.array(dtype=wp.uint64), + flexid: int, group_root: int, pnt: wp.vec3, vec: wp.vec3, @@ -769,7 +770,7 @@ def ray_flex_with_bvh( n = wp.vec3(0.0, 0.0, 0.0) f = int(-1) - hit = wp.mesh_query_ray(bvh_id, pnt, vec, max_t, t, u, v, sign, n, f, group_root) + hit = wp.mesh_query_ray(flex_bvh_id[flexid], pnt, vec, max_t, t, u, v, sign, n, f, group_root) if hit: return t, n, u, v, f @@ -777,6 +778,23 @@ def ray_flex_with_bvh( return -1.0, wp.vec3(0.0, 0.0, 0.0), 0.0, 0.0, -1 +@wp.func +def ray_flex_with_bvh_anyhit( + # In: + flex_bvh_id: wp.array(dtype=wp.uint64), + flexid: int, + group_root: int, + pnt: wp.vec3, + vec: wp.vec3, + max_t: float, +) -> bool: + """Returns True if there is any hit for ray flex intersections. + + Requires wp.Mesh be constructed and their ids to be passed. Flex are already in world space. + """ + return wp.mesh_query_ray_anyhit(flex_bvh_id[flexid], pnt, vec, max_t, group_root) + + @wp.func def ray_geom(pos: wp.vec3, mat: wp.mat33, size: wp.vec3, pnt: wp.vec3, vec: wp.vec3, geomtype: int) -> Tuple[float, wp.vec3]: """Returns distance along ray to intersection with geom and normal at intersection point. diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/render.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/render.py index 28a4284f2d..bc8d16c3ad 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/render.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/render.py @@ -23,6 +23,7 @@ from mujoco.mjx.third_party.mujoco_warp._src.ray import ray_cylinder from mujoco.mjx.third_party.mujoco_warp._src.ray import ray_ellipsoid from mujoco.mjx.third_party.mujoco_warp._src.ray import ray_flex_with_bvh +from mujoco.mjx.third_party.mujoco_warp._src.ray import ray_flex_with_bvh_anyhit from mujoco.mjx.third_party.mujoco_warp._src.ray import ray_mesh_with_bvh from mujoco.mjx.third_party.mujoco_warp._src.ray import ray_mesh_with_bvh_anyhit from mujoco.mjx.third_party.mujoco_warp._src.ray import ray_plane @@ -39,10 +40,6 @@ wp.set_module_options({"enable_backward": False}) -# TODO(team): remove after mjwarp depends on warp-lang >= 1.12 in pyproject.toml -from mujoco.mjx.third_party.mujoco_warp._src.types import TEXTURE_DTYPE - - @wp.func def sample_texture( # Model: @@ -51,7 +48,7 @@ def sample_texture( # In: geom_id: int, tex_repeat: wp.vec2, - tex: TEXTURE_DTYPE, + tex: wp.Texture2D, pos: wp.vec3, rot: wp.mat33, mesh_facetexcoord: wp.array(dtype=wp.vec3i), @@ -94,17 +91,26 @@ def cast_ray( geom_type: wp.array(dtype=int), geom_dataid: wp.array(dtype=int), geom_size: wp.array2d(dtype=wp.vec3), + flex_vertadr: wp.array(dtype=int), + flex_edge: wp.array(dtype=wp.vec2i), + flex_radius: wp.array(dtype=float), # Data in: geom_xpos_in: wp.array2d(dtype=wp.vec3), geom_xmat_in: wp.array2d(dtype=wp.mat33), + flexvert_xpos_in: wp.array2d(dtype=wp.vec3), # In: bvh_id: wp.uint64, group_root: int, - world_id: int, + worldid: int, bvh_ngeom: int, + flex_bvh_ngeom: int, enabled_geom_ids: wp.array(dtype=int), mesh_bvh_id: wp.array(dtype=wp.uint64), hfield_bvh_id: wp.array(dtype=wp.uint64), + flex_geom_flexid: wp.array(dtype=int), + flex_geom_edgeid: wp.array(dtype=int), + flex_bvh_id: wp.array(dtype=wp.uint64), + flex_group_root: wp.array2d(dtype=int), ray_origin_world: wp.vec3, ray_dir_world: wp.vec3, ) -> Tuple[int, float, wp.vec3, float, float, int, int]: @@ -118,91 +124,127 @@ def cast_ray( query = wp.bvh_query_ray(bvh_id, ray_origin_world, ray_dir_world, group_root) bounds_nr = int(0) + ngeom = bvh_ngeom + flex_bvh_ngeom while wp.bvh_query_next(query, bounds_nr, dist): gi_global = bounds_nr - gi_bvh_local = gi_global - (world_id * bvh_ngeom) - gi = enabled_geom_ids[gi_bvh_local] + local_id = gi_global - (worldid * ngeom) + d = float(-1.0) hit_mesh_id = int(-1) u = float(0.0) v = float(0.0) f = int(-1) n = wp.vec3(0.0, 0.0, 0.0) + hit_geom_id = int(-1) + + if local_id < bvh_ngeom: + gi = enabled_geom_ids[local_id] + gtype = geom_type[gi] + else: + gi = local_id - bvh_ngeom + gtype = GeomType.FLEX + + hit_geom_id = gi # TODO: Investigate branch elimination with static loop unrolling - if geom_type[gi] == GeomType.PLANE: + if gtype == GeomType.PLANE: d, n = ray_plane( - geom_xpos_in[world_id, gi], - geom_xmat_in[world_id, gi], - geom_size[world_id % geom_size.shape[0], gi], + geom_xpos_in[worldid, gi], + geom_xmat_in[worldid, gi], + geom_size[worldid % geom_size.shape[0], gi], ray_origin_world, ray_dir_world, ) - if geom_type[gi] == GeomType.HFIELD: + if gtype == GeomType.HFIELD: d, n, u, v, f, geom_hfield_id = ray_mesh_with_bvh( hfield_bvh_id, geom_dataid[gi], - geom_xpos_in[world_id, gi], - geom_xmat_in[world_id, gi], + geom_xpos_in[worldid, gi], + geom_xmat_in[worldid, gi], ray_origin_world, ray_dir_world, dist, ) - if geom_type[gi] == GeomType.SPHERE: + if gtype == GeomType.SPHERE: d, n = ray_sphere( - geom_xpos_in[world_id, gi], - geom_size[world_id % geom_size.shape[0], gi][0] * geom_size[world_id % geom_size.shape[0], gi][0], + geom_xpos_in[worldid, gi], + geom_size[worldid % geom_size.shape[0], gi][0] * geom_size[worldid % geom_size.shape[0], gi][0], ray_origin_world, ray_dir_world, ) - if geom_type[gi] == GeomType.ELLIPSOID: + if gtype == GeomType.ELLIPSOID: d, n = ray_ellipsoid( - geom_xpos_in[world_id, gi], - geom_xmat_in[world_id, gi], - geom_size[world_id % geom_size.shape[0], gi], + geom_xpos_in[worldid, gi], + geom_xmat_in[worldid, gi], + geom_size[worldid % geom_size.shape[0], gi], ray_origin_world, ray_dir_world, ) - if geom_type[gi] == GeomType.CAPSULE: + if gtype == GeomType.CAPSULE: d, n = ray_capsule( - geom_xpos_in[world_id, gi], - geom_xmat_in[world_id, gi], - geom_size[world_id % geom_size.shape[0], gi], + geom_xpos_in[worldid, gi], + geom_xmat_in[worldid, gi], + geom_size[worldid % geom_size.shape[0], gi], ray_origin_world, ray_dir_world, ) - if geom_type[gi] == GeomType.CYLINDER: + if gtype == GeomType.CYLINDER: d, n = ray_cylinder( - geom_xpos_in[world_id, gi], - geom_xmat_in[world_id, gi], - geom_size[world_id % geom_size.shape[0], gi], + geom_xpos_in[worldid, gi], + geom_xmat_in[worldid, gi], + geom_size[worldid % geom_size.shape[0], gi], ray_origin_world, ray_dir_world, ) - if geom_type[gi] == GeomType.BOX: + if gtype == GeomType.BOX: d, all, n = ray_box( - geom_xpos_in[world_id, gi], - geom_xmat_in[world_id, gi], - geom_size[world_id % geom_size.shape[0], gi], + geom_xpos_in[worldid, gi], + geom_xmat_in[worldid, gi], + geom_size[worldid % geom_size.shape[0], gi], ray_origin_world, ray_dir_world, ) - if geom_type[gi] == GeomType.MESH: + if gtype == GeomType.MESH: d, n, u, v, f, hit_mesh_id = ray_mesh_with_bvh( mesh_bvh_id, geom_dataid[gi], - geom_xpos_in[world_id, gi], - geom_xmat_in[world_id, gi], + geom_xpos_in[worldid, gi], + geom_xmat_in[worldid, gi], ray_origin_world, ray_dir_world, dist, ) + if gtype == GeomType.FLEX: + hit_geom_id = -2 + flexid = flex_geom_flexid[gi] + edge_id = flex_geom_edgeid[gi] + + if edge_id >= 0: + edge = flex_edge[edge_id] + vert_adr = flex_vertadr[flexid] + v0 = flexvert_xpos_in[worldid, vert_adr + edge[0]] + v1 = flexvert_xpos_in[worldid, vert_adr + edge[1]] + pos = 0.5 * (v0 + v1) + vec = v1 - v0 + + length = wp.length(vec) + edgeq = math.quat_z2vec(vec) + mat = math.quat_to_mat(edgeq) + size = wp.vec3(flex_radius[flexid], 0.5 * length, 0.0) + + d, n = ray_capsule(pos, mat, size, ray_origin_world, ray_dir_world) + hit_mesh_id = flexid + else: + flex_gr = flex_group_root[worldid, flexid] + d, n, u, v, f = ray_flex_with_bvh(flex_bvh_id, flexid, flex_gr, ray_origin_world, ray_dir_world, dist) + if d >= 0.0: + hit_mesh_id = flexid if d >= 0.0 and d < dist: dist = d normal = n - geom_id = gi + geom_id = hit_geom_id bary_u = u bary_v = v face_idx = f @@ -217,17 +259,26 @@ def cast_ray_first_hit( geom_type: wp.array(dtype=int), geom_dataid: wp.array(dtype=int), geom_size: wp.array2d(dtype=wp.vec3), + flex_vertadr: wp.array(dtype=int), + flex_edge: wp.array(dtype=wp.vec2i), + flex_radius: wp.array(dtype=float), # Data in: geom_xpos_in: wp.array2d(dtype=wp.vec3), geom_xmat_in: wp.array2d(dtype=wp.mat33), + flexvert_xpos_in: wp.array2d(dtype=wp.vec3), # In: bvh_id: wp.uint64, group_root: int, - world_id: int, + worldid: int, bvh_ngeom: int, + bvh_nflexgeom: int, enabled_geom_ids: wp.array(dtype=int), mesh_bvh_id: wp.array(dtype=wp.uint64), hfield_bvh_id: wp.array(dtype=wp.uint64), + flex_geom_flexid: wp.array(dtype=int), + flex_geom_edgeid: wp.array(dtype=int), + flex_bvh_id: wp.array(dtype=wp.uint64), + flex_group_root: wp.array2d(dtype=int), ray_origin_world: wp.vec3, ray_dir_world: wp.vec3, max_dist: float, @@ -235,81 +286,119 @@ def cast_ray_first_hit( """A simpler version of casting rays that only checks for the first hit.""" query = wp.bvh_query_ray(bvh_id, ray_origin_world, ray_dir_world, group_root) bounds_nr = int(0) + ngeom = bvh_ngeom + bvh_nflexgeom while wp.bvh_query_next(query, bounds_nr, max_dist): gi_global = bounds_nr - gi_bvh_local = gi_global - (world_id * bvh_ngeom) - gi = enabled_geom_ids[gi_bvh_local] + local_id = gi_global - (worldid * ngeom) + + d = float(-1.0) + n = wp.vec3(0.0, 0.0, 0.0) + + if local_id < bvh_ngeom: + gi = enabled_geom_ids[local_id] + gtype = geom_type[gi] + else: + gi = local_id - bvh_ngeom + gtype = GeomType.FLEX # TODO: Investigate branch elimination with static loop unrolling - if geom_type[gi] == GeomType.PLANE: + if gtype == GeomType.PLANE: d, n = ray_plane( - geom_xpos_in[world_id, gi], - geom_xmat_in[world_id, gi], - geom_size[world_id % geom_size.shape[0], gi], + geom_xpos_in[worldid, gi], + geom_xmat_in[worldid, gi], + geom_size[worldid % geom_size.shape[0], gi], ray_origin_world, ray_dir_world, ) - if geom_type[gi] == GeomType.HFIELD: + if gtype == GeomType.HFIELD: d, n, u, v, f, geom_hfield_id = ray_mesh_with_bvh( hfield_bvh_id, geom_dataid[gi], - geom_xpos_in[world_id, gi], - geom_xmat_in[world_id, gi], + geom_xpos_in[worldid, gi], + geom_xmat_in[worldid, gi], ray_origin_world, ray_dir_world, max_dist, ) - if geom_type[gi] == GeomType.SPHERE: + if gtype == GeomType.SPHERE: d, n = ray_sphere( - geom_xpos_in[world_id, gi], - geom_size[world_id % geom_size.shape[0], gi][0] * geom_size[world_id % geom_size.shape[0], gi][0], + geom_xpos_in[worldid, gi], + geom_size[worldid % geom_size.shape[0], gi][0] * geom_size[worldid % geom_size.shape[0], gi][0], ray_origin_world, ray_dir_world, ) - if geom_type[gi] == GeomType.ELLIPSOID: + if gtype == GeomType.ELLIPSOID: d, n = ray_ellipsoid( - geom_xpos_in[world_id, gi], - geom_xmat_in[world_id, gi], - geom_size[world_id % geom_size.shape[0], gi], + geom_xpos_in[worldid, gi], + geom_xmat_in[worldid, gi], + geom_size[worldid % geom_size.shape[0], gi], ray_origin_world, ray_dir_world, ) - if geom_type[gi] == GeomType.CAPSULE: + if gtype == GeomType.CAPSULE: d, n = ray_capsule( - geom_xpos_in[world_id, gi], - geom_xmat_in[world_id, gi], - geom_size[world_id % geom_size.shape[0], gi], + geom_xpos_in[worldid, gi], + geom_xmat_in[worldid, gi], + geom_size[worldid % geom_size.shape[0], gi], ray_origin_world, ray_dir_world, ) - if geom_type[gi] == GeomType.CYLINDER: + if gtype == GeomType.CYLINDER: d, n = ray_cylinder( - geom_xpos_in[world_id, gi], - geom_xmat_in[world_id, gi], - geom_size[world_id % geom_size.shape[0], gi], + geom_xpos_in[worldid, gi], + geom_xmat_in[worldid, gi], + geom_size[worldid % geom_size.shape[0], gi], ray_origin_world, ray_dir_world, ) - if geom_type[gi] == GeomType.BOX: + if gtype == GeomType.BOX: d, all, n = ray_box( - geom_xpos_in[world_id, gi], - geom_xmat_in[world_id, gi], - geom_size[world_id % geom_size.shape[0], gi], + geom_xpos_in[worldid, gi], + geom_xmat_in[worldid, gi], + geom_size[worldid % geom_size.shape[0], gi], ray_origin_world, ray_dir_world, ) - if geom_type[gi] == GeomType.MESH: + if gtype == GeomType.MESH: hit = ray_mesh_with_bvh_anyhit( mesh_bvh_id, geom_dataid[gi], - geom_xpos_in[world_id, gi], - geom_xmat_in[world_id, gi], + geom_xpos_in[worldid, gi], + geom_xmat_in[worldid, gi], ray_origin_world, ray_dir_world, max_dist, ) d = 0.0 if hit else -1.0 + if gtype == GeomType.FLEX: + flexid = flex_geom_flexid[gi] + edge_id = flex_geom_edgeid[gi] + + if edge_id >= 0: + edge = flex_edge[edge_id] + vert_adr = flex_vertadr[flexid] + v0 = flexvert_xpos_in[worldid, vert_adr + edge[0]] + v1 = flexvert_xpos_in[worldid, vert_adr + edge[1]] + pos = 0.5 * (v0 + v1) + vec = v1 - v0 + + length = wp.length(vec) + edgeq = math.quat_z2vec(vec) + mat = math.quat_to_mat(edgeq) + size = wp.vec3(flex_radius[flexid], 0.5 * length, 0.0) + + d, n = ray_capsule(pos, mat, size, ray_origin_world, ray_dir_world) + else: + hit = ray_flex_with_bvh_anyhit( + flex_bvh_id, + flexid, + flex_group_root[worldid, flexid], + ray_origin_world, + ray_dir_world, + max_dist, + ) + d = 0.0 if hit else -1.0 if d >= 0.0 and d < max_dist: return True @@ -323,18 +412,27 @@ def compute_lighting( geom_type: wp.array(dtype=int), geom_dataid: wp.array(dtype=int), geom_size: wp.array2d(dtype=wp.vec3), + flex_vertadr: wp.array(dtype=int), + flex_edge: wp.array(dtype=wp.vec2i), + flex_radius: wp.array(dtype=float), # Data in: geom_xpos_in: wp.array2d(dtype=wp.vec3), geom_xmat_in: wp.array2d(dtype=wp.mat33), + flexvert_xpos_in: wp.array2d(dtype=wp.vec3), # In: use_shadows: bool, bvh_id: wp.uint64, group_root: int, bvh_ngeom: int, + bvh_nflexgeom: int, enabled_geom_ids: wp.array(dtype=int), - world_id: int, + worldid: int, mesh_bvh_id: wp.array(dtype=wp.uint64), hfield_bvh_id: wp.array(dtype=wp.uint64), + flex_geom_flexid: wp.array(dtype=int), + flex_geom_edgeid: wp.array(dtype=int), + flex_bvh_id: wp.array(dtype=wp.uint64), + flex_group_root: wp.array2d(dtype=int), lightactive: bool, lighttype: int, lightcastshadow: bool, @@ -385,15 +483,24 @@ def compute_lighting( geom_type, geom_dataid, geom_size, + flex_vertadr, + flex_edge, + flex_radius, geom_xpos_in, geom_xmat_in, + flexvert_xpos_in, bvh_id, group_root, - world_id, + worldid, bvh_ngeom, + bvh_nflexgeom, enabled_geom_ids, mesh_bvh_id, hfield_bvh_id, + flex_geom_flexid, + flex_geom_edgeid, + flex_bvh_id, + flex_group_root, shadow_origin, L, max_t, @@ -418,6 +525,7 @@ def render(m: Model, d: Data, rc: RenderContext): """ rc.rgb_data.fill_(rc.background_color) rc.depth_data.fill_(0.0) + rc.seg_data.fill_(-1) @wp.kernel(module="unique", enable_backward=False) def _render_megakernel( @@ -434,6 +542,9 @@ def _render_megakernel( light_type: wp.array2d(dtype=int), light_castshadow: wp.array2d(dtype=bool), light_active: wp.array2d(dtype=bool), + flex_vertadr: wp.array(dtype=int), + flex_edge: wp.array(dtype=wp.vec2i), + flex_radius: wp.array(dtype=float), mesh_faceadr: wp.array(dtype=int), mat_texid: wp.array3d(dtype=int), mat_texrepeat: wp.array2d(dtype=wp.vec2), @@ -445,21 +556,25 @@ def _render_megakernel( cam_xmat_in: wp.array2d(dtype=wp.mat33), light_xpos_in: wp.array2d(dtype=wp.vec3), light_xdir_in: wp.array2d(dtype=wp.vec3), + flexvert_xpos_in: wp.array2d(dtype=wp.vec3), # In: nrender: int, use_shadows: bool, bvh_ngeom: int, + bvh_nflexgeom: int, cam_res: wp.array(dtype=wp.vec2i), cam_id_map: wp.array(dtype=int), ray: wp.array(dtype=wp.vec3), rgb_adr: wp.array(dtype=int), depth_adr: wp.array(dtype=int), + seg_adr: wp.array(dtype=int), render_rgb: wp.array(dtype=bool), render_depth: wp.array(dtype=bool), + render_seg: wp.array(dtype=bool), bvh_id: wp.uint64, group_root: wp.array(dtype=int), - flex_bvh_id: wp.uint64, - flex_group_root: wp.array(dtype=int), + flex_bvh_id: wp.array(dtype=wp.uint64), + flex_group_root: wp.array2d(dtype=int), enabled_geom_ids: wp.array(dtype=int), mesh_bvh_id: wp.array(dtype=wp.uint64), mesh_facetexcoord: wp.array(dtype=wp.vec3i), @@ -467,46 +582,48 @@ def _render_megakernel( mesh_texcoord_offsets: wp.array(dtype=int), hfield_bvh_id: wp.array(dtype=wp.uint64), flex_rgba: wp.array(dtype=wp.vec4), - # TODO: remove after mjwarp depends on warp-lang >= 1.12 in pyproject.toml - textures: wp.array(dtype=TEXTURE_DTYPE), + flex_geom_flexid: wp.array(dtype=int), + flex_geom_edgeid: wp.array(dtype=int), + textures: wp.array(dtype=wp.Texture2D), # Out: rgb_out: wp.array2d(dtype=wp.uint32), depth_out: wp.array2d(dtype=float), + seg_out: wp.array2d(dtype=int), ): - world_idx, ray_idx = wp.tid() + worldid, rayid = wp.tid() - # Map global ray_idx -> (cam_idx, ray_idx_local) using cumulative sizes + # Map global rayid -> (cam_idx, rayid_local) using cumulative sizes cam_idx = int(-1) - ray_idx_local = int(-1) + rayid_local = int(-1) accum = int(0) for i in range(nrender): num_i = cam_res[i][0] * cam_res[i][1] - if ray_idx < accum + num_i: + if rayid < accum + num_i: cam_idx = i - ray_idx_local = ray_idx - accum + rayid_local = rayid - accum break accum += num_i - if cam_idx == -1 or ray_idx_local < 0: + if cam_idx == -1 or rayid_local < 0: return - if not render_rgb[cam_idx] and not render_depth[cam_idx]: + if not render_rgb[cam_idx] and not render_depth[cam_idx] and not render_seg[cam_idx]: return # Map active camera index to MuJoCo camera ID mujoco_cam_id = cam_id_map[cam_idx] if wp.static(rc.use_precomputed_rays): - ray_dir_local_cam = ray[ray_idx] + ray_dir_local_cam = ray[rayid] else: img_w = cam_res[cam_idx][0] img_h = cam_res[cam_idx][1] - px = ray_idx_local % img_w - py = ray_idx_local // img_w + px = rayid_local % img_w + py = rayid_local // img_w ray_dir_local_cam = compute_ray( cam_projection[mujoco_cam_id], - cam_fovy[world_idx % cam_fovy.shape[0], mujoco_cam_id], + cam_fovy[worldid % cam_fovy.shape[0], mujoco_cam_id], cam_sensorsize[mujoco_cam_id], - cam_intrinsic[world_idx % cam_intrinsic.shape[0], mujoco_cam_id], + cam_intrinsic[worldid % cam_intrinsic.shape[0], mujoco_cam_id], img_w, img_h, px, @@ -514,38 +631,37 @@ def _render_megakernel( wp.static(rc.znear), ) - ray_dir_world = cam_xmat_in[world_idx, mujoco_cam_id] @ ray_dir_local_cam - ray_origin_world = cam_xpos_in[world_idx, mujoco_cam_id] + ray_dir_world = cam_xmat_in[worldid, mujoco_cam_id] @ ray_dir_local_cam + ray_origin_world = cam_xpos_in[worldid, mujoco_cam_id] geom_id, dist, normal, u, v, f, mesh_id = cast_ray( geom_type, geom_dataid, geom_size, + flex_vertadr, + flex_edge, + flex_radius, geom_xpos_in, geom_xmat_in, + flexvert_xpos_in, bvh_id, - group_root[world_idx], - world_idx, + group_root[worldid], + worldid, bvh_ngeom, + bvh_nflexgeom, enabled_geom_ids, mesh_bvh_id, hfield_bvh_id, + flex_geom_flexid, + flex_geom_edgeid, + flex_bvh_id, + flex_group_root, ray_origin_world, ray_dir_world, ) - if wp.static(m.nflex > 0): - d, n, u, v, f = ray_flex_with_bvh( - flex_bvh_id, - flex_group_root[world_idx], - ray_origin_world, - ray_dir_world, - dist, - ) - if d >= 0.0 and d < dist: - dist = d - normal = n - geom_id = -2 + if render_seg[cam_idx] and geom_id != -1: + seg_out[worldid, seg_adr[cam_idx] + rayid_local] = geom_id # Early Out if geom_id == -1: @@ -556,9 +672,7 @@ def _render_megakernel( # In camera-local coordinates, the optical axis is -Z. The Z-component of the # normalized ray direction is negative, so -ray_dir_local_cam[2] gives cos(θ) # between the ray and the optical axis. - depth_out[world_idx, depth_adr[cam_idx] + ray_idx_local] = dist * ( - -ray_dir_local_cam[2] - ) + depth_out[worldid, depth_adr[cam_idx] + rayid_local] = dist * (-ray_dir_local_cam[2]) if not render_rgb[cam_idx]: return @@ -567,31 +681,30 @@ def _render_megakernel( hit_point = ray_origin_world + ray_dir_world * dist if geom_id == -2: - # TODO: Currently flex textures are not supported, and only the first rgba value - # is used until further flex support is added. - color = flex_rgba[0] - elif geom_matid[world_idx % geom_matid.shape[0], geom_id] == -1: - color = geom_rgba[world_idx % geom_rgba.shape[0], geom_id] + # We encode flex_id in mesh_id for flex ray hits during cast_ray + color = flex_rgba[mesh_id] + elif geom_matid[worldid % geom_matid.shape[0], geom_id] == -1: + color = geom_rgba[worldid % geom_rgba.shape[0], geom_id] else: - color = mat_rgba[world_idx % mat_rgba.shape[0], geom_matid[world_idx % geom_matid.shape[0], geom_id]] + color = mat_rgba[worldid % mat_rgba.shape[0], geom_matid[worldid % geom_matid.shape[0], geom_id]] base_color = wp.vec3(color[0], color[1], color[2]) hit_color = base_color if wp.static(rc.use_textures): if geom_id != -2: - mat_id = geom_matid[world_idx % geom_matid.shape[0], geom_id] + mat_id = geom_matid[worldid % geom_matid.shape[0], geom_id] if mat_id >= 0: - tex_id = mat_texid[world_idx % mat_texid.shape[0], mat_id, 1] + tex_id = mat_texid[worldid % mat_texid.shape[0], mat_id, 1] if tex_id >= 0: tex_color = sample_texture( geom_type, mesh_faceadr, geom_id, - mat_texrepeat[world_idx % mat_texrepeat.shape[0], mat_id], + mat_texrepeat[worldid % mat_texrepeat.shape[0], mat_id], textures[tex_id], - geom_xpos_in[world_idx, geom_id], - geom_xmat_in[world_idx, geom_id], + geom_xpos_in[worldid, geom_id], + geom_xmat_in[worldid, geom_id], mesh_facetexcoord, mesh_texcoord, mesh_texcoord_offsets, @@ -616,21 +729,30 @@ def _render_megakernel( geom_type, geom_dataid, geom_size, + flex_vertadr, + flex_edge, + flex_radius, geom_xpos_in, geom_xmat_in, + flexvert_xpos_in, use_shadows, bvh_id, - group_root[world_idx], + group_root[worldid], bvh_ngeom, + bvh_nflexgeom, enabled_geom_ids, - world_idx, + worldid, mesh_bvh_id, hfield_bvh_id, - light_active[world_idx % light_active.shape[0], l], - light_type[world_idx % light_type.shape[0], l], - light_castshadow[world_idx % light_castshadow.shape[0], l], - light_xpos_in[world_idx, l], - light_xdir_in[world_idx, l], + flex_geom_flexid, + flex_geom_edgeid, + flex_bvh_id, + flex_group_root, + light_active[worldid % light_active.shape[0], l], + light_type[worldid % light_type.shape[0], l], + light_castshadow[worldid % light_castshadow.shape[0], l], + light_xpos_in[worldid, l], + light_xdir_in[worldid, l], normal, hit_point, ) @@ -639,7 +761,7 @@ def _render_megakernel( hit_color = wp.min(result, wp.vec3(1.0, 1.0, 1.0)) hit_color = wp.max(hit_color, wp.vec3(0.0, 0.0, 0.0)) - rgb_out[world_idx, rgb_adr[cam_idx] + ray_idx_local] = pack_rgba_to_uint32( + rgb_out[worldid, rgb_adr[cam_idx] + rayid_local] = pack_rgba_to_uint32( hit_color[0] * 255.0, hit_color[1] * 255.0, hit_color[2] * 255.0, @@ -662,6 +784,9 @@ def _render_megakernel( m.light_type, m.light_castshadow, m.light_active, + m.flex_vertadr, + m.flex_edge, + m.flex_radius, m.mesh_faceadr, m.mat_texid, m.mat_texrepeat, @@ -672,16 +797,20 @@ def _render_megakernel( d.cam_xmat, d.light_xpos, d.light_xdir, + d.flexvert_xpos, rc.nrender, rc.use_shadows, rc.bvh_ngeom, + rc.bvh_nflexgeom, rc.cam_res, rc.cam_id_map, rc.ray, rc.rgb_adr, rc.depth_adr, + rc.seg_adr, rc.render_rgb, rc.render_depth, + rc.render_seg, rc.bvh_id, rc.group_root, rc.flex_bvh_id, @@ -693,10 +822,13 @@ def _render_megakernel( rc.mesh_texcoord_offsets, rc.hfield_bvh_id, rc.flex_rgba, + rc.flex_geom_flexid, + rc.flex_geom_edgeid, rc.textures, ], outputs=[ rc.rgb_data, rc.depth_data, + rc.seg_data, ], ) diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/render_util.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/render_util.py index ccb808ff47..36958f8e98 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/render_util.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/render_util.py @@ -206,3 +206,41 @@ def get_depth(rc: RenderContext, camera_index: int, depth_scale: float, depth_ou inputs=[rc.depth_data, rc.depth_adr, camera_index, depth_scale], outputs=[depth_out], ) + + +@wp.kernel +def _extract_seg_kernel( + # In: + seg_data: wp.array2d(dtype=int), + seg_adr: wp.array(dtype=int), + camera_index: int, + # Out: + seg_out: wp.array3d(dtype=int), +): + """Extract per-pixel geom IDs from the render context buffers for a given camera index.""" + worldid, pixelid = wp.tid() + xid = pixelid % seg_out.shape[2] + yid = pixelid // seg_out.shape[2] + + seg_adr_offset = seg_adr[camera_index] + seg_out[worldid, yid, xid] = seg_data[worldid, seg_adr_offset + pixelid] + + +def get_segmentation(rc: RenderContext, camera_index: int, seg_out: wp.array3d(dtype=int)): + """Get the segmentation data from the render context buffers for a given camera index. + + Each pixel contains the MuJoCo geom ID of the geometry hit by the ray, -1 for + background, or -2 for flex bodies. + + Args: + rc: The render context on device. + camera_index: The index of the camera to get the segmentation data for. + seg_out: The output array to store the geom IDs in, with shape + (nworld, height, width). + """ + wp.launch( + _extract_seg_kernel, + dim=(seg_out.shape[0], seg_out.shape[1] * seg_out.shape[2]), + inputs=[rc.seg_data, rc.seg_adr, camera_index], + outputs=[seg_out], + ) diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/sensor.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/sensor.py index 859ddf8a86..2c8177b831 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/sensor.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/sensor.py @@ -15,12 +15,17 @@ from typing import Any, Tuple +import warp as wp + from mujoco.mjx.third_party.mujoco_warp._src import math from mujoco.mjx.third_party.mujoco_warp._src import ray from mujoco.mjx.third_party.mujoco_warp._src import smooth from mujoco.mjx.third_party.mujoco_warp._src import support from mujoco.mjx.third_party.mujoco_warp._src.collision_sdf import get_sdf_params from mujoco.mjx.third_party.mujoco_warp._src.collision_sdf import sdf +from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MAXCONPAIR +from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MAXVAL +from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MINVAL from mujoco.mjx.third_party.mujoco_warp._src.types import ConeType from mujoco.mjx.third_party.mujoco_warp._src.types import ConstraintType from mujoco.mjx.third_party.mujoco_warp._src.types import ContactType @@ -28,9 +33,6 @@ from mujoco.mjx.third_party.mujoco_warp._src.types import DataType from mujoco.mjx.third_party.mujoco_warp._src.types import DisableBit from mujoco.mjx.third_party.mujoco_warp._src.types import JointType -from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MAXCONPAIR -from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MAXVAL -from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MINVAL from mujoco.mjx.third_party.mujoco_warp._src.types import Model from mujoco.mjx.third_party.mujoco_warp._src.types import ObjType from mujoco.mjx.third_party.mujoco_warp._src.types import SensorType @@ -40,10 +42,10 @@ from mujoco.mjx.third_party.mujoco_warp._src.types import vec6 from mujoco.mjx.third_party.mujoco_warp._src.types import vec8 from mujoco.mjx.third_party.mujoco_warp._src.types import vec8i +from mujoco.mjx.third_party.mujoco_warp._src.types import vec_pluginattr from mujoco.mjx.third_party.mujoco_warp._src.util_misc import inside_geom from mujoco.mjx.third_party.mujoco_warp._src.warp_util import cache_kernel from mujoco.mjx.third_party.mujoco_warp._src.warp_util import event_scope -import warp as wp wp.set_module_options({"enable_backward": False}) @@ -2081,16 +2083,16 @@ def _transform_spatial(vec: wp.spatial_vector, dif: wp.vec3) -> wp.vec3: @wp.kernel def _preprocess_tactile_contacts( - # Model: - body_weldid: wp.array(dtype=int), - geom_bodyid: wp.array(dtype=int), - # Data in: - contact_geom_in: wp.array(dtype=wp.vec2i), - contact_worldid_in: wp.array(dtype=int), - nacon_in: wp.array(dtype=int), - # Out: - weld_geom_count_out: wp.array2d(dtype=int), - weld_geom_list_out: wp.array3d(dtype=int), + # Model: + body_weldid: wp.array(dtype=int), + geom_bodyid: wp.array(dtype=int), + # Data in: + contact_geom_in: wp.array(dtype=wp.vec2i), + contact_worldid_in: wp.array(dtype=int), + nacon_in: wp.array(dtype=int), + # Out: + weld_geom_count_out: wp.array2d(dtype=int), + weld_geom_list_out: wp.array3d(dtype=int), ): conid = wp.tid() ncon = nacon_in[0] @@ -2118,42 +2120,43 @@ def _preprocess_tactile_contacts( @wp.kernel def _sensor_tactile( - # Model: - body_rootid: wp.array(dtype=int), - body_weldid: wp.array(dtype=int), - oct_child: wp.array(dtype=vec8i), - oct_aabb: wp.array2d(dtype=wp.vec3), - oct_coeff: wp.array(dtype=vec8), - geom_type: wp.array(dtype=int), - geom_bodyid: wp.array(dtype=int), - geom_size: wp.array2d(dtype=wp.vec3), - mesh_vertadr: wp.array(dtype=int), - mesh_vertnum: wp.array(dtype=int), - mesh_octadr: wp.array(dtype=int), - mesh_normaladr: wp.array(dtype=int), - mesh_normalnum: wp.array(dtype=int), - mesh_vert: wp.array(dtype=wp.vec3), - mesh_normal: wp.array(dtype=wp.vec3), - mesh_quat: wp.array(dtype=wp.quat), - sensor_objid: wp.array(dtype=int), - sensor_refid: wp.array(dtype=int), - sensor_dim: wp.array(dtype=int), - sensor_adr: wp.array(dtype=int), - plugin: wp.array(dtype=int), - plugin_attr: wp.array(dtype=wp.vec3f), - geom_plugin_index: wp.array(dtype=int), - taxel_vertadr: wp.array(dtype=int), - taxel_sensorid: wp.array(dtype=int), - # Data in: - geom_xpos_in: wp.array2d(dtype=wp.vec3), - geom_xmat_in: wp.array2d(dtype=wp.mat33), - subtree_com_in: wp.array2d(dtype=wp.vec3), - cvel_in: wp.array2d(dtype=wp.spatial_vector), - # In: - weld_geom_count_in: wp.array2d(dtype=int), - weld_geom_list_in: wp.array3d(dtype=int), - # Data out: - sensordata_out: wp.array2d(dtype=float), + # Model: + body_rootid: wp.array(dtype=int), + body_weldid: wp.array(dtype=int), + oct_child: wp.array(dtype=vec8i), + oct_aabb: wp.array2d(dtype=wp.vec3), + oct_coeff: wp.array(dtype=vec8), + geom_type: wp.array(dtype=int), + geom_bodyid: wp.array(dtype=int), + geom_dataid: wp.array(dtype=int), + geom_size: wp.array2d(dtype=wp.vec3), + mesh_vertadr: wp.array(dtype=int), + mesh_vertnum: wp.array(dtype=int), + mesh_octadr: wp.array(dtype=int), + mesh_normaladr: wp.array(dtype=int), + mesh_normalnum: wp.array(dtype=int), + mesh_vert: wp.array(dtype=wp.vec3), + mesh_normal: wp.array(dtype=wp.vec3), + mesh_quat: wp.array(dtype=wp.quat), + sensor_objid: wp.array(dtype=int), + sensor_refid: wp.array(dtype=int), + sensor_dim: wp.array(dtype=int), + sensor_adr: wp.array(dtype=int), + plugin: wp.array(dtype=int), + plugin_attr: wp.array(dtype=vec_pluginattr), + geom_plugin_index: wp.array(dtype=int), + taxel_vertadr: wp.array(dtype=int), + taxel_sensorid: wp.array(dtype=int), + # Data in: + geom_xpos_in: wp.array2d(dtype=wp.vec3), + geom_xmat_in: wp.array2d(dtype=wp.mat33), + subtree_com_in: wp.array2d(dtype=wp.vec3), + cvel_in: wp.array2d(dtype=wp.spatial_vector), + # In: + weld_geom_count_in: wp.array2d(dtype=int), + weld_geom_list_in: wp.array3d(dtype=int), + # Data out: + sensordata_out: wp.array2d(dtype=float), ): worldid, taxelid = wp.tid() @@ -2211,40 +2214,25 @@ def _sensor_tactile( contact_type = geom_type[geom] plugin_attributes, plugin_index, volume_data, mesh_data = get_sdf_params( - oct_child, - oct_aabb, - oct_coeff, - mesh_octadr, - plugin, - plugin_attr, - contact_type, - geom_size[worldid % geom_size.shape[0], geom], - plugin_id, - mesh_id, + oct_child, + oct_aabb, + oct_coeff, + mesh_octadr, + plugin, + plugin_attr, + contact_type, + geom_size[worldid % geom_size.shape[0], geom], + plugin_id, + geom_dataid[geom], ) - depth = wp.min( - sdf( - contact_type, - lpos, - plugin_attributes, - plugin_index, - volume_data, - mesh_data, - ), - 0.0, - ) + depth = wp.min(sdf(contact_type, lpos, plugin_attributes, plugin_index, volume_data, mesh_data), 0.0) if depth >= 0.0: continue - vel_sensor = _transform_spatial( - cvel_in[worldid, parent_weld], - xpos - subtree_com_in[worldid, body_rootid[parent_weld]], - ) + vel_sensor = _transform_spatial(cvel_in[worldid, parent_weld], xpos - subtree_com_in[worldid, body_rootid[parent_weld]]) vel_other = _transform_spatial( - cvel_in[worldid, body], - geom_xpos_in[worldid, geom] - - subtree_com_in[worldid, body_rootid[body]], + cvel_in[worldid, body], geom_xpos_in[worldid, geom] - subtree_com_in[worldid, body_rootid[body]] ) vel_rel = vel_sensor - vel_other @@ -2259,24 +2247,9 @@ def _sensor_tactile( forceT[2] = wp.abs(wp.dot(vel_rel, tang2)) dim = sensor_dim[sensor_id] // 3 - wp.atomic_add( - sensordata_out, - worldid, - sensor_adr[sensor_id] + 0 * dim + vertid, - forceT[0], - ) - wp.atomic_add( - sensordata_out, - worldid, - sensor_adr[sensor_id] + 1 * dim + vertid, - forceT[1], - ) - wp.atomic_add( - sensordata_out, - worldid, - sensor_adr[sensor_id] + 2 * dim + vertid, - forceT[2], - ) + wp.atomic_add(sensordata_out, worldid, sensor_adr[sensor_id] + 0 * dim + vertid, forceT[0]) + wp.atomic_add(sensordata_out, worldid, sensor_adr[sensor_id] + 1 * dim + vertid, forceT[1]) + wp.atomic_add(sensordata_out, worldid, sensor_adr[sensor_id] + 2 * dim + vertid, forceT[2]) @wp.func @@ -2507,60 +2480,61 @@ def sensor_acc(m: Model, d: Data): weld_geom_count = wp.zeros((d.nworld, m.nbody), dtype=int) weld_geom_list = wp.full((d.nworld, m.nbody, MJ_MAXCONPAIR), -1, dtype=int) wp.launch( - _preprocess_tactile_contacts, - dim=d.naconmax, - inputs=[ - m.body_weldid, - m.geom_bodyid, - d.contact.geom, - d.contact.worldid, - d.nacon, - ], - outputs=[ - weld_geom_count, - weld_geom_list, - ], + _preprocess_tactile_contacts, + dim=d.naconmax, + inputs=[ + m.body_weldid, + m.geom_bodyid, + d.contact.geom, + d.contact.worldid, + d.nacon, + ], + outputs=[ + weld_geom_count, + weld_geom_list, + ], ) wp.launch( - _sensor_tactile, - dim=(d.nworld, m.nsensortaxel), - inputs=[ - m.body_rootid, - m.body_weldid, - m.oct_child, - m.oct_aabb, - m.oct_coeff, - m.geom_type, - m.geom_bodyid, - m.geom_size, - m.mesh_vertadr, - m.mesh_vertnum, - m.mesh_octadr, - m.mesh_normaladr, - m.mesh_normalnum, - m.mesh_vert, - m.mesh_normal, - m.mesh_quat, - m.sensor_objid, - m.sensor_refid, - m.sensor_dim, - m.sensor_adr, - m.plugin, - m.plugin_attr, - m.geom_plugin_index, - m.taxel_vertadr, - m.taxel_sensorid, - d.geom_xpos, - d.geom_xmat, - d.subtree_com, - d.cvel, - weld_geom_count, - weld_geom_list, - ], - outputs=[ - d.sensordata, - ], + _sensor_tactile, + dim=(d.nworld, m.nsensortaxel), + inputs=[ + m.body_rootid, + m.body_weldid, + m.oct_child, + m.oct_aabb, + m.oct_coeff, + m.geom_type, + m.geom_bodyid, + m.geom_dataid, + m.geom_size, + m.mesh_vertadr, + m.mesh_vertnum, + m.mesh_octadr, + m.mesh_normaladr, + m.mesh_normalnum, + m.mesh_vert, + m.mesh_normal, + m.mesh_quat, + m.sensor_objid, + m.sensor_refid, + m.sensor_dim, + m.sensor_adr, + m.plugin, + m.plugin_attr, + m.geom_plugin_index, + m.taxel_vertadr, + m.taxel_sensorid, + d.geom_xpos, + d.geom_xmat, + d.subtree_com, + d.cvel, + weld_geom_count, + weld_geom_list, + ], + outputs=[ + d.sensordata, + ], ) sensor_contact_nmatch = wp.empty((d.nworld, m.nsensorcontact), dtype=int) @@ -2882,12 +2856,12 @@ def energy_pos(m: Model, d: Data): wp.launch(_energy_pos_zero, dim=d.nworld, outputs=[d.energy]) # init potential energy: -sum_i(body_i.mass * dot(gravity, body_i.pos)) - if not m.opt.disableflags & DisableBit.GRAVITY: + if not (m.opt.disableflags & DisableBit.GRAVITY): wp.launch( _energy_pos_gravity, dim=(d.nworld, m.nbody - 1), inputs=[m.opt.gravity, m.body_mass, d.xipos], outputs=[d.energy] ) - if not m.opt.disableflags & DisableBit.SPRING: + if not (m.opt.disableflags & DisableBit.SPRING): # add joint-level springs wp.launch( _energy_pos_passive_joint, diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/smooth.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/smooth.py index 51b3640334..51dfadb461 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/smooth.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/smooth.py @@ -14,29 +14,29 @@ # ============================================================================== +import warp as wp + from mujoco.mjx.third_party.mujoco_warp._src import math from mujoco.mjx.third_party.mujoco_warp._src import support from mujoco.mjx.third_party.mujoco_warp._src import util_misc +from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MAXVAL +from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MINVAL from mujoco.mjx.third_party.mujoco_warp._src.types import CamLightType from mujoco.mjx.third_party.mujoco_warp._src.types import ConeType from mujoco.mjx.third_party.mujoco_warp._src.types import Data from mujoco.mjx.third_party.mujoco_warp._src.types import DisableBit from mujoco.mjx.third_party.mujoco_warp._src.types import EqType from mujoco.mjx.third_party.mujoco_warp._src.types import JointType -from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MAXVAL -from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MINVAL from mujoco.mjx.third_party.mujoco_warp._src.types import Model from mujoco.mjx.third_party.mujoco_warp._src.types import ObjType -from mujoco.mjx.third_party.mujoco_warp._src.types import SPARSE_CONSTRAINT_JACOBIAN from mujoco.mjx.third_party.mujoco_warp._src.types import TileSet from mujoco.mjx.third_party.mujoco_warp._src.types import TrnType +from mujoco.mjx.third_party.mujoco_warp._src.types import WrapType +from mujoco.mjx.third_party.mujoco_warp._src.types import vec5 from mujoco.mjx.third_party.mujoco_warp._src.types import vec10 from mujoco.mjx.third_party.mujoco_warp._src.types import vec11 -from mujoco.mjx.third_party.mujoco_warp._src.types import vec5 -from mujoco.mjx.third_party.mujoco_warp._src.types import WrapType from mujoco.mjx.third_party.mujoco_warp._src.warp_util import cache_kernel from mujoco.mjx.third_party.mujoco_warp._src.warp_util import event_scope -import warp as wp wp.set_module_options({"enable_backward": False}) @@ -227,38 +227,59 @@ def _site_local_to_global( @wp.kernel def _flex_vertices( # Model: + nflex: int, + flex_vertadr: wp.array(dtype=int), + flex_vertnum: wp.array(dtype=int), flex_vertbodyid: wp.array(dtype=int), + flex_vert: wp.array(dtype=wp.vec3), + flex_centered: wp.array(dtype=bool), # Data in: xpos_in: wp.array2d(dtype=wp.vec3), + xmat_in: wp.array2d(dtype=wp.mat33), # Data out: flexvert_xpos_out: wp.array2d(dtype=wp.vec3), ): worldid, vertid = wp.tid() - flexvert_xpos_out[worldid, vertid] = xpos_in[worldid, flex_vertbodyid[vertid]] + + for f in range(nflex): + locid = vertid - flex_vertadr[f] + if locid >= 0 and locid < flex_vertnum[f]: + break + + bodyid = flex_vertbodyid[vertid] + xpos = xpos_in[worldid, bodyid] + + if flex_centered[f]: + flexvert_xpos_out[worldid, vertid] = xpos + else: + xmat = xmat_in[worldid, bodyid] + local_pos = flex_vert[vertid] + flexvert_xpos_out[worldid, vertid] = xmat @ local_pos + xpos @wp.kernel def _flex_edges( - # Model: - nflex: int, - body_rootid: wp.array(dtype=int), - body_dofadr: wp.array(dtype=int), - flex_vertadr: wp.array(dtype=int), - flex_edgeadr: wp.array(dtype=int), - flex_edgenum: wp.array(dtype=int), - flex_vertbodyid: wp.array(dtype=int), - flex_edge: wp.array(dtype=wp.vec2i), - flexedge_J_rowadr: wp.array(dtype=int), - flexedge_J_colind: wp.array(dtype=int), - # Data in: - qvel_in: wp.array2d(dtype=float), - subtree_com_in: wp.array2d(dtype=wp.vec3), - cdof_in: wp.array2d(dtype=wp.spatial_vector), - flexvert_xpos_in: wp.array2d(dtype=wp.vec3), - # Data out: - flexedge_J_out: wp.array2d(dtype=float), - flexedge_length_out: wp.array2d(dtype=float), - flexedge_velocity_out: wp.array2d(dtype=float), + # Model: + nflex: int, + body_rootid: wp.array(dtype=int), + body_dofnum: wp.array(dtype=int), + body_dofadr: wp.array(dtype=int), + flex_vertadr: wp.array(dtype=int), + flex_edgeadr: wp.array(dtype=int), + flex_edgenum: wp.array(dtype=int), + flex_vertbodyid: wp.array(dtype=int), + flex_edge: wp.array(dtype=wp.vec2i), + flexedge_J_rowadr: wp.array(dtype=int), + flexedge_J_colind: wp.array(dtype=int), + # Data in: + qvel_in: wp.array2d(dtype=float), + subtree_com_in: wp.array2d(dtype=wp.vec3), + cdof_in: wp.array2d(dtype=wp.spatial_vector), + flexvert_xpos_in: wp.array2d(dtype=wp.vec3), + # Data out: + flexedge_J_out: wp.array2d(dtype=float), + flexedge_length_out: wp.array2d(dtype=float), + flexedge_velocity_out: wp.array2d(dtype=float), ): worldid, edgeid = wp.tid() for i in range(nflex): @@ -281,42 +302,56 @@ def _flex_edges( b1 = flex_vertbodyid[vbase0] b2 = flex_vertbodyid[vbase1] - dofi = body_dofadr[b1] - dofj = body_dofadr[b2] - - vel1 = wp.vec3( - qvel_in[worldid, dofi], - qvel_in[worldid, dofi + 1], - qvel_in[worldid, dofi + 2], - ) - vel2 = wp.vec3( - qvel_in[worldid, dofj], - qvel_in[worldid, dofj + 1], - qvel_in[worldid, dofj + 2], - ) - flexedge_velocity_out[worldid, edgeid] = wp.dot(vel2 - vel1, edge) + dofnum1 = body_dofnum[b1] + dofnum2 = body_dofnum[b2] + + # velocity via Jacobian: sum_k J_k * qvel_k for each body + vel = float(0.0) + if dofnum1 > 0: + dofi = body_dofadr[b1] + offset1 = pos1 - wp.vec3(subtree_com_in[worldid, body_rootid[b1]]) + for k in range(dofnum1): + cdof = cdof_in[worldid, dofi + k] + cdof_ang = wp.spatial_top(cdof) + cdof_lin = wp.spatial_bottom(cdof) + jacp1 = cdof_lin + wp.cross(cdof_ang, offset1) + vel -= wp.dot(jacp1, edge) * qvel_in[worldid, dofi + k] + if dofnum2 > 0: + dofj = body_dofadr[b2] + offset2 = pos2 - wp.vec3(subtree_com_in[worldid, body_rootid[b2]]) + for k in range(dofnum2): + cdof = cdof_in[worldid, dofj + k] + cdof_ang = wp.spatial_top(cdof) + cdof_lin = wp.spatial_bottom(cdof) + jacp2 = cdof_lin + wp.cross(cdof_ang, offset2) + vel += wp.dot(jacp2, edge) * qvel_in[worldid, dofj + k] + flexedge_velocity_out[worldid, edgeid] = vel rowadr = flexedge_J_rowadr[edgeid] - - # compute offsets once per body (avoids 12 redundant tree-ancestry walks in jac_dof) - offset1 = pos1 - wp.vec3(subtree_com_in[worldid, body_rootid[b1]]) - offset2 = pos2 - wp.vec3(subtree_com_in[worldid, body_rootid[b2]]) + nnz_offset = 0 # body1 DOFs: b1 is in subtree, b2 is not -> jacdif = 0 - jacp1 = -jacp1 - for k in range(3): - cdof = cdof_in[worldid, dofi + k] - cdof_ang = wp.spatial_top(cdof) - cdof_lin = wp.spatial_bottom(cdof) - jacp1 = cdof_lin + wp.cross(cdof_ang, offset1) - flexedge_J_out[worldid, rowadr + k] = wp.dot(-jacp1, edge) + if dofnum1 > 0: + dofi = body_dofadr[b1] + offset1 = pos1 - wp.vec3(subtree_com_in[worldid, body_rootid[b1]]) + for k in range(dofnum1): + cdof = cdof_in[worldid, dofi + k] + cdof_ang = wp.spatial_top(cdof) + cdof_lin = wp.spatial_bottom(cdof) + jacp1 = cdof_lin + wp.cross(cdof_ang, offset1) + flexedge_J_out[worldid, rowadr + nnz_offset + k] = wp.dot(-jacp1, edge) + nnz_offset += dofnum1 # body2 DOFs: b2 is in subtree, b1 is not -> jacdif = jacp2 - 0 = jacp2 - for k in range(3): - cdof = cdof_in[worldid, dofj + k] - cdof_ang = wp.spatial_top(cdof) - cdof_lin = wp.spatial_bottom(cdof) - jacp2 = cdof_lin + wp.cross(cdof_ang, offset2) - flexedge_J_out[worldid, rowadr + 3 + k] = wp.dot(jacp2, edge) + if dofnum2 > 0: + dofj = body_dofadr[b2] + offset2 = pos2 - wp.vec3(subtree_com_in[worldid, body_rootid[b2]]) + for k in range(dofnum2): + cdof = cdof_in[worldid, dofj + k] + cdof_ang = wp.spatial_top(cdof) + cdof_lin = wp.spatial_bottom(cdof) + jacp2 = cdof_lin + wp.cross(cdof_ang, offset2) + flexedge_J_out[worldid, rowadr + nnz_offset + k] = wp.dot(jacp2, edge) @event_scope @@ -382,13 +417,28 @@ def kinematics(m: Model, d: Data): @event_scope def flex(m: Model, d: Data): - wp.launch(_flex_vertices, dim=(d.nworld, m.nflexvert), inputs=[m.flex_vertbodyid, d.xpos], outputs=[d.flexvert_xpos]) + wp.launch( + _flex_vertices, + dim=(d.nworld, m.nflexvert), + inputs=[ + m.nflex, + m.flex_vertadr, + m.flex_vertnum, + m.flex_vertbodyid, + m.flex_vert, + m.flex_centered, + d.xpos, + d.xmat, + ], + outputs=[d.flexvert_xpos], + ) wp.launch( _flex_edges, dim=(d.nworld, m.nflexedge), inputs=[ m.nflex, m.body_rootid, + m.body_dofnum, m.body_dofadr, m.flex_vertadr, m.flex_edgeadr, @@ -790,9 +840,7 @@ def _qM_sparse( bodyid = dof_bodyid[dofid] # init M(i,i) with armature inertia - qM_out[worldid, 0, madr_ij] = dof_armature[ - worldid % dof_armature.shape[0], dofid - ] + qM_out[worldid, 0, madr_ij] = dof_armature[worldid % dof_armature.shape[0], dofid] # precompute buf = crb_body_i * cdof_i buf = math.inert_vec(crb_in[worldid, bodyid], cdof_in[worldid, dofid]) @@ -869,35 +917,55 @@ def _tendon_armature( # Model: dof_parentid: wp.array(dtype=int), dof_Madr: wp.array(dtype=int), + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), tendon_armature: wp.array2d(dtype=float), is_sparse: bool, # Data in: - ten_J_in: wp.array3d(dtype=float), + ten_J_in: wp.array2d(dtype=float), # Data out: qM_out: wp.array3d(dtype=float), ): worldid, tenid, dofid = wp.tid() - if is_sparse: # is_sparse is not batched - madr_ij = dof_Madr[dofid] - armature = tendon_armature[worldid % tendon_armature.shape[0], tenid] if armature == 0.0: return - ten_Ji = ten_J_in[worldid, tenid, dofid] + rownnz = ten_J_rownnz[tenid] + if dofid >= rownnz: + return + rowadr = ten_J_rowadr[tenid] + dofid_sparse = dofid + sparseid = rowadr + dofid_sparse + dofid = ten_J_colind[sparseid] + ten_Ji = ten_J_in[worldid, sparseid] if ten_Ji == 0.0: return + if is_sparse: + madr_ij = dof_Madr[dofid] + # sparse backward pass over ancestors dofidi = dofid + ptr = dofid_sparse while dofid >= 0: - if dofid != dofidi: - ten_Jj = ten_J_in[worldid, tenid, dofid] - else: + if dofid == dofidi: ten_Jj = ten_Ji + else: + # scan pointer backward to find matching colind entry + while ptr >= 0: + sparseid = rowadr + ptr + if ten_J_colind[sparseid] <= dofid: + break + ptr -= 1 + if ptr >= 0 and ten_J_colind[sparseid] == dofid: + ten_Jj = ten_J_in[worldid, sparseid] + else: + ten_Jj = float(0.0) qMij = armature * ten_Jj * ten_Ji @@ -917,8 +985,17 @@ def tendon_armature(m: Model, d: Data): """Add tendon armature to qM.""" wp.launch( _tendon_armature, - dim=(d.nworld, m.ntendon, m.nv), - inputs=[m.dof_parentid, m.dof_Madr, m.tendon_armature, m.is_sparse, d.ten_J], + dim=(d.nworld, m.ntendon, m.max_ten_J_rownnz), + inputs=[ + m.dof_parentid, + m.dof_Madr, + m.ten_J_rownnz, + m.ten_J_rowadr, + m.ten_J_colind, + m.tendon_armature, + m.is_sparse, + d.ten_J, + ], outputs=[d.qM], ) @@ -1504,19 +1581,93 @@ def rne_postconstraint(m: Model, d: Data): _rne_cfrc_backward(m, d) +@wp.func +def _accumulate_jac_dot_chain( + # Model: + body_parentid: wp.array(dtype=int), + body_dofnum: wp.array(dtype=int), + body_dofadr: wp.array(dtype=int), + jnt_type: wp.array(dtype=int), + jnt_dofadr: wp.array(dtype=int), + dof_jntid: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), + # Data in: + cdof_in: wp.array2d(dtype=wp.spatial_vector), + cvel_in: wp.array2d(dtype=wp.spatial_vector), + cdof_dot_in: wp.array2d(dtype=wp.spatial_vector), + # In: + offset: wp.vec3, + pvel_lin: wp.vec3, + dpnt: wp.vec3, + dvel: wp.vec3, + bodyid: int, + rowadr: int, + rownnz: int, + scale: float, + worldid: int, + # Out: + ten_Jdot_out: wp.array2d(dtype=float), +): + """Walk body chain from bodyid to root, accumulate Jdot contributions.""" + ptr = rownnz - 1 + bid = bodyid + while bid > 0: + bdofadr = body_dofadr[bid] + bdofnum = body_dofnum[bid] + # iterate DOFs in this body in descending order + for k_rev in range(bdofnum): + dof = bdofadr + bdofnum - 1 - k_rev + # scan pointer backward to find matching colind entry + while ptr >= 0: + sparseid = rowadr + ptr + if ten_J_colind[sparseid] <= dof: + break + ptr -= 1 + if ptr >= 0 and ten_J_colind[sparseid] == dof: + cdof = cdof_in[worldid, dof] + cdof_ang = wp.spatial_top(cdof) + cdof_lin = wp.spatial_bottom(cdof) + cdof_dot = cdof_dot_in[worldid, dof] + + # quaternion override: use cvel of DOF's body (which is bid) + dofjntid = dof_jntid[dof] + jnttype = jnt_type[dofjntid] + jntdofadr = jnt_dofadr[dofjntid] + if (jnttype == JointType.BALL) or ((jnttype == JointType.FREE) and dof >= jntdofadr + 3): + cdof_dot = math.motion_cross(cvel_in[worldid, bid], cdof) + + cdof_dot_ang = wp.spatial_top(cdof_dot) + cdof_dot_lin = wp.spatial_bottom(cdof_dot) + + # jacp_dot (from jac_dot_dof) + jacp_dot = cdof_dot_lin + wp.cross(cdof_dot_ang, offset) + wp.cross(cdof_ang, pvel_lin) + + # jacp (from jac_dof) + jacp = cdof_lin + wp.cross(cdof_ang, offset) + + # combined: dot(jacdot, dpnt) + dot(jac, dvel) + Jdot = (wp.dot(jacp_dot, dpnt) + wp.dot(jacp, dvel)) * scale + if Jdot != 0.0: + wp.atomic_add(ten_Jdot_out[worldid], sparseid, Jdot) + bid = body_parentid[bid] + + @wp.kernel def _tendon_dot( # Model: - nv: int, body_parentid: wp.array(dtype=int), body_rootid: wp.array(dtype=int), + body_dofnum: wp.array(dtype=int), + body_dofadr: wp.array(dtype=int), jnt_type: wp.array(dtype=int), jnt_dofadr: wp.array(dtype=int), - dof_bodyid: wp.array(dtype=int), dof_jntid: wp.array(dtype=int), site_bodyid: wp.array(dtype=int), tendon_adr: wp.array(dtype=int), tendon_num: wp.array(dtype=int), + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), tendon_armature: wp.array2d(dtype=float), wrap_type: wp.array(dtype=int), wrap_objid: wp.array(dtype=int), @@ -1528,7 +1679,7 @@ def _tendon_dot( cvel_in: wp.array2d(dtype=wp.spatial_vector), cdof_dot_in: wp.array2d(dtype=wp.spatial_vector), # Out: - ten_Jdot_out: wp.array3d(dtype=float), + ten_Jdot_out: wp.array2d(dtype=float), ): worldid, tenid = wp.tid() @@ -1565,13 +1716,11 @@ def _tendon_dot( # init sequence; assume it start with site wpnt0 = site_xpos_in[worldid, id0] - bodyid0 = site_bodyid[id0] - pos0 = site_xpos_in[worldid, id0] - cvel0 = cvel_in[worldid, bodyid0] - subtree_com0 = subtree_com_in[worldid, body_rootid[bodyid0]] - dif0 = pos0 - subtree_com0 - wvel0 = wp.spatial_bottom(cvel0) - wp.cross(dif0, wp.spatial_top(cvel0)) wbody0 = site_bodyid[id0] + cvel0 = cvel_in[worldid, wbody0] + subtree_com0 = subtree_com_in[worldid, body_rootid[wbody0]] + offset0 = wpnt0 - subtree_com0 + pvel_lin0 = wp.spatial_bottom(cvel0) - wp.cross(offset0, wp.spatial_top(cvel0)) # second object is geom: process site-geom-site if (type1 == WrapType.SPHERE) or (type1 == WrapType.CYLINDER): @@ -1582,12 +1731,10 @@ def _tendon_dot( wbody1 = site_bodyid[id1] wpnt1 = site_xpos_in[worldid, id1] - bodyid1 = site_bodyid[id1] - pos1 = site_xpos_in[worldid, id1] - cvel1 = cvel_in[worldid, bodyid1] - subtree_com1 = subtree_com_in[worldid, body_rootid[bodyid1]] - dif1 = pos1 - subtree_com1 - wvel1 = wp.spatial_bottom(cvel1) - wp.cross(dif1, wp.spatial_top(cvel1)) + cvel1 = cvel_in[worldid, wbody1] + subtree_com1 = subtree_com_in[worldid, body_rootid[wbody1]] + offset1 = wpnt1 - subtree_com1 + pvel_lin1 = wp.spatial_bottom(cvel1) - wp.cross(offset1, wp.spatial_top(cvel1)) # accumulate moments if consecutive points are in different bodies if wbody0 != wbody1: @@ -1595,6 +1742,8 @@ def _tendon_dot( dpnt, norm = math.normalize_with_norm(wpnt1 - wpnt0) # dvel = d / dt (dpnt) + wvel0 = wp.spatial_bottom(cvel0) - wp.cross(wpnt0 - subtree_com0, wp.spatial_top(cvel0)) + wvel1 = wp.spatial_bottom(cvel1) - wp.cross(wpnt1 - subtree_com1, wp.spatial_top(cvel1)) dvel = wvel1 - wvel0 dot = wp.dot(dpnt, dvel) dvel += dpnt * (-dot) @@ -1603,75 +1752,55 @@ def _tendon_dot( else: dvel = wp.vec3(0.0) - # get endpoint Jacobian time derivatives, subtract - # TODO(team): parallelize? - for i in range(nv): - jac1, _ = support.jac_dot_dof( - body_parentid, - body_rootid, - jnt_type, - jnt_dofadr, - dof_bodyid, - dof_jntid, - subtree_com_in, - cdof_in, - cvel_in, - cdof_dot_in, - wpnt0, - wbody0, - i, - worldid, - ) - jac2, _ = support.jac_dot_dof( - body_parentid, - body_rootid, - jnt_type, - jnt_dofadr, - dof_bodyid, - dof_jntid, - subtree_com_in, - cdof_in, - cvel_in, - cdof_dot_in, - wpnt1, - wbody1, - i, - worldid, - ) - jacdif = jac2 - jac1 - - # chain rule, first term: Jdot += d / dt (jac2 - jac1) * dpnt - Jdot = wp.dot(jacdif, dpnt) - - # get endpoint Jacobians, subtract - jac1, _ = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - wpnt0, - wbody0, - i, - worldid, - ) - jac2, _ = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - wpnt1, - wbody1, - i, - worldid, - ) - jacdif = jac2 - jac1 - - # chain rule, second term: Jdot += (jac2 - jac1) * d / dt (dpnt) - Jdot += wp.dot(jacdif, dvel) + rownnz = ten_J_rownnz[tenid] + rowadr = ten_J_rowadr[tenid] + inv_divisor = math.safe_div(float(1.0), divisor) - ten_Jdot_out[worldid, tenid, i] += math.safe_div(Jdot, divisor) + # body0 contributes with negative sign, body1 with positive + _accumulate_jac_dot_chain( + body_parentid, + body_dofnum, + body_dofadr, + jnt_type, + jnt_dofadr, + dof_jntid, + ten_J_colind, + cdof_in, + cvel_in, + cdof_dot_in, + offset0, + pvel_lin0, + dpnt, + dvel, + wbody0, + rowadr, + rownnz, + -inv_divisor, + worldid, + ten_Jdot_out, + ) + _accumulate_jac_dot_chain( + body_parentid, + body_dofnum, + body_dofadr, + jnt_type, + jnt_dofadr, + dof_jntid, + ten_J_colind, + cdof_in, + cvel_in, + cdof_dot_in, + offset1, + pvel_lin1, + dpnt, + dvel, + wbody1, + rowadr, + rownnz, + inv_divisor, + worldid, + ten_Jdot_out, + ) # TODO(team): j += 2 if geom wrapping j += 1 @@ -1680,33 +1809,45 @@ def _tendon_dot( @wp.kernel def _tendon_bias_coef( # Model: + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), tendon_armature: wp.array2d(dtype=float), # Data in: qvel_in: wp.array2d(dtype=float), # In: - ten_Jdot_in: wp.array3d(dtype=float), + ten_Jdot_in: wp.array2d(dtype=float), # Out: ten_bias_coef_out: wp.array2d(dtype=float), ): - worldid, tenid, dofid = wp.tid() + worldid, tenid, dofid_sparse = wp.tid() armature = tendon_armature[worldid % tendon_armature.shape[0], tenid] if armature == 0.0: return - ten_Jdot = ten_Jdot_in[worldid, tenid, dofid] + rownnz = ten_J_rownnz[tenid] + if dofid_sparse >= rownnz: + return + rowadr = ten_J_rowadr[tenid] + sparseid = rowadr + dofid_sparse + ten_Jdot = ten_Jdot_in[worldid, sparseid] if ten_Jdot == 0.0: return + dofid = ten_J_colind[sparseid] wp.atomic_add(ten_bias_coef_out[worldid], tenid, ten_Jdot * qvel_in[worldid, dofid]) @wp.kernel def _tendon_bias_qfrc( # Model: + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), tendon_armature: wp.array2d(dtype=float), # Data in: - ten_J_in: wp.array3d(dtype=float), + ten_J_in: wp.array2d(dtype=float), # In: ten_bias_coef_in: wp.array2d(dtype=float), # Out: @@ -1718,10 +1859,18 @@ def _tendon_bias_qfrc( if armature == 0.0: return - ten_J = ten_J_in[worldid, tenid, dofid] + rownnz = ten_J_rownnz[tenid] + if dofid >= rownnz: + return + rowadr = ten_J_rowadr[tenid] + sparseid = rowadr + dofid + ten_J = ten_J_in[worldid, sparseid] + if ten_J == 0.0: return + dofid = ten_J_colind[sparseid] + wp.atomic_add(qfrc_out[worldid], dofid, ten_J * armature * ten_bias_coef_in[worldid, tenid]) @@ -1735,21 +1884,24 @@ def tendon_bias(m: Model, d: Data, qfrc: wp.array2d(dtype=float)): qfrc: Force. """ # time derivative of tendon Jacobian - ten_Jdot = wp.zeros((d.nworld, m.ntendon, m.nv), dtype=float) + ten_Jdot = wp.zeros((d.nworld, m.nJten), dtype=float) wp.launch( _tendon_dot, dim=(d.nworld, m.ntendon), inputs=[ - m.nv, m.body_parentid, m.body_rootid, + m.body_dofnum, + m.body_dofadr, m.jnt_type, m.jnt_dofadr, - m.dof_bodyid, m.dof_jntid, m.site_bodyid, m.tendon_adr, m.tendon_num, + m.ten_J_rownnz, + m.ten_J_rowadr, + m.ten_J_colind, m.tendon_armature, m.wrap_type, m.wrap_objid, @@ -1767,15 +1919,15 @@ def tendon_bias(m: Model, d: Data, qfrc: wp.array2d(dtype=float)): ten_bias_coef = wp.zeros((d.nworld, m.ntendon), dtype=float) wp.launch( _tendon_bias_coef, - dim=(d.nworld, m.ntendon, m.nv), - inputs=[m.tendon_armature, d.qvel, ten_Jdot], + dim=(d.nworld, m.ntendon, m.max_ten_J_rownnz), + inputs=[m.ten_J_rownnz, m.ten_J_rowadr, m.ten_J_colind, m.tendon_armature, d.qvel, ten_Jdot], outputs=[ten_bias_coef], ) wp.launch( _tendon_bias_qfrc, - dim=(d.nworld, m.ntendon, m.nv), - inputs=[m.tendon_armature, d.ten_J, ten_bias_coef], + dim=(d.nworld, m.ntendon, m.max_ten_J_rownnz), + inputs=[m.ten_J_rownnz, m.ten_J_rowadr, m.ten_J_colind, m.tendon_armature, d.ten_J, ten_bias_coef], outputs=[qfrc], ) @@ -1888,45 +2040,44 @@ def com_vel(m: Model, d: Data): @wp.kernel def _transmission( - # Model: - nv: int, - body_parentid: wp.array(dtype=int), - body_rootid: wp.array(dtype=int), - body_weldid: wp.array(dtype=int), - body_dofnum: wp.array(dtype=int), - body_dofadr: wp.array(dtype=int), - jnt_type: wp.array(dtype=int), - jnt_qposadr: wp.array(dtype=int), - jnt_dofadr: wp.array(dtype=int), - dof_bodyid: wp.array(dtype=int), - dof_parentid: wp.array(dtype=int), - site_bodyid: wp.array(dtype=int), - site_quat: wp.array2d(dtype=wp.quat), - tendon_adr: wp.array(dtype=int), - tendon_num: wp.array(dtype=int), - wrap_type: wp.array(dtype=int), - wrap_objid: wp.array(dtype=int), - actuator_trntype: wp.array(dtype=int), - actuator_trnid: wp.array(dtype=wp.vec2i), - actuator_gear: wp.array2d(dtype=wp.spatial_vector), - actuator_cranklength: wp.array2d(dtype=float), - # Data in: - qpos_in: wp.array2d(dtype=float), - xquat_in: wp.array2d(dtype=wp.quat), - site_xpos_in: wp.array2d(dtype=wp.vec3), - site_xmat_in: wp.array2d(dtype=wp.mat33), - subtree_com_in: wp.array2d(dtype=wp.vec3), - cdof_in: wp.array2d(dtype=wp.spatial_vector), - ten_J_in: wp.array3d(dtype=float), - ten_length_in: wp.array2d(dtype=float), - # In: - moment_nnz: wp.array(dtype=int), - # Data out: - actuator_length_out: wp.array2d(dtype=float), - moment_rownnz_out: wp.array2d(dtype=int), - moment_rowadr_out: wp.array2d(dtype=int), - moment_colind_out: wp.array2d(dtype=int), - actuator_moment_out: wp.array2d(dtype=float), + # Model: + nv: int, + body_parentid: wp.array(dtype=int), + body_rootid: wp.array(dtype=int), + body_weldid: wp.array(dtype=int), + body_dofnum: wp.array(dtype=int), + body_dofadr: wp.array(dtype=int), + jnt_type: wp.array(dtype=int), + jnt_qposadr: wp.array(dtype=int), + jnt_dofadr: wp.array(dtype=int), + dof_bodyid: wp.array(dtype=int), + dof_parentid: wp.array(dtype=int), + site_bodyid: wp.array(dtype=int), + site_quat: wp.array2d(dtype=wp.quat), + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), + actuator_trntype: wp.array(dtype=int), + actuator_trnid: wp.array(dtype=wp.vec2i), + actuator_gear: wp.array2d(dtype=wp.spatial_vector), + actuator_cranklength: wp.array2d(dtype=float), + # Data in: + qpos_in: wp.array2d(dtype=float), + xquat_in: wp.array2d(dtype=wp.quat), + site_xpos_in: wp.array2d(dtype=wp.vec3), + site_xmat_in: wp.array2d(dtype=wp.mat33), + subtree_com_in: wp.array2d(dtype=wp.vec3), + cdof_in: wp.array2d(dtype=wp.spatial_vector), + ten_J_in: wp.array2d(dtype=float), + ten_length_in: wp.array2d(dtype=float), + # In: + moment_nnz: wp.array(dtype=int), + # Data out: + actuator_length_out: wp.array2d(dtype=float), + moment_rownnz_out: wp.array2d(dtype=int), + moment_rowadr_out: wp.array2d(dtype=int), + moment_colind_out: wp.array2d(dtype=int), + actuator_moment_out: wp.array2d(dtype=float), ): worldid, actid = wp.tid() trntype = actuator_trntype[actid] @@ -2068,28 +2219,12 @@ def _transmission( # get Jacobians of axis(jacA) and vec(jac) jacp, jacr = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - site_xpos_idslider, - site_bodyid[idslider], - da, - worldid, + body_parentid, body_rootid, dof_bodyid, subtree_com_in, cdof_in, site_xpos_idslider, site_bodyid[idslider], da, worldid ) jacS = jacp jacA = wp.cross(jacr, axis) jac, _ = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - site_xpos_id, - site_bodyid[id], - da, - worldid, + body_parentid, body_rootid, dof_bodyid, subtree_com_in, cdof_in, site_xpos_id, site_bodyid[id], da, worldid ) jac -= jacS @@ -2110,38 +2245,18 @@ def _transmission( gear0 = gear[0] actuator_length_out[worldid, actid] = ten_length_in[worldid, tenid] * gear0 - # fixed - adr = tendon_adr[tenid] - if wrap_type[adr] == WrapType.JOINT: - ten_num = tendon_num[tenid] - rowadr = wp.atomic_add(moment_nnz, worldid, ten_num) - moment_rownnz_out[worldid, actid] = ten_num - moment_rowadr_out[worldid, actid] = rowadr + rownnz_ten = ten_J_rownnz[tenid] + rowadr_ten = ten_J_rowadr[tenid] - for i in range(ten_num): - dofadr = jnt_dofadr[wrap_objid[adr + i]] - sparseid = rowadr + i - moment_colind_out[worldid, sparseid] = dofadr - actuator_moment_out[worldid, sparseid] = ( - ten_J_in[worldid, tenid, dofadr] * gear0 - ) - else: # spatial - # TODO(team): sparse tendon jacobian - ten_nnz = int(0) - for dofadr in range(nv): - if ten_J_in[worldid, tenid, dofadr] != 0.0: - ten_nnz += 1 - rowadr = wp.atomic_add(moment_nnz, worldid, ten_nnz) - moment_rownnz_out[worldid, actid] = ten_nnz - moment_rowadr_out[worldid, actid] = rowadr - ptr = int(0) - for dofadr in range(nv): - J = ten_J_in[worldid, tenid, dofadr] - if J != 0.0: - sparseid = rowadr + ptr - moment_colind_out[worldid, sparseid] = dofadr - actuator_moment_out[worldid, sparseid] = J * gear0 - ptr += 1 + rowadr_mom = wp.atomic_add(moment_nnz, worldid, rownnz_ten) + moment_rownnz_out[worldid, actid] = rownnz_ten + moment_rowadr_out[worldid, actid] = rowadr_mom + + for k in range(rownnz_ten): + sparseid_ten = rowadr_ten + k + sparseid_mom = rowadr_mom + k + moment_colind_out[worldid, sparseid_mom] = ten_J_colind[sparseid_ten] + actuator_moment_out[worldid, sparseid_mom] = ten_J_in[worldid, sparseid_ten] * gear0 elif trntype == TrnType.BODY: # cannot compute meaningful length, set to zero actuator_length_out[worldid, actid] = 0.0 @@ -2195,19 +2310,17 @@ def _transmission( ptr = ndof - 1 while da >= 0: jacp, jacr = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - site_xpos_in[worldid, siteid], - site_bodyid[siteid], - da, - worldid, - ) - moment = wp.dot(jacp, wrench_translation) + wp.dot( - jacr, wrench_rotation + body_parentid, + body_rootid, + dof_bodyid, + subtree_com_in, + cdof_in, + site_xpos_in[worldid, siteid], + site_bodyid[siteid], + da, + worldid, ) + moment = wp.dot(jacp, wrench_translation) + wp.dot(jacr, wrench_rotation) sparseid = rowadr + ptr moment_colind_out[worldid, sparseid] = da actuator_moment_out[worldid, sparseid] = moment @@ -2306,26 +2419,10 @@ def _transmission( break jacp, jacr = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - site_xpos, - site_bodyid[siteid], - da, - worldid, + body_parentid, body_rootid, dof_bodyid, subtree_com_in, cdof_in, site_xpos, site_bodyid[siteid], da, worldid ) jacpref, jacrref = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - ref_xpos, - site_bodyid[refid], - da, - worldid, + body_parentid, body_rootid, dof_bodyid, subtree_com_in, cdof_in, ref_xpos, site_bodyid[refid], da, worldid ) moment = float(0.0) @@ -2349,37 +2446,37 @@ def _transmission( @wp.kernel def _transmission_body_moment( - # Model: - opt_cone: int, - body_parentid: wp.array(dtype=int), - body_rootid: wp.array(dtype=int), - dof_bodyid: wp.array(dtype=int), - geom_bodyid: wp.array(dtype=int), - actuator_trnid: wp.array(dtype=wp.vec2i), - actuator_trntype_body_adr: wp.array(dtype=int), - # Data in: - subtree_com_in: wp.array2d(dtype=wp.vec3), - cdof_in: wp.array2d(dtype=wp.spatial_vector), - moment_rowadr_in: wp.array2d(dtype=int), - contact_dist_in: wp.array(dtype=float), - contact_pos_in: wp.array(dtype=wp.vec3), - contact_frame_in: wp.array(dtype=wp.mat33), - contact_includemargin_in: wp.array(dtype=float), - contact_dim_in: wp.array(dtype=int), - contact_geom_in: wp.array(dtype=wp.vec2i), - contact_efc_address_in: wp.array2d(dtype=int), - contact_worldid_in: wp.array(dtype=int), - efc_J_rownnz_in: wp.array2d(dtype=int), - efc_J_rowadr_in: wp.array2d(dtype=int), - efc_J_colind_in: wp.array3d(dtype=int), - efc_J_in: wp.array3d(dtype=float), - nacon_in: wp.array(dtype=int), - # In: - efc_is_sparse: bool, - # Data out: - actuator_moment_out: wp.array2d(dtype=float), - # Out: - actuator_trntype_body_ncon_out: wp.array2d(dtype=int), + # Model: + opt_cone: int, + body_parentid: wp.array(dtype=int), + body_rootid: wp.array(dtype=int), + dof_bodyid: wp.array(dtype=int), + geom_bodyid: wp.array(dtype=int), + actuator_trnid: wp.array(dtype=wp.vec2i), + actuator_trntype_body_adr: wp.array(dtype=int), + # Data in: + subtree_com_in: wp.array2d(dtype=wp.vec3), + cdof_in: wp.array2d(dtype=wp.spatial_vector), + moment_rowadr_in: wp.array2d(dtype=int), + contact_dist_in: wp.array(dtype=float), + contact_pos_in: wp.array(dtype=wp.vec3), + contact_frame_in: wp.array(dtype=wp.mat33), + contact_includemargin_in: wp.array(dtype=float), + contact_dim_in: wp.array(dtype=int), + contact_geom_in: wp.array(dtype=wp.vec2i), + contact_efc_address_in: wp.array2d(dtype=int), + contact_worldid_in: wp.array(dtype=int), + efc_J_rownnz_in: wp.array2d(dtype=int), + efc_J_rowadr_in: wp.array2d(dtype=int), + efc_J_colind_in: wp.array3d(dtype=int), + efc_J_in: wp.array3d(dtype=float), + nacon_in: wp.array(dtype=int), + # In: + efc_is_sparse: bool, + # Data out: + actuator_moment_out: wp.array2d(dtype=float), + # Out: + actuator_trntype_body_ncon_out: wp.array2d(dtype=int), ): trnbodyid, conid, dofid = wp.tid() actid = actuator_trntype_body_adr[trnbodyid] @@ -2427,20 +2524,12 @@ def _transmission_body_moment( efc_rowadr = efc_J_rowadr_in[worldid, efcid0] efc_sparseid = efc_rowadr + dofid colind = efc_J_colind_in[worldid, 0, efc_sparseid] - wp.atomic_add( - actuator_moment_out[worldid], - rowadr + colind, - efc_J_in[worldid, 0, efc_sparseid], - ) + wp.atomic_add(actuator_moment_out[worldid], rowadr + colind, efc_J_in[worldid, 0, efc_sparseid]) else: return else: colind = dofid - wp.atomic_add( - actuator_moment_out[worldid], - rowadr + colind, - efc_J_in[worldid, efcid0, dofid], - ) + wp.atomic_add(actuator_moment_out[worldid], rowadr + colind, efc_J_in[worldid, efcid0, dofid]) else: npyramid = contact_dim - 1 # number of frictional directions efc_force = 0.5 / float(npyramid) @@ -2453,20 +2542,12 @@ def _transmission_body_moment( efc_rowadr = efc_J_rowadr_in[worldid, efcid] efc_sparseid = efc_rowadr + dofid colind = efc_J_colind_in[worldid, 0, efc_sparseid] - wp.atomic_add( - actuator_moment_out[worldid], - rowadr + colind, - efc_J_in[worldid, 0, efc_sparseid] * efc_force, - ) + wp.atomic_add(actuator_moment_out[worldid], rowadr + colind, efc_J_in[worldid, 0, efc_sparseid] * efc_force) else: return else: colind = dofid - wp.atomic_add( - actuator_moment_out[worldid], - rowadr + colind, - efc_J_in[worldid, efcid, dofid] * efc_force, - ) + wp.atomic_add(actuator_moment_out[worldid], rowadr + colind, efc_J_in[worldid, efcid, dofid] * efc_force) # excluded contact in gap: get Jacobian, accumulate elif contact_exclude == 1: @@ -2487,46 +2568,28 @@ def _transmission_body_moment( colind = dofid jacp1, _ = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - contact_pos, - b1, - colind, - worldid, + body_parentid, body_rootid, dof_bodyid, subtree_com_in, cdof_in, contact_pos, b1, colind, worldid ) jacp2, _ = support.jac_dof( - body_parentid, - body_rootid, - dof_bodyid, - subtree_com_in, - cdof_in, - contact_pos, - b2, - colind, - worldid, + body_parentid, body_rootid, dof_bodyid, subtree_com_in, cdof_in, contact_pos, b2, colind, worldid ) jacdif = jacp2 - jacp1 # project Jacobian along the normal of the contact frame - wp.atomic_add( - actuator_moment_out[worldid], rowadr + colind, wp.dot(normal, jacdif) - ) + wp.atomic_add(actuator_moment_out[worldid], rowadr + colind, wp.dot(normal, jacdif)) @wp.kernel def _transmission_body_moment_scale( - # Model: - actuator_trntype_body_adr: wp.array(dtype=int), - # Data in: - moment_rowadr_in: wp.array2d(dtype=int), - # In: - actuator_trntype_body_ncon_in: wp.array2d(dtype=int), - # Data out: - actuator_moment_out: wp.array2d(dtype=float), + # Model: + actuator_trntype_body_adr: wp.array(dtype=int), + # Data in: + moment_rowadr_in: wp.array2d(dtype=int), + # In: + actuator_trntype_body_ncon_in: wp.array2d(dtype=int), + # Data out: + actuator_moment_out: wp.array2d(dtype=float), ): worldid, trnbodyid, dofid = wp.tid() @@ -2549,47 +2612,40 @@ def transmission(m: Model, d: Data): moment_nnz = wp.zeros((d.nworld,), dtype=int) wp.launch( - _transmission, - dim=(d.nworld, m.nu), - inputs=[ - m.nv, - m.body_parentid, - m.body_rootid, - m.body_weldid, - m.body_dofnum, - m.body_dofadr, - m.jnt_type, - m.jnt_qposadr, - m.jnt_dofadr, - m.dof_bodyid, - m.dof_parentid, - m.site_bodyid, - m.site_quat, - m.tendon_adr, - m.tendon_num, - m.wrap_type, - m.wrap_objid, - m.actuator_trntype, - m.actuator_trnid, - m.actuator_gear, - m.actuator_cranklength, - d.qpos, - d.xquat, - d.site_xpos, - d.site_xmat, - d.subtree_com, - d.cdof, - d.ten_J, - d.ten_length, - moment_nnz, - ], - outputs=[ - d.actuator_length, - d.moment_rownnz, - d.moment_rowadr, - d.moment_colind, - d.actuator_moment, - ], + _transmission, + dim=(d.nworld, m.nu), + inputs=[ + m.nv, + m.body_parentid, + m.body_rootid, + m.body_weldid, + m.body_dofnum, + m.body_dofadr, + m.jnt_type, + m.jnt_qposadr, + m.jnt_dofadr, + m.dof_bodyid, + m.dof_parentid, + m.site_bodyid, + m.site_quat, + m.ten_J_rownnz, + m.ten_J_rowadr, + m.ten_J_colind, + m.actuator_trntype, + m.actuator_trnid, + m.actuator_gear, + m.actuator_cranklength, + d.qpos, + d.xquat, + d.site_xpos, + d.site_xmat, + d.subtree_com, + d.cdof, + d.ten_J, + d.ten_length, + moment_nnz, + ], + outputs=[d.actuator_length, d.moment_rownnz, d.moment_rowadr, d.moment_colind, d.actuator_moment], ) if m.nacttrnbody: @@ -2597,83 +2653,105 @@ def transmission(m: Model, d: Data): ncon = wp.zeros((d.nworld, m.nacttrnbody), dtype=int) wp.launch( - _transmission_body_moment, - dim=(m.nacttrnbody, d.naconmax, m.nv), - inputs=[ - m.opt.cone, - m.body_parentid, - m.body_rootid, - m.dof_bodyid, - m.geom_bodyid, - m.actuator_trnid, - m.actuator_trntype_body_adr, - d.subtree_com, - d.cdof, - d.moment_rowadr, - d.contact.dist, - d.contact.pos, - d.contact.frame, - d.contact.includemargin, - d.contact.dim, - d.contact.geom, - d.contact.efc_address, - d.contact.worldid, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.nacon, - SPARSE_CONSTRAINT_JACOBIAN, - ], - outputs=[d.actuator_moment, ncon], + _transmission_body_moment, + dim=(m.nacttrnbody, d.naconmax, m.nv), + inputs=[ + m.opt.cone, + m.body_parentid, + m.body_rootid, + m.dof_bodyid, + m.geom_bodyid, + m.actuator_trnid, + m.actuator_trntype_body_adr, + d.subtree_com, + d.cdof, + d.moment_rowadr, + d.contact.dist, + d.contact.pos, + d.contact.frame, + d.contact.includemargin, + d.contact.dim, + d.contact.geom, + d.contact.efc_address, + d.contact.worldid, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.nacon, + m.is_sparse, + ], + outputs=[d.actuator_moment, ncon], ) # scale moments wp.launch( - _transmission_body_moment_scale, - dim=(d.nworld, m.nacttrnbody, m.nv), - inputs=[m.actuator_trntype_body_adr, d.moment_rowadr, ncon], - outputs=[d.actuator_moment], + _transmission_body_moment_scale, + dim=(d.nworld, m.nacttrnbody, m.nv), + inputs=[m.actuator_trntype_body_adr, d.moment_rowadr, ncon], + outputs=[d.actuator_moment], ) -@wp.kernel -def _solve_LD_sparse_x_acc_up( - # In: - L: wp.array3d(dtype=float), - qLD_updates_: wp.array(dtype=wp.vec3i), - # Out: - x: wp.array2d(dtype=float), -): - worldid, nodeid = wp.tid() - update = qLD_updates_[nodeid] - i, k, Madr_ki = update[0], update[1], update[2] - wp.atomic_sub(x[worldid], i, L[worldid, 0, Madr_ki] * x[worldid, k]) - - -@wp.kernel -def _solve_LD_sparse_qLDiag_mul( - # In: - D: wp.array2d(dtype=float), - # Out: - out: wp.array2d(dtype=float), -): - worldid, dofid = wp.tid() - out[worldid, dofid] *= D[worldid, dofid] +@cache_kernel +def _solve_LD_sparse_fused(nv: int, nlevels: int): + """Fused sparse backsubstitution: UP + diag + DOWN in one kernel.""" + @wp.func_native(snippet="WP_TILE_SYNC();") + def _syncthreads(): + pass -@wp.kernel -def _solve_LD_sparse_x_acc_down( - # In: - L: wp.array3d(dtype=float), - qLD_updates_: wp.array(dtype=wp.vec3i), - # Out: - x: wp.array2d(dtype=float), -): - worldid, nodeid = wp.tid() - update = qLD_updates_[nodeid] - i, k, Madr_ki = update[0], update[1], update[2] - wp.atomic_sub(x[worldid], k, L[worldid, 0, Madr_ki] * x[worldid, i]) + @wp.kernel(module="unique", enable_backward=False) + def kernel( + # In: + L: wp.array3d(dtype=float), + D: wp.array2d(dtype=float), + all_updates: wp.array(dtype=wp.vec3i), + level_offsets: wp.array(dtype=int), + y: wp.array2d(dtype=float), + # Out: + x_out: wp.array2d(dtype=float), + ): + worldid, tid = wp.tid() + NV = wp.static(nv) + NLEVELS = wp.static(nlevels) + BLOCK_DIM = wp.block_dim() + + # Copy y to x_out + for dofid in range(tid, NV, BLOCK_DIM): + x_out[worldid, dofid] = y[worldid, dofid] + _syncthreads() + + # Forward substitution + for level in range(NLEVELS): + level_idx = NLEVELS - 1 - level + level_offset = level_offsets[level_idx] + level_size = level_offsets[level_idx + 1] - level_offset + + for u in range(tid, level_size, BLOCK_DIM): + update = all_updates[level_offset + u] + i, k, Madr_ki = update[0], update[1], update[2] + wp.atomic_sub(x_out[worldid], i, L[worldid, 0, Madr_ki] * x_out[worldid, k]) + _syncthreads() + + # Diagonal multiply + for dofid in range(tid, NV, BLOCK_DIM): + x_out[worldid, dofid] *= D[worldid, dofid] + _syncthreads() + + # Backward substitution + for level in range(NLEVELS): + level_idx = level + level_offset = level_offsets[level_idx] + level_size = level_offsets[level_idx + 1] - level_offset + + for u in range(tid, level_size, BLOCK_DIM): + update = all_updates[level_offset + u] + i, k, Madr_ki = update[0], update[1], update[2] + wp.atomic_sub(x_out[worldid], k, L[worldid, 0, Madr_ki] * x_out[worldid, i]) + _syncthreads() + + return kernel def _solve_LD_sparse( @@ -2685,14 +2763,20 @@ def _solve_LD_sparse( y: wp.array2d(dtype=float), ): """Computes sparse backsubstitution: x = inv(L'*D*L)*y.""" - wp.copy(x, y) - for qLD_updates in reversed(m.qLD_updates): - wp.launch(_solve_LD_sparse_x_acc_up, dim=(d.nworld, qLD_updates.size), inputs=[L, qLD_updates], outputs=[x]) - - wp.launch(_solve_LD_sparse_qLDiag_mul, dim=(d.nworld, m.nv), inputs=[D], outputs=[x]) + nlevels = len(m.qLD_updates) + if wp.get_device().is_cuda: + dim_block = m.block_dim.solve_LD_sparse_fused + else: + # Fallback for CPU + dim_block = 1 - for qLD_updates in m.qLD_updates: - wp.launch(_solve_LD_sparse_x_acc_down, dim=(d.nworld, qLD_updates.size), inputs=[L, qLD_updates], outputs=[x]) + wp.launch( + _solve_LD_sparse_fused(m.nv, nlevels), + dim=(d.nworld, dim_block), + inputs=[L, D, m.qLD_all_updates, m.qLD_level_offsets, y], + outputs=[x], + block_dim=dim_block, + ) @cache_kernel @@ -3005,6 +3089,9 @@ def _joint_tendon( # Model: jnt_qposadr: wp.array(dtype=int), jnt_dofadr: wp.array(dtype=int), + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), wrap_objid: wp.array(dtype=int), wrap_prm: wp.array(dtype=float), tendon_jnt_adr: wp.array(dtype=int), @@ -3012,34 +3099,87 @@ def _joint_tendon( # Data in: qpos_in: wp.array2d(dtype=float), # Data out: - ten_J_out: wp.array3d(dtype=float), + ten_J_out: wp.array2d(dtype=float), ten_length_out: wp.array2d(dtype=float), ): worldid, wrapid = wp.tid() - tendon_jnt_adr_ = tendon_jnt_adr[wrapid] - wrap_jnt_adr_ = wrap_jnt_adr[wrapid] - - wrap_objid_ = wrap_objid[wrap_jnt_adr_] - prm = wrap_prm[wrap_jnt_adr_] + tenid = tendon_jnt_adr[wrapid] + wrapjntid = wrap_jnt_adr[wrapid] + wrapobjid = wrap_objid[wrapjntid] + prm = wrap_prm[wrapjntid] # add to length - L = prm * qpos_in[worldid, jnt_qposadr[wrap_objid_]] - # TODO(team): compare atomic_add and for loop - wp.atomic_add(ten_length_out[worldid], tendon_jnt_adr_, L) + L = prm * qpos_in[worldid, jnt_qposadr[wrapobjid]] + wp.atomic_add(ten_length_out[worldid], tenid, L) # add to moment - ten_J_out[worldid, tendon_jnt_adr_, jnt_dofadr[wrap_objid_]] = prm + dofadr = jnt_dofadr[wrapobjid] + rowadr = ten_J_rowadr[tenid] + rownnz = ten_J_rownnz[tenid] + for k in range(rownnz): + if ten_J_colind[rowadr + k] == dofadr: + ten_J_out[worldid, rowadr + k] = prm + break + + +@wp.func +def _accumulate_jac_chain( + # Model: + body_parentid: wp.array(dtype=int), + body_dofnum: wp.array(dtype=int), + body_dofadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), + # Data in: + cdof_in: wp.array2d(dtype=wp.spatial_vector), + # In: + offset: wp.vec3, + vec: wp.vec3, + bodyid: int, + rowadr: int, + rownnz: int, + scale: float, + worldid: int, + # Data out: + ten_J_out: wp.array2d(dtype=float), +): + """Walk body chain from bodyid to root, accumulate Jacobian contributions.""" + ptr = rownnz - 1 + bid = bodyid + while bid > 0: + bdofadr = body_dofadr[bid] + bdofnum = body_dofnum[bid] + # iterate DOFs in this body in descending order + for k_rev in range(bdofnum): + dof = bdofadr + bdofnum - 1 - k_rev + # scan pointer backward to find matching colind entry + while ptr >= 0: + sparseid = rowadr + ptr + if ten_J_colind[sparseid] <= dof: + break + ptr -= 1 + if ptr >= 0 and ten_J_colind[sparseid] == dof: + cdof = cdof_in[worldid, dof] + cdof_ang = wp.spatial_top(cdof) + cdof_lin = wp.spatial_bottom(cdof) + jacp = cdof_lin + wp.cross(cdof_ang, offset) + J = wp.dot(jacp, vec) * scale + if J != 0.0: + wp.atomic_add(ten_J_out[worldid], sparseid, J) + bid = body_parentid[bid] @wp.kernel def _spatial_site_tendon( # Model: - nv: int, body_parentid: wp.array(dtype=int), body_rootid: wp.array(dtype=int), - dof_bodyid: wp.array(dtype=int), + body_dofnum: wp.array(dtype=int), + body_dofadr: wp.array(dtype=int), site_bodyid: wp.array(dtype=int), + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), wrap_objid: wp.array(dtype=int), tendon_site_pair_adr: wp.array(dtype=int), wrap_site_pair_adr: wp.array(dtype=int), @@ -3049,14 +3189,14 @@ def _spatial_site_tendon( subtree_com_in: wp.array2d(dtype=wp.vec3), cdof_in: wp.array2d(dtype=wp.spatial_vector), # Data out: - ten_J_out: wp.array3d(dtype=float), + ten_J_out: wp.array2d(dtype=float), ten_length_out: wp.array2d(dtype=float), ): worldid, elementid = wp.tid() # site pairs site_pair_adr = wrap_site_pair_adr[elementid] - ten_adr = tendon_site_pair_adr[elementid] + tenid = tendon_site_pair_adr[elementid] # pulley scaling pulley_scale = wrap_pulley_scale[site_pair_adr] @@ -3068,7 +3208,7 @@ def _spatial_site_tendon( pnt1 = site_xpos_in[worldid, id1] dif = pnt1 - pnt0 vec, length = math.normalize_with_norm(dif) - wp.atomic_add(ten_length_out[worldid], ten_adr, length * pulley_scale) + wp.atomic_add(ten_length_out[worldid], tenid, length * pulley_scale) if length < MJ_MINVAL: vec = wp.vec3(1.0, 0.0, 0.0) @@ -3076,26 +3216,55 @@ def _spatial_site_tendon( body0 = site_bodyid[id0] body1 = site_bodyid[id1] if body0 != body1: - # TODO(team): parallelize - for i in range(nv): - jacp1, _ = support.jac_dof(body_parentid, body_rootid, dof_bodyid, subtree_com_in, cdof_in, pnt0, body0, i, worldid) - jacp2, _ = support.jac_dof(body_parentid, body_rootid, dof_bodyid, subtree_com_in, cdof_in, pnt1, body1, i, worldid) - - J = wp.dot(jacp2 - jacp1, vec) - if J: - wp.atomic_add(ten_J_out[worldid, ten_adr], i, J * pulley_scale) + rownnz = ten_J_rownnz[tenid] + rowadr = ten_J_rowadr[tenid] + offset0 = pnt0 - subtree_com_in[worldid, body_rootid[body0]] + offset1 = pnt1 - subtree_com_in[worldid, body_rootid[body1]] + _accumulate_jac_chain( + body_parentid, + body_dofnum, + body_dofadr, + ten_J_colind, + cdof_in, + offset0, + vec, + body0, + rowadr, + rownnz, + -pulley_scale, + worldid, + ten_J_out, + ) + _accumulate_jac_chain( + body_parentid, + body_dofnum, + body_dofadr, + ten_J_colind, + cdof_in, + offset1, + vec, + body1, + rowadr, + rownnz, + pulley_scale, + worldid, + ten_J_out, + ) @wp.kernel def _spatial_geom_tendon( # Model: - nv: int, body_parentid: wp.array(dtype=int), body_rootid: wp.array(dtype=int), - dof_bodyid: wp.array(dtype=int), + body_dofnum: wp.array(dtype=int), + body_dofadr: wp.array(dtype=int), geom_bodyid: wp.array(dtype=int), geom_size: wp.array2d(dtype=wp.vec3), site_bodyid: wp.array(dtype=int), + ten_J_rownnz: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), wrap_type: wp.array(dtype=int), wrap_objid: wp.array(dtype=int), wrap_prm: wp.array(dtype=float), @@ -3109,14 +3278,14 @@ def _spatial_geom_tendon( subtree_com_in: wp.array2d(dtype=wp.vec3), cdof_in: wp.array2d(dtype=wp.spatial_vector), # Data out: - ten_J_out: wp.array3d(dtype=float), + ten_J_out: wp.array2d(dtype=float), ten_length_out: wp.array2d(dtype=float), # Out: wrap_geom_xpos_out: wp.array2d(dtype=wp.spatial_vector), ): worldid, elementid = wp.tid() wrap_adr = wrap_geom_adr[elementid] - ten_adr = tendon_geom_adr[elementid] + tenid = tendon_geom_adr[elementid] # pulley scaling pulley_scale = wrap_pulley_scale[wrap_adr] @@ -3154,6 +3323,9 @@ def _spatial_geom_tendon( # store geom points wrap_geom_xpos_out[worldid, elementid] = wp.spatial_vector(geom_pnt0, geom_pnt1) + rownnz = ten_J_rownnz[tenid] + rowadr = ten_J_rowadr[tenid] + if length_geomgeom >= 0.0: dif_sitegeom = geom_pnt0 - site_pnt0 dif_geomsite = site_pnt1 - geom_pnt1 @@ -3164,7 +3336,7 @@ def _spatial_geom_tendon( length_sitegeomsite = length_sitegeom + length_geomgeom + length_geomsite if length_sitegeomsite: - wp.atomic_add(ten_length_out[worldid], ten_adr, length_sitegeomsite * pulley_scale) + wp.atomic_add(ten_length_out[worldid], tenid, length_sitegeomsite * pulley_scale) # moment if length_sitegeom < MJ_MINVAL: @@ -3176,61 +3348,120 @@ def _spatial_geom_tendon( dif_body_sitegeom = bodyid_site0 != bodyid_geom dif_body_geomsite = bodyid_geom != bodyid_site1 - # TODO(team): parallelize - for i in range(nv): - J = float(0.0) - # site-geom - if dif_body_sitegeom: - jacp_site0, _ = support.jac_dof( - body_parentid, body_rootid, dof_bodyid, subtree_com_in, cdof_in, site_pnt0, bodyid_site0, i, worldid - ) - - jacp_geom0, _ = support.jac_dof( - body_parentid, body_rootid, dof_bodyid, subtree_com_in, cdof_in, geom_pnt0, bodyid_geom, i, worldid - ) - - J += wp.dot(jacp_geom0 - jacp_site0, vec_sitegeom) - - # geom-site - if dif_body_geomsite: - jacp_geom1, _ = support.jac_dof( - body_parentid, body_rootid, dof_bodyid, subtree_com_in, cdof_in, geom_pnt1, bodyid_geom, i, worldid - ) - - jacp_site1, _ = support.jac_dof( - body_parentid, body_rootid, dof_bodyid, subtree_com_in, cdof_in, site_pnt1, bodyid_site1, i, worldid - ) - - J += wp.dot(jacp_site1 - jacp_geom1, vec_geomsite) + # site-geom segment + if dif_body_sitegeom: + offset_site0 = site_pnt0 - subtree_com_in[worldid, body_rootid[bodyid_site0]] + offset_geom0 = geom_pnt0 - subtree_com_in[worldid, body_rootid[bodyid_geom]] + _accumulate_jac_chain( + body_parentid, + body_dofnum, + body_dofadr, + ten_J_colind, + cdof_in, + offset_site0, + vec_sitegeom, + bodyid_site0, + rowadr, + rownnz, + -pulley_scale, + worldid, + ten_J_out, + ) + _accumulate_jac_chain( + body_parentid, + body_dofnum, + body_dofadr, + ten_J_colind, + cdof_in, + offset_geom0, + vec_sitegeom, + bodyid_geom, + rowadr, + rownnz, + pulley_scale, + worldid, + ten_J_out, + ) - if J: - wp.atomic_add(ten_J_out[worldid, ten_adr], i, J * pulley_scale) + # geom-site segment + if dif_body_geomsite: + offset_geom1 = geom_pnt1 - subtree_com_in[worldid, body_rootid[bodyid_geom]] + offset_site1 = site_pnt1 - subtree_com_in[worldid, body_rootid[bodyid_site1]] + _accumulate_jac_chain( + body_parentid, + body_dofnum, + body_dofadr, + ten_J_colind, + cdof_in, + offset_geom1, + vec_geomsite, + bodyid_geom, + rowadr, + rownnz, + -pulley_scale, + worldid, + ten_J_out, + ) + _accumulate_jac_chain( + body_parentid, + body_dofnum, + body_dofadr, + ten_J_colind, + cdof_in, + offset_site1, + vec_geomsite, + bodyid_site1, + rowadr, + rownnz, + pulley_scale, + worldid, + ten_J_out, + ) else: dif_sitesite = site_pnt1 - site_pnt0 vec_sitesite, length_sitesite = math.normalize_with_norm(dif_sitesite) # length if length_sitesite: - wp.atomic_add(ten_length_out[worldid], ten_adr, length_sitesite * pulley_scale) + wp.atomic_add(ten_length_out[worldid], tenid, length_sitesite * pulley_scale) # moment if length_sitesite < MJ_MINVAL: vec_sitesite = wp.vec3(1.0, 0.0, 0.0) if bodyid_site0 != bodyid_site1: - # TODO(team): parallelize - for i in range(nv): - jacp1, _ = support.jac_dof( - body_parentid, body_rootid, dof_bodyid, subtree_com_in, cdof_in, site_pnt0, bodyid_site0, i, worldid - ) - jacp2, _ = support.jac_dof( - body_parentid, body_rootid, dof_bodyid, subtree_com_in, cdof_in, site_pnt1, bodyid_site1, i, worldid - ) - - J = wp.dot(jacp2 - jacp1, vec_sitesite) - - if J: - wp.atomic_add(ten_J_out[worldid, ten_adr], i, J * pulley_scale) + offset_site0 = site_pnt0 - subtree_com_in[worldid, body_rootid[bodyid_site0]] + offset_site1 = site_pnt1 - subtree_com_in[worldid, body_rootid[bodyid_site1]] + _accumulate_jac_chain( + body_parentid, + body_dofnum, + body_dofadr, + ten_J_colind, + cdof_in, + offset_site0, + vec_sitesite, + bodyid_site0, + rowadr, + rownnz, + -pulley_scale, + worldid, + ten_J_out, + ) + _accumulate_jac_chain( + body_parentid, + body_dofnum, + body_dofadr, + ten_J_colind, + cdof_in, + offset_site1, + vec_sitesite, + bodyid_site1, + rowadr, + rownnz, + pulley_scale, + worldid, + ten_J_out, + ) @wp.kernel @@ -3412,7 +3643,18 @@ def tendon(m: Model, d: Data): wp.launch( _joint_tendon, dim=(d.nworld, m.wrap_jnt_adr.size), - inputs=[m.jnt_qposadr, m.jnt_dofadr, m.wrap_objid, m.wrap_prm, m.tendon_jnt_adr, m.wrap_jnt_adr, d.qpos], + inputs=[ + m.jnt_qposadr, + m.jnt_dofadr, + m.ten_J_rownnz, + m.ten_J_rowadr, + m.ten_J_colind, + m.wrap_objid, + m.wrap_prm, + m.tendon_jnt_adr, + m.wrap_jnt_adr, + d.qpos, + ], outputs=[d.ten_J, d.ten_length], ) @@ -3428,11 +3670,14 @@ def tendon(m: Model, d: Data): _spatial_site_tendon, dim=(d.nworld, m.wrap_site_pair_adr.size), inputs=[ - m.nv, m.body_parentid, m.body_rootid, - m.dof_bodyid, + m.body_dofnum, + m.body_dofadr, m.site_bodyid, + m.ten_J_rownnz, + m.ten_J_rowadr, + m.ten_J_colind, m.wrap_objid, m.tendon_site_pair_adr, m.wrap_site_pair_adr, @@ -3449,13 +3694,16 @@ def tendon(m: Model, d: Data): _spatial_geom_tendon, dim=(d.nworld, m.wrap_geom_adr.size), inputs=[ - m.nv, m.body_parentid, m.body_rootid, - m.dof_bodyid, + m.body_dofnum, + m.body_dofadr, m.geom_bodyid, m.geom_size, m.site_bodyid, + m.ten_J_rownnz, + m.ten_J_rowadr, + m.ten_J_colind, m.wrap_type, m.wrap_objid, m.wrap_prm, diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/solver.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/solver.py index 82ac23c7c0..2fabebe0ad 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/solver.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/solver.py @@ -17,17 +17,17 @@ from math import ceil from math import sqrt +import warp as wp + from mujoco.mjx.third_party.mujoco_warp._src import math from mujoco.mjx.third_party.mujoco_warp._src import smooth from mujoco.mjx.third_party.mujoco_warp._src import support from mujoco.mjx.third_party.mujoco_warp._src import types from mujoco.mjx.third_party.mujoco_warp._src.block_cholesky import create_blocked_cholesky_func from mujoco.mjx.third_party.mujoco_warp._src.block_cholesky import create_blocked_cholesky_solve_func -from mujoco.mjx.third_party.mujoco_warp._src.types import SPARSE_CONSTRAINT_JACOBIAN from mujoco.mjx.third_party.mujoco_warp._src.warp_util import cache_kernel from mujoco.mjx.third_party.mujoco_warp._src.warp_util import event_scope from mujoco.mjx.third_party.mujoco_warp._src.warp_util import scoped_mathdx_gemm_disabled -import warp as wp wp.set_module_options({"enable_backward": False}) @@ -91,14 +91,14 @@ def create_inverse_context(m: types.Model, d: types.Data) -> InverseContext: njmax = d.njmax return InverseContext( - Jaref=wp.empty((nworld, njmax), dtype=float), - search_dot=wp.empty((nworld,), dtype=float), - gauss=wp.empty((nworld,), dtype=float), - cost=wp.empty((nworld,), dtype=float), - prev_cost=wp.empty((nworld,), dtype=float), - done=wp.empty((nworld,), dtype=bool), - changed_efc_ids=wp.empty((nworld, 0), dtype=int), - changed_efc_count=wp.empty((0,), dtype=int), + Jaref=wp.empty((nworld, njmax), dtype=float), + search_dot=wp.empty((nworld,), dtype=float), + gauss=wp.empty((nworld,), dtype=float), + cost=wp.empty((nworld,), dtype=float), + prev_cost=wp.empty((nworld,), dtype=float), + done=wp.empty((nworld,), dtype=bool), + changed_efc_ids=wp.empty((nworld, 0), dtype=int), + changed_efc_count=wp.empty((0,), dtype=int), ) @@ -121,36 +121,28 @@ def create_solver_context(m: types.Model, d: types.Data) -> SolverContext: alloc_hfactor = alloc_h and nv > _BLOCK_CHOLESKY_DIM return SolverContext( - Jaref=wp.empty((nworld, njmax), dtype=float), - search_dot=wp.empty((nworld,), dtype=float), - gauss=wp.empty((nworld,), dtype=float), - cost=wp.empty((nworld,), dtype=float), - prev_cost=wp.empty((nworld,), dtype=float), - done=wp.empty((nworld,), dtype=bool), - grad=wp.zeros((nworld, nv_pad), dtype=float), - grad_dot=wp.empty((nworld,), dtype=float), - Mgrad=wp.zeros((nworld, nv_pad), dtype=float), - search=wp.empty((nworld, nv), dtype=float), - mv=wp.empty((nworld, nv), dtype=float), - jv=wp.empty((nworld, njmax), dtype=float), - quad=wp.empty((nworld, njmax), dtype=wp.vec3), - quad_gauss=wp.empty((nworld,), dtype=wp.vec3), - alpha=wp.empty((nworld,), dtype=float), - prev_grad=wp.empty((nworld, nv), dtype=float), - prev_Mgrad=wp.empty((nworld, nv), dtype=float), - beta=wp.empty((nworld,), dtype=float), - h=wp.zeros((nworld, nv_pad, nv_pad), dtype=float) - if alloc_h - else wp.empty((nworld, 0, 0), dtype=float), - hfactor=wp.zeros((nworld, nv_pad, nv_pad), dtype=float) - if alloc_hfactor - else wp.empty((nworld, 0, 0), dtype=float), - changed_efc_ids=wp.empty((nworld, njmax), dtype=int) - if alloc_h - else wp.empty((nworld, 0), dtype=int), - changed_efc_count=wp.empty((nworld,), dtype=int) - if alloc_h - else wp.empty((0,), dtype=int), + Jaref=wp.empty((nworld, njmax), dtype=float), + search_dot=wp.empty((nworld,), dtype=float), + gauss=wp.empty((nworld,), dtype=float), + cost=wp.empty((nworld,), dtype=float), + prev_cost=wp.empty((nworld,), dtype=float), + done=wp.empty((nworld,), dtype=bool), + grad=wp.zeros((nworld, nv_pad), dtype=float), + grad_dot=wp.empty((nworld,), dtype=float), + Mgrad=wp.zeros((nworld, nv_pad), dtype=float), + search=wp.empty((nworld, nv), dtype=float), + mv=wp.empty((nworld, nv), dtype=float), + jv=wp.empty((nworld, njmax), dtype=float), + quad=wp.empty((nworld, njmax), dtype=wp.vec3), + quad_gauss=wp.empty((nworld,), dtype=wp.vec3), + alpha=wp.empty((nworld,), dtype=float), + prev_grad=wp.empty((nworld, nv), dtype=float), + prev_Mgrad=wp.empty((nworld, nv), dtype=float), + beta=wp.empty((nworld,), dtype=float), + h=wp.zeros((nworld, nv_pad, nv_pad), dtype=float) if alloc_h else wp.empty((nworld, 0, 0), dtype=float), + hfactor=wp.zeros((nworld, nv_pad, nv_pad), dtype=float) if alloc_hfactor else wp.empty((nworld, 0, 0), dtype=float), + changed_efc_ids=wp.empty((nworld, njmax), dtype=int) if alloc_h else wp.empty((nworld, 0), dtype=int), + changed_efc_count=wp.empty((nworld,), dtype=int) if alloc_h else wp.empty((0,), dtype=int), ) @@ -892,18 +884,19 @@ def _compute_efc_eval_pt_3alphas_elliptic( @cache_kernel -def linesearch_iterative(ls_iterations: int, cone_type: types.ConeType, fuse_jv: bool): +def linesearch_iterative(ls_iterations: int, cone_type: types.ConeType, fuse_jv: bool, is_sparse: bool): """Factory for iterative linesearch kernel. Args: - block_dim: Number of threads per block for tile reductions. ls_iterations: Max linesearch iterations (compile-time constant for loop optimization). cone_type: Friction cone type (PYRAMIDAL or ELLIPTIC) for compile-time optimization. fuse_jv: Whether to compute jv = J @ search in-kernel (efficient for small nv). + is_sparse: Use sparse matrix representation for constraint Jacobian. """ LS_ITERATIONS = ls_iterations IS_ELLIPTIC = cone_type == types.ConeType.ELLIPTIC FUSE_JV = fuse_jv + IS_SPARSE = is_sparse # Native snippet for CUDA __syncthreads() @wp.func_native(snippet="WP_TILE_SYNC();") @@ -922,46 +915,46 @@ def _syncthreads(): @wp.kernel(module="unique", enable_backward=False) def kernel( - # Model: - nv: int, - opt_tolerance: wp.array(dtype=float), - opt_ls_tolerance: wp.array(dtype=float), - opt_impratio_invsqrt: wp.array(dtype=float), - stat_meaninertia: wp.array(dtype=float), - # Data in: - ne_in: wp.array(dtype=int), - nf_in: wp.array(dtype=int), - nefc_in: wp.array(dtype=int), - qfrc_smooth_in: wp.array2d(dtype=float), - contact_friction_in: wp.array(dtype=types.vec5), - contact_dim_in: wp.array(dtype=int), - contact_efc_address_in: wp.array2d(dtype=int), - efc_type_in: wp.array2d(dtype=int), - efc_id_in: wp.array2d(dtype=int), - efc_J_rownnz_in: wp.array2d(dtype=int), - efc_J_rowadr_in: wp.array2d(dtype=int), - efc_J_colind_in: wp.array3d(dtype=int), - efc_J_in: wp.array3d(dtype=float), - efc_D_in: wp.array2d(dtype=float), - efc_frictionloss_in: wp.array2d(dtype=float), - njmax_in: int, - nacon_in: wp.array(dtype=int), - # In: - ctx_Jaref_in: wp.array2d(dtype=float), - ctx_search_in: wp.array2d(dtype=float), - ctx_search_dot_in: wp.array(dtype=float), - ctx_gauss_in: wp.array(dtype=float), - ctx_mv_in: wp.array2d(dtype=float), - ctx_jv_in: wp.array2d(dtype=float), - ctx_quad_in: wp.array2d(dtype=wp.vec3), - ctx_done_in: wp.array(dtype=bool), - # Data out: - qacc_out: wp.array2d(dtype=float), - efc_Ma_out: wp.array2d(dtype=float), - # Out: - ctx_Jaref_out: wp.array2d(dtype=float), - ctx_jv_out: wp.array2d(dtype=float), - ctx_quad_out: wp.array2d(dtype=wp.vec3), + # Model: + nv: int, + opt_tolerance: wp.array(dtype=float), + opt_ls_tolerance: wp.array(dtype=float), + opt_impratio_invsqrt: wp.array(dtype=float), + stat_meaninertia: wp.array(dtype=float), + # Data in: + ne_in: wp.array(dtype=int), + nf_in: wp.array(dtype=int), + nefc_in: wp.array(dtype=int), + qfrc_smooth_in: wp.array2d(dtype=float), + contact_friction_in: wp.array(dtype=types.vec5), + contact_dim_in: wp.array(dtype=int), + contact_efc_address_in: wp.array2d(dtype=int), + efc_type_in: wp.array2d(dtype=int), + efc_id_in: wp.array2d(dtype=int), + efc_J_rownnz_in: wp.array2d(dtype=int), + efc_J_rowadr_in: wp.array2d(dtype=int), + efc_J_colind_in: wp.array3d(dtype=int), + efc_J_in: wp.array3d(dtype=float), + efc_D_in: wp.array2d(dtype=float), + efc_frictionloss_in: wp.array2d(dtype=float), + njmax_in: int, + nacon_in: wp.array(dtype=int), + # In: + ctx_Jaref_in: wp.array2d(dtype=float), + ctx_search_in: wp.array2d(dtype=float), + ctx_search_dot_in: wp.array(dtype=float), + ctx_gauss_in: wp.array(dtype=float), + ctx_mv_in: wp.array2d(dtype=float), + ctx_jv_in: wp.array2d(dtype=float), + ctx_quad_in: wp.array2d(dtype=wp.vec3), + ctx_done_in: wp.array(dtype=bool), + # Data out: + qacc_out: wp.array2d(dtype=float), + efc_Ma_out: wp.array2d(dtype=float), + # Out: + ctx_Jaref_out: wp.array2d(dtype=float), + ctx_jv_out: wp.array2d(dtype=float), + ctx_quad_out: wp.array2d(dtype=wp.vec3), ): worldid, tid = wp.tid() @@ -976,15 +969,13 @@ def kernel( if wp.static(FUSE_JV): for efcid in range(tid, nefc, wp.block_dim()): jv = float(0.0) - if wp.static(SPARSE_CONSTRAINT_JACOBIAN): + if wp.static(IS_SPARSE): rownnz = efc_J_rownnz_in[worldid, efcid] rowadr = efc_J_rowadr_in[worldid, efcid] for k in range(rownnz): sparseid = rowadr + k colind = efc_J_colind_in[worldid, 0, sparseid] - jv += ( - efc_J_in[worldid, 0, sparseid] * ctx_search_in[worldid, colind] - ) + jv += efc_J_in[worldid, 0, sparseid] * ctx_search_in[worldid, colind] else: for i in range(nv): jv += efc_J_in[worldid, efcid, i] * ctx_search_in[worldid, i] @@ -1360,42 +1351,42 @@ def _linesearch_iterative(m: types.Model, d: types.Data, ctx: SolverContext, fus fuse_jv: Whether jv is computed in-kernel (True) or pre-computed (False). """ wp.launch_tiled( - linesearch_iterative(m.opt.ls_iterations, m.opt.cone, fuse_jv), - dim=d.nworld, - inputs=[ - m.nv, - m.opt.tolerance, - m.opt.ls_tolerance, - m.opt.impratio_invsqrt, - m.stat.meaninertia, - d.ne, - d.nf, - d.nefc, - d.qfrc_smooth, - d.contact.friction, - d.contact.dim, - d.contact.efc_address, - d.efc.type, - d.efc.id, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.D, - d.efc.frictionloss, - d.njmax, - d.nacon, - ctx.Jaref, - ctx.search, - ctx.search_dot, - ctx.gauss, - ctx.mv, - ctx.jv, - ctx.quad, - ctx.done, - ], - outputs=[d.qacc, d.efc.Ma, ctx.Jaref, ctx.jv, ctx.quad], - block_dim=m.block_dim.linesearch_iterative, + linesearch_iterative(m.opt.ls_iterations, m.opt.cone, fuse_jv, m.is_sparse), + dim=d.nworld, + inputs=[ + m.nv, + m.opt.tolerance, + m.opt.ls_tolerance, + m.opt.impratio_invsqrt, + m.stat.meaninertia, + d.ne, + d.nf, + d.nefc, + d.qfrc_smooth, + d.contact.friction, + d.contact.dim, + d.contact.efc_address, + d.efc.type, + d.efc.id, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.efc.D, + d.efc.frictionloss, + d.njmax, + d.nacon, + ctx.Jaref, + ctx.search, + ctx.search_dot, + ctx.gauss, + ctx.mv, + ctx.jv, + ctx.quad, + ctx.done, + ], + outputs=[d.qacc, d.efc.Ma, ctx.Jaref, ctx.jv, ctx.quad], + block_dim=m.block_dim.linesearch_iterative, ) @@ -1420,20 +1411,20 @@ def linesearch_zero_jv( @cache_kernel -def linesearch_jv_fused(opt_is_sparse: bool, nv: int, dofs_per_thread: int): +def linesearch_jv_fused(is_sparse: bool, nv: int, dofs_per_thread: int): @wp.kernel(module="unique", enable_backward=False) def kernel( - # Data in: - nefc_in: wp.array(dtype=int), - efc_J_rownnz_in: wp.array2d(dtype=int), - efc_J_rowadr_in: wp.array2d(dtype=int), - efc_J_colind_in: wp.array3d(dtype=int), - efc_J_in: wp.array3d(dtype=float), - # In: - ctx_search_in: wp.array2d(dtype=float), - ctx_done_in: wp.array(dtype=bool), - # Out: - ctx_jv_out: wp.array2d(dtype=float), + # Data in: + nefc_in: wp.array(dtype=int), + efc_J_rownnz_in: wp.array2d(dtype=int), + efc_J_rowadr_in: wp.array2d(dtype=int), + efc_J_colind_in: wp.array3d(dtype=int), + efc_J_in: wp.array3d(dtype=float), + # In: + ctx_search_in: wp.array2d(dtype=float), + ctx_done_in: wp.array(dtype=bool), + # Out: + ctx_jv_out: wp.array2d(dtype=float), ): worldid, efcid, dofstart = wp.tid() @@ -1446,23 +1437,21 @@ def kernel( jv_out = float(0.0) if wp.static(dofs_per_thread >= nv): - if wp.static(SPARSE_CONSTRAINT_JACOBIAN): + if wp.static(is_sparse): # Sparse: iterate over non-zero entries in the row rownnz = efc_J_rownnz_in[worldid, efcid] rowadr = efc_J_rowadr_in[worldid, efcid] for k in range(rownnz): sparseid = rowadr + k colind = efc_J_colind_in[worldid, 0, sparseid] - jv_out += ( - efc_J_in[worldid, 0, sparseid] * ctx_search_in[worldid, colind] - ) + jv_out += efc_J_in[worldid, 0, sparseid] * ctx_search_in[worldid, colind] else: for i in range(wp.static(min(dofs_per_thread, nv))): jv_out += efc_J_in[worldid, efcid, i] * ctx_search_in[worldid, i] ctx_jv_out[worldid, efcid] = jv_out else: - if wp.static(SPARSE_CONSTRAINT_JACOBIAN): + if wp.static(is_sparse): # Sparse: thread 0 handles entire row (sparse entries << nv typically) if dofstart == 0: rownnz = efc_J_rownnz_in[worldid, efcid] @@ -1470,9 +1459,7 @@ def kernel( for k in range(rownnz): sparseid = rowadr + k colind = efc_J_colind_in[worldid, 0, sparseid] - jv_out += ( - efc_J_in[worldid, 0, sparseid] * ctx_search_in[worldid, colind] - ) + jv_out += efc_J_in[worldid, 0, sparseid] * ctx_search_in[worldid, colind] ctx_jv_out[worldid, efcid] = jv_out else: for i in range(wp.static(dofs_per_thread)): @@ -1583,10 +1570,7 @@ def linesearch_prepare_quad( dim = contact_dim_in[conid] friction = contact_friction_in[conid] - mu = ( - friction[0] - * opt_impratio_invsqrt[worldid % opt_impratio_invsqrt.shape[0]] - ) + mu = friction[0] * opt_impratio_invsqrt[worldid % opt_impratio_invsqrt.shape[0]] u0 = Jaref * mu v0 = jv * mu @@ -1707,18 +1691,10 @@ def _linesearch(m: types.Model, d: types.Data, ctx: SolverContext, cost: wp.arra ) wp.launch( - linesearch_jv_fused(m.is_sparse, m.nv, dofs_per_thread), - dim=(d.nworld, d.njmax, threads_per_efc), - inputs=[ - d.nefc, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - ctx.search, - ctx.done, - ], - outputs=[ctx.jv], + linesearch_jv_fused(m.is_sparse, m.nv, dofs_per_thread), + dim=(d.nworld, d.njmax, threads_per_efc), + inputs=[d.nefc, d.efc.J_rownnz, d.efc.J_rowadr, d.efc.J_colind, d.efc.J, ctx.search, ctx.done], + outputs=[ctx.jv], ) if m.opt.ls_parallel: @@ -1744,19 +1720,19 @@ def solve_init_efc( @cache_kernel -def solve_init_jaref(opt_is_sparse: bool, nv: int, dofs_per_thread: int): +def solve_init_jaref(is_sparse: bool, nv: int, dofs_per_thread: int): @wp.kernel(module="unique", enable_backward=False) def kernel( - # Data in: - nefc_in: wp.array(dtype=int), - qacc_in: wp.array2d(dtype=float), - efc_J_rownnz_in: wp.array2d(dtype=int), - efc_J_rowadr_in: wp.array2d(dtype=int), - efc_J_colind_in: wp.array3d(dtype=int), - efc_J_in: wp.array3d(dtype=float), - efc_aref_in: wp.array2d(dtype=float), - # Out: - ctx_Jaref_out: wp.array2d(dtype=float), + # Data in: + nefc_in: wp.array(dtype=int), + qacc_in: wp.array2d(dtype=float), + efc_J_rownnz_in: wp.array2d(dtype=int), + efc_J_rowadr_in: wp.array2d(dtype=int), + efc_J_colind_in: wp.array3d(dtype=int), + efc_J_in: wp.array3d(dtype=float), + efc_aref_in: wp.array2d(dtype=float), + # Out: + ctx_Jaref_out: wp.array2d(dtype=float), ): worldid, efcid, dofstart = wp.tid() @@ -1764,7 +1740,7 @@ def kernel( return jaref = float(0.0) - if wp.static(SPARSE_CONSTRAINT_JACOBIAN): + if wp.static(is_sparse): rownnz = efc_J_rownnz_in[worldid, efcid] rowadr = efc_J_rowadr_in[worldid, efcid] for i in range(rownnz): @@ -1785,9 +1761,7 @@ def kernel( jaref += efc_J_in[worldid, efcid, ii] * qacc_in[worldid, ii] if dofstart == 0: - wp.atomic_add( - ctx_Jaref_out, worldid, efcid, jaref - efc_aref_in[worldid, efcid] - ) + wp.atomic_add(ctx_Jaref_out, worldid, efcid, jaref - efc_aref_in[worldid, efcid]) else: wp.atomic_add(ctx_Jaref_out, worldid, efcid, jaref) @@ -1834,30 +1808,30 @@ def update_constraint_efc(track_changes: bool): @wp.kernel(module="unique", enable_backward=False) def kernel( - # Model: - opt_impratio_invsqrt: wp.array(dtype=float), - # Data in: - ne_in: wp.array(dtype=int), - nf_in: wp.array(dtype=int), - nefc_in: wp.array(dtype=int), - contact_friction_in: wp.array(dtype=types.vec5), - contact_dim_in: wp.array(dtype=int), - contact_efc_address_in: wp.array2d(dtype=int), - efc_type_in: wp.array2d(dtype=int), - efc_id_in: wp.array2d(dtype=int), - efc_D_in: wp.array2d(dtype=float), - efc_frictionloss_in: wp.array2d(dtype=float), - nacon_in: wp.array(dtype=int), - # In: - ctx_Jaref_in: wp.array2d(dtype=float), - ctx_done_in: wp.array(dtype=bool), - # Data out: - efc_force_out: wp.array2d(dtype=float), - efc_state_out: wp.array2d(dtype=int), - # Out: - ctx_cost_out: wp.array(dtype=float), - changed_ids_out: wp.array2d(dtype=int), - changed_count_out: wp.array(dtype=int), + # Model: + opt_impratio_invsqrt: wp.array(dtype=float), + # Data in: + ne_in: wp.array(dtype=int), + nf_in: wp.array(dtype=int), + nefc_in: wp.array(dtype=int), + contact_friction_in: wp.array(dtype=types.vec5), + contact_dim_in: wp.array(dtype=int), + contact_efc_address_in: wp.array2d(dtype=int), + efc_type_in: wp.array2d(dtype=int), + efc_id_in: wp.array2d(dtype=int), + efc_D_in: wp.array2d(dtype=float), + efc_frictionloss_in: wp.array2d(dtype=float), + nacon_in: wp.array(dtype=int), + # In: + ctx_Jaref_in: wp.array2d(dtype=float), + ctx_done_in: wp.array(dtype=bool), + # Data out: + efc_force_out: wp.array2d(dtype=float), + efc_state_out: wp.array2d(dtype=int), + # Out: + ctx_cost_out: wp.array(dtype=float), + changed_ids_out: wp.array2d(dtype=int), + changed_count_out: wp.array(dtype=int), ): worldid, efcid = wp.tid() @@ -1869,9 +1843,7 @@ def kernel( # Read old QUADRATIC status before overwriting if wp.static(TRACK_CHANGES): - old_quad = ( - efc_state_out[worldid, efcid] == types.ConstraintState.QUADRATIC.value - ) + old_quad = efc_state_out[worldid, efcid] == types.ConstraintState.QUADRATIC.value efc_D = efc_D_in[worldid, efcid] Jaref = ctx_Jaref_in[worldid, efcid] @@ -1919,10 +1891,7 @@ def kernel( dim = contact_dim_in[conid] friction = contact_friction_in[conid] - mu = ( - friction[0] - * opt_impratio_invsqrt[worldid % opt_impratio_invsqrt.shape[0]] - ) + mu = friction[0] * opt_impratio_invsqrt[worldid % opt_impratio_invsqrt.shape[0]] efcid0 = contact_efc_address_in[conid, 0] if efcid0 < 0: @@ -1984,17 +1953,17 @@ def kernel( @wp.kernel def update_constraint_init_qfrc_constraint_sparse( - # Data in: - nefc_in: wp.array(dtype=int), - efc_J_rownnz_in: wp.array2d(dtype=int), - efc_J_rowadr_in: wp.array2d(dtype=int), - efc_J_colind_in: wp.array3d(dtype=int), - efc_J_in: wp.array3d(dtype=float), - efc_force_in: wp.array2d(dtype=float), - # In: - ctx_done_in: wp.array(dtype=bool), - # Data out: - qfrc_constraint_out: wp.array2d(dtype=float), + # Data in: + nefc_in: wp.array(dtype=int), + efc_J_rownnz_in: wp.array2d(dtype=int), + efc_J_rowadr_in: wp.array2d(dtype=int), + efc_J_colind_in: wp.array3d(dtype=int), + efc_J_in: wp.array3d(dtype=float), + efc_force_in: wp.array2d(dtype=float), + # In: + ctx_done_in: wp.array(dtype=bool), + # Data out: + qfrc_constraint_out: wp.array2d(dtype=float), ): worldid, efcid = wp.tid() @@ -2017,15 +1986,15 @@ def update_constraint_init_qfrc_constraint_sparse( @wp.kernel def update_constraint_init_qfrc_constraint_dense( - # Data in: - nefc_in: wp.array(dtype=int), - efc_J_in: wp.array3d(dtype=float), - efc_force_in: wp.array2d(dtype=float), - njmax_in: int, - # In: - ctx_done_in: wp.array(dtype=bool), - # Data out: - qfrc_constraint_out: wp.array2d(dtype=float), + # Data in: + nefc_in: wp.array(dtype=int), + efc_J_in: wp.array3d(dtype=float), + efc_force_in: wp.array2d(dtype=float), + njmax_in: int, + # In: + ctx_done_in: wp.array(dtype=bool), + # Data out: + qfrc_constraint_out: wp.array2d(dtype=float), ): worldid, dofid = wp.tid() @@ -2076,23 +2045,23 @@ def kernel( gauss_cost += (efc_Ma_in[worldid, ii] - qfrc_smooth_in[worldid, ii]) * ( qacc_in[worldid, ii] - qacc_smooth_in[worldid, ii] ) - wp.atomic_add(ctx_gauss_out, worldid, gauss_cost) - wp.atomic_add(ctx_cost_out, worldid, gauss_cost) + wp.atomic_add(ctx_gauss_out, worldid, 0.5 * gauss_cost) + wp.atomic_add(ctx_cost_out, worldid, 0.5 * gauss_cost) return kernel @wp.kernel def update_gradient_h_incremental( - # Data in: - efc_J_in: wp.array3d(dtype=float), - efc_D_in: wp.array2d(dtype=float), - efc_state_in: wp.array2d(dtype=int), - # In: - changed_ids_in: wp.array2d(dtype=int), - changed_count_in: wp.array(dtype=int), - # Out: - ctx_h_out: wp.array3d(dtype=float), + # Data in: + efc_J_in: wp.array3d(dtype=float), + efc_D_in: wp.array2d(dtype=float), + efc_state_in: wp.array2d(dtype=int), + # In: + changed_ids_in: wp.array2d(dtype=int), + changed_count_in: wp.array(dtype=int), + # Out: + ctx_h_out: wp.array3d(dtype=float), ): """Incrementally update lower triangle of H for changed constraints. @@ -2131,18 +2100,18 @@ def update_gradient_h_incremental( @wp.kernel def update_gradient_h_incremental_sparse( - # Data in: - efc_J_rownnz_in: wp.array2d(dtype=int), - efc_J_rowadr_in: wp.array2d(dtype=int), - efc_J_colind_in: wp.array3d(dtype=int), - efc_J_in: wp.array3d(dtype=float), - efc_D_in: wp.array2d(dtype=float), - efc_state_in: wp.array2d(dtype=int), - # In: - changed_ids_in: wp.array2d(dtype=int), - changed_count_in: wp.array(dtype=int), - # Out: - ctx_h_out: wp.array3d(dtype=float), + # Data in: + efc_J_rownnz_in: wp.array2d(dtype=int), + efc_J_rowadr_in: wp.array2d(dtype=int), + efc_J_colind_in: wp.array3d(dtype=int), + efc_J_in: wp.array3d(dtype=float), + efc_D_in: wp.array2d(dtype=float), + efc_state_in: wp.array2d(dtype=int), + # In: + changed_ids_in: wp.array2d(dtype=int), + changed_count_in: wp.array(dtype=int), + # Out: + ctx_h_out: wp.array3d(dtype=float), ): """Incrementally update lower triangle of H for changed constraints (sparse J).""" worldid, change_idx = wp.tid() @@ -2182,12 +2151,7 @@ def update_gradient_h_incremental_sparse( wp.atomic_add(ctx_h_out[worldid, colindj], colindi, h) -def _update_constraint( - m: types.Model, - d: types.Data, - ctx: SolverContext | InverseContext, - track_changes: bool = False, -): +def _update_constraint(m: types.Model, d: types.Data, ctx: SolverContext | InverseContext, track_changes: bool = False): """Update constraint arrays after each solve iteration.""" wp.launch( update_constraint_init_cost, @@ -2197,58 +2161,44 @@ def _update_constraint( ) efc_inputs = [ - m.opt.impratio_invsqrt, - d.ne, - d.nf, - d.nefc, - d.contact.friction, - d.contact.dim, - d.contact.efc_address, - d.efc.type, - d.efc.id, - d.efc.D, - d.efc.frictionloss, - d.nacon, - ctx.Jaref, - ctx.done, + m.opt.impratio_invsqrt, + d.ne, + d.nf, + d.nefc, + d.contact.friction, + d.contact.dim, + d.contact.efc_address, + d.efc.type, + d.efc.id, + d.efc.D, + d.efc.frictionloss, + d.nacon, + ctx.Jaref, + ctx.done, ] wp.launch( - update_constraint_efc(track_changes), - dim=(d.nworld, d.njmax), - inputs=efc_inputs, - outputs=[ - d.efc.force, - d.efc.state, - ctx.cost, - ctx.changed_efc_ids, - ctx.changed_efc_count, - ], + update_constraint_efc(track_changes), + dim=(d.nworld, d.njmax), + inputs=efc_inputs, + outputs=[d.efc.force, d.efc.state, ctx.cost, ctx.changed_efc_ids, ctx.changed_efc_count], ) # qfrc_constraint = efc_J.T @ efc_force - if SPARSE_CONSTRAINT_JACOBIAN: + if m.is_sparse: d.qfrc_constraint.zero_() wp.launch( - update_constraint_init_qfrc_constraint_sparse, - dim=(d.nworld, d.njmax), - inputs=[ - d.nefc, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.force, - ctx.done, - ], - outputs=[d.qfrc_constraint], + update_constraint_init_qfrc_constraint_sparse, + dim=(d.nworld, d.njmax), + inputs=[d.nefc, d.efc.J_rownnz, d.efc.J_rowadr, d.efc.J_colind, d.efc.J, d.efc.force, ctx.done], + outputs=[d.qfrc_constraint], ) else: wp.launch( - update_constraint_init_qfrc_constraint_dense, - dim=(d.nworld, m.nv), - inputs=[d.nefc, d.efc.J, d.efc.force, d.njmax, ctx.done], - outputs=[d.qfrc_constraint], + update_constraint_init_qfrc_constraint_dense, + dim=(d.nworld, m.nv), + inputs=[d.nefc, d.efc.J, d.efc.force, d.njmax, ctx.done], + outputs=[d.qfrc_constraint], ) # if we are only using 1 thread, it makes sense to do more dofs and skip the atomics. @@ -2441,9 +2391,7 @@ def kernel( nefc = nefc_in[worldid] - sum_val = wp.tile_load( - qM_in[worldid], shape=(nv_pad, nv_pad), bounds_check=True - ) + sum_val = wp.tile_load(qM_in[worldid], shape=(nv_pad, nv_pad), bounds_check=True) # Each tile processes one output tile by looping over all constraints for k in range(0, njmax, TILE_SIZE_K): @@ -2453,12 +2401,7 @@ def kernel( # AD: leaving bounds-check disabled here because I'm not entirely sure that # everything always hits the fast path. The padding takes care of any # potential OOB accesses. - J_kj = wp.tile_load( - efc_J_in[worldid], - shape=(TILE_SIZE_K, nv_pad), - offset=(k, 0), - bounds_check=False, - ) + J_kj = wp.tile_load(efc_J_in[worldid], shape=(TILE_SIZE_K, nv_pad), offset=(k, 0), bounds_check=False) # state check D_k = wp.tile_load(efc_D_in[worldid], shape=TILE_SIZE_K, offset=k, bounds_check=False) @@ -2473,11 +2416,7 @@ def kernel( active_tile = wp.tile_map(active_check, tid_tile, threshold_tile) D_k = wp.tile_map(wp.mul, active_tile, D_k) - J_ki = wp.tile_map( - wp.mul, - wp.tile_transpose(J_kj), - wp.tile_broadcast(D_k, shape=(nv_pad, TILE_SIZE_K)), - ) + J_ki = wp.tile_map(wp.mul, wp.tile_transpose(J_kj), wp.tile_broadcast(D_k, shape=(nv_pad, TILE_SIZE_K))) sum_val += wp.tile_matmul(J_ki, J_kj) @@ -2489,32 +2428,32 @@ def kernel( # TODO(thowell): combine with JTDAJ ? @wp.kernel def update_gradient_JTCJ_sparse( - # Model: - opt_impratio_invsqrt: wp.array(dtype=float), - dof_tri_row: wp.array(dtype=int), - dof_tri_col: wp.array(dtype=int), - # Data in: - contact_dist_in: wp.array(dtype=float), - contact_includemargin_in: wp.array(dtype=float), - contact_friction_in: wp.array(dtype=types.vec5), - contact_dim_in: wp.array(dtype=int), - contact_efc_address_in: wp.array2d(dtype=int), - contact_worldid_in: wp.array(dtype=int), - efc_J_rownnz_in: wp.array2d(dtype=int), - efc_J_rowadr_in: wp.array2d(dtype=int), - efc_J_colind_in: wp.array3d(dtype=int), - efc_J_in: wp.array3d(dtype=float), - efc_D_in: wp.array2d(dtype=float), - efc_state_in: wp.array2d(dtype=int), - naconmax_in: int, - nacon_in: wp.array(dtype=int), - # In: - ctx_Jaref_in: wp.array2d(dtype=float), - ctx_done_in: wp.array(dtype=bool), - nblocks_perblock: int, - dim_block: int, - # Out: - h_out: wp.array3d(dtype=float), + # Model: + opt_impratio_invsqrt: wp.array(dtype=float), + dof_tri_row: wp.array(dtype=int), + dof_tri_col: wp.array(dtype=int), + # Data in: + contact_dist_in: wp.array(dtype=float), + contact_includemargin_in: wp.array(dtype=float), + contact_friction_in: wp.array(dtype=types.vec5), + contact_dim_in: wp.array(dtype=int), + contact_efc_address_in: wp.array2d(dtype=int), + contact_worldid_in: wp.array(dtype=int), + efc_J_rownnz_in: wp.array2d(dtype=int), + efc_J_rowadr_in: wp.array2d(dtype=int), + efc_J_colind_in: wp.array3d(dtype=int), + efc_J_in: wp.array3d(dtype=float), + efc_D_in: wp.array2d(dtype=float), + efc_state_in: wp.array2d(dtype=int), + naconmax_in: int, + nacon_in: wp.array(dtype=int), + # In: + ctx_Jaref_in: wp.array2d(dtype=float), + ctx_done_in: wp.array(dtype=bool), + nblocks_perblock: int, + dim_block: int, + # Out: + ctx_h_out: wp.array3d(dtype=float), ): conid_start, elementid = wp.tid() @@ -2529,20 +2468,37 @@ def update_gradient_JTCJ_sparse( worldid = contact_worldid_in[conid] if ctx_done_in[worldid]: - return + continue condim = contact_dim_in[conid] if condim == 1: - return + continue # check contact status if contact_dist_in[conid] - contact_includemargin_in[conid] >= 0.0: - return + continue efcid0 = contact_efc_address_in[conid, 0] if efc_state_in[worldid, efcid0] != types.ConstraintState.CONE: - return + continue + + # All dims share the same sparsity pattern. Scan colind once to find + # the sparse positions of dof1id and dof2id. Skip if either is absent. + rownnz = efc_J_rownnz_in[worldid, efcid0] + rowadr0 = efc_J_rowadr_in[worldid, efcid0] + pos1 = int(-1) + pos2 = int(-1) + for k in range(rownnz): + col = efc_J_colind_in[worldid, 0, rowadr0 + k] + if col == dof1id: + pos1 = k + if col == dof2id: + pos2 = k + if pos1 >= 0 and pos2 >= 0: + break + if pos1 < 0 or pos2 < 0: + continue fri = contact_friction_in[conid] mu = fri[0] * opt_impratio_invsqrt[worldid % opt_impratio_invsqrt.shape[0]] @@ -2551,7 +2507,7 @@ def update_gradient_JTCJ_sparse( dm = math.safe_div(efc_D_in[worldid, efcid0], mu2 * (1.0 + mu2)) if dm == 0.0: - return + continue n = ctx_Jaref_in[worldid, efcid0] * mu u = types.vec6(n, 0.0, 0.0, 0.0, 0.0, 0.0) @@ -2570,52 +2526,40 @@ def update_gradient_JTCJ_sparse( t = wp.max(t, types.MJ_MINVAL) ttt = wp.max(t * t * t, types.MJ_MINVAL) + # Precompute common subexpressions. + mu_over_t = math.safe_div(mu, t) + mu_n_over_ttt = mu * math.safe_div(n, ttt) + mu2_minus_mu_n_over_t = mu2 - mu * math.safe_div(n, t) + h = float(0.0) for dim1id in range(condim): if dim1id == 0: - efcid1 = efcid0 + rowadr1 = rowadr0 + dm_fri1 = dm * mu else: efcid1 = contact_efc_address_in[conid, dim1id] + rowadr1 = efc_J_rowadr_in[worldid, efcid1] + dm_fri1 = dm * fri[dim1id - 1] - # TODO(team): improve performance for sparse code path - rownnz1 = efc_J_rownnz_in[worldid, efcid1] - rowadr1 = efc_J_rowadr_in[worldid, efcid1] - - efc_J11 = float(0.0) - efc_J12 = float(0.0) - for i1 in range(rownnz1): - sparseid1 = rowadr1 + i1 - colind1 = efc_J_colind_in[worldid, 0, sparseid1] - if dof1id == colind1: - efc_J11 = efc_J_in[worldid, 0, sparseid1] - if dof2id == colind1: - efc_J12 = efc_J_in[worldid, 0, sparseid1] - if efc_J11 != 0.0 and efc_J12 != 0.0: - break + # Direct J reads using cached sparse positions. + efc_J11 = efc_J_in[worldid, 0, rowadr1 + pos1] + efc_J12 = efc_J_in[worldid, 0, rowadr1 + pos2] ui = u[dim1id] for dim2id in range(0, dim1id + 1): if dim2id == 0: - efcid2 = efcid0 + rowadr2 = rowadr0 + dm_fri12 = dm_fri1 * mu else: efcid2 = contact_efc_address_in[conid, dim2id] + rowadr2 = efc_J_rowadr_in[worldid, efcid2] + dm_fri12 = dm_fri1 * fri[dim2id - 1] - rownnz2 = efc_J_rownnz_in[worldid, efcid2] - rowadr2 = efc_J_rowadr_in[worldid, efcid2] - - efc_J21 = float(0.0) - efc_J22 = float(0.0) - for i2 in range(rownnz2): - sparseid2 = rowadr2 + i2 - colind2 = efc_J_colind_in[worldid, 0, sparseid2] - if dof1id == colind2: - efc_J21 = efc_J_in[worldid, 0, sparseid2] - if dof2id == colind2: - efc_J22 = efc_J_in[worldid, 0, sparseid2] - if efc_J21 != 0.0 and efc_J22 != 0.0: - break + # Direct J reads using cached sparse positions. + efc_J21 = efc_J_in[worldid, 0, rowadr2 + pos1] + efc_J22 = efc_J_in[worldid, 0, rowadr2 + pos2] uj = u[dim2id] @@ -2623,28 +2567,17 @@ def update_gradient_JTCJ_sparse( if dim1id == 0 and dim2id == 0: hcone = 1.0 elif dim1id == 0: - hcone = -math.safe_div(mu, t) * uj + hcone = -mu_over_t * uj elif dim2id == 0: - hcone = -math.safe_div(mu, t) * ui + hcone = -mu_over_t * ui else: - hcone = mu * math.safe_div(n, ttt) * ui * uj + hcone = mu_n_over_ttt * ui * uj # add to diagonal: mu^2 - mu * n / t if dim1id == dim2id: - hcone += mu2 - mu * math.safe_div(n, t) + hcone += mu2_minus_mu_n_over_t - # pre and post multiply by diag(mu, friction) scale by dm - if dim1id == 0: - fri1 = mu - else: - fri1 = fri[dim1id - 1] - - if dim2id == 0: - fri2 = mu - else: - fri2 = fri[dim2id - 1] - - hcone *= dm * fri1 * fri2 + hcone *= dm_fri12 if hcone != 0.0: h += hcone * efc_J11 * efc_J22 @@ -2652,34 +2585,34 @@ def update_gradient_JTCJ_sparse( if dim1id != dim2id: h += hcone * efc_J12 * efc_J21 - h_out[worldid, dof1id, dof2id] += h + ctx_h_out[worldid, dof1id, dof2id] += h @wp.kernel def update_gradient_JTCJ_dense( - # Model: - opt_impratio_invsqrt: wp.array(dtype=float), - dof_tri_row: wp.array(dtype=int), - dof_tri_col: wp.array(dtype=int), - # Data in: - contact_dist_in: wp.array(dtype=float), - contact_includemargin_in: wp.array(dtype=float), - contact_friction_in: wp.array(dtype=types.vec5), - contact_dim_in: wp.array(dtype=int), - contact_efc_address_in: wp.array2d(dtype=int), - contact_worldid_in: wp.array(dtype=int), - efc_J_in: wp.array3d(dtype=float), - efc_D_in: wp.array2d(dtype=float), - efc_state_in: wp.array2d(dtype=int), - naconmax_in: int, - nacon_in: wp.array(dtype=int), - # In: - ctx_Jaref_in: wp.array2d(dtype=float), - ctx_done_in: wp.array(dtype=bool), - nblocks_perblock: int, - dim_block: int, - # Out: - ctx_h_out: wp.array3d(dtype=float), + # Model: + opt_impratio_invsqrt: wp.array(dtype=float), + dof_tri_row: wp.array(dtype=int), + dof_tri_col: wp.array(dtype=int), + # Data in: + contact_dist_in: wp.array(dtype=float), + contact_includemargin_in: wp.array(dtype=float), + contact_friction_in: wp.array(dtype=types.vec5), + contact_dim_in: wp.array(dtype=int), + contact_efc_address_in: wp.array2d(dtype=int), + contact_worldid_in: wp.array(dtype=int), + efc_J_in: wp.array3d(dtype=float), + efc_D_in: wp.array2d(dtype=float), + efc_state_in: wp.array2d(dtype=int), + naconmax_in: int, + nacon_in: wp.array(dtype=int), + # In: + ctx_Jaref_in: wp.array2d(dtype=float), + ctx_done_in: wp.array(dtype=bool), + nblocks_perblock: int, + dim_block: int, + # Out: + ctx_h_out: wp.array3d(dtype=float), ): conid_start, elementid = wp.tid() @@ -2863,40 +2796,86 @@ def padding_h(nv: int, ctx_done_in: wp.array(dtype=bool), ctx_h_out: wp.array3d( ctx_h_out[worldid, dofid, dofid] = 1.0 -def _cholesky_factorize_solve( - m: types.Model, d: types.Data, ctx: SolverContext -): +def _cholesky_factorize_solve(m: types.Model, d: types.Data, ctx: SolverContext): """Cholesky factorize ctx.h and solve for Mgrad.""" if m.nv <= _BLOCK_CHOLESKY_DIM: wp.launch_tiled( - update_gradient_cholesky(m.nv), - dim=d.nworld, - inputs=[ctx.grad, ctx.h, ctx.done], - outputs=[ctx.Mgrad], - block_dim=m.block_dim.update_gradient_cholesky, + update_gradient_cholesky(m.nv), + dim=d.nworld, + inputs=[ctx.grad, ctx.h, ctx.done], + outputs=[ctx.Mgrad], + block_dim=m.block_dim.update_gradient_cholesky, ) else: wp.launch( - padding_h, - dim=(d.nworld, m.nv_pad - m.nv), - inputs=[m.nv, ctx.done], - outputs=[ctx.h], + padding_h, + dim=(d.nworld, m.nv_pad - m.nv), + inputs=[m.nv, ctx.done], + outputs=[ctx.h], ) wp.launch_tiled( - update_gradient_cholesky_blocked(types.TILE_SIZE_JTDAJ_DENSE, m.nv_pad), - dim=d.nworld, - inputs=[ - ctx.done, - ctx.grad.reshape(shape=(d.nworld, ctx.grad.shape[1], 1)), - ctx.h, - ctx.hfactor, - ], - outputs=[ctx.Mgrad.reshape(shape=(d.nworld, ctx.Mgrad.shape[1], 1))], - block_dim=m.block_dim.update_gradient_cholesky_blocked, + update_gradient_cholesky_blocked(types.TILE_SIZE_JTDAJ_DENSE, m.nv_pad), + dim=d.nworld, + inputs=[ctx.done, ctx.grad.reshape(shape=(d.nworld, ctx.grad.shape[1], 1)), ctx.h, ctx.hfactor], + outputs=[ctx.Mgrad.reshape(shape=(d.nworld, ctx.Mgrad.shape[1], 1))], + block_dim=m.block_dim.update_gradient_cholesky_blocked, ) +@wp.kernel +def _JTDAJ_sparse( + # Data in: + nefc_in: wp.array(dtype=int), + efc_J_rownnz_in: wp.array2d(dtype=int), + efc_J_rowadr_in: wp.array2d(dtype=int), + efc_J_colind_in: wp.array3d(dtype=int), + efc_J_in: wp.array3d(dtype=float), + efc_D_in: wp.array2d(dtype=float), + efc_state_in: wp.array2d(dtype=int), + # In: + ctx_done_in: wp.array(dtype=bool), + # Out: + h_out: wp.array3d(dtype=float), +): + worldid, efcid = wp.tid() + + if ctx_done_in[worldid]: + return + + if efcid >= nefc_in[worldid]: + return + + efc_D = efc_D_in[worldid, efcid] + efc_state = efc_state_in[worldid, efcid] + + if state_check(efc_D, efc_state) == 0.0: + return + + rownnz = efc_J_rownnz_in[worldid, efcid] + rowadr = efc_J_rowadr_in[worldid, efcid] + + for i in range(rownnz): + sparseidi = rowadr + i + Ji = efc_J_in[worldid, 0, sparseidi] + colindi = efc_J_colind_in[worldid, 0, sparseidi] + for j in range(i, rownnz): + if j == i: + sparseidj = sparseidi + Jj = Ji + colindj = colindi + else: + sparseidj = rowadr + j + Jj = efc_J_in[worldid, 0, sparseidj] + colindj = efc_J_colind_in[worldid, 0, sparseidj] + + h = Ji * Jj * efc_D + wp.atomic_add(h_out[worldid, colindi], colindj, h) + + if i != j: + wp.atomic_add(h_out[worldid, colindj], colindi, h) + + def _update_gradient(m: types.Model, d: types.Data, ctx: SolverContext): # grad = Ma - qfrc_smooth - qfrc_constraint wp.launch(update_gradient_zero_grad_dot, dim=(d.nworld), inputs=[ctx.done], outputs=[ctx.grad_dot]) @@ -2912,126 +2891,15 @@ def _update_gradient(m: types.Model, d: types.Data, ctx: SolverContext): smooth.solve_m(m, d, ctx.Mgrad, ctx.grad) elif m.opt.solver == types.SolverType.NEWTON: # h = qM + (efc_J.T * efc_D * active) @ efc_J - if SPARSE_CONSTRAINT_JACOBIAN: - # TODO(team): improve performance for sparse code path - @wp.kernel(module="unique", enable_backward=False) - def _JTDAJ_sparse( - # Data in: - nefc_in: wp.array(dtype=int), - efc_J_rownnz_in: wp.array2d(dtype=int), - efc_J_rowadr_in: wp.array2d(dtype=int), - efc_J_colind_in: wp.array3d(dtype=int), - efc_J_in: wp.array3d(dtype=float), - efc_D_in: wp.array2d(dtype=float), - efc_state_in: wp.array2d(dtype=int), - # In: - ctx_done_in: wp.array(dtype=bool), - # Out: - h_out: wp.array3d(dtype=float), - ): - worldid, efcid = wp.tid() - - if ctx_done_in[worldid]: - return - - if efcid >= nefc_in[worldid]: - return - - efc_D = efc_D_in[worldid, efcid] - efc_state = efc_state_in[worldid, efcid] - - if state_check(efc_D, efc_state) == 0.0: - return - - rownnz = efc_J_rownnz_in[worldid, efcid] - rowadr = efc_J_rowadr_in[worldid, efcid] - - for i in range(rownnz): - sparseidi = rowadr + i - Ji = efc_J_in[worldid, 0, sparseidi] - colindi = efc_J_colind_in[worldid, 0, sparseidi] - for j in range(i, rownnz): - if j == i: - sparseidj = sparseidi - Jj = Ji - colindj = colindi - else: - sparseidj = rowadr + j - Jj = efc_J_in[worldid, 0, sparseidj] - colindj = efc_J_colind_in[worldid, 0, sparseidj] - - h = Ji * Jj * efc_D - wp.atomic_add(h_out[worldid, colindi], colindj, h) - - if i != j: - wp.atomic_add(h_out[worldid, colindj], colindi, h) - + if m.is_sparse: + ctx.h.zero_() wp.launch( - _JTDAJ_sparse, - dim=(d.nworld, d.njmax), - inputs=[ - d.nefc, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.D, - d.efc.state, - ctx.done, - ], - outputs=[ctx.h], + _JTDAJ_sparse, + dim=(d.nworld, d.njmax), + inputs=[d.nefc, d.efc.J_rownnz, d.efc.J_rowadr, d.efc.J_colind, d.efc.J, d.efc.D, d.efc.state, ctx.done], + outputs=[ctx.h], ) - if m.is_sparse: - wp.launch( - update_gradient_set_h_qM_lower_sparse, - dim=(d.nworld, m.qM_fullm_i.size), - inputs=[m.qM_fullm_i, m.qM_fullm_j, d.qM, ctx.done], - outputs=[ctx.h], - ) - else: - # dense M: copy qM directly into h - @wp.kernel(module="unique", enable_backward=False) - def _set_h_qM_dense( - nv: int, - qM_in: wp.array3d(dtype=float), - ctx_done_in: wp.array(dtype=bool), - ctx_h_out: wp.array3d(dtype=float), - ): - worldid, i, j = wp.tid() - if ctx_done_in[worldid]: - return - if i >= nv or j >= nv: - return - if i >= j: - ctx_h_out[worldid, i, j] += qM_in[worldid, i, j] - - wp.launch( - _set_h_qM_dense, - dim=(d.nworld, m.nv, m.nv), - inputs=[m.nv, d.qM, ctx.done], - outputs=[ctx.h], - ) - elif m.is_sparse: - num_blocks_ceil = ceil(m.nv / types.TILE_SIZE_JTDAJ_SPARSE) - lower_triangle_dim = int(num_blocks_ceil * (num_blocks_ceil + 1) / 2) - with scoped_mathdx_gemm_disabled(): - wp.launch_tiled( - update_gradient_JTDAJ_sparse_tiled( - types.TILE_SIZE_JTDAJ_SPARSE, d.njmax - ), - dim=(d.nworld, lower_triangle_dim), - inputs=[ - d.nefc, - d.efc.J, - d.efc.D, - d.efc.state, - ctx.done, - ], - outputs=[ctx.h], - block_dim=m.block_dim.update_gradient_JTDAJ_sparse, - ) - wp.launch( update_gradient_set_h_qM_lower_sparse, dim=(d.nworld, m.qM_fullm_i.size), @@ -3041,20 +2909,18 @@ def _set_h_qM_dense( else: with scoped_mathdx_gemm_disabled(): wp.launch_tiled( - update_gradient_JTDAJ_dense_tiled( - m.nv_pad, types.TILE_SIZE_JTDAJ_DENSE, d.njmax - ), - dim=d.nworld, - inputs=[ - d.nefc, - d.qM, - d.efc.J, - d.efc.D, - d.efc.state, - ctx.done, - ], - outputs=[ctx.h], - block_dim=m.block_dim.update_gradient_JTDAJ_dense, + update_gradient_JTDAJ_dense_tiled(m.nv_pad, types.TILE_SIZE_JTDAJ_DENSE, d.njmax), + dim=d.nworld, + inputs=[ + d.nefc, + d.qM, + d.efc.J, + d.efc.D, + d.efc.state, + ctx.done, + ], + outputs=[ctx.h], + block_dim=m.block_dim.update_gradient_JTDAJ_dense, ) if m.opt.cone == types.ConeType.ELLIPTIC: @@ -3081,60 +2947,60 @@ def _set_h_qM_dense( nblocks_perblock = int((d.naconmax + dim_block - 1) / dim_block) - if SPARSE_CONSTRAINT_JACOBIAN: + if m.is_sparse: wp.launch( - update_gradient_JTCJ_sparse, - dim=(d.naconmax, m.dof_tri_row.size), - inputs=[ - m.opt.impratio_invsqrt, - m.dof_tri_row, - m.dof_tri_col, - d.contact.dist, - d.contact.includemargin, - d.contact.friction, - d.contact.dim, - d.contact.efc_address, - d.contact.worldid, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.D, - d.efc.state, - d.naconmax, - d.nacon, - ctx.Jaref, - ctx.done, - nblocks_perblock, - dim_block, - ], - outputs=[ctx.h], + update_gradient_JTCJ_sparse, + dim=(dim_block, m.dof_tri_row.size), + inputs=[ + m.opt.impratio_invsqrt, + m.dof_tri_row, + m.dof_tri_col, + d.contact.dist, + d.contact.includemargin, + d.contact.friction, + d.contact.dim, + d.contact.efc_address, + d.contact.worldid, + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.efc.D, + d.efc.state, + d.naconmax, + d.nacon, + ctx.Jaref, + ctx.done, + nblocks_perblock, + dim_block, + ], + outputs=[ctx.h], ) else: wp.launch( - update_gradient_JTCJ_dense, - dim=(dim_block, m.dof_tri_row.size), - inputs=[ - m.opt.impratio_invsqrt, - m.dof_tri_row, - m.dof_tri_col, - d.contact.dist, - d.contact.includemargin, - d.contact.friction, - d.contact.dim, - d.contact.efc_address, - d.contact.worldid, - d.efc.J, - d.efc.D, - d.efc.state, - d.naconmax, - d.nacon, - ctx.Jaref, - ctx.done, - nblocks_perblock, - dim_block, - ], - outputs=[ctx.h], + update_gradient_JTCJ_dense, + dim=(dim_block, m.dof_tri_row.size), + inputs=[ + m.opt.impratio_invsqrt, + m.dof_tri_row, + m.dof_tri_col, + d.contact.dist, + d.contact.includemargin, + d.contact.friction, + d.contact.dim, + d.contact.efc_address, + d.contact.worldid, + d.efc.J, + d.efc.D, + d.efc.state, + d.naconmax, + d.nacon, + ctx.Jaref, + ctx.done, + nblocks_perblock, + dim_block, + ], + outputs=[ctx.h], ) _cholesky_factorize_solve(m, d, ctx) @@ -3142,58 +3008,51 @@ def _set_h_qM_dense( raise ValueError(f"Unknown solver type: {m.opt.solver}") -def _update_gradient_incremental( - m: types.Model, d: types.Data, ctx: SolverContext -): +def _update_gradient_incremental(m: types.Model, d: types.Data, ctx: SolverContext): """Incremental gradient update: update H for changed constraints + re-factorize. Skips the full J^T*D*J rebuild by applying only the delta from constraints that changed QUADRATIC state, then re-factorizes and solves. """ - wp.launch( - update_gradient_zero_grad_dot, - dim=(d.nworld), - inputs=[ctx.done], - outputs=[ctx.grad_dot], - ) + wp.launch(update_gradient_zero_grad_dot, dim=(d.nworld), inputs=[ctx.done], outputs=[ctx.grad_dot]) wp.launch( - update_gradient_grad, - dim=(d.nworld, m.nv), - inputs=[d.qfrc_smooth, d.qfrc_constraint, d.efc.Ma, ctx.done], - outputs=[ctx.grad, ctx.grad_dot], + update_gradient_grad, + dim=(d.nworld, m.nv), + inputs=[d.qfrc_smooth, d.qfrc_constraint, d.efc.Ma, ctx.done], + outputs=[ctx.grad, ctx.grad_dot], ) # Update lower triangle of H with delta from changed constraints - if SPARSE_CONSTRAINT_JACOBIAN: + if m.is_sparse: wp.launch( - update_gradient_h_incremental_sparse, - dim=(d.nworld, ctx.changed_efc_ids.shape[1]), - inputs=[ - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.D, - d.efc.state, - ctx.changed_efc_ids, - ctx.changed_efc_count, - ], - outputs=[ctx.h], + update_gradient_h_incremental_sparse, + dim=(d.nworld, ctx.changed_efc_ids.shape[1]), + inputs=[ + d.efc.J_rownnz, + d.efc.J_rowadr, + d.efc.J_colind, + d.efc.J, + d.efc.D, + d.efc.state, + ctx.changed_efc_ids, + ctx.changed_efc_count, + ], + outputs=[ctx.h], ) else: lower_tri_dim = m.nv * (m.nv + 1) // 2 wp.launch( - update_gradient_h_incremental, - dim=(d.nworld, lower_tri_dim), - inputs=[ - d.efc.J, - d.efc.D, - d.efc.state, - ctx.changed_efc_ids, - ctx.changed_efc_count, - ], - outputs=[ctx.h], + update_gradient_h_incremental, + dim=(d.nworld, lower_tri_dim), + inputs=[ + d.efc.J, + d.efc.D, + d.efc.state, + ctx.changed_efc_ids, + ctx.changed_efc_count, + ], + outputs=[ctx.h], ) _cholesky_factorize_solve(m, d, ctx) @@ -3347,10 +3206,7 @@ def _solver_iteration( # path in update_constraint_efc has early returns that skip state change # tracking, and the additional JTCJ Hessian term depends on Jaref which # changes every iteration. - incremental = ( - m.opt.solver == types.SolverType.NEWTON - and m.opt.cone != types.ConeType.ELLIPTIC - ) + incremental = m.opt.solver == types.SolverType.NEWTON and m.opt.cone != types.ConeType.ELLIPTIC if incremental: # Must complete before update_constraint_efc which atomically increments. @@ -3422,18 +3278,10 @@ def init_context(m: types.Model, d: types.Data, ctx: SolverContext | InverseCont ctx.Jaref.zero_() wp.launch( - solve_init_jaref(m.is_sparse, m.nv, dofs_per_thread), - dim=(d.nworld, d.njmax, threads_per_efc), - inputs=[ - d.nefc, - d.qacc, - d.efc.J_rownnz, - d.efc.J_rowadr, - d.efc.J_colind, - d.efc.J, - d.efc.aref, - ], - outputs=[ctx.Jaref], + solve_init_jaref(m.is_sparse, m.nv, dofs_per_thread), + dim=(d.nworld, d.njmax, threads_per_efc), + inputs=[d.nefc, d.qacc, d.efc.J_rownnz, d.efc.J_rowadr, d.efc.J_colind, d.efc.J, d.efc.aref], + outputs=[ctx.Jaref], ) # Ma = qM @ qacc diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/support.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/support.py index b45472c459..995b2a7c84 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/support.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/support.py @@ -18,18 +18,52 @@ import warp as wp from mujoco.mjx.third_party.mujoco_warp._src.math import motion_cross +from mujoco.mjx.third_party.mujoco_warp._src.types import MJ_MINVAL from mujoco.mjx.third_party.mujoco_warp._src.types import ConeType from mujoco.mjx.third_party.mujoco_warp._src.types import Data +from mujoco.mjx.third_party.mujoco_warp._src.types import DynType from mujoco.mjx.third_party.mujoco_warp._src.types import JointType from mujoco.mjx.third_party.mujoco_warp._src.types import Model from mujoco.mjx.third_party.mujoco_warp._src.types import State from mujoco.mjx.third_party.mujoco_warp._src.types import vec5 +from mujoco.mjx.third_party.mujoco_warp._src.types import vec10f from mujoco.mjx.third_party.mujoco_warp._src.warp_util import cache_kernel from mujoco.mjx.third_party.mujoco_warp._src.warp_util import event_scope wp.set_module_options({"enable_backward": False}) +# TODO(team): kernel analyzer array slice? +@wp.func +def next_act( + # Model: + opt_timestep: float, # kernel_analyzer: ignore + actuator_dyntype: int, # kernel_analyzer: ignore + actuator_dynprm: vec10f, # kernel_analyzer: ignore + actuator_actrange: wp.vec2, # kernel_analyzer: ignore + # Data In: + act_in: float, # kernel_analyzer: ignore + act_dot_in: float, # kernel_analyzer: ignore + # In: + act_dot_scale: float, + clamp: bool, +) -> float: + # advance actuation + if actuator_dyntype == DynType.FILTEREXACT: + tau = wp.max(MJ_MINVAL, actuator_dynprm[0]) + act = act_in + act_dot_scale * act_dot_in * tau * (1.0 - wp.exp(-opt_timestep / tau)) + elif actuator_dyntype == DynType.USER: + return act_in + else: + act = act_in + act_dot_scale * act_dot_in * opt_timestep + + # clamp to actrange + if clamp: + act = wp.clamp(act, actuator_actrange[0], actuator_actrange[1]) + + return act + + @cache_kernel def mul_m_sparse(check_skip: bool): @wp.kernel(module="unique") diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/types.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/types.py index 94434ff9ef..11b7a7c090 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/types.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/types.py @@ -33,11 +33,8 @@ TILE_SIZE_JTDAJ_SPARSE = 16 TILE_SIZE_JTDAJ_DENSE = 16 -# TODO(team): remove after improving performance for sparse constraint jacobian -SPARSE_CONSTRAINT_JACOBIAN = False - -# TODO(team): remove after mjwarp depends on warp-lang >= 1.12 in pyproject.toml -TEXTURE_DTYPE = wp.Texture2D if hasattr(wp, "Texture2D") else int +# maximum number of plugin attributes +_NPLUGINATTR = 128 # TODO(team): add check that all wp.launch_tiled 'block_dim' settings are configurable @@ -53,7 +50,6 @@ class BlockDim: # forward euler_dense: int = 32 actuator_velocity: int = 32 - tendon_velocity: int = 32 # ray ray: int = 64 # sensor @@ -63,6 +59,7 @@ class BlockDim: cholesky_factorize: int = 32 cholesky_solve: int = 32 cholesky_factorize_solve: int = 32 + solve_LD_sparse_fused: int = 64 # solver update_gradient_cholesky: int = 64 update_gradient_cholesky_blocked: int = 32 @@ -351,6 +348,7 @@ class GeomType(enum.IntEnum): BOX: box MESH: mesh SDF: sdf + FLEX: flex """ PLANE = mujoco.mjtGeom.mjGEOM_PLANE @@ -362,6 +360,7 @@ class GeomType(enum.IntEnum): BOX = mujoco.mjtGeom.mjGEOM_BOX MESH = mujoco.mjtGeom.mjGEOM_MESH SDF = mujoco.mjtGeom.mjGEOM_SDF + FLEX = mujoco.mjtGeom.mjGEOM_FLEX # unsupported: NGEOMTYPES, ARROW*, LINE, SKIN, LABEL, NONE @@ -662,6 +661,10 @@ class vec11f(wp.types.vector(length=11, dtype=float)): pass +class vec_pluginattr(wp.types.vector(length=_NPLUGINATTR, dtype=float)): + pass + + class mat23f(wp.types.matrix(shape=(2, 3), dtype=float)): pass @@ -679,6 +682,7 @@ class mat63f(wp.types.matrix(shape=(6, 3), dtype=float)): vec8 = vec8f vec10 = vec10f vec11 = vec11f +vec128 = vec_pluginattr mat23 = mat23f mat43 = mat43f mat63 = mat63f @@ -841,6 +845,7 @@ class Model: nflexelem: number of elements in all flexes nflexelemdata: number of element vertex ids in all flexes nflexelemedge: number of element edge ids in all flexes + nflexshelldata: number of shell fragment vertex ids in all flexes nJfe: number of non-zeros in sparse flexedge Jacobian nmesh: number of meshes nmeshvert: number of vertices for all meshes @@ -857,6 +862,7 @@ class Model: nexclude: number of excluded geom pairs neq: number of equality constraints ntendon: number of tendons + nJten: number of non-zeros in sparse tendon Jacobian nwrap: number of wrap objects in all tendon paths nsensor: number of sensors nmocap: number of mocap bodies @@ -973,6 +979,11 @@ class Model: light_poscom0: global position rel. to sub-com in qpos0 (*, nlight, 3) light_pos0: global position rel. to body in qpos0 (*, nlight, 3) light_dir0: global direction in qpos0 (*, nlight, 3) + flex_contype: flex contact type (nflex,) + flex_conaffinity: flex contact affinity (nflex,) + flex_condim: contact dimensionality (1, 3, 4, 6) (nflex,) + flex_friction: friction for (slide, spin, roll) (nflex, 3) + flex_margin: detect contact if dist= 1.12 in pyproject.toml - textures: array("*", TEXTURE_DTYPE) - textures_registry: list[TEXTURE_DTYPE] + textures: array("*", wp.Texture2D) + textures_registry: list[wp.Texture2D] hfield_registry: dict hfield_bvh_id: array("nhfield", wp.uint64) hfield_bounds_size: array("nhfield", wp.vec3) - flex_mesh: wp.Mesh + flex_mesh_registry: dict flex_rgba: array("nflex", wp.vec4) - flex_bvh_id: wp.uint64 - flex_face_point: array("*", wp.vec3) - flex_faceadr: array("nflex", int) - flex_nface: int - flex_nwork: int - flex_group_root: array("nworld", int) - flex_elemdataadr: array("nflex", int) - flex_shell: array("*", int) - flex_shelldataadr: array("nflex", int) - flex_radius: array("nflex", float) - flex_workadr: array("nflex", int) - flex_worknum: array("nflex", int) + flex_bvh_id: array("*", wp.uint64) + flex_group_root: array("nworld", "*", int) flex_render_smooth: bool + bvh_nflexgeom: int + flex_dim_np: array("nflex", int) + flex_geom_flexid: array("*", int) + flex_geom_edgeid: array("*", int) bvh: wp.Bvh bvh_id: wp.uint64 lower: array("*", wp.vec3) @@ -1988,5 +1978,8 @@ class RenderContext: depth_adr: array("ncam", int) render_rgb: array("ncam", bool) render_depth: array("ncam", bool) + seg_data: array("*", int) + seg_adr: array("ncam", int) + render_seg: array("ncam", bool) znear: float total_rays: int diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/util_pkg.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/util_pkg.py index b7debea4d3..e2f8acf9cd 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/util_pkg.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/util_pkg.py @@ -37,9 +37,7 @@ def _parse_version(version_str: str) -> tuple[tuple[int, int | str], ...]: """ # Split on both '.' and '-' parts = re.split(r"[.\-]", version_str) - return tuple( - [(0, int(p)) if p.isdigit() else (-1, p) for p in parts] + [(0, 0)] - ) + return tuple([(0, int(p)) if p.isdigit() else (-1, p) for p in parts] + [(0, 0)]) def check_version(spec: str) -> bool: @@ -65,9 +63,7 @@ def check_version(spec: str) -> bool: """ match = re.match(r"^([a-zA-Z0-9_\-]+)(>=|<=|>|<|==|!=)(.+)$", spec) if not match: - raise ValueError( - f"Invalid version spec '{spec}'. Expected format: 'package>=version'" - ) + raise ValueError(f"Invalid version spec '{spec}'. Expected format: 'package>=version'") package_name, op, version_str = match.groups() required_version = _parse_version(version_str) @@ -87,11 +83,11 @@ def check_version(spec: str) -> bool: installed_version = _parse_version(installed_str) ops = { - ">=": operator.ge, - "<=": operator.le, - ">": operator.gt, - "<": operator.lt, - "==": operator.eq, - "!=": operator.ne, + ">=": operator.ge, + "<=": operator.le, + ">": operator.gt, + "<": operator.lt, + "==": operator.eq, + "!=": operator.ne, } return ops[op](installed_version, required_version) diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/warp_util.py b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/warp_util.py index 4ac1cb0de6..960e426629 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/_src/warp_util.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/_src/warp_util.py @@ -146,13 +146,13 @@ def check_toolkit_driver(): if wp.get_device().is_cuda: if not wp.is_conditional_graph_supported(): warnings.warn( - """ + """ CUDA version < 12.4 detected - graph capture may be unreliable for < 12.3 - conditional graph nodes are not available for < 12.4 Model.opt.graph_conditional should be set to False """, - stacklevel=2, + stacklevel=2, ) diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/pyproject.toml b/mjx/mujoco/mjx/third_party/mujoco_warp/pyproject.toml index 373052487b..e8d98eb460 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/pyproject.toml +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/pyproject.toml @@ -28,7 +28,7 @@ requires-python = ">=3.10" dependencies = [ "absl-py", "etils[epath]", - "mujoco>=3.5.0", + "mujoco>=3.6.0", "numpy", "warp-lang>=1.12", ] @@ -55,7 +55,7 @@ dev = [ "ruff", "pygls>=1.0.0,<2.0.0", "lsprotocol>=2023.0.1,<2024.0.0", - "mujoco>=3.5.0.dev0", + "mujoco>=3.6.0.dev0", "warp-lang>=1.11.0.dev0", ] # TODO(team): cpu and cuda JAX optional dependencies are temporary, remove after we land MJX:Warp diff --git a/mjx/mujoco/mjx/third_party/mujoco_warp/viewer.py b/mjx/mujoco/mjx/third_party/mujoco_warp/viewer.py index 5f1de2d49f..cf65f02aec 100644 --- a/mjx/mujoco/mjx/third_party/mujoco_warp/viewer.py +++ b/mjx/mujoco/mjx/third_party/mujoco_warp/viewer.py @@ -18,7 +18,7 @@ Usage: mjwarp-viewer [flags] Example: - mjwarp-viewer benchmark/humanoid/humanoid.xml -o "opt.solver=cg" + mjwarp-viewer benchmarks/humanoid/humanoid.xml -o "opt.solver=cg" """ import copy @@ -56,6 +56,7 @@ class EngineOptions(enum.IntEnum): _ENGINE = flags.DEFINE_enum_class("engine", EngineOptions.WARP, EngineOptions, "Simulation engine") _NCONMAX = flags.DEFINE_integer("nconmax", None, "Maximum number of contacts.") _NJMAX = flags.DEFINE_integer("njmax", None, "Maximum number of constraints per world.") +_NJMAX_NNZ = flags.DEFINE_integer("njmax_nnz", None, "Maximum number of non-zeros in constraint Jacobian.") _NCCDMAX = flags.DEFINE_integer("nccdmax", None, "Maximum number of CCD contacts per world.") _OVERRIDE = flags.DEFINE_multi_string("override", [], "Model overrides (notation: foo.bar = baz)", short_name="o") _KEYFRAME = flags.DEFINE_integer("keyframe", 0, "keyframe to initialize simulation.") @@ -149,7 +150,7 @@ def _main(argv: Sequence[str]) -> None: override_model(mjm, _OVERRIDE.value) m = mjw.put_model(mjm) override_model(m, _OVERRIDE.value) - d = mjw.put_data(mjm, mjd, nconmax=_NCONMAX.value, njmax=_NJMAX.value, nccdmax=_NCCDMAX.value) + d = mjw.put_data(mjm, mjd, nconmax=_NCONMAX.value, njmax=_NJMAX.value, njmax_nnz=_NJMAX_NNZ.value, nccdmax=_NCCDMAX.value) graph = _compile_step(m, d) if wp.get_device().is_cuda else None if graph is None: mjw.step(m, d) # warmup step diff --git a/mjx/mujoco/mjx/warp/bvh.py b/mjx/mujoco/mjx/warp/bvh.py index 2bb522f2aa..2c1fee49fa 100644 --- a/mjx/mujoco/mjx/warp/bvh.py +++ b/mjx/mujoco/mjx/warp/bvh.py @@ -48,20 +48,27 @@ **{f.name: None for f in dataclasses.fields(mjwp_types.Callback) if f.init} ) + @ffi.format_args_for_warp def _refit_bvh_shim( # Model nworld: int, flex_dim: wp.array(dtype=int), + flex_edge: wp.array(dtype=wp.vec2i), flex_elem: wp.array(dtype=int), + flex_elemadr: wp.array(dtype=int), + flex_elemdataadr: wp.array(dtype=int), flex_elemnum: wp.array(dtype=int), + flex_radius: wp.array(dtype=float), + flex_shell: wp.array(dtype=int), + flex_shelldataadr: wp.array(dtype=int), flex_vertadr: wp.array(dtype=int), + flex_vertnum: wp.array(dtype=int), geom_dataid: wp.array(dtype=int), geom_size: wp.array2d(dtype=wp.vec3), geom_type: wp.array(dtype=int), nflex: int, - nflexelemdata: int, - nflexvert: int, + nflexelem: int, # Data flexvert_xpos: wp.array2d(dtype=wp.vec3), geom_xmat: wp.array2d(dtype=wp.mat33), @@ -77,15 +84,21 @@ def _refit_bvh_shim( _d.efc = _e _d.contact = _c _m.flex_dim = flex_dim + _m.flex_edge = flex_edge _m.flex_elem = flex_elem + _m.flex_elemadr = flex_elemadr + _m.flex_elemdataadr = flex_elemdataadr _m.flex_elemnum = flex_elemnum + _m.flex_radius = flex_radius + _m.flex_shell = flex_shell + _m.flex_shelldataadr = flex_shelldataadr _m.flex_vertadr = flex_vertadr + _m.flex_vertnum = flex_vertnum _m.geom_dataid = geom_dataid _m.geom_size = geom_size _m.geom_type = geom_type _m.nflex = nflex - _m.nflexelemdata = nflexelemdata - _m.nflexvert = nflexvert + _m.nflexelem = nflexelem _d.flexvert_xpos = flexvert_xpos _d.geom_xmat = geom_xmat _d.geom_xpos = geom_xpos @@ -113,15 +126,21 @@ def _refit_bvh_jax_impl( out = jf( d.qpos.shape[0], m._impl.flex_dim, + m._impl.flex_edge, m._impl.flex_elem, + m._impl.flex_elemadr, + m._impl.flex_elemdataadr, m._impl.flex_elemnum, + m._impl.flex_radius, + m._impl.flex_shell, + m._impl.flex_shelldataadr, m._impl.flex_vertadr, + m._impl.flex_vertnum, m.geom_dataid, m.geom_size, m.geom_type, m._impl.nflex, - m._impl.nflexelemdata, - m._impl.nflexvert, + m._impl.nflexelem, d._impl.flexvert_xpos, d.geom_xmat, d.geom_xpos, diff --git a/mjx/mujoco/mjx/warp/collision_driver.py b/mjx/mujoco/mjx/warp/collision_driver.py index 265bfba3ba..9d5412d9c9 100644 --- a/mjx/mujoco/mjx/warp/collision_driver.py +++ b/mjx/mujoco/mjx/warp/collision_driver.py @@ -52,8 +52,26 @@ def _collision_shim( # Model nworld: int, block_dim: mjwp_types.BlockDim, + flex_conaffinity: wp.array(dtype=int), + flex_condim: wp.array(dtype=int), + flex_contype: wp.array(dtype=int), + flex_dim: wp.array(dtype=int), + flex_elem: wp.array(dtype=int), + flex_elemadr: wp.array(dtype=int), + flex_elemdataadr: wp.array(dtype=int), + flex_elemnum: wp.array(dtype=int), + flex_friction: wp.array(dtype=wp.vec3), + flex_margin: wp.array(dtype=float), + flex_radius: wp.array(dtype=float), + flex_shell: wp.array(dtype=int), + flex_shelldataadr: wp.array(dtype=int), + flex_shellnum: wp.array(dtype=int), + flex_vertadr: wp.array(dtype=int), + flex_vertflexid: wp.array(dtype=int), geom_aabb: wp.array3d(dtype=wp.vec3), + geom_conaffinity: wp.array(dtype=int), geom_condim: wp.array(dtype=int), + geom_contype: wp.array(dtype=int), geom_dataid: wp.array(dtype=int), geom_friction: wp.array2d(dtype=wp.vec3), geom_gap: wp.array2d(dtype=float), @@ -90,6 +108,10 @@ def _collision_shim( mesh_vert: wp.array(dtype=wp.vec3), mesh_vertadr: wp.array(dtype=int), mesh_vertnum: wp.array(dtype=int), + nflex: int, + nflexelem: int, + nflexshelldata: int, + nflexvert: int, ngeom: int, nmaxmeshdeg: int, nmaxpolygon: int, @@ -108,7 +130,7 @@ def _collision_shim( pair_solref: wp.array2d(dtype=wp.vec2), pair_solreffriction: wp.array2d(dtype=wp.vec2), plugin: wp.array(dtype=int), - plugin_attr: wp.array(dtype=wp.vec3f), + plugin_attr: wp.array(dtype=mjwp_types.vec_pluginattr), opt__broadphase: int, opt__broadphase_filter: int, opt__ccd_iterations: int, @@ -120,12 +142,15 @@ def _collision_shim( # Data naccdmax: int, naconmax: int, + flexvert_xpos: wp.array2d(dtype=wp.vec3), geom_xmat: wp.array2d(dtype=wp.mat33), geom_xpos: wp.array2d(dtype=wp.vec3), nacon: wp.array(dtype=int), ncollision: wp.array(dtype=int), contact__dim: wp.array(dtype=int), contact__dist: wp.array(dtype=float), + contact__efc_address: wp.array2d(dtype=int), + contact__flex: wp.array(dtype=wp.vec2i), contact__frame: wp.array(dtype=wp.mat33), contact__friction: wp.array(dtype=mjwp_types.vec5), contact__geom: wp.array(dtype=wp.vec2i), @@ -136,6 +161,7 @@ def _collision_shim( contact__solref: wp.array(dtype=wp.vec2), contact__solreffriction: wp.array(dtype=wp.vec2), contact__type: wp.array(dtype=int), + contact__vert: wp.array(dtype=wp.vec2i), contact__worldid: wp.array(dtype=int), ): _m.stat = _s @@ -144,8 +170,26 @@ def _collision_shim( _d.efc = _e _d.contact = _c _m.block_dim = block_dim + _m.flex_conaffinity = flex_conaffinity + _m.flex_condim = flex_condim + _m.flex_contype = flex_contype + _m.flex_dim = flex_dim + _m.flex_elem = flex_elem + _m.flex_elemadr = flex_elemadr + _m.flex_elemdataadr = flex_elemdataadr + _m.flex_elemnum = flex_elemnum + _m.flex_friction = flex_friction + _m.flex_margin = flex_margin + _m.flex_radius = flex_radius + _m.flex_shell = flex_shell + _m.flex_shelldataadr = flex_shelldataadr + _m.flex_shellnum = flex_shellnum + _m.flex_vertadr = flex_vertadr + _m.flex_vertflexid = flex_vertflexid _m.geom_aabb = geom_aabb + _m.geom_conaffinity = geom_conaffinity _m.geom_condim = geom_condim + _m.geom_contype = geom_contype _m.geom_dataid = geom_dataid _m.geom_friction = geom_friction _m.geom_gap = geom_gap @@ -182,6 +226,10 @@ def _collision_shim( _m.mesh_vert = mesh_vert _m.mesh_vertadr = mesh_vertadr _m.mesh_vertnum = mesh_vertnum + _m.nflex = nflex + _m.nflexelem = nflexelem + _m.nflexshelldata = nflexshelldata + _m.nflexvert = nflexvert _m.ngeom = ngeom _m.nmaxmeshdeg = nmaxmeshdeg _m.nmaxpolygon = nmaxpolygon @@ -211,6 +259,8 @@ def _collision_shim( _m.plugin_attr = plugin_attr _d.contact.dim = contact__dim _d.contact.dist = contact__dist + _d.contact.efc_address = contact__efc_address + _d.contact.flex = contact__flex _d.contact.frame = contact__frame _d.contact.friction = contact__friction _d.contact.geom = contact__geom @@ -221,7 +271,9 @@ def _collision_shim( _d.contact.solref = contact__solref _d.contact.solreffriction = contact__solreffriction _d.contact.type = contact__type + _d.contact.vert = contact__vert _d.contact.worldid = contact__worldid + _d.flexvert_xpos = flexvert_xpos _d.geom_xmat = geom_xmat _d.geom_xpos = geom_xpos _d.naccdmax = naccdmax @@ -238,6 +290,8 @@ def _collision_jax_impl(m: types.Model, d: types.Data): 'ncollision': d._impl.ncollision.shape, 'contact__dim': d._impl.contact__dim.shape, 'contact__dist': d._impl.contact__dist.shape, + 'contact__efc_address': d._impl.contact__efc_address.shape, + 'contact__flex': d._impl.contact__flex.shape, 'contact__frame': d._impl.contact__frame.shape, 'contact__friction': d._impl.contact__friction.shape, 'contact__geom': d._impl.contact__geom.shape, @@ -248,11 +302,12 @@ def _collision_jax_impl(m: types.Model, d: types.Data): 'contact__solref': d._impl.contact__solref.shape, 'contact__solreffriction': d._impl.contact__solreffriction.shape, 'contact__type': d._impl.contact__type.shape, + 'contact__vert': d._impl.contact__vert.shape, 'contact__worldid': d._impl.contact__worldid.shape, } jf = ffi.jax_callable_variadic_tuple( _collision_shim, - num_outputs=15, + num_outputs=18, output_dims=output_dims, vmap_method=None, in_out_argnames=set([ @@ -260,6 +315,8 @@ def _collision_jax_impl(m: types.Model, d: types.Data): 'ncollision', 'contact__dim', 'contact__dist', + 'contact__efc_address', + 'contact__flex', 'contact__frame', 'contact__friction', 'contact__geom', @@ -270,6 +327,7 @@ def _collision_jax_impl(m: types.Model, d: types.Data): 'contact__solref', 'contact__solreffriction', 'contact__type', + 'contact__vert', 'contact__worldid', ]), stage_in_argnames=set([ @@ -299,8 +357,26 @@ def _collision_jax_impl(m: types.Model, d: types.Data): out = jf( d.qpos.shape[0], m._impl.block_dim, + m._impl.flex_conaffinity, + m._impl.flex_condim, + m._impl.flex_contype, + m._impl.flex_dim, + m._impl.flex_elem, + m._impl.flex_elemadr, + m._impl.flex_elemdataadr, + m._impl.flex_elemnum, + m._impl.flex_friction, + m._impl.flex_margin, + m._impl.flex_radius, + m._impl.flex_shell, + m._impl.flex_shelldataadr, + m._impl.flex_shellnum, + m._impl.flex_vertadr, + m._impl.flex_vertflexid, m.geom_aabb, + m.geom_conaffinity, m.geom_condim, + m.geom_contype, m.geom_dataid, m.geom_friction, m.geom_gap, @@ -337,6 +413,10 @@ def _collision_jax_impl(m: types.Model, d: types.Data): m.mesh_vert, m.mesh_vertadr, m.mesh_vertnum, + m._impl.nflex, + m._impl.nflexelem, + m._impl.nflexshelldata, + m._impl.nflexvert, m.ngeom, m._impl.nmaxmeshdeg, m._impl.nmaxpolygon, @@ -366,12 +446,15 @@ def _collision_jax_impl(m: types.Model, d: types.Data): m.opt._impl.sdf_iterations, d._impl.naccdmax, d._impl.naconmax, + d._impl.flexvert_xpos, d.geom_xmat, d.geom_xpos, d._impl.nacon, d._impl.ncollision, d._impl.contact__dim, d._impl.contact__dist, + d._impl.contact__efc_address, + d._impl.contact__flex, d._impl.contact__frame, d._impl.contact__friction, d._impl.contact__geom, @@ -382,6 +465,7 @@ def _collision_jax_impl(m: types.Model, d: types.Data): d._impl.contact__solref, d._impl.contact__solreffriction, d._impl.contact__type, + d._impl.contact__vert, d._impl.contact__worldid, ) d = d.tree_replace({ @@ -389,17 +473,20 @@ def _collision_jax_impl(m: types.Model, d: types.Data): '_impl.ncollision': out[1], '_impl.contact__dim': out[2], '_impl.contact__dist': out[3], - '_impl.contact__frame': out[4], - '_impl.contact__friction': out[5], - '_impl.contact__geom': out[6], - '_impl.contact__geomcollisionid': out[7], - '_impl.contact__includemargin': out[8], - '_impl.contact__pos': out[9], - '_impl.contact__solimp': out[10], - '_impl.contact__solref': out[11], - '_impl.contact__solreffriction': out[12], - '_impl.contact__type': out[13], - '_impl.contact__worldid': out[14], + '_impl.contact__efc_address': out[4], + '_impl.contact__flex': out[5], + '_impl.contact__frame': out[6], + '_impl.contact__friction': out[7], + '_impl.contact__geom': out[8], + '_impl.contact__geomcollisionid': out[9], + '_impl.contact__includemargin': out[10], + '_impl.contact__pos': out[11], + '_impl.contact__solimp': out[12], + '_impl.contact__solref': out[13], + '_impl.contact__solreffriction': out[14], + '_impl.contact__type': out[15], + '_impl.contact__vert': out[16], + '_impl.contact__worldid': out[17], }) return d diff --git a/mjx/mujoco/mjx/warp/forward.py b/mjx/mujoco/mjx/warp/forward.py index e38336011e..e0f5c05323 100644 --- a/mjx/mujoco/mjx/warp/forward.py +++ b/mjx/mujoco/mjx/warp/forward.py @@ -138,6 +138,10 @@ def _forward_shim( eq_type: wp.array(dtype=int), eq_wld_adr: wp.array(dtype=int), flex_bending: wp.array2d(dtype=float), + flex_centered: wp.array(dtype=bool), + flex_conaffinity: wp.array(dtype=int), + flex_condim: wp.array(dtype=int), + flex_contype: wp.array(dtype=int), flex_damping: wp.array(dtype=float), flex_dim: wp.array(dtype=int), flex_edge: wp.array(dtype=wp.vec2i), @@ -146,12 +150,22 @@ def _forward_shim( flex_edgenum: wp.array(dtype=int), flex_elem: wp.array(dtype=int), flex_elemadr: wp.array(dtype=int), + flex_elemdataadr: wp.array(dtype=int), flex_elemedge: wp.array(dtype=int), flex_elemedgeadr: wp.array(dtype=int), flex_elemnum: wp.array(dtype=int), + flex_friction: wp.array(dtype=wp.vec3), + flex_margin: wp.array(dtype=float), + flex_radius: wp.array(dtype=float), + flex_shell: wp.array(dtype=int), + flex_shelldataadr: wp.array(dtype=int), + flex_shellnum: wp.array(dtype=int), flex_stiffness: wp.array2d(dtype=float), + flex_vert: wp.array(dtype=wp.vec3), flex_vertadr: wp.array(dtype=int), flex_vertbodyid: wp.array(dtype=int), + flex_vertflexid: wp.array(dtype=int), + flex_vertnum: wp.array(dtype=int), flexedge_J_colind: wp.array(dtype=int), flexedge_J_rowadr: wp.array(dtype=int), flexedge_J_rownnz: wp.array(dtype=int), @@ -159,7 +173,9 @@ def _forward_shim( flexedge_length0: wp.array(dtype=float), geom_aabb: wp.array3d(dtype=wp.vec3), geom_bodyid: wp.array(dtype=int), + geom_conaffinity: wp.array(dtype=int), geom_condim: wp.array(dtype=int), + geom_contype: wp.array(dtype=int), geom_dataid: wp.array(dtype=int), geom_fluid: wp.array2d(dtype=float), geom_friction: wp.array2d(dtype=wp.vec3), @@ -213,6 +229,7 @@ def _forward_shim( light_targetbodyid: wp.array(dtype=int), mapM2M: wp.array(dtype=int), mat_rgba: wp.array2d(dtype=wp.vec4), + max_ten_J_rownnz: int, mesh_face: wp.array(dtype=wp.vec3i), mesh_faceadr: wp.array(dtype=int), mesh_graph: wp.array(dtype=int), @@ -235,6 +252,7 @@ def _forward_shim( mesh_vertadr: wp.array(dtype=int), mesh_vertnum: wp.array(dtype=int), nC: int, + nJten: int, na: int, nacttrnbody: int, nbody: int, @@ -244,6 +262,7 @@ def _forward_shim( nflex: int, nflexedge: int, nflexelem: int, + nflexshelldata: int, nflexvert: int, ngeom: int, ngravcomp: int, @@ -279,7 +298,9 @@ def _forward_shim( pair_solref: wp.array2d(dtype=wp.vec2), pair_solreffriction: wp.array2d(dtype=wp.vec2), plugin: wp.array(dtype=int), - plugin_attr: wp.array(dtype=wp.vec3f), + plugin_attr: wp.array(dtype=mjwp_types.vec_pluginattr), + qLD_all_updates: wp.array(dtype=wp.vec3i), + qLD_level_offsets: wp.array(dtype=int), qLD_updates: tuple[wp.array(dtype=wp.vec3i), ...], qM_fullm_i: wp.array(dtype=int), qM_fullm_j: wp.array(dtype=int), @@ -323,6 +344,9 @@ def _forward_shim( site_type: wp.array(dtype=int), taxel_sensorid: wp.array(dtype=int), taxel_vertadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_rownnz: wp.array(dtype=int), tendon_actfrclimited: wp.array(dtype=bool), tendon_actfrcrange: wp.array2d(dtype=wp.vec2), tendon_adr: wp.array(dtype=int), @@ -382,6 +406,7 @@ def _forward_shim( naccdmax: int, naconmax: int, njmax: int, + njmax_nnz: int, act: wp.array2d(dtype=float), act_dot: wp.array2d(dtype=float), actuator_force: wp.array2d(dtype=float), @@ -446,7 +471,7 @@ def _forward_shim( subtree_angmom: wp.array2d(dtype=wp.vec3), subtree_com: wp.array2d(dtype=wp.vec3), subtree_linvel: wp.array2d(dtype=wp.vec3), - ten_J: wp.array3d(dtype=float), + ten_J: wp.array2d(dtype=float), ten_length: wp.array2d(dtype=float), ten_velocity: wp.array2d(dtype=float), ten_wrapadr: wp.array2d(dtype=int), @@ -466,6 +491,7 @@ def _forward_shim( contact__dim: wp.array(dtype=int), contact__dist: wp.array(dtype=float), contact__efc_address: wp.array2d(dtype=int), + contact__flex: wp.array(dtype=wp.vec2i), contact__frame: wp.array(dtype=wp.mat33), contact__friction: wp.array(dtype=mjwp_types.vec5), contact__geom: wp.array(dtype=wp.vec2i), @@ -476,6 +502,7 @@ def _forward_shim( contact__solref: wp.array(dtype=wp.vec2), contact__solreffriction: wp.array(dtype=wp.vec2), contact__type: wp.array(dtype=int), + contact__vert: wp.array(dtype=wp.vec2i), contact__worldid: wp.array(dtype=int), efc__D: wp.array2d(dtype=float), efc__J: wp.array3d(dtype=float), @@ -585,6 +612,10 @@ def _forward_shim( _m.eq_type = eq_type _m.eq_wld_adr = eq_wld_adr _m.flex_bending = flex_bending + _m.flex_centered = flex_centered + _m.flex_conaffinity = flex_conaffinity + _m.flex_condim = flex_condim + _m.flex_contype = flex_contype _m.flex_damping = flex_damping _m.flex_dim = flex_dim _m.flex_edge = flex_edge @@ -593,12 +624,22 @@ def _forward_shim( _m.flex_edgenum = flex_edgenum _m.flex_elem = flex_elem _m.flex_elemadr = flex_elemadr + _m.flex_elemdataadr = flex_elemdataadr _m.flex_elemedge = flex_elemedge _m.flex_elemedgeadr = flex_elemedgeadr _m.flex_elemnum = flex_elemnum + _m.flex_friction = flex_friction + _m.flex_margin = flex_margin + _m.flex_radius = flex_radius + _m.flex_shell = flex_shell + _m.flex_shelldataadr = flex_shelldataadr + _m.flex_shellnum = flex_shellnum _m.flex_stiffness = flex_stiffness + _m.flex_vert = flex_vert _m.flex_vertadr = flex_vertadr _m.flex_vertbodyid = flex_vertbodyid + _m.flex_vertflexid = flex_vertflexid + _m.flex_vertnum = flex_vertnum _m.flexedge_J_colind = flexedge_J_colind _m.flexedge_J_rowadr = flexedge_J_rowadr _m.flexedge_J_rownnz = flexedge_J_rownnz @@ -606,7 +647,9 @@ def _forward_shim( _m.flexedge_length0 = flexedge_length0 _m.geom_aabb = geom_aabb _m.geom_bodyid = geom_bodyid + _m.geom_conaffinity = geom_conaffinity _m.geom_condim = geom_condim + _m.geom_contype = geom_contype _m.geom_dataid = geom_dataid _m.geom_fluid = geom_fluid _m.geom_friction = geom_friction @@ -660,6 +703,7 @@ def _forward_shim( _m.light_targetbodyid = light_targetbodyid _m.mapM2M = mapM2M _m.mat_rgba = mat_rgba + _m.max_ten_J_rownnz = max_ten_J_rownnz _m.mesh_face = mesh_face _m.mesh_faceadr = mesh_faceadr _m.mesh_graph = mesh_graph @@ -682,6 +726,7 @@ def _forward_shim( _m.mesh_vertadr = mesh_vertadr _m.mesh_vertnum = mesh_vertnum _m.nC = nC + _m.nJten = nJten _m.na = na _m.nacttrnbody = nacttrnbody _m.nbody = nbody @@ -691,6 +736,7 @@ def _forward_shim( _m.nflex = nflex _m.nflexedge = nflexedge _m.nflexelem = nflexelem + _m.nflexshelldata = nflexshelldata _m.nflexvert = nflexvert _m.ngeom = ngeom _m.ngravcomp = ngravcomp @@ -753,6 +799,8 @@ def _forward_shim( _m.pair_solreffriction = pair_solreffriction _m.plugin = plugin _m.plugin_attr = plugin_attr + _m.qLD_all_updates = qLD_all_updates + _m.qLD_level_offsets = qLD_level_offsets _m.qLD_updates = qLD_updates _m.qM_fullm_i = qM_fullm_i _m.qM_fullm_j = qM_fullm_j @@ -797,6 +845,9 @@ def _forward_shim( _m.stat.meaninertia = stat__meaninertia _m.taxel_sensorid = taxel_sensorid _m.taxel_vertadr = taxel_vertadr + _m.ten_J_colind = ten_J_colind + _m.ten_J_rowadr = ten_J_rowadr + _m.ten_J_rownnz = ten_J_rownnz _m.tendon_actfrclimited = tendon_actfrclimited _m.tendon_actfrcrange = tendon_actfrcrange _m.tendon_adr = tendon_adr @@ -842,6 +893,7 @@ def _forward_shim( _d.contact.dim = contact__dim _d.contact.dist = contact__dist _d.contact.efc_address = contact__efc_address + _d.contact.flex = contact__flex _d.contact.frame = contact__frame _d.contact.friction = contact__friction _d.contact.geom = contact__geom @@ -852,6 +904,7 @@ def _forward_shim( _d.contact.solref = contact__solref _d.contact.solreffriction = contact__solreffriction _d.contact.type = contact__type + _d.contact.vert = contact__vert _d.contact.worldid = contact__worldid _d.crb = crb _d.ctrl = ctrl @@ -895,6 +948,7 @@ def _forward_shim( _d.nf = nf _d.nisland = nisland _d.njmax = njmax + _d.njmax_nnz = njmax_nnz _d.nl = nl _d.qLD = qLD _d.qLDiagInv = qLDiagInv @@ -1018,6 +1072,7 @@ def _forward_jax_impl(m: types.Model, d: types.Data): 'contact__dim': d._impl.contact__dim.shape, 'contact__dist': d._impl.contact__dist.shape, 'contact__efc_address': d._impl.contact__efc_address.shape, + 'contact__flex': d._impl.contact__flex.shape, 'contact__frame': d._impl.contact__frame.shape, 'contact__friction': d._impl.contact__friction.shape, 'contact__geom': d._impl.contact__geom.shape, @@ -1028,6 +1083,7 @@ def _forward_jax_impl(m: types.Model, d: types.Data): 'contact__solref': d._impl.contact__solref.shape, 'contact__solreffriction': d._impl.contact__solreffriction.shape, 'contact__type': d._impl.contact__type.shape, + 'contact__vert': d._impl.contact__vert.shape, 'contact__worldid': d._impl.contact__worldid.shape, 'efc__D': d._impl.efc__D.shape, 'efc__J': d._impl.efc__J.shape, @@ -1047,7 +1103,7 @@ def _forward_jax_impl(m: types.Model, d: types.Data): } jf = ffi.jax_callable_variadic_tuple( _forward_shim, - num_outputs=100, + num_outputs=102, output_dims=output_dims, vmap_method=None, in_out_argnames=set([ @@ -1125,6 +1181,7 @@ def _forward_jax_impl(m: types.Model, d: types.Data): 'contact__dim', 'contact__dist', 'contact__efc_address', + 'contact__flex', 'contact__frame', 'contact__friction', 'contact__geom', @@ -1135,6 +1192,7 @@ def _forward_jax_impl(m: types.Model, d: types.Data): 'contact__solref', 'contact__solreffriction', 'contact__type', + 'contact__vert', 'contact__worldid', 'efc__D', 'efc__J', @@ -1417,6 +1475,10 @@ def _forward_jax_impl(m: types.Model, d: types.Data): m.eq_type, m._impl.eq_wld_adr, m._impl.flex_bending, + m._impl.flex_centered, + m._impl.flex_conaffinity, + m._impl.flex_condim, + m._impl.flex_contype, m._impl.flex_damping, m._impl.flex_dim, m._impl.flex_edge, @@ -1425,12 +1487,22 @@ def _forward_jax_impl(m: types.Model, d: types.Data): m._impl.flex_edgenum, m._impl.flex_elem, m._impl.flex_elemadr, + m._impl.flex_elemdataadr, m._impl.flex_elemedge, m._impl.flex_elemedgeadr, m._impl.flex_elemnum, + m._impl.flex_friction, + m._impl.flex_margin, + m._impl.flex_radius, + m._impl.flex_shell, + m._impl.flex_shelldataadr, + m._impl.flex_shellnum, m._impl.flex_stiffness, + m._impl.flex_vert, m._impl.flex_vertadr, m._impl.flex_vertbodyid, + m._impl.flex_vertflexid, + m._impl.flex_vertnum, m._impl.flexedge_J_colind, m._impl.flexedge_J_rowadr, m._impl.flexedge_J_rownnz, @@ -1438,7 +1510,9 @@ def _forward_jax_impl(m: types.Model, d: types.Data): m._impl.flexedge_length0, m.geom_aabb, m.geom_bodyid, + m.geom_conaffinity, m.geom_condim, + m.geom_contype, m.geom_dataid, m.geom_fluid, m.geom_friction, @@ -1492,6 +1566,7 @@ def _forward_jax_impl(m: types.Model, d: types.Data): m._impl.light_targetbodyid, m._impl.mapM2M, m.mat_rgba, + m._impl.max_ten_J_rownnz, m.mesh_face, m.mesh_faceadr, m.mesh_graph, @@ -1514,6 +1589,7 @@ def _forward_jax_impl(m: types.Model, d: types.Data): m.mesh_vertadr, m.mesh_vertnum, m.nC, + m.nJten, m.na, m._impl.nacttrnbody, m.nbody, @@ -1523,6 +1599,7 @@ def _forward_jax_impl(m: types.Model, d: types.Data): m._impl.nflex, m._impl.nflexedge, m._impl.nflexelem, + m._impl.nflexshelldata, m._impl.nflexvert, m.ngeom, m.ngravcomp, @@ -1559,6 +1636,8 @@ def _forward_jax_impl(m: types.Model, d: types.Data): m.pair_solreffriction, m._impl.plugin, m._impl.plugin_attr, + m._impl.qLD_all_updates, + m._impl.qLD_level_offsets, m._impl.qLD_updates, m._impl.qM_fullm_i, m._impl.qM_fullm_j, @@ -1602,6 +1681,9 @@ def _forward_jax_impl(m: types.Model, d: types.Data): m.site_type, m._impl.taxel_sensorid, m._impl.taxel_vertadr, + m._impl.ten_J_colind, + m._impl.ten_J_rowadr, + m._impl.ten_J_rownnz, m.tendon_actfrclimited, m.tendon_actfrcrange, m.tendon_adr, @@ -1660,6 +1742,7 @@ def _forward_jax_impl(m: types.Model, d: types.Data): d._impl.naccdmax, d._impl.naconmax, d._impl.njmax, + d._impl.njmax_nnz, d.act, d.act_dot, d.actuator_force, @@ -1744,6 +1827,7 @@ def _forward_jax_impl(m: types.Model, d: types.Data): d._impl.contact__dim, d._impl.contact__dist, d._impl.contact__efc_address, + d._impl.contact__flex, d._impl.contact__frame, d._impl.contact__friction, d._impl.contact__geom, @@ -1754,6 +1838,7 @@ def _forward_jax_impl(m: types.Model, d: types.Data): d._impl.contact__solref, d._impl.contact__solreffriction, d._impl.contact__type, + d._impl.contact__vert, d._impl.contact__worldid, d._impl.efc__D, d._impl.efc__J, @@ -1846,32 +1931,34 @@ def _forward_jax_impl(m: types.Model, d: types.Data): '_impl.contact__dim': out[71], '_impl.contact__dist': out[72], '_impl.contact__efc_address': out[73], - '_impl.contact__frame': out[74], - '_impl.contact__friction': out[75], - '_impl.contact__geom': out[76], - '_impl.contact__geomcollisionid': out[77], - '_impl.contact__includemargin': out[78], - '_impl.contact__pos': out[79], - '_impl.contact__solimp': out[80], - '_impl.contact__solref': out[81], - '_impl.contact__solreffriction': out[82], - '_impl.contact__type': out[83], - '_impl.contact__worldid': out[84], - '_impl.efc__D': out[85], - '_impl.efc__J': out[86], - '_impl.efc__J_colind': out[87], - '_impl.efc__J_rowadr': out[88], - '_impl.efc__J_rownnz': out[89], - '_impl.efc__Ma': out[90], - '_impl.efc__aref': out[91], - '_impl.efc__force': out[92], - '_impl.efc__frictionloss': out[93], - '_impl.efc__id': out[94], - '_impl.efc__margin': out[95], - '_impl.efc__pos': out[96], - '_impl.efc__state': out[97], - '_impl.efc__type': out[98], - '_impl.efc__vel': out[99], + '_impl.contact__flex': out[74], + '_impl.contact__frame': out[75], + '_impl.contact__friction': out[76], + '_impl.contact__geom': out[77], + '_impl.contact__geomcollisionid': out[78], + '_impl.contact__includemargin': out[79], + '_impl.contact__pos': out[80], + '_impl.contact__solimp': out[81], + '_impl.contact__solref': out[82], + '_impl.contact__solreffriction': out[83], + '_impl.contact__type': out[84], + '_impl.contact__vert': out[85], + '_impl.contact__worldid': out[86], + '_impl.efc__D': out[87], + '_impl.efc__J': out[88], + '_impl.efc__J_colind': out[89], + '_impl.efc__J_rowadr': out[90], + '_impl.efc__J_rownnz': out[91], + '_impl.efc__Ma': out[92], + '_impl.efc__aref': out[93], + '_impl.efc__force': out[94], + '_impl.efc__frictionloss': out[95], + '_impl.efc__id': out[96], + '_impl.efc__margin': out[97], + '_impl.efc__pos': out[98], + '_impl.efc__state': out[99], + '_impl.efc__type': out[100], + '_impl.efc__vel': out[101], }) return d @@ -1980,6 +2067,10 @@ def _step_shim( eq_type: wp.array(dtype=int), eq_wld_adr: wp.array(dtype=int), flex_bending: wp.array2d(dtype=float), + flex_centered: wp.array(dtype=bool), + flex_conaffinity: wp.array(dtype=int), + flex_condim: wp.array(dtype=int), + flex_contype: wp.array(dtype=int), flex_damping: wp.array(dtype=float), flex_dim: wp.array(dtype=int), flex_edge: wp.array(dtype=wp.vec2i), @@ -1988,12 +2079,22 @@ def _step_shim( flex_edgenum: wp.array(dtype=int), flex_elem: wp.array(dtype=int), flex_elemadr: wp.array(dtype=int), + flex_elemdataadr: wp.array(dtype=int), flex_elemedge: wp.array(dtype=int), flex_elemedgeadr: wp.array(dtype=int), flex_elemnum: wp.array(dtype=int), + flex_friction: wp.array(dtype=wp.vec3), + flex_margin: wp.array(dtype=float), + flex_radius: wp.array(dtype=float), + flex_shell: wp.array(dtype=int), + flex_shelldataadr: wp.array(dtype=int), + flex_shellnum: wp.array(dtype=int), flex_stiffness: wp.array2d(dtype=float), + flex_vert: wp.array(dtype=wp.vec3), flex_vertadr: wp.array(dtype=int), flex_vertbodyid: wp.array(dtype=int), + flex_vertflexid: wp.array(dtype=int), + flex_vertnum: wp.array(dtype=int), flexedge_J_colind: wp.array(dtype=int), flexedge_J_rowadr: wp.array(dtype=int), flexedge_J_rownnz: wp.array(dtype=int), @@ -2001,7 +2102,9 @@ def _step_shim( flexedge_length0: wp.array(dtype=float), geom_aabb: wp.array3d(dtype=wp.vec3), geom_bodyid: wp.array(dtype=int), + geom_conaffinity: wp.array(dtype=int), geom_condim: wp.array(dtype=int), + geom_contype: wp.array(dtype=int), geom_dataid: wp.array(dtype=int), geom_fluid: wp.array2d(dtype=float), geom_friction: wp.array2d(dtype=wp.vec3), @@ -2055,6 +2158,7 @@ def _step_shim( light_targetbodyid: wp.array(dtype=int), mapM2M: wp.array(dtype=int), mat_rgba: wp.array2d(dtype=wp.vec4), + max_ten_J_rownnz: int, mesh_face: wp.array(dtype=wp.vec3i), mesh_faceadr: wp.array(dtype=int), mesh_graph: wp.array(dtype=int), @@ -2077,6 +2181,7 @@ def _step_shim( mesh_vertadr: wp.array(dtype=int), mesh_vertnum: wp.array(dtype=int), nC: int, + nJten: int, nM: int, na: int, nacttrnbody: int, @@ -2087,6 +2192,7 @@ def _step_shim( nflex: int, nflexedge: int, nflexelem: int, + nflexshelldata: int, nflexvert: int, ngeom: int, ngravcomp: int, @@ -2122,7 +2228,9 @@ def _step_shim( pair_solref: wp.array2d(dtype=wp.vec2), pair_solreffriction: wp.array2d(dtype=wp.vec2), plugin: wp.array(dtype=int), - plugin_attr: wp.array(dtype=wp.vec3f), + plugin_attr: wp.array(dtype=mjwp_types.vec_pluginattr), + qLD_all_updates: wp.array(dtype=wp.vec3i), + qLD_level_offsets: wp.array(dtype=int), qLD_updates: tuple[wp.array(dtype=wp.vec3i), ...], qM_fullm_i: wp.array(dtype=int), qM_fullm_j: wp.array(dtype=int), @@ -2166,6 +2274,9 @@ def _step_shim( site_type: wp.array(dtype=int), taxel_sensorid: wp.array(dtype=int), taxel_vertadr: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_rownnz: wp.array(dtype=int), tendon_actfrclimited: wp.array(dtype=bool), tendon_actfrcrange: wp.array2d(dtype=wp.vec2), tendon_adr: wp.array(dtype=int), @@ -2226,6 +2337,7 @@ def _step_shim( naccdmax: int, naconmax: int, njmax: int, + njmax_nnz: int, act: wp.array2d(dtype=float), act_dot: wp.array2d(dtype=float), actuator_force: wp.array2d(dtype=float), @@ -2290,7 +2402,7 @@ def _step_shim( subtree_angmom: wp.array2d(dtype=wp.vec3), subtree_com: wp.array2d(dtype=wp.vec3), subtree_linvel: wp.array2d(dtype=wp.vec3), - ten_J: wp.array3d(dtype=float), + ten_J: wp.array2d(dtype=float), ten_length: wp.array2d(dtype=float), ten_velocity: wp.array2d(dtype=float), ten_wrapadr: wp.array2d(dtype=int), @@ -2310,6 +2422,7 @@ def _step_shim( contact__dim: wp.array(dtype=int), contact__dist: wp.array(dtype=float), contact__efc_address: wp.array2d(dtype=int), + contact__flex: wp.array(dtype=wp.vec2i), contact__frame: wp.array(dtype=wp.mat33), contact__friction: wp.array(dtype=mjwp_types.vec5), contact__geom: wp.array(dtype=wp.vec2i), @@ -2320,6 +2433,7 @@ def _step_shim( contact__solref: wp.array(dtype=wp.vec2), contact__solreffriction: wp.array(dtype=wp.vec2), contact__type: wp.array(dtype=int), + contact__vert: wp.array(dtype=wp.vec2i), contact__worldid: wp.array(dtype=int), efc__D: wp.array2d(dtype=float), efc__J: wp.array3d(dtype=float), @@ -2429,6 +2543,10 @@ def _step_shim( _m.eq_type = eq_type _m.eq_wld_adr = eq_wld_adr _m.flex_bending = flex_bending + _m.flex_centered = flex_centered + _m.flex_conaffinity = flex_conaffinity + _m.flex_condim = flex_condim + _m.flex_contype = flex_contype _m.flex_damping = flex_damping _m.flex_dim = flex_dim _m.flex_edge = flex_edge @@ -2437,12 +2555,22 @@ def _step_shim( _m.flex_edgenum = flex_edgenum _m.flex_elem = flex_elem _m.flex_elemadr = flex_elemadr + _m.flex_elemdataadr = flex_elemdataadr _m.flex_elemedge = flex_elemedge _m.flex_elemedgeadr = flex_elemedgeadr _m.flex_elemnum = flex_elemnum + _m.flex_friction = flex_friction + _m.flex_margin = flex_margin + _m.flex_radius = flex_radius + _m.flex_shell = flex_shell + _m.flex_shelldataadr = flex_shelldataadr + _m.flex_shellnum = flex_shellnum _m.flex_stiffness = flex_stiffness + _m.flex_vert = flex_vert _m.flex_vertadr = flex_vertadr _m.flex_vertbodyid = flex_vertbodyid + _m.flex_vertflexid = flex_vertflexid + _m.flex_vertnum = flex_vertnum _m.flexedge_J_colind = flexedge_J_colind _m.flexedge_J_rowadr = flexedge_J_rowadr _m.flexedge_J_rownnz = flexedge_J_rownnz @@ -2450,7 +2578,9 @@ def _step_shim( _m.flexedge_length0 = flexedge_length0 _m.geom_aabb = geom_aabb _m.geom_bodyid = geom_bodyid + _m.geom_conaffinity = geom_conaffinity _m.geom_condim = geom_condim + _m.geom_contype = geom_contype _m.geom_dataid = geom_dataid _m.geom_fluid = geom_fluid _m.geom_friction = geom_friction @@ -2504,6 +2634,7 @@ def _step_shim( _m.light_targetbodyid = light_targetbodyid _m.mapM2M = mapM2M _m.mat_rgba = mat_rgba + _m.max_ten_J_rownnz = max_ten_J_rownnz _m.mesh_face = mesh_face _m.mesh_faceadr = mesh_faceadr _m.mesh_graph = mesh_graph @@ -2526,6 +2657,7 @@ def _step_shim( _m.mesh_vertadr = mesh_vertadr _m.mesh_vertnum = mesh_vertnum _m.nC = nC + _m.nJten = nJten _m.nM = nM _m.na = na _m.nacttrnbody = nacttrnbody @@ -2536,6 +2668,7 @@ def _step_shim( _m.nflex = nflex _m.nflexedge = nflexedge _m.nflexelem = nflexelem + _m.nflexshelldata = nflexshelldata _m.nflexvert = nflexvert _m.ngeom = ngeom _m.ngravcomp = ngravcomp @@ -2599,6 +2732,8 @@ def _step_shim( _m.pair_solreffriction = pair_solreffriction _m.plugin = plugin _m.plugin_attr = plugin_attr + _m.qLD_all_updates = qLD_all_updates + _m.qLD_level_offsets = qLD_level_offsets _m.qLD_updates = qLD_updates _m.qM_fullm_i = qM_fullm_i _m.qM_fullm_j = qM_fullm_j @@ -2643,6 +2778,9 @@ def _step_shim( _m.stat.meaninertia = stat__meaninertia _m.taxel_sensorid = taxel_sensorid _m.taxel_vertadr = taxel_vertadr + _m.ten_J_colind = ten_J_colind + _m.ten_J_rowadr = ten_J_rowadr + _m.ten_J_rownnz = ten_J_rownnz _m.tendon_actfrclimited = tendon_actfrclimited _m.tendon_actfrcrange = tendon_actfrcrange _m.tendon_adr = tendon_adr @@ -2688,6 +2826,7 @@ def _step_shim( _d.contact.dim = contact__dim _d.contact.dist = contact__dist _d.contact.efc_address = contact__efc_address + _d.contact.flex = contact__flex _d.contact.frame = contact__frame _d.contact.friction = contact__friction _d.contact.geom = contact__geom @@ -2698,6 +2837,7 @@ def _step_shim( _d.contact.solref = contact__solref _d.contact.solreffriction = contact__solreffriction _d.contact.type = contact__type + _d.contact.vert = contact__vert _d.contact.worldid = contact__worldid _d.crb = crb _d.ctrl = ctrl @@ -2741,6 +2881,7 @@ def _step_shim( _d.nf = nf _d.nisland = nisland _d.njmax = njmax + _d.njmax_nnz = njmax_nnz _d.nl = nl _d.qLD = qLD _d.qLDiagInv = qLDiagInv @@ -2868,6 +3009,7 @@ def _step_jax_impl(m: types.Model, d: types.Data): 'contact__dim': d._impl.contact__dim.shape, 'contact__dist': d._impl.contact__dist.shape, 'contact__efc_address': d._impl.contact__efc_address.shape, + 'contact__flex': d._impl.contact__flex.shape, 'contact__frame': d._impl.contact__frame.shape, 'contact__friction': d._impl.contact__friction.shape, 'contact__geom': d._impl.contact__geom.shape, @@ -2878,6 +3020,7 @@ def _step_jax_impl(m: types.Model, d: types.Data): 'contact__solref': d._impl.contact__solref.shape, 'contact__solreffriction': d._impl.contact__solreffriction.shape, 'contact__type': d._impl.contact__type.shape, + 'contact__vert': d._impl.contact__vert.shape, 'contact__worldid': d._impl.contact__worldid.shape, 'efc__D': d._impl.efc__D.shape, 'efc__J': d._impl.efc__J.shape, @@ -2897,7 +3040,7 @@ def _step_jax_impl(m: types.Model, d: types.Data): } jf = ffi.jax_callable_variadic_tuple( _step_shim, - num_outputs=104, + num_outputs=106, output_dims=output_dims, vmap_method=None, in_out_argnames=set([ @@ -2979,6 +3122,7 @@ def _step_jax_impl(m: types.Model, d: types.Data): 'contact__dim', 'contact__dist', 'contact__efc_address', + 'contact__flex', 'contact__frame', 'contact__friction', 'contact__geom', @@ -2989,6 +3133,7 @@ def _step_jax_impl(m: types.Model, d: types.Data): 'contact__solref', 'contact__solreffriction', 'contact__type', + 'contact__vert', 'contact__worldid', 'efc__D', 'efc__J', @@ -3275,6 +3420,10 @@ def _step_jax_impl(m: types.Model, d: types.Data): m.eq_type, m._impl.eq_wld_adr, m._impl.flex_bending, + m._impl.flex_centered, + m._impl.flex_conaffinity, + m._impl.flex_condim, + m._impl.flex_contype, m._impl.flex_damping, m._impl.flex_dim, m._impl.flex_edge, @@ -3283,12 +3432,22 @@ def _step_jax_impl(m: types.Model, d: types.Data): m._impl.flex_edgenum, m._impl.flex_elem, m._impl.flex_elemadr, + m._impl.flex_elemdataadr, m._impl.flex_elemedge, m._impl.flex_elemedgeadr, m._impl.flex_elemnum, + m._impl.flex_friction, + m._impl.flex_margin, + m._impl.flex_radius, + m._impl.flex_shell, + m._impl.flex_shelldataadr, + m._impl.flex_shellnum, m._impl.flex_stiffness, + m._impl.flex_vert, m._impl.flex_vertadr, m._impl.flex_vertbodyid, + m._impl.flex_vertflexid, + m._impl.flex_vertnum, m._impl.flexedge_J_colind, m._impl.flexedge_J_rowadr, m._impl.flexedge_J_rownnz, @@ -3296,7 +3455,9 @@ def _step_jax_impl(m: types.Model, d: types.Data): m._impl.flexedge_length0, m.geom_aabb, m.geom_bodyid, + m.geom_conaffinity, m.geom_condim, + m.geom_contype, m.geom_dataid, m.geom_fluid, m.geom_friction, @@ -3350,6 +3511,7 @@ def _step_jax_impl(m: types.Model, d: types.Data): m._impl.light_targetbodyid, m._impl.mapM2M, m.mat_rgba, + m._impl.max_ten_J_rownnz, m.mesh_face, m.mesh_faceadr, m.mesh_graph, @@ -3372,6 +3534,7 @@ def _step_jax_impl(m: types.Model, d: types.Data): m.mesh_vertadr, m.mesh_vertnum, m.nC, + m.nJten, m.nM, m.na, m._impl.nacttrnbody, @@ -3382,6 +3545,7 @@ def _step_jax_impl(m: types.Model, d: types.Data): m._impl.nflex, m._impl.nflexedge, m._impl.nflexelem, + m._impl.nflexshelldata, m._impl.nflexvert, m.ngeom, m.ngravcomp, @@ -3418,6 +3582,8 @@ def _step_jax_impl(m: types.Model, d: types.Data): m.pair_solreffriction, m._impl.plugin, m._impl.plugin_attr, + m._impl.qLD_all_updates, + m._impl.qLD_level_offsets, m._impl.qLD_updates, m._impl.qM_fullm_i, m._impl.qM_fullm_j, @@ -3461,6 +3627,9 @@ def _step_jax_impl(m: types.Model, d: types.Data): m.site_type, m._impl.taxel_sensorid, m._impl.taxel_vertadr, + m._impl.ten_J_colind, + m._impl.ten_J_rowadr, + m._impl.ten_J_rownnz, m.tendon_actfrclimited, m.tendon_actfrcrange, m.tendon_adr, @@ -3520,6 +3689,7 @@ def _step_jax_impl(m: types.Model, d: types.Data): d._impl.naccdmax, d._impl.naconmax, d._impl.njmax, + d._impl.njmax_nnz, d.act, d.act_dot, d.actuator_force, @@ -3604,6 +3774,7 @@ def _step_jax_impl(m: types.Model, d: types.Data): d._impl.contact__dim, d._impl.contact__dist, d._impl.contact__efc_address, + d._impl.contact__flex, d._impl.contact__frame, d._impl.contact__friction, d._impl.contact__geom, @@ -3614,6 +3785,7 @@ def _step_jax_impl(m: types.Model, d: types.Data): d._impl.contact__solref, d._impl.contact__solreffriction, d._impl.contact__type, + d._impl.contact__vert, d._impl.contact__worldid, d._impl.efc__D, d._impl.efc__J, @@ -3710,32 +3882,34 @@ def _step_jax_impl(m: types.Model, d: types.Data): '_impl.contact__dim': out[75], '_impl.contact__dist': out[76], '_impl.contact__efc_address': out[77], - '_impl.contact__frame': out[78], - '_impl.contact__friction': out[79], - '_impl.contact__geom': out[80], - '_impl.contact__geomcollisionid': out[81], - '_impl.contact__includemargin': out[82], - '_impl.contact__pos': out[83], - '_impl.contact__solimp': out[84], - '_impl.contact__solref': out[85], - '_impl.contact__solreffriction': out[86], - '_impl.contact__type': out[87], - '_impl.contact__worldid': out[88], - '_impl.efc__D': out[89], - '_impl.efc__J': out[90], - '_impl.efc__J_colind': out[91], - '_impl.efc__J_rowadr': out[92], - '_impl.efc__J_rownnz': out[93], - '_impl.efc__Ma': out[94], - '_impl.efc__aref': out[95], - '_impl.efc__force': out[96], - '_impl.efc__frictionloss': out[97], - '_impl.efc__id': out[98], - '_impl.efc__margin': out[99], - '_impl.efc__pos': out[100], - '_impl.efc__state': out[101], - '_impl.efc__type': out[102], - '_impl.efc__vel': out[103], + '_impl.contact__flex': out[78], + '_impl.contact__frame': out[79], + '_impl.contact__friction': out[80], + '_impl.contact__geom': out[81], + '_impl.contact__geomcollisionid': out[82], + '_impl.contact__includemargin': out[83], + '_impl.contact__pos': out[84], + '_impl.contact__solimp': out[85], + '_impl.contact__solref': out[86], + '_impl.contact__solreffriction': out[87], + '_impl.contact__type': out[88], + '_impl.contact__vert': out[89], + '_impl.contact__worldid': out[90], + '_impl.efc__D': out[91], + '_impl.efc__J': out[92], + '_impl.efc__J_colind': out[93], + '_impl.efc__J_rowadr': out[94], + '_impl.efc__J_rownnz': out[95], + '_impl.efc__Ma': out[96], + '_impl.efc__aref': out[97], + '_impl.efc__force': out[98], + '_impl.efc__frictionloss': out[99], + '_impl.efc__id': out[100], + '_impl.efc__margin': out[101], + '_impl.efc__pos': out[102], + '_impl.efc__state': out[103], + '_impl.efc__type': out[104], + '_impl.efc__vel': out[105], }) return d diff --git a/mjx/mujoco/mjx/warp/forward_test.py b/mjx/mujoco/mjx/warp/forward_test.py index 15e874e3eb..b80c921dcc 100644 --- a/mjx/mujoco/mjx/warp/forward_test.py +++ b/mjx/mujoco/mjx/warp/forward_test.py @@ -157,7 +157,16 @@ def test_forward(self, xml: str, batch_size: int): m.ten_J_rowadr, m.ten_J_colind, ) - tu.assert_eq(dx._impl.ten_J, ten_J, 'ten_J') + # convert sparse warp ten_J to dense representation + warp_ten_J = np.zeros((m.ntendon, m.nv)) + mujoco.mju_sparse2dense( + warp_ten_J, + np.asarray(dx._impl.ten_J), + mx._impl.ten_J_rownnz, + mx._impl.ten_J_rowadr, + mx._impl.ten_J_colind, + ) + tu.assert_eq(warp_ten_J, ten_J, 'ten_J') tu.assert_attr_eq(dx._impl, d, 'ten_wrapadr') tu.assert_attr_eq(dx._impl, d, 'ten_wrapnum') tu.assert_attr_eq(dx._impl, d, 'wrap_xpos') diff --git a/mjx/mujoco/mjx/warp/render.py b/mjx/mujoco/mjx/warp/render.py index 0bab51a3fb..e723e6b076 100644 --- a/mjx/mujoco/mjx/warp/render.py +++ b/mjx/mujoco/mjx/warp/render.py @@ -48,6 +48,7 @@ **{f.name: None for f in dataclasses.fields(mjwp_types.Callback) if f.init} ) + @ffi.format_args_for_warp def _render_shim( # Model @@ -56,6 +57,9 @@ def _render_shim( cam_intrinsic: wp.array2d(dtype=wp.vec4), cam_projection: wp.array(dtype=int), cam_sensorsize: wp.array(dtype=wp.vec2), + flex_edge: wp.array(dtype=wp.vec2i), + flex_radius: wp.array(dtype=float), + flex_vertadr: wp.array(dtype=int), geom_dataid: wp.array(dtype=int), geom_matid: wp.array2d(dtype=int), geom_rgba: wp.array2d(dtype=wp.vec4), @@ -68,11 +72,11 @@ def _render_shim( mat_texid: wp.array3d(dtype=int), mat_texrepeat: wp.array2d(dtype=wp.vec2), mesh_faceadr: wp.array(dtype=int), - nflex: int, nlight: int, # Data cam_xmat: wp.array2d(dtype=wp.mat33), cam_xpos: wp.array2d(dtype=wp.vec3), + flexvert_xpos: wp.array2d(dtype=wp.vec3), geom_xmat: wp.array2d(dtype=wp.mat33), geom_xpos: wp.array2d(dtype=wp.vec3), light_xdir: wp.array2d(dtype=wp.vec3), @@ -91,6 +95,9 @@ def _render_shim( _m.cam_intrinsic = cam_intrinsic _m.cam_projection = cam_projection _m.cam_sensorsize = cam_sensorsize + _m.flex_edge = flex_edge + _m.flex_radius = flex_radius + _m.flex_vertadr = flex_vertadr _m.geom_dataid = geom_dataid _m.geom_matid = geom_matid _m.geom_rgba = geom_rgba @@ -103,10 +110,10 @@ def _render_shim( _m.mat_texid = mat_texid _m.mat_texrepeat = mat_texrepeat _m.mesh_faceadr = mesh_faceadr - _m.nflex = nflex _m.nlight = nlight _d.cam_xmat = cam_xmat _d.cam_xpos = cam_xpos + _d.flexvert_xpos = flexvert_xpos _d.geom_xmat = geom_xmat _d.geom_xpos = geom_xpos _d.light_xdir = light_xdir @@ -155,6 +162,9 @@ def _render_jax_impl(m: types.Model, d: types.Data, ctx: RenderContextPytree): m.cam_intrinsic, m._impl.cam_projection, m.cam_sensorsize, + m._impl.flex_edge, + m._impl.flex_radius, + m._impl.flex_vertadr, m.geom_dataid, m.geom_matid, m.geom_rgba, @@ -167,10 +177,10 @@ def _render_jax_impl(m: types.Model, d: types.Data, ctx: RenderContextPytree): m.mat_texid, m._impl.mat_texrepeat, m.mesh_faceadr, - m._impl.nflex, m.nlight, d.cam_xmat, d.cam_xpos, + d._impl.flexvert_xpos, d.geom_xmat, d.geom_xpos, d._impl.light_xdir, diff --git a/mjx/mujoco/mjx/warp/smooth.py b/mjx/mujoco/mjx/warp/smooth.py index eeef2d924e..3fe3a712b8 100644 --- a/mjx/mujoco/mjx/warp/smooth.py +++ b/mjx/mujoco/mjx/warp/smooth.py @@ -297,17 +297,20 @@ def kinematics_vmap( def _tendon_shim( # Model nworld: int, + body_dofadr: wp.array(dtype=int), + body_dofnum: wp.array(dtype=int), body_parentid: wp.array(dtype=int), body_rootid: wp.array(dtype=int), - dof_bodyid: wp.array(dtype=int), geom_bodyid: wp.array(dtype=int), geom_size: wp.array2d(dtype=wp.vec3), jnt_dofadr: wp.array(dtype=int), jnt_qposadr: wp.array(dtype=int), ntendon: int, - nv: int, nwrap: int, site_bodyid: wp.array(dtype=int), + ten_J_colind: wp.array(dtype=int), + ten_J_rowadr: wp.array(dtype=int), + ten_J_rownnz: wp.array(dtype=int), tendon_adr: wp.array(dtype=int), tendon_geom_adr: wp.array(dtype=int), tendon_jnt_adr: wp.array(dtype=int), @@ -327,7 +330,7 @@ def _tendon_shim( qpos: wp.array2d(dtype=float), site_xpos: wp.array2d(dtype=wp.vec3), subtree_com: wp.array2d(dtype=wp.vec3), - ten_J: wp.array3d(dtype=float), + ten_J: wp.array2d(dtype=float), ten_length: wp.array2d(dtype=float), ten_wrapadr: wp.array2d(dtype=int), ten_wrapnum: wp.array2d(dtype=int), @@ -339,17 +342,20 @@ def _tendon_shim( _m.callback = _cb _d.efc = _e _d.contact = _c + _m.body_dofadr = body_dofadr + _m.body_dofnum = body_dofnum _m.body_parentid = body_parentid _m.body_rootid = body_rootid - _m.dof_bodyid = dof_bodyid _m.geom_bodyid = geom_bodyid _m.geom_size = geom_size _m.jnt_dofadr = jnt_dofadr _m.jnt_qposadr = jnt_qposadr _m.ntendon = ntendon - _m.nv = nv _m.nwrap = nwrap _m.site_bodyid = site_bodyid + _m.ten_J_colind = ten_J_colind + _m.ten_J_rowadr = ten_J_rowadr + _m.ten_J_rownnz = ten_J_rownnz _m.tendon_adr = tendon_adr _m.tendon_geom_adr = tendon_geom_adr _m.tendon_jnt_adr = tendon_jnt_adr @@ -416,17 +422,20 @@ def _tendon_jax_impl(m: types.Model, d: types.Data): ) out = jf( d.qpos.shape[0], + m.body_dofadr, + m.body_dofnum, m.body_parentid, m.body_rootid, - m.dof_bodyid, m.geom_bodyid, m.geom_size, m.jnt_dofadr, m.jnt_qposadr, m.ntendon, - m.nv, m.nwrap, m.site_bodyid, + m._impl.ten_J_colind, + m._impl.ten_J_rowadr, + m._impl.ten_J_rownnz, m.tendon_adr, m._impl.tendon_geom_adr, m._impl.tendon_jnt_adr, diff --git a/mjx/mujoco/mjx/warp/types.py b/mjx/mujoco/mjx/warp/types.py index ff85189f6e..ef75edc40a 100644 --- a/mjx/mujoco/mjx/warp/types.py +++ b/mjx/mujoco/mjx/warp/types.py @@ -83,7 +83,7 @@ class BlockDim: qderiv_actuator_dense: int ray: int segmented_sort: int - tendon_velocity: int + solve_LD_sparse_fused: int update_gradient_JTDAJ_dense: int update_gradient_JTDAJ_sparse: int update_gradient_cholesky: int @@ -141,6 +141,10 @@ class ModelWarp(PyTreeNode): eq_ten_adr: np.ndarray eq_wld_adr: np.ndarray flex_bending: np.ndarray + flex_centered: np.ndarray + flex_conaffinity: np.ndarray + flex_condim: np.ndarray + flex_contype: np.ndarray flex_damping: np.ndarray flex_dim: np.ndarray flex_edge: np.ndarray @@ -149,12 +153,21 @@ class ModelWarp(PyTreeNode): flex_edgenum: np.ndarray flex_elem: np.ndarray flex_elemadr: np.ndarray + flex_elemdataadr: np.ndarray flex_elemedge: np.ndarray flex_elemedgeadr: np.ndarray flex_elemnum: np.ndarray + flex_friction: np.ndarray + flex_margin: np.ndarray + flex_radius: np.ndarray + flex_shell: np.ndarray + flex_shelldataadr: np.ndarray + flex_shellnum: np.ndarray flex_stiffness: np.ndarray + flex_vert: np.ndarray flex_vertadr: np.ndarray flex_vertbodyid: np.ndarray + flex_vertflexid: np.ndarray flex_vertnum: np.ndarray flexedge_J_colind: np.ndarray flexedge_J_rowadr: np.ndarray @@ -173,6 +186,7 @@ class ModelWarp(PyTreeNode): light_targetbodyid: np.ndarray mapM2M: np.ndarray mat_texrepeat: jax.Array + max_ten_J_rownnz: int mesh_polyadr: np.ndarray mesh_polymap: np.ndarray mesh_polymapadr: np.ndarray @@ -191,6 +205,7 @@ class ModelWarp(PyTreeNode): nflexelem: int nflexelemdata: int nflexelemedge: int + nflexshelldata: int nflexvert: int nmaxcondim: int nmaxmeshdeg: int @@ -213,6 +228,8 @@ class ModelWarp(PyTreeNode): oct_coeff: np.ndarray plugin: np.ndarray plugin_attr: np.ndarray + qLD_all_updates: np.ndarray + qLD_level_offsets: np.ndarray qLD_updates: Tuple[np.ndarray, ...] qM_fullm_i: np.ndarray qM_fullm_j: np.ndarray @@ -240,6 +257,9 @@ class ModelWarp(PyTreeNode): sensor_vel_adr: np.ndarray taxel_sensorid: np.ndarray taxel_vertadr: np.ndarray + ten_J_colind: np.ndarray + ten_J_rowadr: np.ndarray + ten_J_rownnz: np.ndarray ten_wrapadr_site: np.ndarray ten_wrapnum_site: np.ndarray tendon_geom_adr: np.ndarray @@ -266,6 +286,7 @@ class DataWarp(PyTreeNode): contact__dim: jax.Array contact__dist: jax.Array contact__efc_address: jax.Array + contact__flex: jax.Array contact__frame: jax.Array contact__friction: jax.Array contact__geom: jax.Array @@ -276,6 +297,7 @@ class DataWarp(PyTreeNode): contact__solref: jax.Array contact__solreffriction: jax.Array contact__type: jax.Array + contact__vert: jax.Array contact__worldid: jax.Array crb: jax.Array efc__D: jax.Array @@ -312,6 +334,7 @@ class DataWarp(PyTreeNode): nf: jax.Array nisland: jax.Array njmax: int + njmax_nnz: int njmax_pad: int nl: jax.Array nworld: int @@ -335,6 +358,7 @@ class DataWarp(PyTreeNode): 'contact__dim', 'contact__dist', 'contact__efc_address', + 'contact__flex', 'contact__frame', 'contact__friction', 'contact__geom', @@ -345,12 +369,14 @@ class DataWarp(PyTreeNode): 'contact__solref', 'contact__solreffriction', 'contact__type', + 'contact__vert', 'contact__worldid', 'naccdmax', 'nacon', 'naconmax', 'ncollision', 'njmax', + 'njmax_nnz', 'njmax_pad', 'nworld', } @@ -398,6 +424,7 @@ def _from_elt(cont, axis_size, d, axis_dest): 'contact__dim': 1, 'contact__dist': 1, 'contact__efc_address': 2, + 'contact__flex': 2, 'contact__frame': 3, 'contact__friction': 2, 'contact__geom': 2, @@ -408,6 +435,7 @@ def _from_elt(cont, axis_size, d, axis_dest): 'contact__solref': 2, 'contact__solreffriction': 2, 'contact__type': 1, + 'contact__vert': 2, 'contact__worldid': 1, 'crb': 3, 'ctrl': 2, @@ -451,6 +479,7 @@ def _from_elt(cont, axis_size, d, axis_dest): 'nf': 1, 'nisland': 1, 'njmax': 0, + 'njmax_nnz': 0, 'njmax_pad': 0, 'nl': 1, 'nworld': 0, @@ -480,7 +509,7 @@ def _from_elt(cont, axis_size, d, axis_dest): 'subtree_angmom': 3, 'subtree_com': 3, 'subtree_linvel': 3, - 'ten_J': 3, + 'ten_J': 2, 'ten_length': 2, 'ten_velocity': 2, 'ten_wrapadr': 2, @@ -535,7 +564,7 @@ def _from_elt(cont, axis_size, d, axis_dest): 'block_dim__qderiv_actuator_dense': 0, 'block_dim__ray': 0, 'block_dim__segmented_sort': 0, - 'block_dim__tendon_velocity': 0, + 'block_dim__solve_LD_sparse_fused': 0, 'block_dim__update_gradient_JTDAJ_dense': 0, 'block_dim__update_gradient_JTDAJ_sparse': 0, 'block_dim__update_gradient_cholesky': 0, @@ -608,6 +637,10 @@ def _from_elt(cont, axis_size, d, axis_dest): 'eq_wld_adr': 1, 'exclude_signature': 1, 'flex_bending': 2, + 'flex_centered': 1, + 'flex_conaffinity': 1, + 'flex_condim': 1, + 'flex_contype': 1, 'flex_damping': 1, 'flex_dim': 1, 'flex_edge': 2, @@ -616,12 +649,21 @@ def _from_elt(cont, axis_size, d, axis_dest): 'flex_edgenum': 1, 'flex_elem': 1, 'flex_elemadr': 1, + 'flex_elemdataadr': 1, 'flex_elemedge': 1, 'flex_elemedgeadr': 1, 'flex_elemnum': 1, + 'flex_friction': 2, + 'flex_margin': 1, + 'flex_radius': 1, + 'flex_shell': 1, + 'flex_shelldataadr': 1, + 'flex_shellnum': 1, 'flex_stiffness': 2, + 'flex_vert': 2, 'flex_vertadr': 1, 'flex_vertbodyid': 1, + 'flex_vertflexid': 1, 'flex_vertnum': 1, 'flexedge_J_colind': 1, 'flexedge_J_rowadr': 1, @@ -692,6 +734,7 @@ def _from_elt(cont, axis_size, d, axis_dest): 'mat_rgba': 3, 'mat_texid': 3, 'mat_texrepeat': 3, + 'max_ten_J_rownnz': 0, 'mesh_face': 2, 'mesh_faceadr': 1, 'mesh_graph': 1, @@ -717,6 +760,7 @@ def _from_elt(cont, axis_size, d, axis_dest): 'nC': 0, 'nJfe': 0, 'nJmom': 0, + 'nJten': 0, 'nM': 0, 'na': 0, 'nacttrnbody': 0, @@ -730,6 +774,7 @@ def _from_elt(cont, axis_size, d, axis_dest): 'nflexelem': 0, 'nflexelemdata': 0, 'nflexelemedge': 0, + 'nflexshelldata': 0, 'nflexvert': 0, 'ngeom': 0, 'ngravcomp': 0, @@ -811,6 +856,8 @@ def _from_elt(cont, axis_size, d, axis_dest): 'pair_solreffriction': 3, 'plugin': 1, 'plugin_attr': 2, + 'qLD_all_updates': 2, + 'qLD_level_offsets': 1, 'qLD_updates': -1, 'qM_fullm_i': 1, 'qM_fullm_j': 1, @@ -856,6 +903,9 @@ def _from_elt(cont, axis_size, d, axis_dest): 'stat__meaninertia': 1, 'taxel_sensorid': 1, 'taxel_vertadr': 1, + 'ten_J_colind': 1, + 'ten_J_rowadr': 1, + 'ten_J_rownnz': 1, 'ten_wrapadr_site': 1, 'ten_wrapnum_site': 1, 'tendon_actfrclimited': 1, @@ -940,6 +990,7 @@ def _from_elt(cont, axis_size, d, axis_dest): 'contact__dim': False, 'contact__dist': False, 'contact__efc_address': False, + 'contact__flex': False, 'contact__frame': False, 'contact__friction': False, 'contact__geom': False, @@ -950,6 +1001,7 @@ def _from_elt(cont, axis_size, d, axis_dest): 'contact__solref': False, 'contact__solreffriction': False, 'contact__type': False, + 'contact__vert': False, 'contact__worldid': False, 'crb': True, 'ctrl': True, @@ -993,6 +1045,7 @@ def _from_elt(cont, axis_size, d, axis_dest): 'nf': True, 'nisland': True, 'njmax': False, + 'njmax_nnz': False, 'njmax_pad': False, 'nl': True, 'nworld': False, @@ -1077,7 +1130,7 @@ def _from_elt(cont, axis_size, d, axis_dest): 'block_dim__qderiv_actuator_dense': False, 'block_dim__ray': False, 'block_dim__segmented_sort': False, - 'block_dim__tendon_velocity': False, + 'block_dim__solve_LD_sparse_fused': False, 'block_dim__update_gradient_JTDAJ_dense': False, 'block_dim__update_gradient_JTDAJ_sparse': False, 'block_dim__update_gradient_cholesky': False, @@ -1150,6 +1203,10 @@ def _from_elt(cont, axis_size, d, axis_dest): 'eq_wld_adr': False, 'exclude_signature': False, 'flex_bending': False, + 'flex_centered': False, + 'flex_conaffinity': False, + 'flex_condim': False, + 'flex_contype': False, 'flex_damping': False, 'flex_dim': False, 'flex_edge': False, @@ -1158,12 +1215,21 @@ def _from_elt(cont, axis_size, d, axis_dest): 'flex_edgenum': False, 'flex_elem': False, 'flex_elemadr': False, + 'flex_elemdataadr': False, 'flex_elemedge': False, 'flex_elemedgeadr': False, 'flex_elemnum': False, + 'flex_friction': False, + 'flex_margin': False, + 'flex_radius': False, + 'flex_shell': False, + 'flex_shelldataadr': False, + 'flex_shellnum': False, 'flex_stiffness': False, + 'flex_vert': False, 'flex_vertadr': False, 'flex_vertbodyid': False, + 'flex_vertflexid': False, 'flex_vertnum': False, 'flexedge_J_colind': False, 'flexedge_J_rowadr': False, @@ -1234,6 +1300,7 @@ def _from_elt(cont, axis_size, d, axis_dest): 'mat_rgba': True, 'mat_texid': True, 'mat_texrepeat': True, + 'max_ten_J_rownnz': False, 'mesh_face': False, 'mesh_faceadr': False, 'mesh_graph': False, @@ -1259,6 +1326,7 @@ def _from_elt(cont, axis_size, d, axis_dest): 'nC': False, 'nJfe': False, 'nJmom': False, + 'nJten': False, 'nM': False, 'na': False, 'nacttrnbody': False, @@ -1272,6 +1340,7 @@ def _from_elt(cont, axis_size, d, axis_dest): 'nflexelem': False, 'nflexelemdata': False, 'nflexelemedge': False, + 'nflexshelldata': False, 'nflexvert': False, 'ngeom': False, 'ngravcomp': False, @@ -1353,6 +1422,8 @@ def _from_elt(cont, axis_size, d, axis_dest): 'pair_solreffriction': True, 'plugin': False, 'plugin_attr': False, + 'qLD_all_updates': False, + 'qLD_level_offsets': False, 'qLD_updates': False, 'qM_fullm_i': False, 'qM_fullm_j': False, @@ -1398,6 +1469,9 @@ def _from_elt(cont, axis_size, d, axis_dest): 'stat__meaninertia': True, 'taxel_sensorid': False, 'taxel_vertadr': False, + 'ten_J_colind': False, + 'ten_J_rowadr': False, + 'ten_J_rownnz': False, 'ten_wrapadr_site': False, 'ten_wrapnum_site': False, 'tendon_actfrclimited': False, From 72231cf83bd2fd0ac6fd5d24d67761ce939bcaa8 Mon Sep 17 00:00:00 2001 From: Sam Haves Date: Thu, 2 Apr 2026 04:42:11 -0700 Subject: [PATCH 20/20] Add condition to team notification of github actions that it's from 'main' PiperOrigin-RevId: 893437916 Change-Id: I0c0b22747e4e4cac23ad0f44cf8b667863cc79ae --- .github/workflows/build.yml | 6 +++--- include/mujoco/mjplugin.h | 10 +++++++++- 2 files changed, 12 insertions(+), 4 deletions(-) diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml index 6389087ef9..1a207fd95b 100644 --- a/.github/workflows/build.yml +++ b/.github/workflows/build.yml @@ -347,7 +347,7 @@ jobs: CHATMSG_AUTHOR_EMAIL: ${{ github.event.head_commit.author.email }} CHATMSG_COMMIT_MESSAGE: ${{ github.event.head_commit.message }} CHATMSG_JOB_ID: ${{ matrix.label }} - if: failure() && github.event_name == 'push' && env.GCHAT_API_URL != '' && github.ref_name == 'main' + if: failure() && github.ref_name == 'main' && github.event_name == 'push' && env.GCHAT_API_URL != '' run: bash ./.github/workflows/build_steps.sh notify_team_chat # This job quickly determines if MuJoCo Studio is broken. @@ -406,7 +406,7 @@ jobs: CHATMSG_AUTHOR_EMAIL: ${{ github.event.head_commit.author.email }} CHATMSG_COMMIT_MESSAGE: ${{ github.event.head_commit.message }} CHATMSG_JOB_ID: ${{ matrix.label }} - if: failure() && github.event_name == 'push' && env.GCHAT_API_URL != '' && github.ref_name == 'main' + if: failure() && github.ref_name == 'main' && github.event_name == 'push' && env.GCHAT_API_URL != '' run: bash ./.github/workflows/build_steps.sh notify_team_chat @@ -451,5 +451,5 @@ jobs: CHATMSG_AUTHOR_EMAIL: ${{ github.event.head_commit.author.email }} CHATMSG_COMMIT_MESSAGE: ${{ github.event.head_commit.message }} CHATMSG_JOB_ID: ${{ env.label }} - if: failure() && github.event_name == 'push' && env.GCHAT_API_URL != '' && github.ref_name == 'main' + if: failure() && github.ref_name == 'main' && github.event_name == 'push' && env.GCHAT_API_URL != '' run: bash ./.github/workflows/build_steps.sh notify_team_chat diff --git a/include/mujoco/mjplugin.h b/include/mujoco/mjplugin.h index ccd7369a54..80b1a96f04 100644 --- a/include/mujoco/mjplugin.h +++ b/include/mujoco/mjplugin.h @@ -199,12 +199,20 @@ typedef struct mjSDF_ mjSDF; #define LINKER_NAME "_mj_ptr_" #endif + #if !defined(mjEXTERNC) + #if defined(__cplusplus) + #define mjEXTERNC extern "C" + #else + #define mjEXTERNC + #endif // defined(__cplusplus) + #endif // !defined(mjEXTERNC) + #pragma section(".CRT$XCU", read) #define mjPLUGIN_LIB_INIT(n) \ static void __cdecl _mj_init_##n(void); \ /* We use extern "C" to prevent C++ name mangling */ \ - extern "C" __declspec(allocate(".CRT$XCU")) \ + mjEXTERNC __declspec(allocate(".CRT$XCU")) \ void (__cdecl * _mj_ptr_##n)(void) = _mj_init_##n; \ /* Force the linker to include the pointer symbol */ \ __pragma(comment(linker, "/include:" LINKER_NAME #n)) \