diff --git a/.git-blame-ignore-revs b/.git-blame-ignore-revs index 5fc6723b30..21efd4a470 100644 --- a/.git-blame-ignore-revs +++ b/.git-blame-ignore-revs @@ -7,5 +7,8 @@ # ruff check --fix (2024-08-12) 45576e056b2a1000a6fa16caabd015ce622093d1 +# pre-commit run -a (2024-08-28) +ccfc8509e21611b504f394b752a2f2a376a83022 + # pre-commit run -a (2024-09-04) d7c57794672df89734a80c40c0bd3166c7a984c6 diff --git a/.github/workflows/linux.yml b/.github/workflows/linux.yml index 78b3faa2e5..0783584bfc 100644 --- a/.github/workflows/linux.yml +++ b/.github/workflows/linux.yml @@ -6,25 +6,21 @@ on: - doc/** - .gitlab-ci.yml - .gitignore - - '*.md' + - '**.md' - CITATION.* - COPYING.LESSER - colcon.pkg - .pre-commit-config.yaml - - CHANGELOG.md - - development/*.md pull_request: paths-ignore: - doc/** - .gitlab-ci.yml - .gitignore - - '*.md' + - '**.md' - CITATION.* - COPYING.LESSER - colcon.pkg - .pre-commit-config.yaml - - CHANGELOG.md - - development/*.md concurrency: group: ${{ github.workflow }}-${{ github.ref }} cancel-in-progress: true @@ -36,7 +32,7 @@ jobs: container: ${{ matrix.container }} strategy: matrix: - container: ['ubuntu:20.04', 'ubuntu:22.04', 'ubuntu:24.04'] + container: ['ubuntu:22.04', 'ubuntu:24.04'] env: CCACHE_BASEDIR: ${GITHUB_WORKSPACE} @@ -211,8 +207,7 @@ jobs: - name: Display ccache statistics run: | - # TODO: Add -v option when we drop ubuntu-20.04 - ccache -s + ccache -sv check: if: always() diff --git a/.github/workflows/macos-linux-windows-pixi.yml b/.github/workflows/macos-linux-windows-pixi.yml index 3cd3c6c1b4..623ceb2662 100644 --- a/.github/workflows/macos-linux-windows-pixi.yml +++ b/.github/workflows/macos-linux-windows-pixi.yml @@ -8,25 +8,21 @@ on: - doc/** - .gitlab-ci.yml - .gitignore - - '*.md' + - '**.md' - CITATION.* - COPYING.LESSER - colcon.pkg - .pre-commit-config.yaml - - CHANGELOG.md - - development/*.md pull_request: paths-ignore: - doc/** - .gitlab-ci.yml - .gitignore - - '*.md' + - '**.md' - CITATION.* - COPYING.LESSER - colcon.pkg - .pre-commit-config.yaml - - CHANGELOG.md - - development/*.md concurrency: group: ${{ github.workflow }}-${{ github.ref }} cancel-in-progress: true diff --git a/.github/workflows/nix.yml b/.github/workflows/nix.yml index 2efe2bfc2b..1ced41bc41 100644 --- a/.github/workflows/nix.yml +++ b/.github/workflows/nix.yml @@ -6,12 +6,10 @@ on: - doc/** - .gitlab-ci.yml - .gitignore - - '*.md' + - '**.md' - CITATION.* - COPYING.LESSER - .pre-commit-config.yaml - - CHANGELOG.md - jobs: nix: runs-on: "${{ matrix.os }}-latest" diff --git a/.github/workflows/ros_ci.yml b/.github/workflows/ros_ci.yml index 101abf6507..ca87cc6230 100644 --- a/.github/workflows/ros_ci.yml +++ b/.github/workflows/ros_ci.yml @@ -10,25 +10,21 @@ on: - doc/** - .gitlab-ci.yml - .gitignore - - '*.md' + - '**.md' - CITATION.* - COPYING.LESSER - colcon.pkg - .pre-commit-config.yaml - - CHANGELOG.md - - development/*.md pull_request: paths-ignore: - doc/** - .gitlab-ci.yml - .gitignore - - '*.md' + - '**.md' - CITATION.* - COPYING.LESSER - colcon.pkg - .pre-commit-config.yaml - - CHANGELOG.md - - development/*.md concurrency: group: ${{ github.workflow }}-${{ github.ref }} cancel-in-progress: true diff --git a/.gitlab-ci-private.yml b/.gitlab-ci-private.yml new file mode 100644 index 0000000000..f4c62825d7 --- /dev/null +++ b/.gitlab-ci-private.yml @@ -0,0 +1,37 @@ +# use docker image with pixi installed (and not much else) +image: ghcr.io/prefix-dev/pixi:noble + +variables: + GIT_SUBMODULE_STRATEGY: recursive + PIXI_ENV: "collision" + CMAKE_BUILD_PARALLEL_LEVEL: 2 + CCACHE_BASEDIR: "${CI_PROJECT_DIR}" + CCACHE_DIR: "${CI_PROJECT_DIR}/.ccache" + CCACHE_COMPRESS: true + CCACHE_COMPRESSLEVEL: 6 + +test-job: + stage: test + tags: + - large + cache: + # Cache .pixi directory, invalidate the cache on lockfile + - key: + files: + - pixi.lock + paths: + - .pixi/ + # Cache .ccache directory for each branch + - key: ccache-$CI_COMMIT_REF_SLUG + fallback_keys: + - ccache-$CI_DEFAULT_BRANCH + paths: + - .ccache/ + + script: + - echo "ccache pre build statistics" + - pixi run -e $PIXI_ENV ccache -sv + - echo "Run pixi run test" + - pixi run -e $PIXI_ENV test + - echo "ccache post build statistics" + - pixi run -e $PIXI_ENV ccache -sv diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 8673a90b5e..038f5ab18a 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -30,6 +30,7 @@ repos: rev: v0.8.6 hooks: - id: ruff + args: [--fix] - id: ruff-format - repo: https://github.com/cheshirekow/cmake-format-precommit rev: v0.6.13 diff --git a/CHANGELOG.md b/CHANGELOG.md index faacbda656..2aec990cfc 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -6,6 +6,37 @@ The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.0.0/). ## [Unreleased] +### Added +- Added Lie group method `tangentMap` which gives, in the form of a `nq x nv` matrix, the linear mapping that transforms a configuration variation expressed in the Lie algebra (size `nv`) into a small variation expressed in the parametric space (size `nq`). Composed with Jacobian of other methods of Pinocchio that use the Lie group structure, it allows obtaining standard Jacobians in order to, for example, insert Pinocchio derivatives into standard Euclidean differentiation pipelines. +- Added Lie group methods `tangentMapProduct` and `tangentMapTransport` that apply `tangentMap` while exploiting sparsity. +- Added model methods `tangentMap`, `tangentMapProduct` and `tangentMapTransport` that perform tangent map for the whole configuration space of the model. +- Now all Lie group related algorithms (e.g. `dIntegrate`...) work seamlessly for models having some mimic joints. +- Added joint methods `jointQrows`, `jointQcols` (resp. `jointQVblock`) that make selections of size `NQ` (resp. `NQ x NV`). +- Added joint method `lieGroup` that returns the Lie group instance associated to a joint. This allows performing some operations (e.g. `integrate`...) individually. +- Added model method `lieGroup` that returns the Lie group instance associated to the model. It is a Cartesian product of multiple Lie groups. It allows combination of the model Lie group with other Lie groups. +- Add Python example showcasing the candlewick visualizer + +### Changed + +- bindings/python : Add missing arg names in `visualizer-visitor.hpp` +- use deprecation, warning macros already provided by jrl-cmakemodules +- renamed `PINOCCHIO_PRAGMA_DEPRECATED_HEADER` to `PINOCCHIO_DEPRECATED_MOVED_HEADER` +- docs : update documentation stylesheet, fix some Doxygen config options + +### Removed + +- Remove unused headers `deprecated-macros.hpp` and `deprecated-namespaces.hpp` +- Remove header `pinocchio/deprecation.hpp`, directly use generated `pinocchio/deprecated.hpp` +- macros.hpp : remove macros already provided by jrl-cmakemodules +- bindings/python : deprecate and remove contents of `utils/copyable.hpp`, `utils/registration.hpp` and `utils/deprecation.hpp`, include corresponding eigenpy headers instead + +## [3.7.0] - 2025-05-21 + +### Changed +- Change the default branch to `devel` ([#2666](https://github.com/stack-of-tasks/pinocchio/pull/2666)) +- Implement `captureImage` for Panda3D visualizer for video recording ([#2668](https://github.com/stack-of-tasks/pinocchio/pull/2668)) +- Drop Ubuntu 20.04 support ([#2680](https://github.com/stack-of-tasks/pinocchio/pull/2680)) + ## [3.6.0] - 2025-04-28 ### Fixed @@ -17,7 +48,6 @@ The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.0.0/). - Add explicit template instantiation for constraint algorithms for `casadi`, `CppAD` and `CppADCodeGen` scalar ([#2659](https://github.com/stack-of-tasks/pinocchio/pull/2659)) - Add `casadi` bindings for `pinocchio.initConstraintDynamics` and `pinocchio.constraintDynamics` ([#2659](https://github.com/stack-of-tasks/pinocchio/pull/2659)) - ## [3.5.0] - 2025-04-02 ### Added @@ -64,8 +94,16 @@ The format is based on [Keep a Changelog](https://keepachangelog.com/en/1.0.0/). ## [3.4.0] - 2025-02-12 ### Added +- Helpers for mapping heap allocation for Eigen::Map via alloca +- Introduce EigenStorageTpl - Add parsing meshes with vertices for MJCF format ([#2537](https://github.com/stack-of-tasks/pinocchio/pull/2537)) +### Changed +- Major refactorization of ContactCholeskyDecompositionTpl to ease online resizing + +### Removed +- Remove DataTpl::lastChild field and associated methods + ### Fixed - Fix mjcf Euler angle parsing: use xyz as a default value for eulerseq compiler option ([#2526](https://github.com/stack-of-tasks/pinocchio/pull/2526)) - Fix variable naming in Python ([#2530](https://github.com/stack-of-tasks/pinocchio/pull/2530)) @@ -1142,7 +1180,8 @@ The model can either be parsed from a URDF format or be created by appendending • Fixed (concatenation of two consecutive bodies) -[Unreleased]: https://github.com/stack-of-tasks/pinocchio/compare/v3.6.0...HEAD +[Unreleased]: https://github.com/stack-of-tasks/pinocchio/compare/v3.7.0...HEAD +[3.7.0]: https://github.com/stack-of-tasks/pinocchio/compare/v3.6.0...v3.7.0 [3.6.0]: https://github.com/stack-of-tasks/pinocchio/compare/v3.5.0...v3.6.0 [3.5.0]: https://github.com/stack-of-tasks/pinocchio/compare/v3.4.0...v3.5.0 [3.4.0]: https://github.com/stack-of-tasks/pinocchio/compare/v3.3.1...v3.4.0 diff --git a/CITATION.cff b/CITATION.cff index 469969df95..a999e80c7a 100644 --- a/CITATION.cff +++ b/CITATION.cff @@ -17,7 +17,7 @@ authors: given-names: Guilhem - family-names: Budhiraja given-names: Rohan -version: 3.6.0 -date-released: "2025-04-28" +version: 3.7.0 +date-released: "2025-05-21" license: BSD-2-Clause repository-code: "https://github.com/stack-of-tasks/pinocchio" diff --git a/CMakeLists.txt b/CMakeLists.txt index 08b2efb83b..b0a616ce92 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -3,7 +3,7 @@ # Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France. # -cmake_minimum_required(VERSION 3.16) +cmake_minimum_required(VERSION 3.22) set(PROJECT_NAME pinocchio) set(PROJECT_DESCRIPTION @@ -87,6 +87,7 @@ include("${JRL_CMAKE_MODULES}/base.cmake") compute_project_args(PROJECT_ARGS LANGUAGES CXX) project(${PROJECT_NAME} ${PROJECT_ARGS}) +include("${JRL_CMAKE_MODULES}/tracy.cmake") include("${JRL_CMAKE_MODULES}/python.cmake") include("${JRL_CMAKE_MODULES}/boost.cmake") include("${JRL_CMAKE_MODULES}/ide.cmake") @@ -162,6 +163,8 @@ option(CHECK_RUNTIME_MALLOC "Check if some memory allocations are performed at r option(ENABLE_TEMPLATE_INSTANTIATION "Template instantiation of the main library" ON) +option(PINOCCHIO_BUILD_WITH_TRACY "Build with tracy profiler for performance analysis" OFF) + # Variable containing all the cflags definition, options and libraries to setup pkg-config. set(CFLAGS_OPTIONS) set(CFLAGS_DEPENDENCIES) @@ -243,6 +246,21 @@ if(BUILD_WITH_PARSERS_SUPPORT) list(APPEND LIBRARIES_DEPENDENCIES ${PROJECT_NAME}_parsers) endif() +# -- tracy (optional) +if(PINOCCHIO_BUILD_WITH_TRACY) + # assume it is installed somewhere + add_project_dependency(Tracy REQUIRED) + set_target_properties(Tracy::TracyClient PROPERTIES POSITION_INDEPENDENT_CODE True) + if(${Tracy_FOUND}) + message(STATUS "Tracy found on your system at ${Tracy_DIR}") + else() + message( + FATAL_ERROR + "Pinocchio support for tracy is enabled, but tracy was not found on your system." + " Install it, or set the option PINOCCHIO_DOWNLOAD_TRACY to ON so we can fetch it.") + endif() +endif(PINOCCHIO_BUILD_WITH_TRACY) + if(BUILD_WITH_AUTODIFF_SUPPORT) # Check first CppADCodeGen if(BUILD_WITH_CODEGEN_SUPPORT) @@ -480,6 +498,10 @@ endmacro( var_name var_value) +if(PINOCCHIO_BUILD_WITH_TRACY) + export_variable(PINOCCHIO_USE_TRACY ON) + set(PACKAGE_EXTRA_MACROS "${PACKAGE_EXTRA_MACROS}\nset(PINOCCHIO_USE_TRACY \"\")") +endif() if(BUILD_WITH_URDF_SUPPORT) export_variable(PINOCCHIO_USE_URDFDOM ON) set(PACKAGE_EXTRA_MACROS "${PACKAGE_EXTRA_MACROS}\nset(PINOCCHIO_USE_URDFDOM \"\")") diff --git a/README.md b/README.md index e9e0b6ff34..5ba1105a18 100644 --- a/README.md +++ b/README.md @@ -1,17 +1,17 @@

- Pinocchio Logo + Pinocchio Logo

License - Documentation - Coverage Report + Documentation + Coverage Report Conda Downloads Conda Version PyPI version - pre-commit.ci status + pre-commit.ci status
- +

@@ -27,7 +27,7 @@ It is built upon Eigen for linear algebra and FCL for collision detection. **Pin **Pinocchio** is now at the heart of various robotics software as [Crocoddyl](https://github.com/loco-3d/crocoddyl/tree/devel), an open-source and efficient Differential Dynamic Programming solver for robotics, the [Stack-of-Tasks](http://stack-of-tasks.github.io), an open-source and versatile hierarchical controller framework or the [Humanoid Path Planner](https://humanoid-path-planner.github.io/hpp-doc), open-source software for Motion and Manipulation Planning. -If you want to learn more about **Pinocchio** internal behaviors and main features, we invite you to read the related [paper](https://hal-laas.archives-ouvertes.fr/hal-01866228) and the online [documentation](https://gepettoweb.laas.fr/doc/stack-of-tasks/pinocchio/master/doxygen-html/). +If you want to learn more about **Pinocchio** internal behaviors and main features, we invite you to read the related [paper](https://hal-laas.archives-ouvertes.fr/hal-01866228) and the online [documentation](https://gepettoweb.laas.fr/doc/stack-of-tasks/pinocchio/devel/doxygen-html/). If you want to dive into **Pinocchio** directly, only one single line is sufficient (assuming you have Conda): @@ -102,17 +102,17 @@ or via pip (currently only available on Linux): ## Documentation -The online **Pinocchio** documentation of the last release is available [here](https://gepettoweb.laas.fr/doc/stack-of-tasks/pinocchio/master/doxygen-html/). A cheat sheet pdf with the main functions and algorithms can be found [here](https://github.com/stack-of-tasks/pinocchio/blob/master/doc/pinocchio_cheat_sheet.pdf). +The online **Pinocchio** documentation of the last release is available [here](https://gepettoweb.laas.fr/doc/stack-of-tasks/pinocchio/devel/doxygen-html/). A cheat sheet pdf with the main functions and algorithms can be found [here](https://github.com/stack-of-tasks/pinocchio/blob/devel/doc/pinocchio_cheat_sheet.pdf). ## Examples -In the [examples](https://github.com/stack-of-tasks/pinocchio/tree/master/examples) directory, we provide some basic examples of using Pinocchio in Python. -Additional examples introducing **Pinocchio** are also available in the [documentation](https://gepettoweb.laas.fr/doc/stack-of-tasks/pinocchio/master/doxygen-html/md_doc_d-practical-exercises_intro.html). +In the [examples](https://github.com/stack-of-tasks/pinocchio/tree/devel/examples) directory, we provide some basic examples of using Pinocchio in Python. +Additional examples introducing **Pinocchio** are also available in the [documentation](https://gepettoweb.laas.fr/doc/stack-of-tasks/pinocchio/devel/doxygen-html/md_doc_d-practical-exercises_intro.html). ## Tutorials **Pinocchio** comes with a large bunch of tutorials aiming at introducing the basic tools for robot control. -Tutorial and training documents are listed [here](https://gepettoweb.laas.fr/doc/stack-of-tasks/pinocchio/master/doxygen-html/index.html#OverviewConclu). +Tutorial and training documents are listed [here](https://gepettoweb.laas.fr/doc/stack-of-tasks/pinocchio/devel/doxygen-html/index.html#OverviewConclu). You can also consider the interactive Jupyter notebook [set of tutorials](https://github.com/ymontmarin/_tps_robotique) developed by [Nicolas Mansard](https://gepettoweb.laas.fr/index.php/Members/NicolasMansard) and [Yann de Mont-Marin](https://github.com/ymontmarin). ## Pinocchio continuous integrations @@ -130,7 +130,7 @@ You can also consider the interactive Jupyter notebook [set of tutorials](https: CI on Windows via Conda windows CI on Linux via Robotpkg - Pipeline Status + Pipeline Status

@@ -140,7 +140,7 @@ You can also consider the interactive Jupyter notebook [set of tutorials](https: **Pinocchio** exploits, at best, the sparsity induced by the kinematic tree of robotics systems. Thanks to modern programming language paradigms, **Pinocchio** can unroll most of the computations directly at compile time, allowing to achieve impressive performances for an extensive range of robots, as illustrated by the plot below, obtained on a standard laptop equipped with an Intel Core i7 CPU @ 2.4 GHz.

- Pinocchio Logo + Pinocchio Logo

For other benchmarks, and mainly the capacity of Pinocchio to exploit, at best, your CPU capacities using advanced code generation techniques, we refer to the technical [paper](https://hal-laas.archives-ouvertes.fr/hal-01866228). @@ -149,7 +149,7 @@ In addition, the [introspection](https://github.com/rbd-benchmarks/rbd-benchmark ## Ongoing developments If you want to follow the current developments, you can refer to the [devel branch](https://github.com/stack-of-tasks/pinocchio/tree/devel). -The [master branch](https://github.com/stack-of-tasks/pinocchio/tree/master/) only contains the latest release. Any new Pull Request should be submitted on the [devel branch](https://github.com/stack-of-tasks/pinocchio/tree/devel/). +The [devel branch](https://github.com/stack-of-tasks/pinocchio/tree/devel/) only contains the latest release. Any new Pull Request should be submitted on the [devel branch](https://github.com/stack-of-tasks/pinocchio/tree/devel/). ## Installation @@ -204,7 +204,7 @@ Please note that we always advise including the `pinocchio/fwd.hpp` header as th - [Panda3d](https://github.com/ikalevatykh/panda3d_viewer): supporting visualization in Python and which can be embedded inside any browser. - [RViz](https://github.com/ros-visualization/rviz): supporting visualization in Python and which can interact with other ROS packages. -Many external viewers can also be integrated. For more information, see the example [here](https://github.com/stack-of-tasks/pinocchio/blob/master/bindings/python/pinocchio/visualize/base_visualizer.py). +Many external viewers can also be integrated. For more information, see the example [here](https://github.com/stack-of-tasks/pinocchio/blob/devel/bindings/python/pinocchio/visualize/base_visualizer.py). ## Citing Pinocchio @@ -253,7 +253,7 @@ The currently active core developers of **Pinocchio** are: - [Justin Carpentier](https://jcarpent.github.io) (Inria): main developer and manager of the project - [Guilhem Saurel](https://www.laas.fr/fr/annuaire/gsaurel) (LAAS-CNRS): CI/CD, packaging - [Etienne Arlaud](https://github.com/EtienneAr) (Inria): core developer -- [Wilson Jallet](https://github.com/ManifoldFR) (LAAS-CNRS/Inria): extension of Python bindings, C++ visualization API +- [Wilson Jallet](https://github.com/ManifoldFR) (Inria): extension of Python bindings, C++ visualization API - [Fabian Schramm](https://github.com/fabinsch) (Inria): core developper - [Stéphane Caron](https://scaron.info) (Inria): core developper - [Joris Vaillant](https://github.com/jorisv) (Inria): core developer and project manager diff --git a/benchmark/CMakeLists.txt b/benchmark/CMakeLists.txt index e8d3b906d8..a3197c7445 100644 --- a/benchmark/CMakeLists.txt +++ b/benchmark/CMakeLists.txt @@ -1,15 +1,16 @@ # -# Copyright (c) 2015-2023 CNRS INRIA +# Copyright (c) 2015-2018 CNRS +# Copyright (c) 2018-2025 INRIA # # ---------------------------------------------------- # --- BENCHMARK -------------------------------------- # ---------------------------------------------------- -add_custom_target(bench) +add_custom_target(${PROJECT_NAME}-benchmarks) add_project_private_dependency(benchmark REQUIRED) -function(ADD_PINOCCHIO_BENCH name) +function(ADD_PINOCCHIO_BENCHMARK name) set(options PARSERS COLLISION @@ -27,7 +28,7 @@ function(ADD_PINOCCHIO_BENCH name) set(multiValueArgs) cmake_parse_arguments(bench "${options}" "${oneValueArgs}" "${multiValueArgs}" ${ARGN}) - set(bench_name "pinocchio-${name}") + set(bench_name "pinocchio-benchmark-${name}") add_executable(${bench_name} ${name}.cpp) target_compile_definitions(${bench_name} PRIVATE PINOCCHIO_MODEL_DIR="${PINOCCHIO_MODEL_DIR}") @@ -65,57 +66,58 @@ function(ADD_PINOCCHIO_BENCH name) target_link_libraries(${bench_name} PRIVATE ${CMAKE_DL_LIBS}) endif() - add_dependencies(bench ${bench_name}) + add_dependencies(${PROJECT_NAME}-benchmarks ${bench_name}) endfunction() +add_pinocchio_benchmark(spatial-operations) + # timings # -add_pinocchio_bench(timings PARSERS) +add_pinocchio_benchmark(timings PARSERS) if(BUILD_WITH_CODEGEN_SUPPORT) - add_pinocchio_bench(timings-cg PARSERS CPPADCG) + add_pinocchio_benchmark(timings-cg PARSERS CPPADCG) endif() if(BUILD_WITH_OPENMP_SUPPORT) - add_pinocchio_bench(timings-parallel PARSERS PARALLEL COLLISION_PARALLEL_OPTIONAL) + add_pinocchio_benchmark(timings-parallel PARSERS PARALLEL COLLISION_PARALLEL_OPTIONAL) endif() # timings cholesky # -add_pinocchio_bench(timings-cholesky PARSERS) +add_pinocchio_benchmark(timings-cholesky PARSERS) +add_pinocchio_benchmark(timings-loop-constrained-aba PARSERS) # timings derivatives # -add_pinocchio_bench(timings-derivatives PARSERS) +add_pinocchio_benchmark(timings-derivatives PARSERS) if(BUILD_WITH_AUTODIFF_SUPPORT) # timings-cppad-jit - add_pinocchio_bench(timings-cppad-jit CPPAD) + add_pinocchio_benchmark(timings-cppad-jit CPPAD) endif() # timings-eigen -add_pinocchio_bench(timings-eigen) -modernize_target_link_libraries( - pinocchio-timings-eigen - SCOPE PUBLIC - TARGETS Eigen3::Eigen - INCLUDE_DIRS ${EIGEN3_INCLUDE_DIR}) +add_pinocchio_benchmark(timings-eigen) + +# timings-linalg +add_pinocchio_benchmark(timings-linalg-inverse) # timings-geometry # if(BUILD_WITH_URDF_SUPPORT AND BUILD_WITH_COLLISION_SUPPORT) - add_pinocchio_bench(timings-geometry PARSERS COLLISION) + add_pinocchio_benchmark(timings-geometry PARSERS COLLISION) endif() # timings-jacobian # -add_pinocchio_bench(timings-jacobian PARSERS) +add_pinocchio_benchmark(timings-jacobian PARSERS) # timings-contact-dynamics # -add_pinocchio_bench(timings-delassus-operations PARSERS) -add_pinocchio_bench(timings-contact-dynamics PARSERS) -add_pinocchio_bench(timings-constrained-dynamics-derivatives PARSERS) +add_pinocchio_benchmark(timings-delassus-operations PARSERS) +add_pinocchio_benchmark(timings-contact-dynamics PARSERS) +add_pinocchio_benchmark(timings-constrained-dynamics-derivatives PARSERS) # timings-impulse-dynamics # -add_pinocchio_bench(timings-impulse-dynamics PARSERS) -add_pinocchio_bench(timings-impulse-dynamics-derivatives PARSERS) +add_pinocchio_benchmark(timings-impulse-dynamics PARSERS) +add_pinocchio_benchmark(timings-impulse-dynamics-derivatives PARSERS) diff --git a/benchmark/model-fixture.hpp b/benchmark/model-fixture.hpp index d7ea4e758b..e05d3f17c9 100644 --- a/benchmark/model-fixture.hpp +++ b/benchmark/model-fixture.hpp @@ -16,8 +16,6 @@ #include -#include - #include /// Store custom command line arguments diff --git a/benchmark/spatial-operations.cpp b/benchmark/spatial-operations.cpp new file mode 100644 index 0000000000..5835ba9049 --- /dev/null +++ b/benchmark/spatial-operations.cpp @@ -0,0 +1,307 @@ +// +// Copyright (c) 2025 INRIA +// + +#include "pinocchio/spatial/inertia.hpp" +#include "pinocchio/spatial/se3.hpp" +#include "pinocchio/spatial/motion.hpp" +#include "pinocchio/spatial/force.hpp" + +#include "pinocchio/algorithm/aba.hpp" + +#include + +using namespace pinocchio; + +static void CustomArguments(benchmark::internal::Benchmark * b) +{ + b->MinWarmUpTime(30.)->Iterations(int(1e8)); +} + +void homgeneous_multiplication(benchmark::State & st) +{ + using Matrix4 = SE3::Matrix4; + Matrix4 M1 = Matrix4::Random(); + Matrix4 M2 = Matrix4::Random(); + for (auto _ : st) + { + Matrix4 M3 = M1 * M2; + benchmark::DoNotOptimize(M3); + } +} + +template +void se3_action(benchmark::State & st) +{ + SE3 M = SE3::Random(); + SpatialType obj = SpatialType::Random(); + for (auto _ : st) + { + auto res = M.act(obj); + benchmark::DoNotOptimize(res); + } +} + +void cross_operation(benchmark::State & st) +{ + SE3::Vector3 t = SE3::Vector3::Random(); + for (auto _ : st) + { + auto t_skew = skew(t); + benchmark::DoNotOptimize(t_skew); + } +} + +template +void matrix_matrix_add(benchmark::State & st) +{ + using Matrix = Eigen::Matrix; + Matrix M1 = Matrix::Random(); + Matrix M2 = Matrix::Random(); + for (auto _ : st) + { + Matrix M3 = M1 + M2; + benchmark::DoNotOptimize(M3); + } +} + +template +void matrix_matrix_plus_equal(benchmark::State & st) +{ + using Matrix = Eigen::Matrix; + Matrix M1 = Matrix::Random(); + Matrix M2 = Matrix::Random(); + for (auto _ : st) + { + M2 += M1; + benchmark::DoNotOptimize(M2); + } +} + +void inertia_matrix_transformation_ouput_arg(benchmark::State & st) +{ + const Inertia spatial_inertia = Inertia::Random(); + Inertia::Matrix6 matrix; + for (auto _ : st) + { + spatial_inertia.matrix(matrix); + benchmark::DoNotOptimize(matrix); + } +} + +void inertia_matrix_transformation_assignment(benchmark::State & st) +{ + const Inertia spatial_inertia = Inertia::Random(); + for (auto _ : st) + { + auto matrix = spatial_inertia.matrix(); + benchmark::DoNotOptimize(matrix); + } +} + +void inertia_se3_action(benchmark::State & st) +{ + Inertia spatial_inertia = Inertia::Random(); + SE3 placement = SE3::Random(); + for (auto _ : st) + { + auto inertia = placement.act(spatial_inertia); + benchmark::DoNotOptimize(inertia); + } +} + +void dense_inertia_se3_action(benchmark::State & st) +{ + using Matrix6 = Inertia::Matrix6; + using Scalar = Inertia::Scalar; + Inertia spatial_inertia = Inertia::Random(); + Matrix6 dense_inertia_matrix = spatial_inertia.matrix(); + SE3 placement = SE3::Random(); + for (auto _ : st) + { + Matrix6 res = impl::internal::SE3actOn::run(placement, dense_inertia_matrix); + benchmark::DoNotOptimize(res); + } +} + +void inertia_set_zero(benchmark::State & st) +{ + for (auto _ : st) + { + Inertia spatial_inertia; + spatial_inertia.setZero(); + benchmark::DoNotOptimize(spatial_inertia); + } +} + +void inertia_init_from_zero(benchmark::State & st) +{ + for (auto _ : st) + { + Inertia spatial_inertia = Inertia::Zero(); + benchmark::DoNotOptimize(spatial_inertia); + } +} + +void inertia_motion_product(benchmark::State & st) +{ + Inertia spatial_inertia = Inertia::Random(); + Motion spatial_motion = Motion::Random(); + for (auto _ : st) + { + Force spatial_force = spatial_inertia * spatial_motion; + benchmark::DoNotOptimize(spatial_force); + } +} + +void force_init_from_zero(benchmark::State & st) +{ + for (auto _ : st) + { + Force spatial_force = Force::Zero(); + benchmark::DoNotOptimize(spatial_force); + } +} + +void force_set_zero(benchmark::State & st) +{ + for (auto _ : st) + { + Force spatial_force; + spatial_force.setZero(); + benchmark::DoNotOptimize(spatial_force); + } +} + +void force_no_init(benchmark::State & st) +{ + for (auto _ : st) + { + Force spatial_force; + benchmark::DoNotOptimize(spatial_force); + } +} + +void matrix_times_vector6(benchmark::State & st) +{ + Inertia::Matrix6 mat6 = Inertia::Matrix6::Random(); + Motion::Vector6 vec6 = Motion::Vector6::Random(); + Force res = Force::Zero(); + for (auto _ : st) + { + res.toVector().noalias() += mat6 * vec6; + benchmark::DoNotOptimize(res); + } +} + +void matrix_times_vector_static_dispatch(benchmark::State & st) +{ + typedef Eigen::Matrix Matrix6; + typedef Eigen::Matrix Vector6; + + Matrix6 mat = Matrix6::Random(); + Vector6 vec = Vector6::Random(); + Force res = Force::Zero(); + for (auto _ : st) + { + auto size = st.range(0); +#define CASE_OP(n) \ + case n: \ + res.toVector().noalias() += mat.leftCols() * vec.head(); \ + break; + +#define CASE_OP_DYN(n) \ + case n: \ + res.toVector().noalias() += mat.leftCols(size) * vec.head(size); \ + break; + + switch (size) + { + CASE_OP(1) + CASE_OP(2) + CASE_OP(3) + CASE_OP(4) + CASE_OP(5) + CASE_OP(6) + default: + break; + } + +#undef CASE_OP + benchmark::DoNotOptimize(size); + benchmark::DoNotOptimize(res); + } +} + +void matrix_times_vector_dynamic_dispatch(benchmark::State & st) +{ + typedef Eigen::Matrix Matrix6; + typedef Eigen::Matrix Vector6; + + Matrix6 mat = Matrix6::Random(); + Vector6 vec = Vector6::Random(); + Force res = Force::Zero(); + for (auto _ : st) + { + auto size = st.range(0); + + res.toVector().noalias() += mat.leftCols(size) * vec.head(size); + benchmark::DoNotOptimize(size); + benchmark::DoNotOptimize(res); + } +} + +// Matrix operations +BENCHMARK(matrix_matrix_add<2>)->Apply(CustomArguments); +BENCHMARK(matrix_matrix_add<3>)->Apply(CustomArguments); +BENCHMARK(matrix_matrix_add<4>)->Apply(CustomArguments); +BENCHMARK(matrix_matrix_add<5>)->Apply(CustomArguments); +BENCHMARK(matrix_matrix_add<6>)->Apply(CustomArguments); + +BENCHMARK(matrix_matrix_plus_equal<2>)->Apply(CustomArguments); +BENCHMARK(matrix_matrix_plus_equal<3>)->Apply(CustomArguments); +BENCHMARK(matrix_matrix_plus_equal<4>)->Apply(CustomArguments); +BENCHMARK(matrix_matrix_plus_equal<5>)->Apply(CustomArguments); +BENCHMARK(matrix_matrix_plus_equal<6>)->Apply(CustomArguments); + +// SE3 +BENCHMARK(homgeneous_multiplication)->Apply(CustomArguments); +BENCHMARK(se3_action)->Apply(CustomArguments); +BENCHMARK(se3_action)->Apply(CustomArguments); +BENCHMARK(se3_action)->Apply(CustomArguments); +BENCHMARK(se3_action)->Apply(CustomArguments); +BENCHMARK(cross_operation)->Apply(CustomArguments); + +// Inertias +BENCHMARK(inertia_init_from_zero)->Apply(CustomArguments); +BENCHMARK(inertia_set_zero)->Apply(CustomArguments); +BENCHMARK(inertia_matrix_transformation_ouput_arg)->Apply(CustomArguments); +BENCHMARK(inertia_matrix_transformation_assignment)->Apply(CustomArguments); +BENCHMARK(inertia_se3_action)->Apply(CustomArguments); +BENCHMARK(inertia_motion_product)->Apply(CustomArguments); +BENCHMARK(dense_inertia_se3_action)->Apply(CustomArguments); + +// Forces +BENCHMARK(force_no_init)->Apply(CustomArguments); +BENCHMARK(force_init_from_zero)->Apply(CustomArguments); +BENCHMARK(force_set_zero)->Apply(CustomArguments); + +// Others +BENCHMARK(matrix_times_vector6)->Apply(CustomArguments); +BENCHMARK(matrix_times_vector_static_dispatch) + ->Apply(CustomArguments) + ->Arg(1) + ->Arg(2) + ->Arg(3) + ->Arg(4) + ->Arg(5) + ->Arg(6); +BENCHMARK(matrix_times_vector_dynamic_dispatch) + ->Apply(CustomArguments) + ->Arg(1) + ->Arg(2) + ->Arg(3) + ->Arg(4) + ->Arg(5) + ->Arg(6); +BENCHMARK_MAIN(); diff --git a/benchmark/timings-eigen.cpp b/benchmark/timings-eigen.cpp index f720800de4..fa92a25a58 100644 --- a/benchmark/timings-eigen.cpp +++ b/benchmark/timings-eigen.cpp @@ -1,12 +1,9 @@ // -// Copyright (c) 2015-2025 CNRS +// Copyright (c) 2015-2018 CNRS +// Copyright (c) 2018-2025 INRIA // -#include "pinocchio/macros.hpp" - -#include -#include -#include +#include "pinocchio/fwd.hpp" #include diff --git a/benchmark/timings-linalg-inverse.cpp b/benchmark/timings-linalg-inverse.cpp new file mode 100644 index 0000000000..67549d2537 --- /dev/null +++ b/benchmark/timings-linalg-inverse.cpp @@ -0,0 +1,229 @@ +// +// Copyright (c) 2025 INRIA +// + +#include "pinocchio/fwd.hpp" +#include "pinocchio/multibody/joint/joint-common-operations.hpp" + +#include + +using namespace pinocchio; + +template +using Matrix = Eigen::Matrix; +using DynamicMatrix = Matrix; + +#define DEFINE_MATRIX(size) \ + using Matrix##size = Matrix; \ + using RowMatrix##size = Matrix; + +DEFINE_MATRIX(1) +DEFINE_MATRIX(2) +DEFINE_MATRIX(3) +DEFINE_MATRIX(4) +DEFINE_MATRIX(5) +DEFINE_MATRIX(6) +DEFINE_MATRIX(7) +DEFINE_MATRIX(8) +DEFINE_MATRIX(9) +DEFINE_MATRIX(10) +DEFINE_MATRIX(11) +DEFINE_MATRIX(12) + +static void CustomArgumentsStaticMatrix(benchmark::internal::Benchmark * b) +{ + b->MinWarmUpTime(3.); +} + +struct MatrixInverseEigen +{ + template + PINOCCHIO_DONT_INLINE static void + run(const Eigen::MatrixBase & mat, const Eigen::MatrixBase & mat_inv) + { + mat_inv.const_cast_derived().noalias() = mat.inverse(); + } +}; + +struct MatrixInversePartialPivLU +{ + template + PINOCCHIO_DONT_INLINE static void + run(const Eigen::MatrixBase & mat, const Eigen::MatrixBase & mat_inv) + { + mat_inv.const_cast_derived().noalias() = mat.partialPivLu().inverse(); + } +}; + +struct MatrixInverseLLT +{ + template + PINOCCHIO_DONT_INLINE static void + run(const Eigen::MatrixBase & mat, const Eigen::MatrixBase & mat_inv) + { + mat_inv.const_cast_derived().setIdentity(); + mat.llt().solveInPlace(mat_inv.const_cast_derived()); + } +}; + +struct MatrixInverseLDLT +{ + template + PINOCCHIO_DONT_INLINE static void + run(const Eigen::MatrixBase & mat, const Eigen::MatrixBase & mat_inv) + { + mat_inv.const_cast_derived().setIdentity(); + mat.ldlt().solveInPlace(mat_inv.const_cast_derived()); + } +}; + +struct MatrixInversePinocchio +{ + template + PINOCCHIO_DONT_INLINE static void + run(const Eigen::MatrixBase & mat, const Eigen::MatrixBase & mat_inv) + { + ::pinocchio::matrix_inversion(mat, mat_inv.const_cast_derived()); + } +}; + +struct MatrixInverseCodeGenerated +{ + template + PINOCCHIO_DONT_INLINE static void + run(const Eigen::MatrixBase & mat, const Eigen::MatrixBase & mat_inv) + { + ::pinocchio::matrix_inversion_code_generated(mat, mat_inv.const_cast_derived()); + } +}; + +template +static void static_matrix_inversion_call(benchmark::State & st) +{ + const InputMatrix input_matrix = InputMatrix::Identity(); + OutputMatrix res = OutputMatrix::Zero(input_matrix.rows(), input_matrix.cols()); + for (auto _ : st) + { + MatrixInverseFunctor::run(input_matrix, res); + benchmark::DoNotOptimize(res); + } +} + +static void CustomArgumentsDynamicMatrix(benchmark::internal::Benchmark * b) +{ + b->MinWarmUpTime(3.); + for (int size = 1; size <= 12; ++size) + b->Arg(size); + + b->Arg(20)->Arg(50)->Arg(100); +} + +template +static void dynamic_matrix_inversion_call(benchmark::State & st) +{ + const auto size = st.range(0); + const InputMatrix input_matrix = InputMatrix::Identity(size, size); + OutputMatrix res = OutputMatrix::Zero(input_matrix.rows(), input_matrix.cols()); + for (auto _ : st) + { + MatrixInverseFunctor::run(input_matrix, res); + // pinocchio::internal::MatrixInversionDynamicMatrixImpl::run(input_matrix, res); + benchmark::DoNotOptimize(res); + } +} + +template +PINOCCHIO_DONT_INLINE void scalar_inversion_op(const Scalar & input_scalar, Scalar & output) +{ + output = Scalar(1) / input_scalar; +} + +void scalar_inversion(benchmark::State & st) +{ + const double input_scalar = Matrix1::Random().coeff(0, 0); + double scalar_inv = 0.; + for (auto _ : st) + { + scalar_inversion_op(input_scalar, scalar_inv); + benchmark::DoNotOptimize(scalar_inv); + } +} + +template +PINOCCHIO_DONT_INLINE void scalar_sqrt_op(const Scalar & input_scalar, Scalar & output) +{ + output = math::sqrt(input_scalar); +} + +void scalar_sqrt(benchmark::State & st) +{ + const double input_scalar = Matrix1::Random().coeff(0, 0); + double res_scalar = 0.; + for (auto _ : st) + { + scalar_sqrt_op(input_scalar, res_scalar); + benchmark::DoNotOptimize(res_scalar); + } +} + +template +PINOCCHIO_DONT_INLINE void scalar_multiplication_op(const Scalar & input_scalar, Scalar & output) +{ + output = input_scalar * input_scalar; +} + +void scalar_multiplication(benchmark::State & st) +{ + const double input_scalar = Matrix1::Random().coeff(0, 0); + double res_scalar = 0.; + for (auto _ : st) + { + scalar_multiplication_op(input_scalar, res_scalar); + benchmark::DoNotOptimize(res_scalar); + } +} + +#define BENCH_MATRIX_INVERSION(Call, Type, MatrixInverseFunctor, Arg) \ + BENCHMARK(Call)->Apply(Arg); \ + //BENCHMARK(Call)->Apply(Arg); \ + //BENCHMARK(Call->Apply(Arg)); \ + //BENCHMARK(Call)->Apply(Arg); + +#define BENCH_STATIC_MATRIX_INVERSION(Type, MatrixInverseFunctor) \ + BENCH_MATRIX_INVERSION( \ + static_matrix_inversion_call, Type, MatrixInverseFunctor, CustomArgumentsStaticMatrix) + +#define BENCH_STATIC_MATRIX_INVERSION_ALL(MatrixInverseFunctor) \ + BENCH_STATIC_MATRIX_INVERSION(Matrix1, MatrixInverseFunctor) \ + BENCH_STATIC_MATRIX_INVERSION(Matrix2, MatrixInverseFunctor) \ + BENCH_STATIC_MATRIX_INVERSION(Matrix3, MatrixInverseFunctor) \ + BENCH_STATIC_MATRIX_INVERSION(Matrix4, MatrixInverseFunctor) \ + BENCH_STATIC_MATRIX_INVERSION(Matrix5, MatrixInverseFunctor) \ + BENCH_STATIC_MATRIX_INVERSION(Matrix6, MatrixInverseFunctor) \ + BENCH_STATIC_MATRIX_INVERSION(Matrix7, MatrixInverseFunctor) \ + BENCH_STATIC_MATRIX_INVERSION(Matrix8, MatrixInverseFunctor) \ + BENCH_STATIC_MATRIX_INVERSION(Matrix9, MatrixInverseFunctor) \ + BENCH_STATIC_MATRIX_INVERSION(Matrix10, MatrixInverseFunctor) \ + BENCH_STATIC_MATRIX_INVERSION(Matrix11, MatrixInverseFunctor) \ + BENCH_STATIC_MATRIX_INVERSION(Matrix12, MatrixInverseFunctor) + +#define BENCH_DYNAMIC_MATRIX_INVERSION_ALL(MatrixInverseFunctor) \ + BENCH_MATRIX_INVERSION( \ + dynamic_matrix_inversion_call, DynamicMatrix, MatrixInverseFunctor, \ + CustomArgumentsDynamicMatrix) + +BENCHMARK(scalar_inversion)->Apply(CustomArgumentsStaticMatrix); +BENCHMARK(scalar_sqrt)->Apply(CustomArgumentsStaticMatrix); +BENCHMARK(scalar_multiplication)->Apply(CustomArgumentsStaticMatrix); + +BENCH_STATIC_MATRIX_INVERSION_ALL(MatrixInverseEigen) +BENCH_STATIC_MATRIX_INVERSION_ALL(MatrixInversePartialPivLU) +BENCH_STATIC_MATRIX_INVERSION_ALL(MatrixInverseLLT) +BENCH_STATIC_MATRIX_INVERSION_ALL(MatrixInverseLDLT) +BENCH_STATIC_MATRIX_INVERSION_ALL(MatrixInverseCodeGenerated) +BENCH_STATIC_MATRIX_INVERSION_ALL(MatrixInversePinocchio) + +BENCH_DYNAMIC_MATRIX_INVERSION_ALL(MatrixInverseEigen) +BENCH_DYNAMIC_MATRIX_INVERSION_ALL(MatrixInversePinocchio) + +BENCHMARK_MAIN(); diff --git a/benchmark/timings-loop-constrained-aba.cpp b/benchmark/timings-loop-constrained-aba.cpp new file mode 100644 index 0000000000..a72a63937a --- /dev/null +++ b/benchmark/timings-loop-constrained-aba.cpp @@ -0,0 +1,412 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#include "pinocchio/algorithm/contact-info.hpp" +#include "pinocchio/algorithm/joint-configuration.hpp" +#include "pinocchio/algorithm/kinematics.hpp" +#include "pinocchio/algorithm/kinematics-derivatives.hpp" +#include "pinocchio/algorithm/model.hpp" +#include "pinocchio/algorithm/rnea-derivatives.hpp" +#include "pinocchio/algorithm/aba-derivatives.hpp" +#include "pinocchio/algorithm/aba.hpp" +#include "pinocchio/algorithm/contact-dynamics.hpp" +#include "pinocchio/algorithm/constrained-dynamics.hpp" +#include "pinocchio/algorithm/cholesky.hpp" +#include "pinocchio/multibody/fwd.hpp" +#include "pinocchio/parsers/urdf.hpp" +#include "pinocchio/parsers/sample-models.hpp" +#include "pinocchio/algorithm/pv.hpp" +#include "pinocchio/algorithm/loop-constrained-aba.hpp" + +#include +#include + +#include "pinocchio/utils/timer.hpp" + +// usage ./benchmark/timings-CLCaba case_num prox-iters mu + +template +void print_first_n_vector_elements(std::vector v, int n) +{ + for (int i = 0; i < n; i++) + { + std::cout << v[i] << ", "; + } + std::cout << "\n"; +} + +int main(int argc, const char ** argv) +{ + using namespace Eigen; + using namespace pinocchio; + + PinocchioTicToc timer(PinocchioTicToc::US); +#ifdef NDEBUG + const int NBT = 10000; +#else + const int NBT = 10; + std::cout << "(the time score in debug mode is not relevant) " << std::endl; +#endif + + // Build model + Model model1; + + bool with_ff = false; + int case_num = 0; + + if (argc > 1) + { + case_num = std::stoi(std::string{argv[1]}); + if (case_num >= 1) + with_ff = true; + } + + // std::string filename = PINOCCHIO_MODEL_DIR + std::string("/shadow_hand.urdf"); + std::string filename; + if (case_num == 0) + filename = PINOCCHIO_MODEL_DIR + + std::string( + "/example-robot-data/robots/allegro_hand_description/urdf/allegro_left_hand.urdf"); + else if (case_num == 1) + filename = PINOCCHIO_MODEL_DIR + + std::string("/example-robot-data/robots/allegro_hand_description/urdf/" + "allegro_left_and_right_hands.urdf"); + else if (case_num >= 2) + filename = PINOCCHIO_MODEL_DIR + + std::string("/example-robot-data/robots/allegro_hand_description/urdf/" + "allegro_left_right_simple_humanoid.urdf"); + // std::string filename2 = PINOCCHIO_MODEL_DIR + + // std::string("/example-robot-data/robots/allegro_hand_description/urdf/allegro_right_hand.urdf"); + + // std::string filename3 = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.urdf"); + // if(argc>2) filename = argv[2]; + + if (with_ff) + pinocchio::urdf::buildModel(filename, JointModelFreeFlyer(), model1); + else + pinocchio::urdf::buildModel(filename, model1); + + Model & model = model1; + + std::vector allegro_hand_links{ + "link_3.0_tip", "link_7.0_tip", "link_11.0_tip", "link_15.0_tip"}; + std::vector allegro_right_hand_links{ + "link_3.0_tip_r", "link_7.0_tip_r", "link_11.0_tip_r", "link_15.0_tip_r"}; + + const std::string RF = allegro_hand_links[3]; + const JointIndex RF_id = model.frames[model.getFrameId(RF)].parent; + const std::string MF = allegro_hand_links[2]; + const JointIndex MF_id = model.frames[model.getFrameId(MF)].parent; + const std::string TF = allegro_hand_links[0]; + const JointIndex TF_id = model.frames[model.getFrameId(TF)].parent; + const std::string IF = allegro_hand_links[1]; + const JointIndex IF_id = model.frames[model.getFrameId(IF)].parent; + + const std::string RF_r = allegro_right_hand_links[3]; + const JointIndex RF_id_r = model.frames[model.getFrameId(RF)].parent; + const std::string MF_r = allegro_right_hand_links[2]; + const JointIndex MF_id_r = model.frames[model.getFrameId(MF)].parent; + const std::string TF_r = allegro_right_hand_links[0]; + const JointIndex TF_id_r = model.frames[model.getFrameId(TF)].parent; + const std::string IF_r = allegro_right_hand_links[1]; + const JointIndex IF_id_r = model.frames[model.getFrameId(IF)].parent; + + JointIndex cube_joint = model.addJoint(0, JointModelFreeFlyer(), SE3::Random(), "joint_cube"); + model.appendBodyToJoint(cube_joint, Inertia::Random(), SE3::Random()); + + ProximalSettings prox_settings; + if (argc > 2) + prox_settings.max_iter = std::stoi(std::string{argv[2]}); + else + prox_settings.max_iter = 20; + + prox_settings.mu = 1e-6; + if (argc > 3) + prox_settings.mu = std::pow(10, -1 * std::stoi(std::string{argv[3]})); + + prox_settings.relative_accuracy = 1e-18; + prox_settings.absolute_accuracy = 1e-10; + + std::cout << "nq = " << model.nq << std::endl; + std::cout << "nv = " << model.nv << std::endl; + std::cout << "--" << std::endl; + + Data data(model), data_caba(model), data_caba_ref(model); + VectorXd qmax = Eigen::VectorXd::Ones(model.nq); + + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(VectorXd) qs(NBT); + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(VectorXd) qdots(NBT); + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(VectorXd) qddots(NBT); + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(VectorXd) taus(NBT); + + for (size_t i = 0; i < NBT; ++i) + { + qs[i] = randomConfiguration(model, -qmax, qmax); + qdots[i] = Eigen::VectorXd::Random(model.nv) * 0; + qddots[i] = Eigen::VectorXd::Random(model.nv); + taus[i] = Eigen::VectorXd::Random(model.nv); + } + + timer.tic(); + SMOOTH(NBT) + { + aba(model, data, qs[_smooth], qdots[_smooth], taus[_smooth]); + } + + double total_time = 0; + + RigidConstraintModel ci_CL(CONTACT_3D, model, TF_id, cube_joint, LOCAL_WORLD_ALIGNED); + // ci_CL.joint1_placement.setRandom(); + ci_CL.joint2_placement.setRandom(); + + RigidConstraintModel ci_CL2(CONTACT_3D, model, IF_id, cube_joint, LOCAL_WORLD_ALIGNED); + // ci_CL2.joint1_placement.setRandom(); + ci_CL2.joint2_placement.setRandom(); + + RigidConstraintModel ci_CL3(CONTACT_3D, model, MF_id, cube_joint, LOCAL_WORLD_ALIGNED); + // ci_CL3.joint1_placement.setRandom(); + ci_CL3.joint2_placement.setRandom(); + + RigidConstraintModel ci_CL4(CONTACT_3D, model, RF_id, cube_joint, LOCAL_WORLD_ALIGNED); + // ci_CL4.joint1_placement.setRandom(); + ci_CL4.joint2_placement.setRandom(); + + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_model_CL; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_data_CL; + + if (case_num >= 0) + { + + contact_model_CL.push_back(ci_CL); + contact_data_CL.push_back(RigidConstraintData(ci_CL)); + contact_model_CL.push_back(ci_CL2); + contact_data_CL.push_back(RigidConstraintData(ci_CL2)); + contact_model_CL.push_back(ci_CL3); + contact_data_CL.push_back(RigidConstraintData(ci_CL3)); + contact_model_CL.push_back(ci_CL4); + contact_data_CL.push_back(RigidConstraintData(ci_CL4)); + } + + if (case_num >= 1) + { + RigidConstraintModel ci_CL_r(CONTACT_3D, model, TF_id_r, cube_joint, LOCAL_WORLD_ALIGNED); + // ci_CL_r.joint1_placement.setRandom(); + ci_CL_r.joint2_placement.setRandom(); + RigidConstraintModel ci_CL2_r(CONTACT_3D, model, IF_id_r, cube_joint, LOCAL_WORLD_ALIGNED); + // ci_CL2_r.joint1_placement.setRandom(); + ci_CL2_r.joint2_placement.setRandom(); + RigidConstraintModel ci_CL3_r(CONTACT_3D, model, MF_id_r, cube_joint, LOCAL_WORLD_ALIGNED); + // ci_CL3_r.joint1_placement.setRandom(); + ci_CL3_r.joint2_placement.setRandom(); + RigidConstraintModel ci_CL4_r(CONTACT_3D, model, RF_id_r, cube_joint, LOCAL_WORLD_ALIGNED); + // ci_CL4_r.joint1_placement.setRandom(); + ci_CL4_r.joint2_placement.setRandom(); + contact_model_CL.push_back(ci_CL_r); + contact_data_CL.push_back(RigidConstraintData(ci_CL_r)); + contact_model_CL.push_back(ci_CL2_r); + contact_data_CL.push_back(RigidConstraintData(ci_CL2_r)); + contact_model_CL.push_back(ci_CL3_r); + contact_data_CL.push_back(RigidConstraintData(ci_CL3_r)); + contact_model_CL.push_back(ci_CL4_r); + contact_data_CL.push_back(RigidConstraintData(ci_CL4_r)); + } + + JointIndex Foot_id; + // FEET constraints + if (case_num >= 3) + { + const std::string RFoot = "RLEG_LINK6"; + const JointIndex RFoot_id = model.frames[model.getFrameId(RFoot)].parent; + const std::string LFoot = "LLEG_LINK6"; + const JointIndex LFoot_id = model.frames[model.getFrameId(LFoot)].parent; + Foot_id = RFoot_id; + RigidConstraintModel ci_LFoot(CONTACT_6D, model, LFoot_id, LOCAL_WORLD_ALIGNED); + RigidConstraintModel ci_RFoot(CONTACT_6D, model, RFoot_id, LOCAL_WORLD_ALIGNED); + contact_model_CL.push_back(ci_LFoot); + contact_data_CL.push_back(RigidConstraintData(ci_LFoot)); + contact_model_CL.push_back(ci_RFoot); + contact_data_CL.push_back(RigidConstraintData(ci_LFoot)); + } + + std::vector lcaba_residual(NBT); + std::vector proxLTL_residual(NBT); + + std::vector lcaba_ddq_residual(NBT); + std::vector proxLTL_ddq_residual(NBT); + + std::vector lcaba_iter_count(NBT); + std::vector ltl_iter_count(NBT); + + bool residual_benchmarking = false; // Set to false to do timings benchmarking + if (residual_benchmarking) + { + // Investigate the convergence of the algorithms over different proximal iterations + computeJointMinimalOrdering(model, data_caba, contact_model_CL); + initConstraintDynamics(model, data_caba_ref, contact_model_CL); + initConstraintDynamics(model, data, contact_model_CL); + + double old_mu = prox_settings.mu; + int old_max_iter = prox_settings.max_iter; + + for (size_t _smooth = 0; _smooth < NBT; _smooth++) + { + prox_settings.max_iter = old_max_iter; + prox_settings.mu = old_mu; + lcaba( + model, data_caba, qs[_smooth], qdots[_smooth], taus[_smooth], contact_model_CL, + contact_data_CL, prox_settings); + lcaba_iter_count[_smooth] = prox_settings.iter; + // std::cout << "lcaba iter count = " << prox_settings.iter << std::endl; + + // ProximalSettings prox_settings_ltl{prox_settings}; + constraintDynamics( + model, data, qs[_smooth], qdots[_smooth], taus[_smooth], contact_model_CL, contact_data_CL, + prox_settings); + ltl_iter_count[_smooth] = prox_settings.iter; + + // std::cout << "proxLTL iter count = " << prox_settings.iter << std::endl; + // std::cout << "Constraint forces = " << data.lambda_c.transpose() << std::endl; + + prox_settings.max_iter = 50; + prox_settings.mu = 1e-3; + constraintDynamics( + model, data_caba_ref, qs[_smooth], qdots[_smooth], taus[_smooth], contact_model_CL, + contact_data_CL, prox_settings); + + long constraint_dim = data.lambda_c_prox.rows(); + const Eigen::MatrixXd & J_ref = + data.contact_chol.matrix().topRightCorner(constraint_dim, model.nv); + const Eigen::MatrixXd & rhs = data.primal_rhs_contact.topRows(constraint_dim); + Eigen::MatrixXd constraint_error = J_ref * data.ddq - rhs; + + lcaba_residual[_smooth] = (J_ref * data_caba.ddq - rhs).template lpNorm(); + proxLTL_residual[_smooth] = (J_ref * data.ddq - rhs).template lpNorm(); + + // std::cout << "ltl ddq = " << data.ddq.transpose() << std::endl; + // std::cout << "caba - ltl ddq = " << (data.ddq - data_caba.ddq).template + // lpNorm() << std::endl; lcaba_residual[_smooth] = + // (J_ref.transpose()*(J_ref*data_caba.ddq - rhs)).template lpNorm(); + // proxLTL_residual[_smooth] = (J_ref.transpose()*(J_ref*data.ddq - rhs)).template + // lpNorm(); + + lcaba_ddq_residual[_smooth] = + (data_caba_ref.ddq - data_caba.ddq).template lpNorm() + / data_caba_ref.ddq.template lpNorm(); + proxLTL_ddq_residual[_smooth] = + (data_caba_ref.ddq - data.ddq).template lpNorm() + / data_caba_ref.ddq.template lpNorm(); + } + + double lcaba_residual_sum = std::accumulate(lcaba_residual.begin(), lcaba_residual.end(), 0.0); + double lcaba_residual_mean = lcaba_residual_sum / NBT; + double lcaba_sq_sum = + std::inner_product(lcaba_residual.begin(), lcaba_residual.end(), lcaba_residual.begin(), 0.0); + double lcaba_residual_stddev = + std::sqrt(lcaba_sq_sum / NBT - lcaba_residual_mean * lcaba_residual_mean); + + // std::cout << "LCABA residual mean = " << lcaba_residual_mean << ", and std = " << + // lcaba_residual_stddev << ", max = " << *std::max_element(lcaba_residual.begin(), + // lcaba_residual.end()) << std::endl; + + // std::cout << "Constraint residual stats:" << lcaba_residual_mean << ", " << + // lcaba_residual_stddev << ", " << *std::max_element(lcaba_residual.begin(), + // lcaba_residual.end()) << ", " << *std::min_element(lcaba_residual.begin(), + // lcaba_residual.end()); + + double proxLTL_residual_sum = + std::accumulate(proxLTL_residual.begin(), proxLTL_residual.end(), 0.0); + double proxLTL_residual_mean = proxLTL_residual_sum / NBT; + double proxLTL_sq_sum = std::inner_product( + proxLTL_residual.begin(), proxLTL_residual.end(), proxLTL_residual.begin(), 0.0); + double proxLTL_residual_stddev = + std::sqrt(proxLTL_sq_sum / NBT - proxLTL_residual_mean * proxLTL_residual_mean); + + // std::cout << ", " << proxLTL_residual_mean << ", " << proxLTL_residual_stddev << ", " << + // *std::max_element(proxLTL_residual.begin(), proxLTL_residual.end()) << ", " << + // *std::min_element(proxLTL_residual.begin(), proxLTL_residual.end()) << std::endl; + + double lcaba_ddq_residual_sum = + std::accumulate(lcaba_ddq_residual.begin(), lcaba_ddq_residual.end(), 0.0); + double lcaba_ddq_residual_mean = lcaba_ddq_residual_sum / NBT; + lcaba_sq_sum = std::inner_product( + lcaba_ddq_residual.begin(), lcaba_ddq_residual.end(), lcaba_ddq_residual.begin(), 0.0); + double lcaba_ddq_residual_stddev = + std::sqrt(lcaba_sq_sum / NBT - lcaba_ddq_residual_mean * lcaba_ddq_residual_mean); + + // std::cout << "ddq residual mean = " << lcaba_ddq_residual_mean << ", and std = " << + // lcaba_ddq_residual_stddev << ", max = " << *std::max_element(lcaba_ddq_residual.begin(), + // lcaba_ddq_residual.end()) << std::endl; + + // std::cout << "LCABA constraint residuals (first 5)"; + // print_first_n_vector_elements(lcaba_residual, 5); std::cout << "LCABA ddq residuals (first + // 5)"; print_first_n_vector_elements(lcaba_ddq_residual, 5); std::cout << "LCABA iter count + // (first 5)"; print_first_n_vector_elements(lcaba_iter_count, 5); std::cout << "LCABA ddq + // residuals (first 5)"; print_first_n_vector_elements(proxLTL_ddq_residual, 5); + + double proxLTL_ddq_residual_sum = + std::accumulate(proxLTL_ddq_residual.begin(), proxLTL_ddq_residual.end(), 0.0); + double proxLTL_ddq_residual_mean = proxLTL_ddq_residual_sum / NBT; + proxLTL_sq_sum = std::inner_product( + proxLTL_ddq_residual.begin(), proxLTL_ddq_residual.end(), proxLTL_ddq_residual.begin(), 0.0); + double proxLTL_ddq_residual_stddev = + std::sqrt(proxLTL_sq_sum / NBT - proxLTL_ddq_residual_mean * proxLTL_ddq_residual_mean); + + // std::cout << "proxLTL ddq residual mean = " << proxLTL_ddq_residual_mean << ", and std = " << + // proxLTL_ddq_residual_stddev << ", max = " << *std::max_element(proxLTL_ddq_residual.begin(), + // proxLTL_ddq_residual.end()) << std::endl; + + std::cout << "ddq residual stats:" << lcaba_ddq_residual_mean << ", " + << lcaba_ddq_residual_stddev << ", " + << *std::max_element(lcaba_ddq_residual.begin(), lcaba_ddq_residual.end()) << ", " + << *std::min_element(lcaba_ddq_residual.begin(), lcaba_ddq_residual.end()) << ", " + << proxLTL_ddq_residual_mean << ", " << proxLTL_ddq_residual_stddev << ", " + << *std::max_element(proxLTL_ddq_residual.begin(), proxLTL_ddq_residual.end()) << ", " + << *std::min_element(proxLTL_ddq_residual.begin(), proxLTL_ddq_residual.end()) + << std::endl; + } + else + { + computeJointMinimalOrdering(model, data_caba, contact_model_CL); + timer.tic(); + SMOOTH(NBT) + { + lcaba( + model, data_caba, qs[_smooth], qdots[_smooth], taus[_smooth], contact_model_CL, + contact_data_CL, prox_settings); + } + std::cout << "CL-constrainedABA closed loops {6D} = \t"; + timer.toc(std::cout, NBT); + + initConstraintDynamics(model, data, contact_model_CL); + timer.tic(); + SMOOTH(NBT) + { + constraintDynamics( + model, data, qs[_smooth], qdots[_smooth], taus[_smooth], contact_model_CL, contact_data_CL, + prox_settings); + } + std::cout << "constraintDynamics closed loops {6D} = \t"; + timer.toc(std::cout, NBT); + + std::cout << "--" << std::endl; + + long constraint_dim = data.lambda_c_prox.rows(); + const Eigen::MatrixXd & J_ref = + data.contact_chol.matrix().topRightCorner(constraint_dim, model.nv); + const Eigen::MatrixXd & rhs = data.primal_rhs_contact.topRows(constraint_dim); + Eigen::VectorXd constraint_error = J_ref * data.ddq - rhs; + std::cout << "Constraint residual LTL = " << constraint_error.template lpNorm() + << std::endl; + std::cout << "Constraint residual LCABA = " + << (J_ref * data_caba.ddq - rhs).template lpNorm() << std::endl; + + std::cout << "constraint accelerations = " << (J_ref * data.ddq).transpose() << std::endl; + + std::cout << "Gravity = " << model.gravity.linear().transpose() << std::endl; + + std::cout << "--" << std::endl; + } + + return 0; +} diff --git a/bindings/python/algorithm/admm-solver.cpp b/bindings/python/algorithm/admm-solver.cpp index b1deeefad4..9c53c681f0 100644 --- a/bindings/python/algorithm/admm-solver.cpp +++ b/bindings/python/algorithm/admm-solver.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2024 INRIA +// Copyright (c) 2024-2025 INRIA // #include @@ -23,136 +23,300 @@ namespace pinocchio { namespace bp = boost::python; - typedef ADMMContactSolverTpl Solver; - typedef Solver::PowerIterationAlgo PowerIterationAlgo; - typedef Solver::SolverStats SolverStats; typedef context::Scalar Scalar; typedef context::VectorXs VectorXs; - typedef const Eigen::Ref ConstRefVectorXs; - typedef ContactCholeskyDecompositionTpl - ContactCholeskyDecomposition; + + typedef ADMMContactSolverTpl Solver; + typedef Solver::ADMMSolverStats SolverStats; + typedef typename Solver::ConstRefVectorXs ConstRefVectorXs; + typedef typename Solver::RefConstVectorXs RefConstVectorXs; + + typedef ContactCholeskyDecompositionTpl ContactCholeskyDecomposition; #ifdef PINOCCHIO_PYTHON_PLAIN_SCALAR_TYPE - template + template static bool solve_wrapper( Solver & solver, DelassusDerived & delassus, - const context::VectorXs & g, - const context::CoulombFrictionConeVector & cones, - const context::VectorXs & R, - const boost::optional primal_solution = boost::none, - const boost::optional dual_solution = boost::none, - bool compute_largest_eigen_values = true, - bool stat_record = false) + const VectorXs & g, + const std::vector & constraint_models, + const Scalar dt, + const boost::optional preconditioner = boost::none, + const boost::optional primal_solution = boost::none, + const boost::optional dual_solution = boost::none, + const bool solve_ncp = true, + const ADMMUpdateRule admm_update_rule = ADMMUpdateRule::SPECTRAL, + const bool stat_record = false) { return solver.solve( - delassus, g, cones, R, primal_solution, dual_solution, compute_largest_eigen_values, - stat_record); + delassus, g, constraint_models, dt, preconditioner, primal_solution, dual_solution, + solve_ncp, admm_update_rule, stat_record); } - template + template static bool solve_wrapper2( Solver & solver, DelassusDerived & delassus, - const context::VectorXs & g, - const context::CoulombFrictionConeVector & cones, - Eigen::Ref x) + const VectorXs & g, + const std::vector & constraint_models, + const Scalar dt, + const VectorXs & primal_guess, + const bool solve_ncp = true) { - return solver.solve(delassus, g, cones, x); + return solver.solve(delassus, g, constraint_models, dt, primal_guess, solve_ncp); } #endif #ifndef PINOCCHIO_PYTHON_SKIP_CASADI_UNSUPPORTED + template static context::VectorXs computeConeProjection_wrapper( - const context::CoulombFrictionConeVector & cones, const context::VectorXs & forces) + const std::vector & constraint_models, + const VectorXs & forces) { context::VectorXs res(forces.size()); - ::pinocchio::internal::computeConeProjection(cones, forces, res); + + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + constraint_models.cbegin(), constraint_models.cend()); + + ::pinocchio::internal::computeConeProjection(wrapped_constraint_models, forces, res); return res; } + template static context::VectorXs computeDualConeProjection_wrapper( - const context::CoulombFrictionConeVector & cones, const context::VectorXs & velocities) + const std::vector & constraint_models, + const VectorXs & velocities) { context::VectorXs res(velocities.size()); - ::pinocchio::internal::computeDualConeProjection(cones, velocities, res); + + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + constraint_models.cbegin(), constraint_models.cend()); + + ::pinocchio::internal::computeDualConeProjection(wrapped_constraint_models, velocities, res); return res; } + template static context::Scalar computePrimalFeasibility_wrapper( - const context::CoulombFrictionConeVector & cones, const context::VectorXs & forces) + const std::vector & constraint_models, + const VectorXs & forces) { - return ::pinocchio::internal::computePrimalFeasibility(cones, forces); + return ::pinocchio::internal::computePrimalFeasibility(constraint_models, forces); } + template static context::Scalar computeReprojectionError_wrapper( - const context::CoulombFrictionConeVector & cones, - const context::VectorXs & forces, - const context::VectorXs & velocities) + const std::vector & constraint_models, + const VectorXs & forces, + const VectorXs & velocities) { - return ::pinocchio::internal::computeReprojectionError(cones, forces, velocities); + return ::pinocchio::internal::computeReprojectionError(constraint_models, forces, velocities); } - static context::VectorXs computeComplementarityShift_wrapper( - const context::CoulombFrictionConeVector & cones, const context::VectorXs & velocities) + template + static context::VectorXs computeDeSaxeCorrection_wrapper( + const std::vector & constraint_models, + const VectorXs & velocities) { context::VectorXs res(velocities.size()); - ::pinocchio::internal::computeComplementarityShift(cones, velocities, res); + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + constraint_models.cbegin(), constraint_models.cend()); + + ::pinocchio::internal::computeDeSaxeCorrection(wrapped_constraint_models, velocities, res); return res; } #endif // PINOCCHIO_PYTHON_SKIP_CASADI_UNSUPPORTED + template + struct SolveMethodExposer + { + SolveMethodExposer(bp::class_ & class_) + : class_(class_) + { + } + + template + void operator()(T) + { + run(static_cast(nullptr)); + } + + template + void run(ConstraintModelBase * ptr = 0) + { + PINOCCHIO_UNUSED_VARIABLE(ptr); + typedef Eigen::aligned_allocator ConstraintModelAllocator; + + if (!eigenpy::register_symbolic_link_to_registered_type<::pinocchio::ADMMUpdateRule>()) + { + bp::enum_<::pinocchio::ADMMUpdateRule>("ADMMUpdateRule") + .value("SPECTRAL", ::pinocchio::ADMMUpdateRule::SPECTRAL) + .value("LINEAR", ::pinocchio::ADMMUpdateRule::LINEAR) + .value("CONSTANT", ::pinocchio::ADMMUpdateRule::CONSTANT) + // .export_values() + ; + } + + class_ + .def( + "solve", + solve_wrapper< + ContactCholeskyDecomposition::DelassusCholeskyExpression, ConstraintModel, + ConstraintModelAllocator>, + (bp::args("self", "delassus", "g", "constraint_models", "dt"), + bp::arg("preconditioner") = boost::none, bp::arg("primal_solution") = boost::none, + bp::arg("dual_solution") = boost::none, bp::arg("solve_ncp") = true, + bp::arg("admm_update_rule") = ADMMUpdateRule::SPECTRAL, + bp::arg("stat_record") = false), + "Solve the constrained conic problem, starting from the optional initial guess.") + .def( + "solve", + solve_wrapper< + context::DelassusOperatorDense, ConstraintModel, ConstraintModelAllocator>, + (bp::args("self", "delassus", "g", "constraint_models", "dt"), + bp::arg("preconditioner") = boost::none, bp::arg("primal_solution") = boost::none, + bp::arg("dual_solution") = boost::none, bp::arg("solve_ncp") = true, + bp::arg("admm_update_rule") = ADMMUpdateRule::SPECTRAL, + bp::arg("stat_record") = false), + "Solve the constrained conic problem, starting from the optional initial guess.") + .def( + "solve", + solve_wrapper< + context::DelassusOperatorSparse, ConstraintModel, ConstraintModelAllocator>, + (bp::args("self", "delassus", "g", "constraint_models", "dt"), + bp::arg("preconditioner") = boost::none, bp::arg("primal_solution") = boost::none, + bp::arg("dual_solution") = boost::none, bp::arg("solve_ncp") = true, + bp::arg("admm_update_rule") = ADMMUpdateRule::SPECTRAL, + bp::arg("stat_record") = false), + "Solve the constrained conic problem, starting from the optional initial guess."); +#ifdef PINOCCHIO_WITH_ACCELERATE_SUPPORT + { + typedef Eigen::AccelerateLLT AccelerateLLT; + typedef DelassusOperatorSparseTpl + DelassusOperatorSparseAccelerate; + class_.def( + "solve", + solve_wrapper< + DelassusOperatorSparseAccelerate, ConstraintModel, ConstraintModelAllocator>, + (bp::args("self", "delassus", "g", "constraint_models", "dt"), + bp::arg("preconditioner") = boost::none, bp::arg("primal_solution") = boost::none, + bp::arg("dual_solution") = boost::none, bp::arg("solve_ncp") = true, + bp::arg("admm_update_rule") = ADMMUpdateRule::SPECTRAL, + bp::arg("stat_record") = false), + "Solve the constrained conic problem, starting from the optional initial guess."); + } +#endif + + bp::def( + "computeConeProjection", + computeConeProjection_wrapper, + bp::args("constraint_models", "forces"), + "Project a vector on the cartesian product of the constraint set associated with each " + "constraint model."); + + bp::def( + "computeDualConeProjection", + computeDualConeProjection_wrapper, + bp::args("constraint_models", "velocities"), + "Project a vector on the cartesian product of dual cones."); + + // TODO(jcarpent): restore these two next signatures + // bp::def( + // "computePrimalFeasibility", computePrimalFeasibility_wrapper, + // bp::args("constraint_models", "forces"), "Compute the primal + // feasibility."); + + // bp::def( + // "computeReprojectionError", computeReprojectionError_wrapper, + // bp::args("constraint_models", "forces", "velocities"), "Compute the + // reprojection error."); + + bp::def( + "computeDeSaxeCorrection", + computeDeSaxeCorrection_wrapper, + bp::args("constraint_models", "velocities"), + "Compute the complementarity shift associated to the De Saxé function."); + } + // + // template + // void run(FictiousConstraintModelTpl * ptr = 0) + // { + // PINOCCHIO_UNUSED_VARIABLE(ptr); + // } + // + void run(boost::blank * ptr = 0) + { + PINOCCHIO_UNUSED_VARIABLE(ptr); + } + + bp::class_ & class_; + }; + + template + static void expose_solve(bp::class_ & class_) + { + SolveMethodExposer expose(class_); + expose.run(static_cast(nullptr)); + } + void exposeADMMContactSolver() { #ifdef PINOCCHIO_PYTHON_PLAIN_SCALAR_TYPE + + // bp::enum_<::pinocchio::ADMMUpdateRule>("ADMMUpdateRule") + // .value("SPECTRAL", ::pinocchio::ADMMUpdateRule::SPECTRAL) + // .value("LINEAR", ::pinocchio::ADMMUpdateRule::LINEAR) + // // .export_values() + // ; + bp::class_ cl( "ADMMContactSolver", "Alternating Direction Method of Multi-pliers solver for contact dynamics.", - bp::init( + bp::init( (bp::arg("self"), bp::arg("problem_dim"), bp::arg("mu_prox") = Scalar(1e-6), bp::arg("tau") = Scalar(0.5), bp::arg("rho_power") = Scalar(0.2), - bp::arg("rho_power_factor") = Scalar(0.05), bp::arg("ratio_primal_dual") = Scalar(10), - bp::arg("max_it_largest_eigen_value_solver") = 20), + bp::arg("rho_power_factor") = Scalar(0.05), + bp::arg("linear_update_rule_factor") = Scalar(10), + bp::arg("ratio_primal_dual") = Scalar(10), bp::arg("lanczos_size") = 3), "Default constructor.")); - cl.def(ContactSolverBasePythonVisitor()) - .def( - "solve", solve_wrapper, - (bp::args("self", "delassus", "g", "cones", "R"), - bp::arg("primal_solution") = boost::none, bp::arg("dual_solution") = boost::none, - bp::arg("compute_largest_eigen_values") = true, bp::arg("stat_record") = false), - "Solve the constrained conic problem, starting from the optional initial guess.") - .def( - "solve", solve_wrapper, - (bp::args("self", "delassus", "g", "cones", "R"), - bp::arg("primal_solution") = boost::none, bp::arg("dual_solution") = boost::none, - bp::arg("compute_largest_eigen_values") = true, bp::arg("stat_record") = false), - "Solve the constrained conic problem, starting from the optional initial guess.") - .def( - "solve", solve_wrapper, - (bp::args("self", "delassus", "g", "cones", "R"), - bp::arg("primal_solution") = boost::none, bp::arg("dual_solution") = boost::none, - bp::arg("compute_largest_eigen_values") = true, bp::arg("stat_record") = false), - "Solve the constrained conic problem, starting from the optional initial guess.") + cl.def(ContactSolverBasePythonVisitor()) .def("setRho", &Solver::setRho, bp::args("self", "rho"), "Set the ADMM penalty value.") .def("getRho", &Solver::getRho, bp::arg("self"), "Get the ADMM penalty value.") .def( "setRhoPower", &Solver::setRhoPower, bp::args("self", "rho_power"), - "Set the power associated to the problem conditionning.") + "Set the power associated to the ADMM spectral update rule.") .def( "getRhoPower", &Solver::getRhoPower, bp::arg("self"), - "Get the power associated to the problem conditionning.") + "Get the power associated to the ADMM spectral update rule.") .def( "setRhoPowerFactor", &Solver::setRhoPowerFactor, bp::args("self", "rho_power_factor"), - "Set the power factor associated to the problem conditionning.") + "Set the power factor associated to the ADMM spectral update rule.") .def( "getRhoPowerFactor", &Solver::getRhoPowerFactor, bp::arg("self"), - "Get the power factor associated to the problem conditionning.") + "Get the power factor associated to the ADMM spectral update rule.") + + .def( + "setLinearUpdateRuleFactor", &Solver::setLinearUpdateRuleFactor, + bp::args("self", "linear_update_rule_factor"), + "Set the factor associated with the ADMM linear update rule.") + .def( + "getLinearUpdateRuleFactor", &Solver::getLinearUpdateRuleFactor, bp::arg("self"), + "Get the factor associated with the ADMM linear update rule.") .def( "setTau", &Solver::setTau, bp::args("self", "tau"), "Set the tau linear scaling factor.") @@ -180,65 +344,39 @@ namespace pinocchio "Returns the dual solution of the problem.", bp::return_internal_reference<>()) .def( - "getCholeskyUpdateCount", &Solver::getCholeskyUpdateCount, bp::arg("self"), - "Returns the number of updates of the Cholesky factorization due to rho updates.") + "setLanczosSize", &Solver::setLanczosSize, bp::args("self", "decomposition_size"), + "Set the size of the Lanczos decomposition.") .def( - "computeRho", &Solver::computeRho, bp::args("L", "m", "rho_power"), - "Compute the penalty ADMM value from the current largest and lowest eigenvalues and " - "the scaling spectral factor.") - .staticmethod("computeRho") - .def( - "computeRhoPower", &Solver::computeRhoPower, bp::args("L", "m", "rho"), - "Compute the scaling spectral factor of the ADMM penalty term from the current " - "largest and lowest eigenvalues and the ADMM penalty term.") - .staticmethod("computeRhoPower") + "getLanczosDecomposition", &Solver::getLanczosDecomposition, bp::arg("self"), + "Get the Lanczos decomposition.", bp::return_internal_reference<>()) .def( - "getPowerIterationAlgo", &Solver::getPowerIterationAlgo, bp::arg("self"), - bp::return_internal_reference<>()) - - .def("getStats", &Solver::getStats, bp::arg("self"), bp::return_internal_reference<>()); - - #ifdef PINOCCHIO_WITH_ACCELERATE_SUPPORT - { - typedef Eigen::AccelerateLLT AccelerateLLT; - typedef DelassusOperatorSparseTpl - DelassusOperatorSparseAccelerate; - cl.def( - "solve", solve_wrapper, - (bp::args("self", "delassus", "g", "cones", "R"), - bp::arg("primal_solution") = boost::none, bp::arg("dual_solution") = boost::none, - bp::arg("compute_largest_eigen_values") = true, bp::arg("stat_record") = false), - "Solve the constrained conic problem, starting from the optional initial guess."); - } - #endif - - bp::def( - "computeConeProjection", computeConeProjection_wrapper, bp::args("cones", "forces"), - "Project a vector on the cartesian product of cones."); + "getCholeskyUpdateCount", &Solver::getCholeskyUpdateCount, bp::arg("self"), + "Returns the number of updates of the Cholesky factorization due to rho updates.") - bp::def( - "computeDualConeProjection", computeDualConeProjection_wrapper, - bp::args("cones", "velocities"), - "Project a vector on the cartesian product of dual cones."); + // .def("computeRho",&Solver::computeRho,bp::args("L","m","rho_power"), + // "Compute the penalty ADMM value from the current largest and lowest eigenvalues + // and the scaling spectral factor.") + // .staticmethod("computeRho") + // .def("computeRhoPower",&Solver::computeRhoPower,bp::args("L","m","rho"), + // "Compute the scaling spectral factor of the ADMM penalty term from the current + // largest and lowest eigenvalues and the ADMM penalty term.") + // .staticmethod("computeRhoPower") - bp::def( - "computePrimalFeasibility", computePrimalFeasibility_wrapper, bp::args("cones", "forces"), - "Compute the primal feasibility."); + .def("getStats", &Solver::getStats, bp::arg("self"), bp::return_internal_reference<>()); - bp::def( - "computeReprojectionError", computeReprojectionError_wrapper, - bp::args("cones", "forces", "velocities"), "Compute the reprojection error."); + // typedef context::ConstraintModel::ConstraintModelVariant ConstraintModelVariant; - bp::def( - "computeComplementarityShift", computeComplementarityShift_wrapper, - bp::args("cones", "velocities"), - "Compute the complementarity shift associated to the De Saxé function."); + // SolveMethodExposer solve_exposer(cl); + // boost::mpl::for_each< + // ConstraintModelVariant::types, + // boost::mpl::make_identity>(solve_exposer); + expose_solve(cl); { bp::class_( - "SolverStats", "", + "ADMMSolverStats", "", bp::init((bp::arg("self"), bp::arg("max_it")), "Default constructor")) .def("reset", &SolverStats::reset, bp::arg("self"), "Reset the stasts.") .def( @@ -247,6 +385,8 @@ namespace pinocchio .PINOCCHIO_ADD_PROPERTY_READONLY(SolverStats, primal_feasibility, "") .PINOCCHIO_ADD_PROPERTY_READONLY(SolverStats, dual_feasibility, "") + .PINOCCHIO_ADD_PROPERTY_READONLY(SolverStats, dual_feasibility_admm, "") + .PINOCCHIO_ADD_PROPERTY_READONLY(SolverStats, dual_feasibility_constraint, "") .PINOCCHIO_ADD_PROPERTY_READONLY(SolverStats, dual_feasibility_ncp, "") .PINOCCHIO_ADD_PROPERTY_READONLY(SolverStats, complementarity, "") .PINOCCHIO_ADD_PROPERTY_READONLY(SolverStats, rho, "") diff --git a/bindings/python/algorithm/constraints/expose-cones.cpp b/bindings/python/algorithm/constraints/expose-cones.cpp index 178e80ac9c..42cd4ab9aa 100644 --- a/bindings/python/algorithm/constraints/expose-cones.cpp +++ b/bindings/python/algorithm/constraints/expose-cones.cpp @@ -1,11 +1,15 @@ // -// Copyright (c) 2022 INRIA +// Copyright (c) 2022-2024 INRIA // #include "pinocchio/serialization/aligned-vector.hpp" #include "pinocchio/bindings/python/fwd.hpp" -#include "pinocchio/bindings/python/algorithm/constraints/coulomb-friction-cone.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/set-coulomb-friction-cone.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/set-box-set.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/set-joint-limit-cone.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/set-trivial-cones.hpp" + // #include "pinocchio/bindings/python/serialization/serialization.hpp" #include "pinocchio/bindings/python/utils/std-aligned-vector.hpp" @@ -13,10 +17,8 @@ namespace pinocchio { namespace python { - void exposeCones() { -#ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS CoulombFrictionConePythonVisitor::expose(); StdVectorPythonVisitor::expose( "StdVec_CoulombFrictionCone"); @@ -27,11 +29,19 @@ namespace pinocchio DualCoulombFrictionConePythonVisitor::expose(); StdVectorPythonVisitor::expose( "StdVec_DualCoulombFrictionCone"); -// #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION -// serialize::vector_type>(); -// #endif -#endif - } + // #ifndef PINOCCHIO_PYTHON_NO_SERIALIZATION + // serialize::vector_type>(); + // #endif + BoxSetPythonVisitor::expose(); + JointLimitConstraintConePythonVisitor::expose(); + TrivialConePythonVisitor::expose( + "NullSet", "Set reduce to 0 singleton in R^d."); + TrivialConePythonVisitor::expose("UnboundedSet", "Set R^d."); + TrivialConePythonVisitor::expose( + "PositiveOrthantCone", "Set R_+^d."); + TrivialConePythonVisitor::expose( + "NegativeOrthantCone", "Set R_-^d."); + } } // namespace python } // namespace pinocchio diff --git a/bindings/python/algorithm/constraints/expose-constraints.cpp b/bindings/python/algorithm/constraints/expose-constraints.cpp new file mode 100644 index 0000000000..79327171c5 --- /dev/null +++ b/bindings/python/algorithm/constraints/expose-constraints.cpp @@ -0,0 +1,33 @@ +// +// Copyright (c) 2025 INRIA +// + +#include "pinocchio/bindings/python/fwd.hpp" +#include "pinocchio/algorithm/constraints/constraints.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/constraints-variant.hpp" +#include "pinocchio/bindings/python/utils/std-aligned-vector.hpp" + +namespace pinocchio +{ + namespace python + { + void exposeConstraints() + { + typedef context::ConstraintCollectionDefault::ConstraintModelVariant ConstraintModelVariant; + boost::mpl::for_each(ConstraintModelExposer()); + boost::mpl::for_each(ConstraintStdVectorExposer()); + bp::to_python_converter< + ConstraintModelVariant, ConstraintVariantVisitor>(); + ConstraintModelPythonVisitor::expose(); + StdAlignedVectorPythonVisitor::expose("StdVec_ConstraintModel"); + + typedef context::ConstraintCollectionDefault::ConstraintDataVariant ConstraintDataVariant; + boost::mpl::for_each(ConstraintDataExposer()); + boost::mpl::for_each(ConstraintStdVectorExposer()); + bp::to_python_converter< + ConstraintDataVariant, ConstraintVariantVisitor>(); + ConstraintDataPythonVisitor::expose(); + StdAlignedVectorPythonVisitor::expose("StdVec_ConstraintData"); + } + } // namespace python +} // namespace pinocchio diff --git a/bindings/python/algorithm/expose-aba-derivatives.cpp b/bindings/python/algorithm/expose-aba-derivatives.cpp index 439cc53d1f..f22d54c945 100644 --- a/bindings/python/algorithm/expose-aba-derivatives.cpp +++ b/bindings/python/algorithm/expose-aba-derivatives.cpp @@ -64,10 +64,10 @@ namespace pinocchio bp::def( "computeABADerivatives", computeABADerivatives, bp::args("model", "data", "q", "v", "tau"), - "Computes the ABA derivatives, store the result in data.ddq_dq, data.ddq_dv and " - "data.Minv (aka ddq_dtau)\n" - "which correspond to the partial derivatives of the joint acceleration vector output " - "with respect to the joint configuration,\n" + "Computes the ABA derivatives, store the result in data.ddq_dq, data.ddq_dv and data.Minv " + "(aka ddq_dtau)\n" + "which correspond to the partial derivatives of the joint acceleration vector output with " + "respect to the joint configuration,\n" "velocity and torque vectors.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" @@ -83,8 +83,8 @@ namespace pinocchio bp::args("model", "data", "q", "v", "tau", "fext"), "Computes the ABA derivatives with external contact foces,\n" "store the result in data.ddq_dq, data.ddq_dv and data.Minv (aka ddq_dtau)\n" - "which correspond to the partial derivatives of the acceleration output with respect " - "to the joint configuration,\n" + "which correspond to the partial derivatives of the acceleration output with respect to " + "the joint configuration,\n" "velocity and torque vectors.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" diff --git a/bindings/python/algorithm/expose-aba.cpp b/bindings/python/algorithm/expose-aba.cpp index 30f11875df..f26109413c 100644 --- a/bindings/python/algorithm/expose-aba.cpp +++ b/bindings/python/algorithm/expose-aba.cpp @@ -1,5 +1,6 @@ // -// Copyright (c) 2015-2021 CNRS INRIA +// Copyright (c) 2015-2018 CNRS +// Copyright (c) 2018-2024 INRIA // #include "pinocchio/bindings/python/algorithm/algorithms.hpp" @@ -67,7 +68,8 @@ namespace pinocchio bp::def( "aba", &aba< - Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs, VectorXs, context::Force>, + Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs, VectorXs, context::Force, + Eigen::aligned_allocator>, (bp::arg("model"), bp::arg("data"), bp::arg("q"), bp::arg("v"), bp::arg("tau"), bp::arg("fext"), bp::arg("convention") = pinocchio::Convention::LOCAL), "Compute ABA with external forces, store the result in data.ddq and return it.\n" diff --git a/bindings/python/algorithm/expose-centroidal.cpp b/bindings/python/algorithm/expose-centroidal.cpp index 1aac2d24a5..3b765acc04 100644 --- a/bindings/python/algorithm/expose-centroidal.cpp +++ b/bindings/python/algorithm/expose-centroidal.cpp @@ -40,8 +40,8 @@ namespace pinocchio "computeCentroidalMomentumTimeVariation", &computeCentroidalMomentumTimeVariation, bp::args("model", "data"), - "Computes the Centroidal momentum and its time derivatives, a.k.a. the total " - "momentum of the system and its time derivative expressed around the center of mass.", + "Computes the Centroidal momentum and its time derivatives, a.k.a. the total momentum of " + "the system and its time derivative expressed around the center of mass.", bp::return_value_policy()); bp::def( @@ -49,8 +49,8 @@ namespace pinocchio &computeCentroidalMomentumTimeVariation< Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs, VectorXs>, bp::args("model", "data", "q", "v", "a"), - "Computes the Centroidal momentum and its time derivatives, a.k.a. the total " - "momentum of the system and its time derivative expressed around the center of mass.", + "Computes the Centroidal momentum and its time derivatives, a.k.a. the total momentum of " + "the system and its time derivative expressed around the center of mass.", bp::return_value_policy()); bp::def( @@ -65,8 +65,8 @@ namespace pinocchio "computeCentroidalMap", &computeCentroidalMap, bp::args("model", "data", "q"), - "Computes the centroidal mapping, puts the result in Data.Ag and returns the " - "centroidal mapping.\n" + "Computes the centroidal mapping, puts the result in Data.Ag and returns the centroidal " + "mapping.\n" "For the same price, it also computes the total joint jacobians (data.J).", bp::return_value_policy()); @@ -84,10 +84,10 @@ namespace pinocchio computeCentroidalMapTimeVariation< Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs>, bp::args("model", "data", "q", "v"), - "Computes the time derivative of the centroidal momentum matrix Ag, puts the result " - "in Data.Ag and returns the centroidal mapping.\n" - "For the same price, it also computes the centroidal momentum matrix (data.Ag), the " - "total joint jacobians (data.J) " + "Computes the time derivative of the centroidal momentum matrix Ag, puts the result in " + "Data.Ag and returns the centroidal mapping.\n" + "For the same price, it also computes the centroidal momentum matrix (data.Ag), the total " + "joint jacobians (data.J) " "and the related joint jacobians time derivative (data.dJ)", mimic_not_supported_function>(0)); } diff --git a/bindings/python/algorithm/expose-cholesky.cpp b/bindings/python/algorithm/expose-cholesky.cpp index 8eb5fe097d..5289ea0bc7 100644 --- a/bindings/python/algorithm/expose-cholesky.cpp +++ b/bindings/python/algorithm/expose-cholesky.cpp @@ -48,8 +48,8 @@ namespace pinocchio bp::def( "computeMinv", &computeMinv, bp::args("Model", "Data"), - "Returns the inverse of the joint space inertia matrix using the results of the " - "Cholesky decomposition\n" + "Returns the inverse of the joint space inertia matrix using the results of the Cholesky " + "decomposition\n" "performed by cholesky.decompose. The result is stored in data.Minv.", mimic_not_supported_function>(0)); } diff --git a/bindings/python/algorithm/expose-constrained-dynamics.cpp b/bindings/python/algorithm/expose-constrained-dynamics.cpp index aff8a57a3f..50ebc291ec 100644 --- a/bindings/python/algorithm/expose-constrained-dynamics.cpp +++ b/bindings/python/algorithm/expose-constrained-dynamics.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2020-2021 INRIA +// Copyright (c) 2020-2025 INRIA // #include "pinocchio/bindings/python/algorithm/algorithms.hpp" @@ -8,7 +8,6 @@ #include "pinocchio/bindings/python/algorithm/contact-cholesky.hpp" #include "pinocchio/bindings/python/utils/std-vector.hpp" -#include "pinocchio/bindings/python/utils/registration.hpp" #include "pinocchio/bindings/python/utils/model-checker.hpp" #include "pinocchio/algorithm/constrained-dynamics.hpp" @@ -25,68 +24,55 @@ namespace pinocchio typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(context::RigidConstraintData) RigidConstraintDataVector; + template static const context::VectorXs constraintDynamics_proxy( const context::Model & model, context::Data & data, const context::VectorXs & q, const context::VectorXs & v, const context::VectorXs & tau, - const RigidConstraintModelVector & contact_models, - RigidConstraintDataVector & contact_datas, + const std::vector> & + contact_models, + std::vector> & contact_datas, context::ProximalSettings & prox_settings) { return constraintDynamics( model, data, q, v, tau, contact_models, contact_datas, prox_settings); } + template static const context::VectorXs constraintDynamics_proxy_default( const context::Model & model, context::Data & data, const context::VectorXs & q, const context::VectorXs & v, const context::VectorXs & tau, - const RigidConstraintModelVector & contact_models, - RigidConstraintDataVector & contact_datas) + const std::vector> & + contact_models, + std::vector> & contact_datas) { return constraintDynamics(model, data, q, v, tau, contact_models, contact_datas); } - void exposeConstraintDynamics() + template + void exposeConstraintDynamicsFor() { - using namespace Eigen; - // Expose type of contacts - if (!register_symbolic_link_to_registered_type()) - { - bp::enum_("ContactType") - .value("CONTACT_3D", CONTACT_3D) - .value("CONTACT_6D", CONTACT_6D) - .value("CONTACT_UNDEFINED", CONTACT_UNDEFINED); - } - - ProximalSettingsPythonVisitor::expose(); - - RigidConstraintModelPythonVisitor::expose(); - RigidConstraintDataPythonVisitor::expose(); - - StdVectorPythonVisitor::expose("StdVec_RigidConstraintModel"); - - StdVectorPythonVisitor::expose("StdVec_RigidConstraintData"); - - ContactCholeskyDecompositionPythonVisitor::expose(); + typedef typename ConstraintModel::ConstraintData ConstraintData; + typedef Eigen::aligned_allocator ConstraintModelAllocator; bp::def( "initConstraintDynamics", &initConstraintDynamics< - context::Scalar, context::Options, JointCollectionDefaultTpl, - typename RigidConstraintModelVector::allocator_type>, + context::Scalar, context::Options, ConstraintModel, JointCollectionDefaultTpl, + ConstraintModelAllocator>, bp::args("model", "data", "contact_models"), "This function allows to allocate the memory before hand for contact dynamics algorithms.\n" "This allows to avoid online memory allocation when running these algorithms.", mimic_not_supported_function<>(0)); bp::def( - "constraintDynamics", constraintDynamics_proxy, + "constraintDynamics", constraintDynamics_proxy, bp::args( "model", "data", "q", "v", "tau", "contact_models", "contact_datas", "prox_settings"), "Computes the forward dynamics with contact constraints according to a given list of " @@ -98,15 +84,43 @@ namespace pinocchio mimic_not_supported_function<>(0)); bp::def( - "constraintDynamics", constraintDynamics_proxy_default, + "constraintDynamics", constraintDynamics_proxy_default, bp::args("model", "data", "q", "v", "tau", "contact_models", "contact_datas"), "Computes the forward dynamics with contact constraints according to a given list of " "Contact information.\n" "When using constraintDynamics for the first time, you should call first " "initConstraintDynamics to initialize the internal memory used in the algorithm.\n" - "This function returns joint acceleration of the system. The contact forces are " - "stored in the list data.contact_forces.", + "This function returns joint acceleration of the system. The contact forces are stored in " + "the list data.contact_forces.", mimic_not_supported_function<>(0)); } + + void exposeConstraintDynamics() + { + using namespace Eigen; + + // Expose type of contacts + if (!register_symbolic_link_to_registered_type()) + { + bp::enum_("ContactType") + .value("CONTACT_3D", CONTACT_3D) + .value("CONTACT_6D", CONTACT_6D) + .value("CONTACT_UNDEFINED", CONTACT_UNDEFINED); + } + + ProximalSettingsPythonVisitor::expose(); + + RigidConstraintModelPythonVisitor::expose(); + RigidConstraintDataPythonVisitor::expose(); + + StdVectorPythonVisitor::expose("StdVec_RigidConstraintModel"); + + StdVectorPythonVisitor::expose("StdVec_RigidConstraintData"); + + ContactCholeskyDecompositionPythonVisitor::expose(); + + exposeConstraintDynamicsFor(); + // exposeConstraintDynamicsFor(); + } } // namespace python } // namespace pinocchio diff --git a/bindings/python/algorithm/expose-contact-inverse-dynamics.cpp b/bindings/python/algorithm/expose-contact-inverse-dynamics.cpp index 29919be566..85f658444d 100644 --- a/bindings/python/algorithm/expose-contact-inverse-dynamics.cpp +++ b/bindings/python/algorithm/expose-contact-inverse-dynamics.cpp @@ -1,15 +1,15 @@ // -// Copyright (c) 2024 INRIA +// Copyright (c) 2024-2025 INRIA // -#define BOOST_PYTHON_MAX_ARITY 24 - #include "pinocchio/bindings/python/algorithm/algorithms.hpp" #include "pinocchio/bindings/python/utils/std-vector.hpp" #include "pinocchio/bindings/python/utils/model-checker.hpp" #include "pinocchio/algorithm/contact-inverse-dynamics.hpp" +#include + namespace pinocchio { namespace python @@ -19,92 +19,83 @@ namespace pinocchio typedef context::Scalar Scalar; typedef context::VectorXs VectorXs; typedef const Eigen::Ref ConstRefVectorXs; - enum - { - Options = context::Options - }; - static ConstRefVectorXs computeContactImpulses_wrapper( - const ModelTpl & model, - DataTpl & data, - const ConstRefVectorXs & c_ref, - const context::RigidConstraintModelVector & contact_models, - context::RigidConstraintDataVector & contact_datas, - const context::CoulombFrictionConeVector & cones, - const ConstRefVectorXs & R, - const ConstRefVectorXs & constraint_correction, + static bp::tuple computeInverseDynamicsConstraintForces_wrapper( + const VectorXs & c_ref, + const context::FrictionalPointConstraintModelVector & contact_models, + const boost::optional & lambda_guess, ProximalSettingsTpl & settings, - const boost::optional & lambda_guess = boost::none) + bool solve_ncp) { - return computeContactImpulses( - model, data, c_ref, contact_models, contact_datas, cones, R, constraint_correction, - settings, lambda_guess); - } + const Eigen::Index problem_size = getTotalConstraintActiveSize(contact_models); + VectorXs lambda_sol(problem_size); + if (lambda_guess) + lambda_sol = lambda_guess.get(); + else + lambda_sol.setZero(); - static ConstRefVectorXs contactInverseDynamics_wrapper( - const ModelTpl & model, - DataTpl & data, - ConstRefVectorXs & q, - ConstRefVectorXs & v, - ConstRefVectorXs & a, - Scalar dt, - const context::RigidConstraintModelVector & contact_models, - context::RigidConstraintDataVector & contact_datas, - const context::CoulombFrictionConeVector & cones, - ConstRefVectorXs & R, - ConstRefVectorXs & constraint_correction, - ProximalSettingsTpl & settings, - const boost::optional & lambda_guess = boost::none) - { - return contactInverseDynamics( - model, data, q, v, a, dt, contact_models, contact_datas, cones, R, constraint_correction, - settings, lambda_guess); + const bool has_converged = computeInverseDynamicsConstraintForces( + contact_models, c_ref, lambda_sol, settings, solve_ncp); + return bp::make_tuple(has_converged, bp::object(lambda_sol)); } + +// static ConstRefVectorXs contactInverseDynamics_wrapper( +// const context::Model & model, +// context::Data & data, +// ConstRefVectorXs & q, +// ConstRefVectorXs & v, +// ConstRefVectorXs & a, +// Scalar dt, +// const context::FrictionalPointConstraintModelVector & contact_models, +// context::FrictionalPointConstraintDataVector & contact_datas, +// ConstRefVectorXs & R, +// ConstRefVectorXs & constraint_correction, +// ProximalSettingsTpl & settings, +// const boost::optional & lambda_guess = boost::none) +// { +// return contactInverseDynamics( +// model, data, q, v, a, dt, contact_models, contact_datas, R, constraint_correction, +// settings, lambda_guess); +// } #endif // PINOCCHIO_PYTHON_SKIP_ALGORITHM_CONSTRAINED_DYNAMICS void exposeContactInverseDynamics() { #ifndef PINOCCHIO_PYTHON_SKIP_ALGORITHM_CONSTRAINED_DYNAMICS bp::def( - "computeContactForces", computeContactImpulses_wrapper, - (bp::arg("model"), "data", "c_ref", "contact_models", "contact_datas", "cones", "R", - "constraint_correction", bp::arg("settings"), bp::arg("lambda_guess") = boost::none), - "Compute the inverse dynamics with frictional contacts, store the result in Data and " - "return it.\n\n" + "computeInverseDynamicsConstraintForces", computeInverseDynamicsConstraintForces_wrapper, + (bp::args("contact_models", "c_ref"), bp::arg("lambda_guess") = boost::none, + bp::arg("settings"), bp::arg("solve_ncp") = true), + "Computes the inverse dynamics with frictional contacts. Returns a tuple containing " + "(has_converged, lambda_sol).\n\n" "Parameters:\n" - "\tmodel: model of the kinematic tree\n" - "\tdata: data related to the model\n" - "\tc_ref: the reference velocity of contact points\n" "\tcontact_models: list of contact models\n" - "\tcontact_datas: list of contact datas\n" - "\tcones: list of friction cones\n" - "\tR: vector representing the diagonal of the compliance matrix\n" - "\tconstraint_correction: vector representing the constraint correction\n" + "\tc_ref: the reference velocity of contact points\n" + "\tlambda_guess: optional initial guess for contact forces\n" "\tsettings: the settings of the proximal algorithm\n" - "\tlambda_guess: initial guess for contact forces\n", + "\tsolve_ncp: whether to solve the NCP (true) or CCP (false)\n", mimic_not_supported_function<>(0)); - bp::def( - "contactInverseDynamics", contactInverseDynamics_wrapper, - (bp::arg("model"), "data", "q", "v", "a", "dt", "contact_models", "contact_datas", "cones", - "R", "constraint_correction", bp::arg("settings"), bp::arg("lambda_guess") = boost::none), - "Compute the inverse dynamics with frictional contacts, store the result in Data and " - "return it.\n\n" - "Parameters:\n" - "\tmodel: model of the kinematic tree\n" - "\tdata: data related to the model\n" - "\tq: the joint configuration vector (size model.nq)\n" - "\tv: the joint velocity vector (size model.nv)\n" - "\ta: the joint acceleration vector (size model.nv)\n" - "\tdt: the time step\n" - "\tcontact_models: list of contact models\n" - "\tcontact_datas: list of contact datas\n" - "\tcones: list of friction cones\n" - "\tR: vector representing the diagonal of the compliance matrix\n" - "\tconstraint_correction: vector representing the constraint correction\n" - "\tsettings: the settings of the proximal algorithm\n" - "\tlambda_guess: initial guess for contact forces\n", - mimic_not_supported_function<>(0)); +// bp::def( +// "contactInverseDynamics", contactInverseDynamics_wrapper, +// (bp::arg("model"), "data", "q", "v", "a", "dt", "contact_models", "contact_datas", "R", +// "constraint_correction", bp::arg("settings"), bp::arg("lambda_guess") = boost::none), +// "Compute the inverse dynamics with frictional contacts, store the result in Data and " +// "return it.\n\n" +// "Parameters:\n" +// "\tmodel: model of the kinematic tree\n" +// "\tdata: data related to the model\n" +// "\tq: the joint configuration vector (size model.nq)\n" +// "\tv: the joint velocity vector (size model.nv)\n" +// "\ta: the joint acceleration vector (size model.nv)\n" +// "\tdt: the time step\n" +// "\tcontact_models: list of contact models\n" +// "\tcontact_datas: list of contact datas\n" +// "\tR: vector representing the diagonal of the compliance matrix\n" +// "\tconstraint_correction: vector representing the constraint correction\n" +// "\tsettings: the settings of the proximal algorithm\n" +// "\tlambda_guess: initial guess for contact forces\n", +// mimic_not_supported_function<>(0)); #endif // PINOCCHIO_PYTHON_SKIP_ALGORITHM_CONSTRAINED_DYNAMICS } } // namespace python diff --git a/bindings/python/algorithm/expose-contact-jacobian.cpp b/bindings/python/algorithm/expose-contact-jacobian.cpp index cb74734441..573af9fbcd 100644 --- a/bindings/python/algorithm/expose-contact-jacobian.cpp +++ b/bindings/python/algorithm/expose-contact-jacobian.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2021 INRIA +// Copyright (c) 2021-2025 INRIA // #include "pinocchio/bindings/python/algorithm/algorithms.hpp" @@ -15,47 +15,60 @@ namespace pinocchio namespace python { - typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(context::RigidConstraintModel) - RigidConstraintModelVector; - typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(context::RigidConstraintData) - RigidConstraintDataVector; - + template static context::MatrixXs getConstraintJacobian_proxy( const context::Model & model, const context::Data & data, - const context::RigidConstraintModel & contact_model, - context::RigidConstraintData & contact_data) + const ConstraintModel & constraint_model, + ConstraintData & constraint_data) { - context::MatrixXs J(contact_model.size(), model.nv); + context::MatrixXs J(constraint_model.size(), model.nv); J.setZero(); - getConstraintJacobian(model, data, contact_model, contact_data, J); + getConstraintJacobian(model, data, constraint_model, constraint_data, J); return J; } + template static context::MatrixXs getConstraintsJacobian_proxy( const context::Model & model, const context::Data & data, - const RigidConstraintModelVector & contact_models, - RigidConstraintDataVector & contact_datas) + const ConstraintModelVector & constraint_models, + ConstraintDataVector & constraint_datas) { - const Eigen::DenseIndex constraint_size = getTotalConstraintSize(contact_models); + const Eigen::DenseIndex constraint_size = getTotalConstraintSize(constraint_models); context::MatrixXs J(constraint_size, model.nv); J.setZero(); - getConstraintsJacobian(model, data, contact_models, contact_datas, J); + getConstraintsJacobian(model, data, constraint_models, constraint_datas, J); return J; } void exposeContactJacobian() { bp::def( - "getConstraintJacobian", getConstraintJacobian_proxy, - bp::args("model", "data", "contact_model", "contact_data"), - "Computes the kinematic Jacobian associatied to a given constraint model.", + "getConstraintJacobian", + getConstraintJacobian_proxy, + bp::args("model", "data", "constraint_model", "constraint_data"), + "Computes the kinematic Jacobian associatied with a given constraint model.", + mimic_not_supported_function<>(0)); + bp::def( + "getConstraintsJacobian", + getConstraintsJacobian_proxy< + context::RigidConstraintModelVector, context::RigidConstraintDataVector>, + bp::args("model", "data", "constraint_models", "constraint_datas"), + "Computes the kinematic Jacobian associatied with a given set of constraint models.", + mimic_not_supported_function<>(0)); + + bp::def( + "getConstraintJacobian", + getConstraintJacobian_proxy, + bp::args("model", "data", "constraint_model", "constraint_data"), + "Computes the kinematic Jacobian associatied with a given constraint model.", mimic_not_supported_function<>(0)); bp::def( - "getConstraintsJacobian", getConstraintsJacobian_proxy, - bp::args("model", "data", "contact_models", "contact_datas"), - "Computes the kinematic Jacobian associatied to a given set of constraint models.", + "getConstraintsJacobian", + getConstraintsJacobian_proxy, + bp::args("model", "data", "constraint_models", "constraint_datas"), + "Computes the kinematic Jacobian associatied with a given set of constraint models.", mimic_not_supported_function<>(0)); } } // namespace python diff --git a/bindings/python/algorithm/expose-delassus.cpp b/bindings/python/algorithm/expose-delassus.cpp index 8ca1e1cd4d..826a372a40 100644 --- a/bindings/python/algorithm/expose-delassus.cpp +++ b/bindings/python/algorithm/expose-delassus.cpp @@ -29,7 +29,7 @@ namespace pinocchio RigidConstraintDataVector & contact_datas, const context::Scalar mu = context::Scalar(0)) { - const size_t constraint_size = getTotalConstraintSize(contact_models); + const Eigen::DenseIndex constraint_size = getTotalConstraintSize(contact_models); context::MatrixXs delassus(constraint_size, constraint_size); computeDelassusMatrix(model, data, q, contact_models, contact_datas, delassus, mu); make_symmetric(delassus); @@ -45,7 +45,7 @@ namespace pinocchio const context::Scalar mu, const bool scaled = false) { - const size_t constraint_size = getTotalConstraintSize(contact_models); + const Eigen::DenseIndex constraint_size = getTotalConstraintSize(contact_models); context::MatrixXs delassus_inverse(constraint_size, constraint_size); computeDampedDelassusMatrixInverse( model, data, q, contact_models, contact_datas, delassus_inverse, mu, scaled); diff --git a/bindings/python/algorithm/expose-frames.cpp b/bindings/python/algorithm/expose-frames.cpp index 0deb64174e..6064801357 100644 --- a/bindings/python/algorithm/expose-frames.cpp +++ b/bindings/python/algorithm/expose-frames.cpp @@ -159,70 +159,70 @@ namespace pinocchio bp::def( "updateFramePlacements", &updateFramePlacements, bp::args("model", "data"), - "Computes the placements of all the operational frames according to the current " - "joint placement stored in data" + "Computes the placements of all the operational frames according to the current joint " + "placement stored in data" "and puts the results in data."); bp::def( "updateFramePlacement", &updateFramePlacement, bp::args("model", "data", "frame_id"), - "Computes the placement of the given operational frame (frame_id) according to the " - "current joint placement stored in data, stores the results in data and returns it.", + "Computes the placement of the given operational frame (frame_id) according to the current " + "joint placement stored in data, stores the results in data and returns it.", bp::return_value_policy()); bp::def( "getFrameVelocity", &get_frame_velocity_proxy1, (bp::arg("model"), bp::arg("data"), bp::arg("frame_id"), bp::arg("reference_frame") = LOCAL), - "Returns the spatial velocity of the frame expressed in the coordinate system given " - "by reference_frame.\n" - "forwardKinematics(model,data,q,v[,a]) should be called first to compute the joint " - "spatial velocity stored in data.v"); + "Returns the spatial velocity of the frame expressed in the coordinate system given by " + "reference_frame.\n" + "forwardKinematics(model,data,q,v[,a]) should be called first to compute the joint spatial " + "velocity stored in data.v"); bp::def( "getFrameVelocity", &get_frame_velocity_proxy2, (bp::arg("model"), bp::arg("data"), bp::arg("joint_id"), bp::arg("placement"), bp::arg("reference_frame") = LOCAL), - "Returns the spatial velocity of the frame expressed in the coordinate system given " - "by reference_frame.\n" - "forwardKinematics(model,data,q,v[,a]) should be called first to compute the joint " - "spatial velocity stored in data.v"); + "Returns the spatial velocity of the frame expressed in the coordinate system given by " + "reference_frame.\n" + "forwardKinematics(model,data,q,v[,a]) should be called first to compute the joint spatial " + "velocity stored in data.v"); bp::def( "getFrameAcceleration", &get_frame_acceleration_proxy1, (bp::arg("model"), bp::arg("data"), bp::arg("frame_id"), bp::arg("reference_frame") = LOCAL), - "Returns the spatial acceleration of the frame expressed in the coordinate system " - "given by reference_frame.\n" - "forwardKinematics(model,data,q,v,a) should be called first to compute the joint " - "spatial acceleration stored in data.a ."); + "Returns the spatial acceleration of the frame expressed in the coordinate system given by " + "reference_frame.\n" + "forwardKinematics(model,data,q,v,a) should be called first to compute the joint spatial " + "acceleration stored in data.a ."); bp::def( "getFrameAcceleration", &get_frame_acceleration_proxy2, (bp::arg("model"), bp::arg("data"), bp::arg("joint_id"), bp::arg("placement"), bp::arg("reference_frame") = LOCAL), - "Returns the spatial acceleration of the frame expressed in the coordinate system " - "given by reference_frame.\n" - "forwardKinematics(model,data,q,v,a) should be called first to compute the joint " - "spatial acceleration stored in data.a ."); + "Returns the spatial acceleration of the frame expressed in the coordinate system given by " + "reference_frame.\n" + "forwardKinematics(model,data,q,v,a) should be called first to compute the joint spatial " + "acceleration stored in data.a ."); bp::def( "getFrameClassicalAcceleration", &get_frame_classical_acceleration_proxy1, (bp::arg("model"), bp::arg("data"), bp::arg("frame_id"), bp::arg("reference_frame") = LOCAL), - "Returns the \"classical\" acceleration of the frame expressed in the coordinate " - "system given by reference_frame.\n" - "forwardKinematics(model,data,q,v,a) should be called first to compute the joint " - "spatial acceleration stored in data.a ."); + "Returns the \"classical\" acceleration of the frame expressed in the coordinate system " + "given by reference_frame.\n" + "forwardKinematics(model,data,q,v,a) should be called first to compute the joint spatial " + "acceleration stored in data.a ."); bp::def( "getFrameClassicalAcceleration", &get_frame_classical_acceleration_proxy2, (bp::arg("model"), bp::arg("data"), bp::arg("joint_id"), bp::arg("placement"), bp::arg("reference_frame") = LOCAL), - "Returns the \"classical\" acceleration of the frame expressed in the coordinate " - "system given by reference_frame.\n" - "forwardKinematics(model,data,q,v,a) should be called first to compute the joint " - "spatial acceleration stored in data.a ."); + "Returns the \"classical\" acceleration of the frame expressed in the coordinate system " + "given by reference_frame.\n" + "forwardKinematics(model,data,q,v,a) should be called first to compute the joint spatial " + "acceleration stored in data.a ."); bp::def( "framesForwardKinematics", @@ -237,8 +237,8 @@ namespace pinocchio const context::Model &, context::Data &, const context::VectorXs &, context::Data::FrameIndex, ReferenceFrame))&compute_frame_jacobian_proxy, bp::args("model", "data", "q", "frame_id", "reference_frame"), - "Computes the Jacobian of the frame given by its frame_id in the coordinate system " - "given by reference_frame.\n"); + "Computes the Jacobian of the frame given by its frame_id in the coordinate system given " + "by reference_frame.\n"); bp::def( "computeFrameJacobian", @@ -257,33 +257,33 @@ namespace pinocchio bp::args("model", "data", "frame_id", "reference_frame"), "Computes the Jacobian of the frame given by its ID either in the LOCAL, " "LOCAL_WORLD_ALIGNED or the WORLD coordinates systems.\n" - "In other words, the velocity of the frame vF expressed in the reference frame is " - "given by J*v," + "In other words, the velocity of the frame vF expressed in the reference frame is given by " + "J*v," "where v is the joint velocity vector.\n" "remarks: computeJointJacobians(model,data,q) must have been called first."); bp::def( "getFrameJacobian", &get_frame_jacobian_proxy2, bp::args("model", "data", "joint_id", "placement", "reference_frame"), - "Computes the Jacobian of the frame given by its placement with respect to the Joint " - "frame and expressed the solution either in the LOCAL, LOCAL_WORLD_ALIGNED or the " - "WORLD coordinates systems.\n" - "In other words, the velocity of the frame vF expressed in the reference frame is " - "given by J*v," + "Computes the Jacobian of the frame given by its placement with respect to the Joint frame " + "and expressed the solution either in the LOCAL, LOCAL_WORLD_ALIGNED or the WORLD " + "coordinates systems.\n" + "In other words, the velocity of the frame vF expressed in the reference frame is given by " + "J*v," "where v is the joint velocity vector.\n\n" "remarks: computeJointJacobians(model,data,q) must have been called first."); bp::def( "frameJacobianTimeVariation", &frame_jacobian_time_variation_proxy, bp::args("model", "data", "q", "v", "frame_id", "reference_frame"), - "Computes the Jacobian Time Variation of the frame given by its frame_id either in " - "the reference frame provided by reference_frame.\n"); + "Computes the Jacobian Time Variation of the frame given by its frame_id either in the " + "reference frame provided by reference_frame.\n"); bp::def( "getFrameJacobianTimeVariation", get_frame_jacobian_time_variation_proxy, bp::args("model", "data", "frame_id", "reference_frame"), - "Returns the Jacobian time variation of the frame given by its frame_id either in " - "the reference frame provided by reference_frame.\n" + "Returns the Jacobian time variation of the frame given by its frame_id either in the " + "reference frame provided by reference_frame.\n" "You have to call computeJointJacobiansTimeVariation(model,data,q,v) and " "updateFramePlacements(model,data) first."); @@ -302,8 +302,8 @@ namespace pinocchio &computeSupportedForceByFrame, bp::args("model", "data", "frame_id"), "Computes the supported force of the frame (given by frame_id) and returns it.\n" - "The supported force corresponds to the sum of all the forces experienced after the " - "given frame.\n" + "The supported force corresponds to the sum of all the forces experienced after the given " + "frame.\n" "You must first call pinocchio::rnea to update placement values in data structure."); } } // namespace python diff --git a/bindings/python/algorithm/expose-geometry.cpp b/bindings/python/algorithm/expose-geometry.cpp index 66b8fc5bd8..c0e12921ae 100644 --- a/bindings/python/algorithm/expose-geometry.cpp +++ b/bindings/python/algorithm/expose-geometry.cpp @@ -24,8 +24,8 @@ namespace pinocchio bp::def( "updateGeometryPlacements", &updateGeometryPlacements, bp::args("model", "data", "geometry_model", "geometry_data"), - "Update the placement of the collision objects according to the current joint " - "placement stored in data."); + "Update the placement of the collision objects according to the current joint placement " + "stored in data."); } } // namespace python } // namespace pinocchio diff --git a/bindings/python/algorithm/expose-jacobian.cpp b/bindings/python/algorithm/expose-jacobian.cpp index c99493f5da..cd364c54f9 100644 --- a/bindings/python/algorithm/expose-jacobian.cpp +++ b/bindings/python/algorithm/expose-jacobian.cpp @@ -56,8 +56,8 @@ namespace pinocchio "computeJointJacobians", &computeJointJacobians, bp::args("model", "data", "q"), - "Computes the full model Jacobian, i.e. the stack of all the motion subspaces " - "expressed in the coordinate world frame.\n" + "Computes the full model Jacobian, i.e. the stack of all the motion subspaces expressed in " + "the coordinate world frame.\n" "The result is accessible through data.J. This function computes also the forward " "kinematics of the model.\n\n" "Parameters:\n" @@ -69,10 +69,10 @@ namespace pinocchio bp::def( "computeJointJacobians", &computeJointJacobians, bp::args("model", "data"), - "Computes the full model Jacobian, i.e. the stack of all motion subspace expressed " - "in the world frame.\n" - "The result is accessible through data.J. This function assumes that forward " - "kinematics (pinocchio.forwardKinematics) has been called first.\n\n" + "Computes the full model Jacobian, i.e. the stack of all motion subspace expressed in the " + "world frame.\n" + "The result is accessible through data.J. This function assumes that forward kinematics " + "(pinocchio.forwardKinematics) has been called first.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" "\tdata: data related to the model\n", @@ -80,8 +80,8 @@ namespace pinocchio bp::def( "computeJointJacobian", compute_jacobian_proxy, bp::args("model", "data", "q", "joint_id"), - "Computes the Jacobian of a specific joint frame expressed in the local frame of the " - "joint according to the given input configuration.\n\n" + "Computes the Jacobian of a specific joint frame expressed in the local frame of the joint " + "according to the given input configuration.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" "\tdata: data related to the model\n" @@ -110,9 +110,9 @@ namespace pinocchio computeJointJacobiansTimeVariation< Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs>, bp::args("model", "data", "q", "v"), - "Computes the full model Jacobian variations with respect to time. It corresponds to " - "dJ/dt which depends both on q and v. It also computes the joint Jacobian of the " - "model (similar to computeJointJacobians)." + "Computes the full model Jacobian variations with respect to time. It corresponds to dJ/dt " + "which depends both on q and v. It also computes the joint Jacobian of the model (similar " + "to computeJointJacobians)." "The result is accessible through data.dJ and data.J.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" diff --git a/bindings/python/algorithm/expose-joints.cpp b/bindings/python/algorithm/expose-joints.cpp index 7d138998da..bcd5d17085 100644 --- a/bindings/python/algorithm/expose-joints.cpp +++ b/bindings/python/algorithm/expose-joints.cpp @@ -10,6 +10,9 @@ namespace pinocchio namespace python { + typedef typename LieGroupMap::template operationProduct::type + LgType; + static context::VectorXs normalize_proxy(const context::Model & model, const context::VectorXs & config) { @@ -86,6 +89,77 @@ namespace pinocchio return J; } + context::MatrixXs tangentMap_proxy(const context::Model & model, const context::VectorXs & q) + { + context::MatrixXs TM(context::MatrixXs::Zero(model.nq, model.nv)); + + tangentMap(model, q, TM, SETTO); + + return TM; + } + + context::MatrixXs + compactTangentMap_proxy(const context::Model & model, const context::VectorXs & q) + { + context::MatrixXs TMc(context::MatrixXs::Zero(model.nq, MAX_JOINT_NV)); + typedef typename context::Model::JointIndex JointIndex; + std::vector joint_selection; + for (JointIndex i = 1; i < (JointIndex)model.njoints; ++i) + { + joint_selection.push_back(i); + } + + compactTangentMap(model, joint_selection, q, TMc); + + return TMc; + } + + context::MatrixXs tangentMapProduct_proxy( + const context::Model & model, const context::VectorXs & q, const context::MatrixXs & mat_in) + { + context::MatrixXs mat_out(context::MatrixXs::Zero(model.nq, mat_in.cols())); + + tangentMapProduct(model, q, mat_in, mat_out, SETTO); + + return mat_out; + } + + context::MatrixXs tangentMapTransposeProduct_proxy( + const context::Model & model, const context::VectorXs & q, const context::MatrixXs & mat_in) + { + context::MatrixXs mat_out(context::MatrixXs::Zero(model.nv, mat_in.cols())); + + tangentMapTransposeProduct(model, q, mat_in, mat_out, SETTO); + + return mat_out; + } + + LgType lieGroup_proxy(const context::Model & model) + { + LgType res; + + lieGroup(model, res); + + return res; + } + + bp::tuple indexvInfo_proxy(const context::Model & model) + { + std::vector nvs; + std::vector idx_vs; + + typedef typename context::Model::JointIndex JointIndex; + std::vector joint_selection; + for (JointIndex i = 1; i < (JointIndex)model.njoints; ++i) + { + joint_selection.push_back(i); + } + + indexvInfo(model, joint_selection, nvs, idx_vs); + + return bp::make_tuple(nvs, idx_vs); + } + void exposeJointsAlgo() { typedef context::Scalar Scalar; @@ -117,8 +191,8 @@ namespace pinocchio bp::def( "dIntegrate", &dIntegrate_arg_proxy, bp::args("model", "q", "v", "argument_position"), - "Computes the partial derivatives of the integrate function with respect to the " - "first (arg == ARG0) " + "Computes the partial derivatives of the integrate function with respect to the first (arg " + "== ARG0) " "or the second argument (arg == ARG1).\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" @@ -130,8 +204,8 @@ namespace pinocchio bp::def( "dIntegrateTransport", &dIntegrateTransport_proxy, bp::args("model", "q", "v", "Jin", "argument_position"), - "Takes a matrix expressed at q (+) v and uses parallel transport to express it in " - "the tangent space at q." + "Takes a matrix expressed at q (+) v and uses parallel transport to express it in the " + "tangent space at q." "\tThis operation does the product of the matrix by the Jacobian of the integration " "operation, but more efficiently." "Parameters:\n" @@ -155,8 +229,8 @@ namespace pinocchio bp::def( "difference", &difference, bp::args("model", "q1", "q2"), - "Difference between two joint configuration vectors, i.e. the tangent vector that " - "must be integrated during one unit time" + "Difference between two joint configuration vectors, i.e. the tangent vector that must be " + "integrated during one unit time" "to go from q1 to q2.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" @@ -193,8 +267,8 @@ namespace pinocchio bp::def( "dDifference", &dDifference_arg_proxy, bp::args("model", "q1", "q2", "argument_position"), - "Computes the partial derivatives of the difference function with respect to the " - "first (arg == ARG0) " + "Computes the partial derivatives of the difference function with respect to the first " + "(arg == ARG0) " "or the second argument (arg == ARG1).\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" @@ -203,6 +277,40 @@ namespace pinocchio "\targument_position: either pinocchio.ArgumentPosition.ARG0 or " "pinocchio.ArgumentPosition.ARG1, depending on the desired Jacobian value.\n"); + bp::def( + "tangentMap", &tangentMap_proxy, bp::args("model", "q"), + "Computes the tangent map in configuration q that map of a small variation express in the " + "Lie algebra as a small variation in the parametric space.\n\n" + "Parameters:\n" + "\tmodel: model of the kinematic tree\n" + "\tq: the joint configuration vector (size model.nq)\n"); + + bp::def( + "compactTangentMap", &compactTangentMap_proxy, bp::args("model", "q"), + "Computes the tangent map in configuration q that map of a small variation express in the " + "Lie algebra as a small variation in the parametric space. Store the result in a compact " + "manner that can be exploited using indexvInfo.\n\n" + "Parameters:\n" + "\tmodel: model of the kinematic tree\n" + "\tq: the joint configuration vector (size model.nq)\n"); + + bp::def( + "tangentMapProduct", &tangentMapProduct_proxy, bp::args("model", "q", "mat_in"), + "Apply the tangent map to a matrix mat_in.\n\n" + "Parameters:\n" + "\tmodel: model of the kinematic tree\n" + "\tq: the joint configuration vector (size model.nq)\n" + "\tmat_in: a matrix (size model.nq, ncols)"); + + bp::def( + "tangentMapTransposeProduct", &tangentMapTransposeProduct_proxy, + bp::args("model", "q", "mat_in"), + "Apply the tangent map to a matrix mat_in.\n\n" + "Parameters:\n" + "\tmodel: model of the kinematic tree\n" + "\tq: the joint configuration vector (size model.nq)\n" + "\tmat_in: a matrix (size model.nv, ncols)"); + bp::def( "randomConfiguration", &randomConfiguration_proxy, bp::arg("model"), "Generate a random configuration in the bounds given by the lower and upper limits " @@ -236,6 +344,20 @@ namespace pinocchio "\tmodel: model of the kinematic tree\n" "\tq: a joint configuration vector to normalize (size model.nq)\n"); + bp::def( + "lieGroup", lieGroup_proxy, bp::args("model"), + "Returns the Lie group associated to the model. It is the cartesian product of the lie " + "groups of all its joints.\n\n" + "Parameters:\n" + "\tmodel: model of the kinematic tree\n"); + + bp::def( + "indexvInfo", indexvInfo_proxy, bp::args("model"), + "Returns two vectors of size model.nq that gives for each q_i, the associated idx_v and nv " + "of the joint for which q_i is a configuration component.\n\n" + "Parameters:\n" + "\tmodel: model of the kinematic tree\n"); + #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS static const Scalar dummy_precision = Eigen::NumTraits::dummy_precision(); @@ -243,8 +365,8 @@ namespace pinocchio "isSameConfiguration", &isSameConfiguration, bp::args("model", "q1", "q2", "prec"), - "Return true if two configurations are equivalent within the given precision " - "provided by prec.\n\n" + "Return true if two configurations are equivalent within the given precision provided by " + "prec.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" "\tq1: a joint configuration vector (size model.nq)\n" @@ -254,8 +376,8 @@ namespace pinocchio bp::def( "isNormalized", &isNormalized, (bp::arg("model"), bp::arg("q"), bp::arg("prec") = dummy_precision), - "Check whether a configuration vector is normalized within the given precision " - "provided by prec.\n\n" + "Check whether a configuration vector is normalized within the given precision provided by " + "prec.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" "\tq: a joint configuration vector (size model.nq)\n" diff --git a/bindings/python/algorithm/expose-kinematic-regressor.cpp b/bindings/python/algorithm/expose-kinematic-regressor.cpp index 1935bd8277..349a996771 100644 --- a/bindings/python/algorithm/expose-kinematic-regressor.cpp +++ b/bindings/python/algorithm/expose-kinematic-regressor.cpp @@ -44,8 +44,8 @@ namespace pinocchio const context::Model &, const context::Data &, const JointIndex, const ReferenceFrame))&computeJointKinematicRegressor, bp::args("model", "data", "joint_id", "reference_frame"), - "Computes the kinematic regressor that links the joint placement variations of the " - "whole kinematic tree to the placement variation of the joint given as input.\n\n" + "Computes the kinematic regressor that links the joint placement variations of the whole " + "kinematic tree to the placement variation of the joint given as input.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" "\tdata: data related to the model\n" @@ -60,8 +60,8 @@ namespace pinocchio const context::Model &, context::Data &, const FrameIndex, const ReferenceFrame))&computeFrameKinematicRegressor, bp::args("model", "data", "frame_id", "reference_frame"), - "Computes the kinematic regressor that links the joint placement variations of the " - "whole kinematic tree to the placement variation of the frame given as input.\n\n" + "Computes the kinematic regressor that links the joint placement variations of the whole " + "kinematic tree to the placement variation of the frame given as input.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" "\tdata: data related to the model\n" diff --git a/bindings/python/algorithm/expose-kinematics-derivatives.cpp b/bindings/python/algorithm/expose-kinematics-derivatives.cpp index b39ab016ea..8f99041d79 100644 --- a/bindings/python/algorithm/expose-kinematics-derivatives.cpp +++ b/bindings/python/algorithm/expose-kinematics-derivatives.cpp @@ -1,5 +1,6 @@ // -// Copyright (c) 2018-2021 CNRS INRIA +// Copyright (c) 2018-2021 CNRS +// Copyright (c) 2018-2024 INRIA // #include "pinocchio/bindings/python/algorithm/algorithms.hpp" #include "pinocchio/algorithm/kinematics-derivatives.hpp" @@ -106,14 +107,29 @@ namespace pinocchio Options = context::Options }; + bp::def( + "computeForwardKinematicsDerivatives", + &computeForwardKinematicsDerivatives< + Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs>, + bp::args("model", "data", "q", "v"), + "Computes all the terms required to compute the derivatives of the placement and spatial " + "velocities\n" + "for any joint/frame of the model.\n" + "The results are stored in data.\n\n" + "Parameters:\n" + "\tmodel: model of the kinematic tree\n" + "\tdata: data related to the model\n" + "\tq: the joint configuration vector (size model.nq)\n" + "\tv: the joint velocity vector (size model.nv)\n"); + bp::def( "computeForwardKinematicsDerivatives", &computeForwardKinematicsDerivatives< Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs, VectorXs>, bp::args("model", "data", "q", "v", "a"), - "Computes all the terms required to compute the derivatives of the placement, " - "spatial velocity and acceleration\n" - "for any joint of the model.\n" + "Computes all the terms required to compute the derivatives of the placement, spatial " + "velocities and accelerations\n" + "for any joint/frame of the model.\n" "The results are stored in data.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" diff --git a/bindings/python/algorithm/expose-kinematics.cpp b/bindings/python/algorithm/expose-kinematics.cpp index b6731b1528..fed73694dd 100644 --- a/bindings/python/algorithm/expose-kinematics.cpp +++ b/bindings/python/algorithm/expose-kinematics.cpp @@ -33,29 +33,29 @@ namespace pinocchio "getVelocity", &getVelocity, (bp::arg("model"), bp::arg("data"), bp::arg("joint_id"), bp::arg("reference_frame") = LOCAL), - "Returns the spatial velocity of the joint expressed in the coordinate system given " - "by reference_frame.\n" - "forwardKinematics(model,data,q,v[,a]) should be called first to compute the joint " - "spatial velocity stored in data.v"); + "Returns the spatial velocity of the joint expressed in the coordinate system given by " + "reference_frame.\n" + "forwardKinematics(model,data,q,v[,a]) should be called first to compute the joint spatial " + "velocity stored in data.v"); bp::def( "getAcceleration", &getAcceleration, (bp::arg("model"), bp::arg("data"), bp::arg("joint_id"), bp::arg("reference_frame") = LOCAL), - "Returns the spatial acceleration of the joint expressed in the coordinate system " - "given by reference_frame.\n" - "forwardKinematics(model,data,q,v,a) should be called first to compute the joint " - "spatial acceleration stored in data.a ."); + "Returns the spatial acceleration of the joint expressed in the coordinate system given by " + "reference_frame.\n" + "forwardKinematics(model,data,q,v,a) should be called first to compute the joint spatial " + "acceleration stored in data.a ."); bp::def( "getClassicalAcceleration", &getClassicalAcceleration, (bp::arg("model"), bp::arg("data"), bp::arg("joint_id"), bp::arg("reference_frame") = LOCAL), - "Returns the \"classical\" acceleration of the joint expressed in the coordinate " - "system given by reference_frame.\n" - "forwardKinematics(model,data,q,v,a) should be called first to compute the joint " - "spatial acceleration stored in data.a ."); + "Returns the \"classical\" acceleration of the joint expressed in the coordinate system " + "given by reference_frame.\n" + "forwardKinematics(model,data,q,v,a) should be called first to compute the joint spatial " + "acceleration stored in data.a ."); bp::def( "forwardKinematics", @@ -86,8 +86,8 @@ namespace pinocchio &forwardKinematics< Scalar, Options, JointCollectionDefaultTpl, VectorXs, VectorXs, VectorXs>, bp::args("model", "data", "q", "v", "a"), - "Compute the global placements, local spatial velocities and spatial accelerations " - "of all the joints of the kinematic " + "Compute the global placements, local spatial velocities and spatial accelerations of all " + "the joints of the kinematic " "tree and store the results in data.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" diff --git a/bindings/python/algorithm/expose-model.cpp b/bindings/python/algorithm/expose-model.cpp index 5332ef5189..73efca844e 100644 --- a/bindings/python/algorithm/expose-model.cpp +++ b/bindings/python/algorithm/expose-model.cpp @@ -123,8 +123,8 @@ namespace pinocchio bp::def( "appendModel", &appendModel_proxy, bp::args("modelA", "modelB", "geomModelA", "geomModelB", "frame_in_modelA", "aMb"), - "Append a child (geometry) model into a parent (geometry) model, after a specific " - "frame given by its index.\n\n" + "Append a child (geometry) model into a parent (geometry) model, after a specific frame " + "given by its index.\n\n" "Parameters:\n" "\tmodelA: the parent model\n" "\tmodelB: the child model\n" @@ -144,8 +144,8 @@ namespace pinocchio "Parameters:\n" "\tmodel: input kinematic modell to reduce\n" "\tlist_of_joints_to_lock: list of joint indexes to lock\n" - "\treference_configuration: reference configuration to compute the placement of the " - "lock joints\n"); + "\treference_configuration: reference configuration to compute the placement of the lock " + "joints\n"); bp::def( "buildReducedModel", @@ -160,8 +160,8 @@ namespace pinocchio "\tmodel: input kinematic model to reduce\n" "\tgeom_model: input geometry model to reduce\n" "\tlist_of_joints_to_lock: list of joint indexes to lock\n" - "\treference_configuration: reference configuration to compute the placement of the " - "locked joints\n"); + "\treference_configuration: reference configuration to compute the placement of the locked " + "joints\n"); bp::def( "buildReducedModel", diff --git a/bindings/python/algorithm/expose-regressor.cpp b/bindings/python/algorithm/expose-regressor.cpp index 28e42e3f61..a1073f2b6f 100644 --- a/bindings/python/algorithm/expose-regressor.cpp +++ b/bindings/python/algorithm/expose-regressor.cpp @@ -62,10 +62,10 @@ namespace pinocchio bp::def( "jointBodyRegressor", &jointBodyRegressor_proxy, bp::args("model", "data", "joint_id"), - "Compute the regressor for the dynamic parameters of a rigid body attached to a " - "given joint.\n" - "This algorithm assumes RNEA has been run to compute the acceleration and " - "gravitational effects.\n\n" + "Compute the regressor for the dynamic parameters of a rigid body attached to a given " + "joint.\n" + "This algorithm assumes RNEA has been run to compute the acceleration and gravitational " + "effects.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" "\tdata: data related to the model\n" @@ -74,10 +74,10 @@ namespace pinocchio bp::def( "frameBodyRegressor", &frameBodyRegressor_proxy, bp::args("model", "data", "frame_id"), - "Computes the regressor for the dynamic parameters of a rigid body attached to a " - "given frame.\n" - "This algorithm assumes RNEA has been run to compute the acceleration and " - "gravitational effects.\n\n" + "Computes the regressor for the dynamic parameters of a rigid body attached to a given " + "frame.\n" + "This algorithm assumes RNEA has been run to compute the acceleration and gravitational " + "effects.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" "\tdata: data related to the model\n" diff --git a/bindings/python/algorithm/expose-rnea-derivatives.cpp b/bindings/python/algorithm/expose-rnea-derivatives.cpp index 795789b29d..28e0d5af63 100644 --- a/bindings/python/algorithm/expose-rnea-derivatives.cpp +++ b/bindings/python/algorithm/expose-rnea-derivatives.cpp @@ -92,10 +92,10 @@ namespace pinocchio bp::def( "computeRNEADerivatives", computeRNEADerivatives, bp::args("model", "data", "q", "v", "a"), - "Computes the RNEA partial derivatives, store the result in data.dtau_dq, " - "data.dtau_dv and data.M (aka dtau_da)\n" - "which correspond to the partial derivatives of the torque output with respect to " - "the joint configuration,\n" + "Computes the RNEA partial derivatives, store the result in data.dtau_dq, data.dtau_dv and " + "data.M (aka dtau_da)\n" + "which correspond to the partial derivatives of the torque output with respect to the " + "joint configuration,\n" "velocity and acceleration vectors.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" @@ -111,8 +111,8 @@ namespace pinocchio bp::args("model", "data", "q", "v", "a", "fext"), "Computes the RNEA partial derivatives with external contact foces,\n" "store the result in data.dtau_dq, data.dtau_dv and data.M (aka dtau_da)\n" - "which correspond to the partial derivatives of the torque output with respect to " - "the joint configuration,\n" + "which correspond to the partial derivatives of the torque output with respect to the " + "joint configuration,\n" "velocity and acceleration vectors.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" diff --git a/bindings/python/algorithm/expose-rnea.cpp b/bindings/python/algorithm/expose-rnea.cpp index 6a6e60e220..ca7231ea4e 100644 --- a/bindings/python/algorithm/expose-rnea.cpp +++ b/bindings/python/algorithm/expose-rnea.cpp @@ -51,8 +51,8 @@ namespace pinocchio "nonLinearEffects", &nonLinearEffects, bp::args("model", "data", "q", "v"), - "Compute the Non Linear Effects (coriolis, centrifugal and gravitational effects), " - "store the result in Data and return it.\n\n" + "Compute the Non Linear Effects (coriolis, centrifugal and gravitational effects), store " + "the result in Data and return it.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" "\tdata: data related to the model\n" @@ -64,8 +64,8 @@ namespace pinocchio "computeGeneralizedGravity", &computeGeneralizedGravity, bp::args("model", "data", "q"), - "Compute the generalized gravity contribution g(q) of the Lagrangian dynamics, store " - "the result in data.g and return it.\n\n" + "Compute the generalized gravity contribution g(q) of the Lagrangian dynamics, store the " + "result in data.g and return it.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" "\tdata: data related to the model\n" @@ -76,8 +76,8 @@ namespace pinocchio "computeStaticTorque", &computeStaticTorque, bp::args("model", "data", "q", "fext"), - "Computes the generalized static torque contribution g(q) - J.T f_ext of the " - "Lagrangian dynamics, store the result in data.tau and return it.\n\n" + "Computes the generalized static torque contribution g(q) - J.T f_ext of the Lagrangian " + "dynamics, store the result in data.tau and return it.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" "\tdata: data related to the model\n" @@ -102,8 +102,8 @@ namespace pinocchio bp::def( "getCoriolisMatrix", &getCoriolisMatrix, bp::args("model", "data"), - "Retrives the Coriolis Matrix C(q,v) of the Lagrangian dynamics after calling one of " - "the derivative algorithms, store the result in data.C and return it.\n\n" + "Retrives the Coriolis Matrix C(q,v) of the Lagrangian dynamics after calling one of the " + "derivative algorithms, store the result in data.C and return it.\n\n" "Parameters:\n" "\tmodel: model of the kinematic tree\n" "\tdata: data related to the model\n", diff --git a/bindings/python/algorithm/pgs-solver.cpp b/bindings/python/algorithm/pgs-solver.cpp index 8378bff610..e58f47c08c 100644 --- a/bindings/python/algorithm/pgs-solver.cpp +++ b/bindings/python/algorithm/pgs-solver.cpp @@ -1,12 +1,14 @@ // -// Copyright (c) 2022-2024 INRIA +// Copyright (c) 2022-2025 INRIA // #include "pinocchio/algorithm/pgs-solver.hpp" +#include "pinocchio/algorithm/constraints/constraints.hpp" #include "pinocchio/bindings/python/fwd.hpp" #include "pinocchio/bindings/python/algorithm/contact-solver-base.hpp" #include "pinocchio/bindings/python/utils/std-vector.hpp" +#include "pinocchio/bindings/python/utils/macros.hpp" #include namespace pinocchio @@ -16,38 +18,123 @@ namespace pinocchio namespace bp = boost::python; typedef PGSContactSolverTpl Solver; + typedef Solver::SolverStats SolverStats; + typedef typename Solver::RefConstVectorXs RefConstVectorXs; #ifdef PINOCCHIO_PYTHON_PLAIN_SCALAR_TYPE - template + template static bool solve_wrapper( Solver & solver, - const DelassusMatrixType & G, + const DelassusOperatorDense & delassus, const context::VectorXs & g, - const context::CoulombFrictionConeVector & cones, - Eigen::Ref x, - const context::Scalar over_relax = 1) + const context::ConstraintModelVector & constraint_models, + const context::Scalar dt, + const boost::optional x = boost::none, + const context::Scalar over_relax = 1, + const bool solve_ncp = true, + const bool stat_record = false) { - return solver.solve(G, g, cones, x, over_relax); + return solver.solve( + delassus, g, constraint_models, dt, x, over_relax, solve_ncp, stat_record); } #endif + template + struct SolveMethodExposer + { + SolveMethodExposer(bp::class_ & class_) + : class_(class_) + { + } + + template + void operator()(T) + { + run(static_cast(nullptr)); + } + + template + void run(ConstraintModelBase * ptr = 0) + { + PINOCCHIO_UNUSED_VARIABLE(ptr); + class_ + .def( + "solve", solve_wrapper, + (bp::args("self", "delassus", "g", "constraint_models", "dt"), + bp::arg("primal_solution") = boost::none, bp::arg("over_relax") = context::Scalar(1), + bp::arg("solve_ncp") = true, bp::arg("stat_record") = false), + "Solve the constrained conic problem composed of problem data (G,g,cones) and starting " + "from the initial guess.") + .def( + "solve", solve_wrapper, + (bp::args("self", "delassus", "g", "constraint_models", "dt"), + bp::arg("primal_solution") = boost::none, bp::arg("over_relax") = context::Scalar(1), + bp::arg("solve_ncp") = true, bp::arg("stat_record") = false), + "Solve the constrained conic problem composed of problem data (G,g,cones) and starting " + "from the initial guess."); + } + + // template + // void run(FictiousConstraintModelTpl * ptr = 0) + // { + // PINOCCHIO_UNUSED_VARIABLE(ptr); + // } + + void run(boost::blank * ptr = 0) + { + PINOCCHIO_UNUSED_VARIABLE(ptr); + } + + bp::class_ & class_; + }; + + template + static void expose_solve(bp::class_ & class_) + { + SolveMethodExposer expose(class_); + expose.run(static_cast(nullptr)); + } + void exposePGSContactSolver() { #ifdef PINOCCHIO_PYTHON_PLAIN_SCALAR_TYPE - bp::class_( + bp::class_ class_( "PGSContactSolver", "Projected Gauss Siedel solver for contact dynamics.", - bp::init(bp::args("self", "problem_dim"), "Default constructor.")) - .def(ContactSolverBasePythonVisitor()) + bp::init(bp::args("self", "problem_dim"), "Default constructor.")); + class_.def(ContactSolverBasePythonVisitor()) .def( - "solve", solve_wrapper, - (bp::args("self", "G", "g", "cones", "x"), (bp::arg("over_relax") = context::Scalar(1))), - "Solve the constrained conic problem composed of problem data (G,g,cones) and starting " - "from the initial guess.") + "getPrimalSolution", &Solver::getPrimalSolution, bp::arg("self"), + "Returns the primal solution of the problem.", bp::return_internal_reference<>()) .def( - "solve", solve_wrapper, - (bp::args("self", "G", "g", "cones", "x"), (bp::arg("over_relax") = context::Scalar(1))), - "Solve the constrained conic problem composed of problem data (G,g,cones) and starting " - "from the initial guess."); + "getDualSolution", &Solver::getDualSolution, bp::arg("self"), + "Returns the dual solution of the problem.", bp::return_internal_reference<>()) + + .def("getStats", &Solver::getStats, bp::arg("self"), bp::return_internal_reference<>()); + + // typedef context::ConstraintModel::ConstraintModelVariant ConstraintModelVariant; + // + // SolveMethodExposer solve_exposer(class_); + // boost::mpl::for_each< + // ConstraintModelVariant::types, + // boost::mpl::make_identity>(solve_exposer); + expose_solve(class_); + + { + bp::class_( + "SolverStats", "", + bp::init((bp::arg("self"), bp::arg("max_it")), "Default constructor")) + .def("reset", &SolverStats::reset, bp::arg("self"), "Reset the stasts.") + .def( + "size", &SolverStats::size, bp::arg("self"), + "Size of the vectors stored in the structure.") + + .PINOCCHIO_ADD_PROPERTY_READONLY(SolverStats, primal_feasibility, "") + .PINOCCHIO_ADD_PROPERTY_READONLY(SolverStats, dual_feasibility, "") + .PINOCCHIO_ADD_PROPERTY_READONLY(SolverStats, dual_feasibility_ncp, "") + .PINOCCHIO_ADD_PROPERTY_READONLY(SolverStats, complementarity, "") + .PINOCCHIO_ADD_PROPERTY_READONLY( + SolverStats, it, "Number of iterations performed by the algorithm."); + } #endif } diff --git a/bindings/python/collision/expose-broadphase-callbacks.cpp b/bindings/python/collision/expose-broadphase-callbacks.cpp index edd202b83b..890e9ab480 100644 --- a/bindings/python/collision/expose-broadphase-callbacks.cpp +++ b/bindings/python/collision/expose-broadphase-callbacks.cpp @@ -54,13 +54,13 @@ namespace pinocchio "Whether there is a collision or not.") .def_readonly( "accumulate", &CollisionCallBackDefault::accumulate, - "Whether the callback is used in an accumulate mode where several collide " - "methods are called successively.") + "Whether the callback is used in an accumulate mode where several collide methods are " + "called successively.") .def( "stop", bp::pure_virtual(&Base::stop), bp::arg("self"), - "If true, the stopping criteria related to the collision callback has been met and " - "one can stop.") + "If true, the stopping criteria related to the collision callback has been met and one " + "can stop.") .def( "done", &Base::done, &CollisionCallBackBaseWrapper::done_default, "Callback method called after the termination of a collisition detection algorithm."); diff --git a/bindings/python/collision/expose-broadphase.cpp b/bindings/python/collision/expose-broadphase.cpp index 1e65c38ab8..61d1967cc7 100644 --- a/bindings/python/collision/expose-broadphase.cpp +++ b/bindings/python/collision/expose-broadphase.cpp @@ -34,15 +34,15 @@ namespace pinocchio "computeCollisions", (bool (*)(BaseManager &, CollisionCallBackBase *))&computeCollisions, (bp::arg("manager"), bp::arg("callback")), "Determine if all collision pairs are effectively in collision or not.\n" - "This function assumes that updateGeometryPlacements and broadphase_manager.update() " - "have been called first."); + "This function assumes that updateGeometryPlacements and broadphase_manager.update() have " + "been called first."); bp::def( "computeCollisions", (bool (*)(BaseManager &, const bool))&computeCollisions, (bp::arg("manager"), bp::arg("stop_at_first_collision") = false), "Determine if all collision pairs are effectively in collision or not.\n" - "This function assumes that updateGeometryPlacements and broadphase_manager.update() " - "have been called first."); + "This function assumes that updateGeometryPlacements and broadphase_manager.update() have " + "been called first."); bp::def( "computeCollisions", @@ -51,8 +51,8 @@ namespace pinocchio const bool))&computeCollisions, (bp::arg("model"), bp::arg("data"), bp::arg("broadphase_manager"), bp::arg("q"), bp::arg("stop_at_first_collision") = false), - "Compute the forward kinematics, update the geometry placements and run the " - "collision detection using the broadphase manager."); + "Compute the forward kinematics, update the geometry placements and run the collision " + "detection using the broadphase manager."); bp::def( "computeCollisions", @@ -63,8 +63,8 @@ namespace pinocchio VectorXd> &))&computeCollisions, (bp::arg("model"), bp::arg("data"), bp::arg("broadphase_manager"), bp::arg("callback"), bp::arg("q")), - "Compute the forward kinematics, update the geometry placements and run the " - "collision detection using the broadphase manager."); + "Compute the forward kinematics, update the geometry placements and run the collision " + "detection using the broadphase manager."); } template diff --git a/bindings/python/collision/expose-collision.cpp b/bindings/python/collision/expose-collision.cpp index fafd7067e1..b9e48bf155 100644 --- a/bindings/python/collision/expose-collision.cpp +++ b/bindings/python/collision/expose-collision.cpp @@ -10,8 +10,6 @@ #include "pinocchio/collision/collision.hpp" #include "pinocchio/collision/distance.hpp" -#include - namespace pinocchio { namespace python @@ -53,9 +51,9 @@ namespace pinocchio static_cast( computeCollision), - bp::args("geometry_model", "geometry_data", "pair_index", "collision_request"), - "Check if the collision objects of a collision pair for a given Geometry Model and " - "Data are in collision.\n" + (bp::args("geometry_model", "geometry_data", "pair_index", "collision_request")), + "Check if the collision objects of a collision pair for a given Geometry Model and Data " + "are in collision.\n" "The collision pair is given by the two index of the collision objects."); bp::def( @@ -63,8 +61,8 @@ namespace pinocchio static_cast( computeCollision), bp::args("geometry_model", "geometry_data", "pair_index"), - "Check if the collision objects of a collision pair for a given Geometry Model and " - "Data are in collision.\n" + "Check if the collision objects of a collision pair for a given Geometry Model and Data " + "are in collision.\n" "The collision pair is given by the two index of the collision objects."); bp::def( @@ -81,11 +79,26 @@ namespace pinocchio "Update the geometry for a given configuration and " "determine if all collision pairs are effectively in collision or not."); + bp::def( + "computeContactPatch", + static_cast( + computeContactPatch), + bp::args("geometry_model", "geometry_data", "pair_index"), + "Compute the contact patch info associated with the collision pair given by pair_id. Note " + "that an actual computation will only occur if the collision pair is indeed in collision " + "(i.e. only if geom_data.collisionResult[pair_id].isCollision() is true)."); + + bp::def( + "computeContactPatches", + static_cast(computeContactPatches), + bp::args("geometry_model", "geometry_data"), + "Calls computeContactPatch for every collision pair."); + bp::def( "computeDistance", &computeDistance, bp::args("geometry_model", "geometry_data", "pair_index"), - "Compute the distance between the two geometry objects of a given collision pair for " - "a GeometryModel and associated GeometryData.", + "Compute the distance between the two geometry objects of a given collision pair for a " + "GeometryModel and associated GeometryData.", bp::with_custodian_and_ward_postcall< 0, 2, bp::return_value_policy>()); @@ -93,8 +106,8 @@ namespace pinocchio "computeDistances", (std::size_t (*)(const GeometryModel &, GeometryData &))&computeDistances, bp::args("geometry_model", "geometry_data"), - "Compute the distance between each collision pair for a given GeometryModel and " - "associated GeometryData."); + "Compute the distance between each collision pair for a given GeometryModel and associated " + "GeometryData."); bp::def( "computeDistances", &computeDistances_proxy, diff --git a/bindings/python/collision/parallel/broadphase.cpp b/bindings/python/collision/parallel/broadphase.cpp index 7f58d89b81..09a762a760 100644 --- a/bindings/python/collision/parallel/broadphase.cpp +++ b/bindings/python/collision/parallel/broadphase.cpp @@ -72,10 +72,10 @@ namespace pinocchio "\tnum_thread: number of threads used for the computation\n" "\tpool: the broadphase manager pool\n" "\tq: the batch of joint configurations\n" - "\tstop_at_first_collision_in_configuration: if set to true, stops when encountering " - "the first collision in a configuration\n" - "\tstop_at_first_collision_in_batch: if set to true, stops when encountering the " - "first collision in a batch.\n"); + "\tstop_at_first_collision_in_configuration: if set to true, stops when encountering the " + "first collision in a configuration\n" + "\tstop_at_first_collision_in_batch: if set to true, stops when encountering the first " + "collision in a batch.\n"); bp::def( "computeCollisionsInParallel", computeCollisionsInParallel_2, diff --git a/bindings/python/collision/parallel/geometry.cpp b/bindings/python/collision/parallel/geometry.cpp index 8ea889c2cb..7bd101ed25 100644 --- a/bindings/python/collision/parallel/geometry.cpp +++ b/bindings/python/collision/parallel/geometry.cpp @@ -95,10 +95,10 @@ namespace pinocchio "\tnum_thread: number of threads used for the computation\n" "\tpool: pool of geometry model/ geometry data\n" "\tq: the joint configuration vector (size model.nq x batch_size)\n" - "\tstop_at_first_collision_in_configuration: if set to true, stops when encountering " - "the first collision in a configuration\n" - "\tstop_at_first_collision_in_batch: if set to true, stops when encountering the " - "first collision in a batch.\n"); + "\tstop_at_first_collision_in_configuration: if set to true, stops when encountering the " + "first collision in a configuration\n" + "\tstop_at_first_collision_in_batch: if set to true, stops when encountering the first " + "collision in a batch.\n"); } } // namespace python diff --git a/bindings/python/math/expose-eigen-types.cpp b/bindings/python/math/expose-eigen-types.cpp index 8095673cdc..24a24d11a4 100644 --- a/bindings/python/math/expose-eigen-types.cpp +++ b/bindings/python/math/expose-eigen-types.cpp @@ -1,15 +1,13 @@ // -// Copyright (c) 2020-2021 INRIA +// Copyright (c) 2020-2025 INRIA // #include "pinocchio/bindings/python/fwd.hpp" -#include "pinocchio/bindings/python/utils/registration.hpp" #include "pinocchio/bindings/python/utils/std-vector.hpp" #include #include -#include #include #include #include @@ -60,8 +58,11 @@ namespace pinocchio if (!register_symbolic_link_to_registered_type()) eigenpy::expose(); #endif - + typedef Eigen::Matrix Matrix76s; + typedef Eigen::Matrix Matrix43s; + typedef Eigen::Matrix Vector2s; typedef Eigen::Matrix Matrix6s; + typedef Eigen::Matrix Matrix63s; typedef Eigen::Matrix Vector6s; typedef Eigen::Matrix Matrix6xs; typedef Eigen::Matrix Matrix3xs; @@ -69,10 +70,14 @@ namespace pinocchio internal::exposeType(); eigenpy::enableEigenPySpecific(); eigenpy::enableEigenPySpecific(); + eigenpy::enableEigenPySpecific(); eigenpy::enableEigenPySpecific(); eigenpy::enableEigenPySpecific(); eigenpy::enableEigenPySpecific(); eigenpy::enableEigenPySpecific(); + eigenpy::enableEigenPySpecific(); + eigenpy::enableEigenPySpecific(); + eigenpy::enableEigenPySpecific(); } } // namespace python diff --git a/bindings/python/math/expose-gram-schmidt-orthonormalisation.cpp b/bindings/python/math/expose-gram-schmidt-orthonormalisation.cpp new file mode 100644 index 0000000000..480bcebb83 --- /dev/null +++ b/bindings/python/math/expose-gram-schmidt-orthonormalisation.cpp @@ -0,0 +1,47 @@ +// +// Copyright (c) 2025 INRIA +// + +#include "pinocchio/bindings/python/fwd.hpp" +#include "pinocchio/math/gram-schmidt-orthonormalisation.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + void exposeGramSchmidtOrthonormalisation() + { +#ifndef PINOCCHIO_PYTHON_SKIP_CASADI_UNSUPPORTED + const context::Scalar prec = Eigen::NumTraits::dummy_precision(); + + bp::def( + "orthogonalization", + +[]( + const context::MatrixXs & mat, context::RefVectorXs vec, + const context::Scalar threshold) -> void { orthogonalization(mat, vec, threshold); }, + (bp::args("basis", "vec"), bp::arg("threshold") = context::Scalar(0)), + "Perform the Gram-Schmidt orthogonalization on the input/output vector for a given input " + "basis."); + + bp::def( + "orthonormalization", + +[](context::MatrixXs & mat, const context::Scalar threshold) -> void { + orthonormalization(mat, threshold); + }, + (bp::arg("matrix"), bp::arg("threshold") = context::Scalar(0)), + "Perform the orthonormalization of the input matrix via the Gram-Schmidt procedure."); + + bp::def( + "isOrthonormal", + +[](context::MatrixXs & matrix, const context::Scalar prec) -> bool { + return isOrthonormal(matrix, prec); + }, + (bp::arg("matrix"), bp::arg("prec") = prec), + "Check whether the input matrix is orthonormal up to a given input precision."); +#endif // PINOCCHIO_PYTHON_SKIP_CASADI_UNSUPPORTED + } + + } // namespace python +} // namespace pinocchio diff --git a/bindings/python/math/expose-rpy.cpp b/bindings/python/math/expose-rpy.cpp index e34bd8fe4a..5d57b120f6 100644 --- a/bindings/python/math/expose-rpy.cpp +++ b/bindings/python/math/expose-rpy.cpp @@ -65,8 +65,8 @@ namespace pinocchio bp::def( "matrixToRpy", - // &matrixToRpy, TODO: change internal routines to - // make them compliant with Autodiff Frameworks + // &matrixToRpy, TODO: change internal routines to make + // them compliant with Autodiff Frameworks &matrixToRpy, bp::arg("R"), "Given a rotation matrix R, the angles (r, p, y) are given so that R = " "R_z(y)R_y(p)R_x(r)," diff --git a/bindings/python/module.cpp b/bindings/python/module.cpp index 8ad837cbfd..2999785104 100644 --- a/bindings/python/module.cpp +++ b/bindings/python/module.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2015-2022 CNRS INRIA +// Copyright (c) 2015-2022 CNRS INRIA, 2025 INRIA // #include "pinocchio/bindings/python/fwd.hpp" @@ -7,7 +7,6 @@ #include "pinocchio/utils/version.hpp" #include "pinocchio/bindings/python/utils/version.hpp" #include "pinocchio/bindings/python/utils/dependencies.hpp" -#include "pinocchio/bindings/python/utils/registration.hpp" #include "pinocchio/bindings/python/utils/std-vector.hpp" #include "pinocchio/spatial/cartesian-axis.hpp" @@ -40,6 +39,7 @@ BOOST_PYTHON_MODULE(PINOCCHIO_PYTHON_MODULE_NAME) eigenpy::OptionalConverter::registration(); eigenpy::OptionalConverter, boost::optional>::registration(); + eigenpy::OptionalConverter, boost::optional>::registration(); eigenpy::OptionalConverter< const Eigen::Ref, boost::optional>::registration(); @@ -98,11 +98,13 @@ BOOST_PYTHON_MODULE(PINOCCHIO_PYTHON_MODULE_NAME) exposeInertia(); exposeSymmetric3(); exposeJoints(); + exposeConstraints(); exposeExplog(); exposeRpy(); exposeLinalg(); exposeTridiagonalMatrix(); exposeLanczosDecomposition(); + exposeGramSchmidtOrthonormalisation(); exposeSkew(); exposeLieGroups(); @@ -144,10 +146,12 @@ BOOST_PYTHON_MODULE(PINOCCHIO_PYTHON_MODULE_NAME) exposeConversions(); typedef std::vector<::pinocchio::VectorXb> StdVec_VectorXb; + typedef std::vector<::Eigen::DenseIndex> StdVec_Index; typedef std::vector StdVec_MatrixXs; StdVectorPythonVisitor::expose( "StdVec_VectorXb", eigenpy::details::overload_base_get_item_for_std_vector()); + StdVectorPythonVisitor::expose("StdVec_long"); StdVectorPythonVisitor::expose( "StdVec_MatrixXs", eigenpy::details::overload_base_get_item_for_std_vector()); } diff --git a/bindings/python/parsers/mjcf/model.cpp b/bindings/python/parsers/mjcf/model.cpp index 6af560818e..9ba11df45c 100644 --- a/bindings/python/parsers/mjcf/model.cpp +++ b/bindings/python/parsers/mjcf/model.cpp @@ -4,9 +4,11 @@ #include "pinocchio/parsers/mjcf.hpp" #include "pinocchio/bindings/python/parsers/mjcf.hpp" +#include "pinocchio/bindings/python/utils/keep-alive.hpp" #include "pinocchio/bindings/python/utils/path.hpp" #include +#include namespace pinocchio { @@ -22,23 +24,105 @@ namespace pinocchio return model; } - Model buildModelFromMJCF(const bp::object & filename, const JointModel & root_joint) + Model & buildModelFromMJCF(const bp::object & filename, Model & model) { - Model model; - ::pinocchio::mjcf::buildModel(path(filename), root_joint, model); + ::pinocchio::mjcf::buildModel(path(filename), model); + return model; + } + + Model & buildModelFromMJCF( + const bp::object & filename, + const JointModel & root_joint, + const std::string & root_joint_name, + Model & model) + { + ::pinocchio::mjcf::buildModel(path(filename), root_joint, root_joint_name, model); return model; } - bp::tuple buildModelFromMJCF( + Model & + buildModelFromMJCF(const bp::object & filename, const JointModel & root_joint, Model & model) + { + return buildModelFromMJCF(filename, root_joint, "root_joint", model); + } + + Model buildModelFromMJCF( const bp::object & filename, const JointModel & root_joint, - const std::string & root_joint_name) + const std::string & root_joint_name = "root_joint") + { + Model model; + return buildModelFromMJCF(filename, root_joint, root_joint_name, model); + } + + Model buildModelFromMJCFString(const std::string & xml_string) { Model model; - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; - ::pinocchio::mjcf::buildModel( - path(filename), root_joint, root_joint_name, model, contact_models); - return bp::make_tuple(model, contact_models); + ::pinocchio::mjcf::buildModelFromXML(xml_string, model); + return model; + } + + Model buildModelFromMJCFString( + const std::string & xml_string, + const JointModel & root_joint, + const std::string & root_joint_name = "root_joint") + { + Model model; + ::pinocchio::mjcf::buildModelFromXML(xml_string, root_joint, root_joint_name, model); + return model; + } + + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + buildBilateralConstraintModelsFromMJCF(Model & model, const bp::object & filename) + { + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + bilateral_constraint_models; + ::pinocchio::mjcf::buildConstraintModelsFromXML( + path(filename), model, bilateral_constraint_models); + return bilateral_constraint_models; + } + + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + &buildBilateralConstraintModelsFromMJCF( + Model & model, + const bp::object & filename, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + & bilateral_constraint_models) + { + ::pinocchio::mjcf::buildConstraintModelsFromXML( + path(filename), model, bilateral_constraint_models); + return bilateral_constraint_models; + } + + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) + buildWeldConstraintModelsFromMJCF(Model & model, const bp::object & filename) + { + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) weld_constraint_models; + ::pinocchio::mjcf::buildConstraintModelsFromXML( + path(filename), model, weld_constraint_models); + return weld_constraint_models; + } + + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) + &buildWeldConstraintModelsFromMJCF( + Model & model, + const bp::object & filename, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) & weld_constraint_models) + { + ::pinocchio::mjcf::buildConstraintModelsFromXML( + path(filename), model, weld_constraint_models); + return weld_constraint_models; + } + + void buildAllConstraintModelsFromMJCF( + Model & model, + const bp::object & filename, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + & bilateral_constraint_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) & weld_constraint_models) + { + ::pinocchio::mjcf::buildConstraintModelsFromXML( + path(filename), model, bilateral_constraint_models, weld_constraint_models); } void exposeMJCFModel() @@ -46,23 +130,95 @@ namespace pinocchio bp::def( "buildModelFromMJCF", static_cast(pinocchio::python::buildModelFromMJCF), - bp::args("mjcf_filename"), + bp::arg("mjcf_filename"), "Parse the MJCF file given in input and return a pinocchio Model."); bp::def( "buildModelFromMJCF", - static_cast( + static_cast( + pinocchio::python::buildModelFromMJCF), + bp::args("mjcf_filename", "model"), + "Parse the MJCF file given in input and return a pinocchio Model.", + bp::return_internal_reference<2>()); + + bp::def( + "buildModelFromMJCF", + static_cast( pinocchio::python::buildModelFromMJCF), - bp::args("mjcf_filename", "root_joint"), + (bp::args("mjcf_filename", "root_joint"), bp::arg("root_joint_name") = "root_joint"), "Parse the MJCF file and return a pinocchio Model with the given root Joint."); bp::def( "buildModelFromMJCF", - static_cast( + static_cast(pinocchio::python::buildModelFromMJCF), + (bp::args("mjcf_filename", "root_joint"), bp::arg("root_joint_name") = "root_joint", + bp::arg("model")), + "Parse the MJCF file and return a pinocchio Model with the given root Joint and the " + "constraint models.", + bp::return_internal_reference<4>()); + + bp::def( + "buildModelFromMJCF", + static_cast( pinocchio::python::buildModelFromMJCF), - bp::args("mjcf_filename", "root_joint", "root_joint_name"), + (bp::args("mjcf_filename", "root_joint"), bp::arg("root_joint_name") = "root_joint"), "Parse the MJCF file and return a pinocchio Model with the given root Joint and its " "specified name as well as a constraint list if some are present in the MJCF file."); + + bp::def( + "buildModelFromMJCFString", + static_cast(pinocchio::python::buildModelFromMJCFString), + bp::args("xml_string"), + "Parse the MJCF string given in input and return a pinocchio Model."); + + bp::def( + "buildModelFromMJCFString", + static_cast( + pinocchio::python::buildModelFromMJCFString), + (bp::args("mjcf_filename", "root_joint"), bp::arg("root_joint_name") = "root_joint"), + "Parse the MJCF string and return a pinocchio Model with the given root Joint and its " + "specified name as well as a constraint list if some are present in the MJCF file."); + + bp::def( + "buildBilateralConstraintModelsFromMJCF", + static_cast(pinocchio::python::buildBilateralConstraintModelsFromMJCF), + bp::args("mjcf_filename", "model"), + "Parse the MJCF file given in input and return a list of pinocchio CosntraintModel."); + + bp::def( + "buildBilateralConstraintModelsFromMJCF", + static_cast < PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + & (*)(Model &, const bp::object &, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) &) + > (pinocchio::python::buildBilateralConstraintModelsFromMJCF), + bp::args("mjcf_filename", "model", "bilateral_point_constraint_models"), + "Parse the MJCF file given in input and return a list of pinocchio CosntraintModel.", + bp::return_internal_reference<3>()); + + bp::def( + "buildWeldConstraintModelsFromMJCF", + static_cast(pinocchio::python::buildWeldConstraintModelsFromMJCF), + bp::args("mjcf_filename", "model"), + "Parse the MJCF file given in input and return a list of pinocchio CosntraintModel."); + + bp::def( + "buildWeldConstraintModelsFromMJCF", + static_cast < PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) + & (*)(Model &, const bp::object &, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) &) + > (pinocchio::python::buildWeldConstraintModelsFromMJCF), + bp::args("mjcf_filename", "model", "weld_constraint_models"), + "Parse the MJCF file given in input and return a list of pinocchio CosntraintModel.", + bp::return_internal_reference<3>()); + + bp::def( + "buildAllConstraintModelsFromMJCF", pinocchio::python::buildAllConstraintModelsFromMJCF, + bp::args( + "mjcf_filename", "model", "bilateral_point_constraint_models", "weld_constraint_models"), + "Parse the MJCF file given in input and fill constaint models vectors."); } } // namespace python } // namespace pinocchio diff --git a/bindings/python/parsers/sdf/model.cpp b/bindings/python/parsers/sdf/model.cpp index 223a54ba66..5ddf45e82f 100644 --- a/bindings/python/parsers/sdf/model.cpp +++ b/bindings/python/parsers/sdf/model.cpp @@ -25,10 +25,10 @@ namespace pinocchio const std::vector & parent_guidance) { Model model; - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) constraint_models; ::pinocchio::sdf::buildModel( - path(filename), model, contact_models, root_link_name, parent_guidance); - return bp::make_tuple(model, contact_models); + path(filename), model, constraint_models, root_link_name, parent_guidance); + return bp::make_tuple(model, constraint_models); } bp::tuple buildModelFromSdf( @@ -38,10 +38,10 @@ namespace pinocchio const std::vector & parent_guidance) { Model model; - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) constraint_models; pinocchio::sdf::buildModel( - path(filename), root_joint, model, contact_models, root_link_name, parent_guidance); - return bp::make_tuple(model, contact_models); + path(filename), root_joint, model, constraint_models, root_link_name, parent_guidance); + return bp::make_tuple(model, constraint_models); } bp::tuple buildModelFromSdf( @@ -52,11 +52,11 @@ namespace pinocchio const std::vector & parent_guidance) { Model model; - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) constraint_models; pinocchio::sdf::buildModel( - path(filename), root_joint, root_joint_name, model, contact_models, root_link_name, + path(filename), root_joint, root_joint_name, model, constraint_models, root_link_name, parent_guidance); - return bp::make_tuple(model, contact_models); + return bp::make_tuple(model, constraint_models); } #endif diff --git a/bindings/python/parsers/urdf/console-bridge.cpp b/bindings/python/parsers/urdf/console-bridge.cpp index 6a37be3597..3a0d97be0f 100644 --- a/bindings/python/parsers/urdf/console-bridge.cpp +++ b/bindings/python/parsers/urdf/console-bridge.cpp @@ -1,10 +1,10 @@ // -// Copyright (c) 2020 INRIA +// Copyright (c) 2020-2025 INRIA // #include +#include #include "pinocchio/bindings/python/parsers/urdf.hpp" -#include "pinocchio/bindings/python/utils/registration.hpp" #ifdef PINOCCHIO_WITH_URDFDOM #include @@ -24,7 +24,7 @@ namespace pinocchio ::console_bridge::setLogLevel(::console_bridge::CONSOLE_BRIDGE_LOG_ERROR); typedef ::console_bridge::LogLevel LogLevel; - if (!register_symbolic_link_to_registered_type()) + if (!eigenpy::register_symbolic_link_to_registered_type()) { bp::enum_("LogLevel") .value("CONSOLE_BRIDGE_LOG_DEBUG", ::console_bridge::CONSOLE_BRIDGE_LOG_DEBUG) diff --git a/bindings/python/pinocchio/robot_wrapper.py b/bindings/python/pinocchio/robot_wrapper.py index 0141ff24ef..d8a42e6f3e 100644 --- a/bindings/python/pinocchio/robot_wrapper.py +++ b/bindings/python/pinocchio/robot_wrapper.py @@ -60,7 +60,7 @@ def BuildFromMJCF(filename, *args, **kwargs): return robot def initFromMJCF(self, filename, *args, **kwargs): - model, collision_model, visual_model = buildModelsFromMJCF( + model, constraint_models, collision_model, visual_model = buildModelsFromMJCF( filename, *args, **kwargs ) @@ -69,14 +69,21 @@ def initFromMJCF(self, filename, *args, **kwargs): model=model, collision_model=collision_model, visual_model=visual_model, + constraint_models=constraint_models ) def __init__( - self, model=pin.Model(), collision_model=None, visual_model=None, verbose=False + self, + model=pin.Model(), + collision_model=None, + visual_model=None, + constraint_models=None, + verbose=False, ): self.model = model self.collision_model = collision_model self.visual_model = visual_model + self.constraint_models = constraint_models self.data, self.collision_data, self.visual_data = createDatas( model, collision_model, visual_model diff --git a/bindings/python/pinocchio/shortcuts.py b/bindings/python/pinocchio/shortcuts.py index 2fa33b9b3f..02b4dd20b3 100644 --- a/bindings/python/pinocchio/shortcuts.py +++ b/bindings/python/pinocchio/shortcuts.py @@ -5,9 +5,6 @@ ## In this file, some shortcuts are provided ## -# TODO: Remove when 20.04 is not supported -from __future__ import annotations - from . import WITH_HPP_FCL, WITH_HPP_FCL_BINDINGS from . import pinocchio_pywrap_default as pin @@ -250,15 +247,15 @@ def buildModelsFromMJCF(filename, *args, **kwargs): - verbose - print information of parsing (default - False) - meshLoader - object used to load meshes (default - hpp::fcl::MeshLoader) - geometry_types - Which geometry model to load. Can be pin.GeometryType.COLLISION, pin.GeometryType.VISUAL or both. (default - [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL]) - - contacts - Boolean to know if contraint models are wanted (default - False) + - constraints - Boolean to know if constraint models are wanted (default - False) Return: - Tuple of the models, in this order : model, collision model, and visual model, or model, constraint_list, collision model, and visual model, if contacts is True. + Tuple of the models, in this order : model, collision model, and visual model, or model, constraint_list, collision model, and visual model, if constraints is True. Example: model, collision_model, visual_model = buildModelsFromMJCF(filename, root_joint, verbose, meshLoader, geometry_types, root_joint_name="root_joint_name") """ # Handle the switch from old to new api - arg_keys = ["root_joint", "verbose", "meshLoader", "geometry_types", "contacts"] + arg_keys = ["root_joint", "verbose", "meshLoader", "geometry_types", "constraints"] if len(args) >= 2: if isinstance(args[1], str): arg_keys = [ @@ -267,7 +264,7 @@ def buildModelsFromMJCF(filename, *args, **kwargs): "verbose", "meshLoader", "geometry_types", - "contacts", + "constraints", ] for key, arg in zip(arg_keys, args): @@ -286,20 +283,19 @@ def _buildModelsFromMJCF( verbose=False, meshLoader=None, geometry_types=None, - contacts=False, + constraints=True, ): if geometry_types is None: geometry_types = [pin.GeometryType.COLLISION, pin.GeometryType.VISUAL] - contact_models = [] + model = pin.Model() + # model, constraint_models = pin.buildModelFromMJCF(filename, root_joint = root_joint, root_joint_name = root_joint_name) if root_joint is None: model = pin.buildModelFromMJCF(filename) elif root_joint is not None and root_joint_name is None: model = pin.buildModelFromMJCF(filename, root_joint) else: - model, contact_models = pin.buildModelFromMJCF( - filename, root_joint, root_joint_name - ) + model = pin.buildModelFromMJCF(filename, root_joint, root_joint_name) if verbose and not WITH_HPP_FCL and meshLoader is not None: print( @@ -312,8 +308,17 @@ def _buildModelsFromMJCF( ) lst = [model] - if contacts: - lst.append(contact_models) + if constraints: + bilateral_constraint_models = pin.buildBilateralConstraintModelsFromMJCF( + model, filename + ) + weld_constraint_models = pin.buildWeldConstraintModelsFromMJCF(model, filename) + lst.append( + { + "bilateral_point_constraint_models": bilateral_constraint_models, + "weld_constraint_models": weld_constraint_models, + } + ) if not hasattr(geometry_types, "__iter__"): geometry_types = [geometry_types] diff --git a/bindings/python/pinocchio/visualize/meshcat_visualizer.py b/bindings/python/pinocchio/visualize/meshcat_visualizer.py index f99ae91c1a..97b14983e0 100644 --- a/bindings/python/pinocchio/visualize/meshcat_visualizer.py +++ b/bindings/python/pinocchio/visualize/meshcat_visualizer.py @@ -1,9 +1,10 @@ -# TODO: Remove when 20.04 is not supported +# TODO: Remove when py39 is dropped +# This allow to use new Optional syntax from __future__ import annotations import warnings from pathlib import Path -from typing import ClassVar +from typing import ClassVar, Union import numpy as np @@ -26,8 +27,8 @@ import xml.etree.ElementTree as Et from typing import Any -# TODO: Remove quote when 20.04 is not supported -MsgType = "dict[str, Union[str, bytes, bool, float, 'MsgType']]" +# TODO: Use Union syntax when py39 is dropped +MsgType = dict[str, Union[str, bytes, bool, float, "MsgType"]] try: import hppfcl diff --git a/bindings/python/pinocchio/visualize/panda3d_visualizer.py b/bindings/python/pinocchio/visualize/panda3d_visualizer.py index dd2b5b314a..24f68d3f6f 100644 --- a/bindings/python/pinocchio/visualize/panda3d_visualizer.py +++ b/bindings/python/pinocchio/visualize/panda3d_visualizer.py @@ -19,7 +19,7 @@ class Panda3dVisualizer(BaseVisualizer): A Pinocchio display using panda3d engine. """ - def initViewer(self, viewer=None, load_model=False): # pylint: disable=arguments-differ + def initViewer(self, viewer=None, load_model=False, open=True): # pylint: disable=arguments-differ """Init the viewer by attaching to / creating a GUI viewer.""" self.visual_group = None self.collision_group = None @@ -30,7 +30,12 @@ def initViewer(self, viewer=None, load_model=False): # pylint: disable=argument from panda3d_viewer import Viewer as Panda3dViewer if viewer is None: - self.viewer = Panda3dViewer(window_title="python-pinocchio") + if not open: + self.viewer = Panda3dViewer( + window_title="python-pinocchio", window_type="offscreen" + ) + else: + self.viewer = Panda3dViewer(window_title="python-pinocchio") if load_model: self.loadViewerModel(group_name=self.model.name) @@ -140,7 +145,10 @@ def setCameraPose(self, pose: np.ndarray): raise NotImplementedError() def captureImage(self, w=None, h=None): - raise NotImplementedError() + rgb = self.viewer.get_screenshot(requested_format="RGB") + if rgb is None: + raise RuntimeError("Failed to capture image from viewer") + return rgb def disableCameraControl(self): raise NotImplementedError() diff --git a/bindings/python/spatial/expose-explog.cpp b/bindings/python/spatial/expose-explog.cpp index 09267d2e35..0f2a5cd815 100644 --- a/bindings/python/spatial/expose-explog.cpp +++ b/bindings/python/spatial/expose-explog.cpp @@ -51,29 +51,29 @@ namespace pinocchio bp::def( "log3", &log3_proxy, bp::args("quat"), - "Log: S^3 -> so3 is the pseudo-inverse of Exp: so3 -> S^3, the exponential map from " - "so3 to the unit" + "Log: S^3 -> so3 is the pseudo-inverse of Exp: so3 -> S^3, the exponential map from so3 to " + "the unit" " quaternions. It maps from S^3 -> { v in so3, ||v|| < 2pi }."); bp::def( "log3", &log3_proxy_quatvec, bp::args("quat"), - "Log: S^3 -> so3 is the pseudo-inverse of Exp: so3 -> S^3, the exponential map from " - "so3 to the unit" + "Log: S^3 -> so3 is the pseudo-inverse of Exp: so3 -> S^3, the exponential map from so3 to " + "the unit" " quaternions. It maps from S^3 -> { v in so3, ||v|| < 2pi }."); bp::def( "log3", &log3_proxy_quatvec, bp::args("quat", "theta"), - "Log: S^3 -> so3 is the pseudo-inverse of Exp: so3 -> S^3, the exponential map from " - "so3 to the unit" + "Log: S^3 -> so3 is the pseudo-inverse of Exp: so3 -> S^3, the exponential map from so3 to " + "the unit" " quaternions. It maps from S^3 -> { v in so3, ||v|| < 2pi }.\n" "It also returns the angle of rotation theta around the rotation axis."); bp::def( "log3", &log3_proxy_quatvec_fix, bp::args("quat", "theta"), - "Log: S^3 -> so3 is the pseudo-inverse of Exp: so3 -> S^3, the exponential map from " - "so3 to the unit" + "Log: S^3 -> so3 is the pseudo-inverse of Exp: so3 -> S^3, the exponential map from so3 to " + "the unit" " quaternions. It maps from S^3 -> { v in so3, ||v|| < 2pi }.\n" "It also returns the angle of rotation theta around the rotation axis."); diff --git a/bindings/python/spatial/expose-skew.cpp b/bindings/python/spatial/expose-skew.cpp index 07ea0a9a30..d5c9696e5e 100644 --- a/bindings/python/spatial/expose-skew.cpp +++ b/bindings/python/spatial/expose-skew.cpp @@ -54,8 +54,8 @@ namespace pinocchio bp::def( "skewSquare", &skewSquare, bp::args("u", "v"), "Computes the skew square representation of two given 3d vectors, " - "i.e. the antisymmetric matrix representation of the chained cross product operator, " - "u x (v x w), where w is another 3d vector.\n" + "i.e. the antisymmetric matrix representation of the chained cross product operator, u x " + "(v x w), where w is another 3d vector.\n" "Parameters:\n" "\tu: the first input vector of dimension 3\n" "\tv: the second input vector of dimension 3"); diff --git a/cmake b/cmake index b5ae8e4930..3632eb9ed4 160000 --- a/cmake +++ b/cmake @@ -1 +1 @@ -Subproject commit b5ae8e49306840a50ae9c752c5b4040f892c89d8 +Subproject commit 3632eb9ed43e29d7acbc5b35d30c9b2aee801702 diff --git a/development/contributing.md b/development/contributing.md index 2cb45c2b29..af33bfb880 100644 --- a/development/contributing.md +++ b/development/contributing.md @@ -19,7 +19,7 @@ Please try to include as much information as you can. Details like these are inc * Anything unusual about your environment or deployment ## Contributing via Pull Requests -The following guidance should be up-to-date, but the documentation as found [here](https://gepettoweb.laas.fr/doc/stack-of-tasks/pinocchio/master/doxygen-html/) should prove as the final say. +The following guidance should be up-to-date, but the documentation as found [here](https://gepettoweb.laas.fr/doc/stack-of-tasks/pinocchio/devel/doxygen-html/) should prove as the final say. Contributions via pull requests are much appreciated. Before sending us a pull request, please ensure that: diff --git a/development/release.md b/development/release.md index 3d79cba799..9d419e5f3a 100644 --- a/development/release.md +++ b/development/release.md @@ -6,7 +6,6 @@ To create a release with Pixi run the following commands on the **devel** branch PINOCCHIO_VERSION=X.Y.Z pixi run release_new_version git push origin git push origin vX.Y.Z -git push origin devel:master ``` Where `X.Y.Z` is the new version. diff --git a/development/scripts/pinocchio/linalg/.gitignore b/development/scripts/pinocchio/linalg/.gitignore new file mode 100644 index 0000000000..3eb5c74d2f --- /dev/null +++ b/development/scripts/pinocchio/linalg/.gitignore @@ -0,0 +1,2 @@ +*_codegen.c +*_codegen.h diff --git a/development/scripts/pinocchio/linalg/benchmark.c b/development/scripts/pinocchio/linalg/benchmark.c new file mode 100644 index 0000000000..c4bb4afbaa --- /dev/null +++ b/development/scripts/pinocchio/linalg/benchmark.c @@ -0,0 +1,65 @@ +#include +#include "inv_A_fun3_codegen.h" +#include "A_inv_chol_fun3_codegen.h" +#include "U_fun3_codegen.h" +#include + +#define casadi_real double +#define casadi_int long long int + +int f(const casadi_real ** arg, casadi_real ** res, casadi_int * iw, casadi_real * w, int mem); + +int main() +{ // + double x[50] = { + 11.97623514, 0.5582902, -2.39658057, -3.75451444, 2.84949994, -4.9783341, + 0.5582902, 5.93341693, -3.76665704, 0.18569052, 3.08882618, -2.88752941, + -2.39658057, -3.76665704, 6.02263329, -0.95414839, -3.62364168, 2.17486679, + -3.75451444, 0.18569052, -0.95414839, 4.01772341, 1.63855904, 0.04778753, + 2.84949994, 3.08882618, -3.62364168, 1.63855904, 5.36739647, -4.06595882, + -4.9783341, -2.88752941, 2.17486679, 0.04778753, -4.06595882, 6.69418877}; //= {9, 16}; + double y[50]; // = {1}; + double z[50]; + double z2[50]; + double z3[50]; + const double * arg[2] = {x, y}; + double * res[1] = {z}; + double * res2[1] = {z2}; + double * res3[1] = {z3}; + double w[60]; + + int N_steps = 10000000; + // Time the loop below + clock_t start = clock(); + for (int i = 0; i < N_steps; i++) + { + inv_A_fun(arg, res, 0, w, 0); + x[0] += 1e-9; + } + clock_t end = clock(); + double time_spent = (double)(end - start) / CLOCKS_PER_SEC / N_steps * 1e9; + printf("Time spent in CasADi inverse: %f nanoseconds\n", time_spent); + // Print the result + + start = clock(); + for (int i = 0; i < N_steps; i++) + { + A_inv_chol_fun(arg, res2, 0, w, 0); + x[0] += 1e-9; + } + end = clock(); + time_spent = (double)(end - start) / CLOCKS_PER_SEC / N_steps * 1e9; + printf("Time spent in LTL inverse: %f nanoseconds\n", time_spent); + + start = clock(); + for (int i = 0; i < N_steps; i++) + { + U_fun(arg, res, 0, w, 0); + x[0] += 1e-9; + } + end = clock(); + time_spent = (double)(end - start) / CLOCKS_PER_SEC / N_steps * 1e9; + printf("Time spent in LTL: %f nanoseconds\n", time_spent); + + return 0; +} diff --git a/development/scripts/pinocchio/linalg/inversion_cholesky_codegen_casadi.py b/development/scripts/pinocchio/linalg/inversion_cholesky_codegen_casadi.py new file mode 100644 index 0000000000..e7113656ef --- /dev/null +++ b/development/scripts/pinocchio/linalg/inversion_cholesky_codegen_casadi.py @@ -0,0 +1,170 @@ +# +# Copyright (c) 2025 INRIA +# + +import casadi as cs +import numpy as np + + +def LTL(M): + n = M.shape[0] + U = cs.SX(n, n) + + for i in range(n - 1, -1, -1): + for j in range(n - 1, i, -1): + s = sum(U[i, k] * U[j, k] for k in range(j + 1, n)) + U[i, j] = (M[i, j] - s) / U[j, j] + + s = sum(U[i, k] ** 2 for k in range(i + 1, n)) + U[i, i] = cs.sqrt(M[i, i] - s) + + return U + + +def LTDL(M): + n = M.shape[0] + U = cs.SX(n, n) + + for i in range(n - 1, -1, -1): + for j in range(n - 1, i, -1): + s = sum(U[i, k] * U[k, k] * U[j, k] for k in range(j + 1, n)) + U[i, j] = (M[i, j] - s) / U[j, j] + + s = sum(U[k, k] * (U[i, k] ** 2) for k in range(i + 1, n)) + U[i, i] = M[i, i] - s + + return U + + +def LLT_backsolve(L, y): + # return x such that L*x = y + + n = L.shape[0] + x = cs.SX(n, y.shape[1]) + + for i in range(n): + s = sum(L[i, j] * x[j, :] for j in range(i)) + x[i, :] = (y[i, :] - s) / L[i, i] + + return x + + +def LDLT_backsolve(L, y): + # return x such that L*x = y + + n = L.shape[0] + x = cs.SX(n, y.shape[1]) + + for i in range(n): + s = sum(L[i, j] * x[j, :] for j in range(i)) + x[i, :] = y[i, :] - s + + return x + + +def LLT_forwardsolve(L, y): + # return x such that L^T*x = y + + n = L.shape[0] + x = cs.SX(n, y.shape[1]) + + for i in range(n - 1, -1, -1): + s = sum(L[j, i] * x[j, :] for j in range(i + 1, n)) + x[i, :] = (y[i, :] - s) / L[i, i] + + return x + + +def LDLT_forwardsolve(L, y): + # return x such that L^T*x = y + + n = L.shape[0] + x = cs.SX(n, y.shape[1]) + + for i in range(n - 1, -1, -1): + s = sum(L[j, i] * x[j, :] for j in range(i + 1, n)) + x[i, :] = y[i, :] - s + + return x + + +def LTL_solve(U, y): + z = LLT_forwardsolve(U.T, y) + x = LLT_backsolve(U.T, z) + + return x + + +def LTDL_solve(U, y): + D = cs.diag(U) + z = LDLT_forwardsolve(U.T, y) + z /= D + x = LDLT_backsolve(U.T, z) + + return x + + +def make_symmetric(M): + m = M.shape[0] + n = M.shape[1] + assert m == n, "Matrix must be square" + for i in range(m): + for j in range(i): + M[i, j] = M[j, i] + + return M + + +def get_num_operations(fun): + return fun.n_instructions() - fun.nnz_in() - fun.nnz_out() + + +decompose = LTDL +solve = LTDL_solve +# decompose = LTL +# solve = LTL_solve + +n = 1 +A = cs.SX.sym("A", n, n) +b = cs.SX.sym("b", n, 1) +U = decompose(A) + +U_fun = cs.Function("U_fun", [A], [U]) +U_fun.generate(f"U_fun{n!s}_codegen.c", {"with_header": True}) + +A_inv_chol = make_symmetric(solve(U, cs.SX.eye(n))) +A_inv_chol_fun = cs.Function("A_inv_chol_fun", [A], [A_inv_chol]) +A_inv_chol_fun.generate(f"A_inv_chol_fun{n!s}_codegen.c", {"with_header": True}) + +inv_A = make_symmetric(cs.inv(A)) +inv_A_fun = cs.Function("inv_A_fun", [A], [inv_A]) +inv_A_fun.generate(f"inv_A_fun{n!s}_codegen.c", {"with_header": True}) + +U_sym = cs.SX.sym("U", n, n) +x_sol = solve(U_sym, b) +x_sol_fun = cs.Function("x_sol_fun", [U_sym, b], [x_sol]) +x_sol_fun.generate(f"x_sol_fun{n!s}_codegen.c", {"with_header": True}) + +A_val = np.random.rand(n, n) +A_val = A_val @ A_val.T +b_val = np.random.rand(n, 1) + +U_val = U_fun(A_val) +# print("U_val", U_val) + +A_inv_chol_val = A_inv_chol_fun(A_val) +# print("A_inv_chol_val", A_inv_chol_val) + +inv_A_val = inv_A_fun(A_val) +# print("inv_A_val", inv_A_val) +assert np.allclose(A_inv_chol_val, inv_A_val) + +x_sol_val = x_sol_fun(U_val, b_val) +# print("x_sol_val", x_sol_val) +# print("A_inv@b_val", inv_A_val @ b_val) +assert np.allclose(x_sol_val, inv_A_val @ b_val) + +print("Num operations Casadi inverse", get_num_operations(inv_A_fun)) +print("Num operations inverse from LTL", get_num_operations(A_inv_chol_fun)) +print("Num operations LTL", get_num_operations(U_fun)) +print("Num operations LTL solve", get_num_operations(x_sol_fun)) diff --git a/doc/Doxyfile.extra.in b/doc/Doxyfile.extra.in index 9f6b0f5806..ca91dac96e 100644 --- a/doc/Doxyfile.extra.in +++ b/doc/Doxyfile.extra.in @@ -315,10 +315,11 @@ FILE_PATTERNS = *.cc *.cpp *.h *.hpp *.hh *.dox *.md *.py # Note that relative paths are relative to the directory from which doxygen is # run. -#EXCLUDE = @PROJECT_SOURCE_DIR@/doc/d-practical-exercises/src +EXCLUDE = @PROJECT_SOURCE_DIR@/doc/d-practical-exercises/src # Put them back for inclusion as whole files -HTML_EXTRA_FILES += @PROJECT_SOURCE_DIR@/doc/d-practical-exercises/src +HTML_EXTRA_FILES += @PROJECT_SOURCE_DIR@/doc/d-practical-exercises/src \ + @PROJECT_SOURCE_DIR@/doc/doxygen-awesome-darkmode-toggle.js # The EXCLUDE_SYMLINKS tag can be used to select whether or not files or # directories that are symbolic links (a Unix file system feature) are excluded @@ -355,8 +356,7 @@ EXCLUDE_PATTERNS += CMake* \ # wildcard * is used, a substring. Examples: ANamespace, AClass, # AClass::ANamespace, ANamespace::*Test -EXCLUDE_SYMBOLS = internal::* \ - *Visitor +EXCLUDE_SYMBOLS = internal::*,detail*::**Visitor,boost::*,Eigen::*,eigenpy::*,std::* # The IMAGE_PATH tag can be used to specify one or more files or # directories that contain image that are included in the documentation (see @@ -397,12 +397,6 @@ VERBATIM_HEADERS = YES ALPHABETICAL_INDEX = YES -# If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then -# the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns -# in which this list will be split (can be a number in the range [1..20]) - -COLS_IN_ALPHA_INDEX = 4 - #--------------------------------------------------------------------------- # configuration options related to the HTML output #--------------------------------------------------------------------------- @@ -413,7 +407,8 @@ COLS_IN_ALPHA_INDEX = 4 # Doxygen will copy the logo to the output directory. PROJECT_LOGO = @PROJECT_SOURCE_DIR@/doc/pinocchio.png -HTML_EXTRA_FILES += pinocchio.png +HTML_EXTRA_FILES += @PROJECT_SOURCE_DIR@/doc/pinocchio.png \ + @PROJECT_SOURCE_DIR@/doc/pinocchio.ico # The HTML_HEADER tag can be used to specify a personal HTML header for # each generated HTML page. If it is left blank doxygen will generate a @@ -427,60 +422,21 @@ HTML_EXTRA_FILES += pinocchio.png # changing the value of configuration settings such as GENERATE_TREEVIEW! HTML_HEADER = @PROJECT_SOURCE_DIR@/doc/header.html -HTML_EXTRA_FILES += @PROJECT_SOURCE_DIR@/doc/pinocchio.ico # The HTML_FOOTER tag can be used to specify a personal HTML footer for # each generated HTML page. If it is left blank doxygen will generate a # standard footer. -HTML_FOOTER = - -# The HTML_STYLESHEET tag can be used to specify a user-defined cascading -# style sheet that is used by each HTML page. It can be used to -# fine-tune the look of the HTML output. If the tag is left blank doxygen -# will generate a default style sheet. Note that doxygen will try to copy -# the style sheet file to the HTML output directory, so don't put your own -# style sheet in the HTML output directory as well, or it will be erased! -# NOTE: It is recommended to use HTML_EXTRA_STYLESHEET instead of this tag, -# as it is more robust and this tag (HTML_STYLESHEET) -# will in the future become obsolete. - -#HTML_STYLESHEET = @PROJECT_SOURCE_DIR@/doc/package.css - -# The HTML_EXTRA_STYLESHEET tag can be used to specify additional user-defined -# cascading style sheets that are included after the standard style sheets -# created by doxygen. Using this option one can overrule certain style aspects. -# This is preferred over using HTML_STYLESHEET since it does not replace -# the standard style sheet and is therefore more robust against future updates. -# Doxygen will copy the style sheet files to the output directory. - -HTML_EXTRA_STYLESHEET = @PROJECT_SOURCE_DIR@/doc/customdoxygen.css - -# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. -# Doxygen will adjust the colors in the style sheet and background images -# according to this color. Hue is specified as an angle on a colorwheel, -# see http://en.wikipedia.org/wiki/Hue for more information. -# For instance the value 0 represents red, 60 is yellow, 120 is green, -# 180 is cyan, 240 is blue, 300 purple, and 360 is red again. -# The allowed range is 0 to 359. -# The default is 220. - -HTML_COLORSTYLE_HUE = 220 - -# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of -# the colors in the HTML output. For a value of 0 the output will use -# grayscales only. A value of 255 will produce the most vivid colors. +HTML_FOOTER = -HTML_COLORSTYLE_SAT = 100 +FULL_SIDEBAR = NO -# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to -# the luminance component of the colors in the HTML output. Values below -# 100 gradually make the output lighter, whereas values above 100 make -# the output darker. The value divided by 100 is the actual gamma applied, -# so 80 represents a gamma of 0.8, The value 220 represents a gamma of 2.2, -# and 100 does not change the gamma. +HTML_EXTRA_STYLESHEET = @PROJECT_SOURCE_DIR@/doc/doxygen-awesome.css -HTML_COLORSTYLE_GAMMA = 80 +HTML_COLORSTYLE_HUE = 209 +HTML_COLORSTYLE_SAT = 255 +HTML_COLORSTYLE_GAMMA = 113 +HTML_COLORSTYLE = LIGHT # If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML # documentation will contain sections that can be hidden and shown after the @@ -534,7 +490,7 @@ ECLIPSE_DOC_ID = org.doxygen.@PACKAGE_NAME@ # top of each HTML page. The value NO (the default) enables the index and # the value YES disables it. -DISABLE_INDEX = YES +DISABLE_INDEX = NO # The GENERATE_TREEVIEW tag is used to specify whether a tree-like index # structure should be generated to display hierarchical information. @@ -608,7 +564,8 @@ PREDEFINED += EIGEN_MAKE_ALIGNED_OPERATOR_NEW \ PINOCCHIO_WITH_URDFDOM \ PINOCCHIO_WITH_CPPAD_SUPPORT \ PINOCCHIO_WITH_CPPADCG_SUPPORT \ - PINOCCHIO_WITH_LUA5 + PINOCCHIO_DONT_INLINE \ + PINOCCHIO_NOEXCEPT=noexcept # The following macros would be better treated with EXPAND_AS_DEFINED. # However, it was not working properly diff --git a/doc/customdoxygen.css b/doc/customdoxygen.css deleted file mode 100644 index 0e3416fd32..0000000000 --- a/doc/customdoxygen.css +++ /dev/null @@ -1,19 +0,0 @@ -/* Customizing Doxygen output */ - -/* Needed to allow line breaks in tables*/ -.memberdecls { - table-layout: fixed; - width: 100%; -} - -/* Needed to break long template names*/ -.memTemplItemLeft { - white-space: normal !important; - word-wrap: break-word; -} - -/* Needed to break long template names*/ -.memItemLeft { - white-space: normal !important; - word-wrap: break-word; -} diff --git a/doc/doxygen-awesome-darkmode-toggle.js b/doc/doxygen-awesome-darkmode-toggle.js new file mode 100644 index 0000000000..40fe2d38e0 --- /dev/null +++ b/doc/doxygen-awesome-darkmode-toggle.js @@ -0,0 +1,157 @@ +/** + +Doxygen Awesome +https://github.com/jothepro/doxygen-awesome-css + +MIT License + +Copyright (c) 2021 - 2023 jothepro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. + +*/ + +class DoxygenAwesomeDarkModeToggle extends HTMLElement { + // SVG icons from https://fonts.google.com/icons + // Licensed under the Apache 2.0 license: + // https://www.apache.org/licenses/LICENSE-2.0.html + static lightModeIcon = `` + static darkModeIcon = `` + static title = "Toggle Light/Dark Mode" + + static prefersLightModeInDarkModeKey = "prefers-light-mode-in-dark-mode" + static prefersDarkModeInLightModeKey = "prefers-dark-mode-in-light-mode" + + static _staticConstructor = function() { + DoxygenAwesomeDarkModeToggle.enableDarkMode(DoxygenAwesomeDarkModeToggle.userPreference) + // Update the color scheme when the browsers preference changes + // without user interaction on the website. + window.matchMedia('(prefers-color-scheme: dark)').addEventListener('change', event => { + DoxygenAwesomeDarkModeToggle.onSystemPreferenceChanged() + }) + // Update the color scheme when the tab is made visible again. + // It is possible that the appearance was changed in another tab + // while this tab was in the background. + document.addEventListener("visibilitychange", visibilityState => { + if (document.visibilityState === 'visible') { + DoxygenAwesomeDarkModeToggle.onSystemPreferenceChanged() + } + }); + }() + + static init() { + $(function() { + $(document).ready(function() { + const toggleButton = document.createElement('doxygen-awesome-dark-mode-toggle') + toggleButton.title = DoxygenAwesomeDarkModeToggle.title + toggleButton.updateIcon() + + window.matchMedia('(prefers-color-scheme: dark)').addEventListener('change', event => { + toggleButton.updateIcon() + }) + document.addEventListener("visibilitychange", visibilityState => { + if (document.visibilityState === 'visible') { + toggleButton.updateIcon() + } + }); + + $(document).ready(function(){ + document.getElementById("MSearchBox").parentNode.appendChild(toggleButton) + }) + $(window).resize(function(){ + document.getElementById("MSearchBox").parentNode.appendChild(toggleButton) + }) + }) + }) + } + + constructor() { + super(); + this.onclick=this.toggleDarkMode + } + + /** + * @returns `true` for dark-mode, `false` for light-mode system preference + */ + static get systemPreference() { + return window.matchMedia('(prefers-color-scheme: dark)').matches + } + + /** + * @returns `true` for dark-mode, `false` for light-mode user preference + */ + static get userPreference() { + return (!DoxygenAwesomeDarkModeToggle.systemPreference && localStorage.getItem(DoxygenAwesomeDarkModeToggle.prefersDarkModeInLightModeKey)) || + (DoxygenAwesomeDarkModeToggle.systemPreference && !localStorage.getItem(DoxygenAwesomeDarkModeToggle.prefersLightModeInDarkModeKey)) + } + + static set userPreference(userPreference) { + DoxygenAwesomeDarkModeToggle.darkModeEnabled = userPreference + if(!userPreference) { + if(DoxygenAwesomeDarkModeToggle.systemPreference) { + localStorage.setItem(DoxygenAwesomeDarkModeToggle.prefersLightModeInDarkModeKey, true) + } else { + localStorage.removeItem(DoxygenAwesomeDarkModeToggle.prefersDarkModeInLightModeKey) + } + } else { + if(!DoxygenAwesomeDarkModeToggle.systemPreference) { + localStorage.setItem(DoxygenAwesomeDarkModeToggle.prefersDarkModeInLightModeKey, true) + } else { + localStorage.removeItem(DoxygenAwesomeDarkModeToggle.prefersLightModeInDarkModeKey) + } + } + DoxygenAwesomeDarkModeToggle.onUserPreferenceChanged() + } + + static enableDarkMode(enable) { + if(enable) { + DoxygenAwesomeDarkModeToggle.darkModeEnabled = true + document.documentElement.classList.add("dark-mode") + document.documentElement.classList.remove("light-mode") + } else { + DoxygenAwesomeDarkModeToggle.darkModeEnabled = false + document.documentElement.classList.remove("dark-mode") + document.documentElement.classList.add("light-mode") + } + } + + static onSystemPreferenceChanged() { + DoxygenAwesomeDarkModeToggle.darkModeEnabled = DoxygenAwesomeDarkModeToggle.userPreference + DoxygenAwesomeDarkModeToggle.enableDarkMode(DoxygenAwesomeDarkModeToggle.darkModeEnabled) + } + + static onUserPreferenceChanged() { + DoxygenAwesomeDarkModeToggle.enableDarkMode(DoxygenAwesomeDarkModeToggle.darkModeEnabled) + } + + toggleDarkMode() { + DoxygenAwesomeDarkModeToggle.userPreference = !DoxygenAwesomeDarkModeToggle.userPreference + this.updateIcon() + } + + updateIcon() { + if(DoxygenAwesomeDarkModeToggle.darkModeEnabled) { + this.innerHTML = DoxygenAwesomeDarkModeToggle.darkModeIcon + } else { + this.innerHTML = DoxygenAwesomeDarkModeToggle.lightModeIcon + } + } +} + +customElements.define("doxygen-awesome-dark-mode-toggle", DoxygenAwesomeDarkModeToggle); diff --git a/doc/doxygen-awesome.css b/doc/doxygen-awesome.css new file mode 100644 index 0000000000..af68d5fea7 --- /dev/null +++ b/doc/doxygen-awesome.css @@ -0,0 +1,2683 @@ +/** + +Doxygen Awesome +https://github.com/jothepro/doxygen-awesome-css + +MIT License + +Copyright (c) 2021 - 2023 jothepro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. + +*/ + +html { + /* primary theme color. This will affect the entire websites color scheme: links, arrows, labels, ... */ + --primary-color: #1779c4; + --primary-dark-color: #335c80; + --primary-light-color: #70b1e9; + --on-primary-color: #ffffff; + + /* page base colors */ + --page-background-color: #ffffff; + --page-foreground-color: #2f4153; + --page-secondary-foreground-color: #6f7e8e; + + /* color for all separators on the website: hr, borders, ... */ + --separator-color: #dedede; + + /* border radius for all rounded components. Will affect many components, like dropdowns, memitems, codeblocks, ... */ + --border-radius-large: 8px; + --border-radius-small: 4px; + --border-radius-medium: 6px; + + /* default spacings. Most components reference these values for spacing, to provide uniform spacing on the page. */ + --spacing-small: 5px; + --spacing-medium: 10px; + --spacing-large: 16px; + + /* default box shadow used for raising an element above the normal content. Used in dropdowns, search result, ... */ + --box-shadow: 0 2px 8px 0 rgba(0,0,0,.075); + + --odd-color: rgba(0,0,0,.028); + + /* font-families. will affect all text on the website + * font-family: the normal font for text, headlines, menus + * font-family-monospace: used for preformatted text in memtitle, code, fragments + */ + --font-family: -apple-system,BlinkMacSystemFont,Segoe UI,Roboto,Oxygen,Ubuntu,Cantarell,Fira Sans,Droid Sans,Helvetica Neue,sans-serif; + --font-family-monospace: ui-monospace,SFMono-Regular,SF Mono,Menlo,Consolas,Liberation Mono,monospace; + + /* font sizes */ + --page-font-size: 15.6px; + --navigation-font-size: 14.4px; + --toc-font-size: 13.4px; + --code-font-size: 14px; /* affects code, fragment */ + --title-font-size: 22px; + + /* content text properties. These only affect the page content, not the navigation or any other ui elements */ + --content-line-height: 27px; + /* The content is centered and constraint in it's width. To make the content fill the whole page, set the variable to auto.*/ + --content-maxwidth: 1050px; + --table-line-height: 24px; + --toc-sticky-top: var(--spacing-medium); + --toc-width: 200px; + --toc-max-height: calc(100vh - 2 * var(--spacing-medium) - 85px); + + /* colors for various content boxes: @warning, @note, @deprecated @bug */ + --warning-color: #faf3d8; + --warning-color-dark: #f3a600; + --warning-color-darker: #5f4204; + --note-color: #e4f3ff; + --note-color-dark: #1879C4; + --note-color-darker: #274a5c; + --todo-color: #e4dafd; + --todo-color-dark: #5b2bdd; + --todo-color-darker: #2a0d72; + --deprecated-color: #ecf0f3; + --deprecated-color-dark: #5b6269; + --deprecated-color-darker: #43454a; + --bug-color: #f8d1cc; + --bug-color-dark: #b61825; + --bug-color-darker: #75070f; + --invariant-color: #d8f1e3; + --invariant-color-dark: #44b86f; + --invariant-color-darker: #265532; + + /* blockquote colors */ + --blockquote-background: #f8f9fa; + --blockquote-foreground: #636568; + + /* table colors */ + --tablehead-background: #f1f1f1; + --tablehead-foreground: var(--page-foreground-color); + + /* menu-display: block | none + * Visibility of the top navigation on screens >= 768px. On smaller screen the menu is always visible. + * `GENERATE_TREEVIEW` MUST be enabled! + */ + --menu-display: block; + + --menu-focus-foreground: var(--on-primary-color); + --menu-focus-background: var(--primary-color); + --menu-selected-background: rgba(0,0,0,.05); + + + --header-background: var(--page-background-color); + --header-foreground: var(--page-foreground-color); + + /* searchbar colors */ + --searchbar-background: var(--side-nav-background); + --searchbar-foreground: var(--page-foreground-color); + + /* searchbar size + * (`searchbar-width` is only applied on screens >= 768px. + * on smaller screens the searchbar will always fill the entire screen width) */ + --searchbar-height: 33px; + --searchbar-width: 210px; + --searchbar-border-radius: var(--searchbar-height); + + /* code block colors */ + --code-background: #f5f5f5; + --code-foreground: var(--page-foreground-color); + + /* fragment colors */ + --fragment-background: #F8F9FA; + --fragment-foreground: #37474F; + --fragment-keyword: #bb6bb2; + --fragment-keywordtype: #8258b3; + --fragment-keywordflow: #d67c3b; + --fragment-token: #438a59; + --fragment-comment: #969696; + --fragment-link: #5383d6; + --fragment-preprocessor: #46aaa5; + --fragment-linenumber-color: #797979; + --fragment-linenumber-background: #f4f4f5; + --fragment-linenumber-border: #e3e5e7; + --fragment-lineheight: 20px; + + /* sidebar navigation (treeview) colors */ + --side-nav-background: #fbfbfb; + --side-nav-foreground: var(--page-foreground-color); + --side-nav-arrow-opacity: 0; + --side-nav-arrow-hover-opacity: 0.9; + + --toc-background: var(--side-nav-background); + --toc-foreground: var(--side-nav-foreground); + + /* height of an item in any tree / collapsible table */ + --tree-item-height: 30px; + + --memname-font-size: var(--code-font-size); + --memtitle-font-size: 18px; + + --webkit-scrollbar-size: 7px; + --webkit-scrollbar-padding: 4px; + --webkit-scrollbar-color: var(--separator-color); + + --animation-duration: .12s +} + +@media screen and (max-width: 767px) { + html { + --page-font-size: 16px; + --navigation-font-size: 16px; + --toc-font-size: 15px; + --code-font-size: 15px; /* affects code, fragment */ + --title-font-size: 22px; + } +} + +@media (prefers-color-scheme: dark) { + html:not(.light-mode) { + color-scheme: dark; + + --primary-color: #1982d2; + --primary-dark-color: #86a9c4; + --primary-light-color: #4779ac; + + --box-shadow: 0 2px 8px 0 rgba(0,0,0,.35); + + --odd-color: rgba(100,100,100,.06); + + --menu-selected-background: rgba(0,0,0,.4); + + --page-background-color: #1C1D1F; + --page-foreground-color: #d2dbde; + --page-secondary-foreground-color: #859399; + --separator-color: #38393b; + --side-nav-background: #252628; + + --code-background: #2a2c2f; + + --tablehead-background: #2a2c2f; + + --blockquote-background: #222325; + --blockquote-foreground: #7e8c92; + + --warning-color: #3b2e04; + --warning-color-dark: #f1b602; + --warning-color-darker: #ceb670; + --note-color: #163750; + --note-color-dark: #1982D2; + --note-color-darker: #dcf0fa; + --todo-color: #2a2536; + --todo-color-dark: #7661b3; + --todo-color-darker: #ae9ed6; + --deprecated-color: #2e323b; + --deprecated-color-dark: #738396; + --deprecated-color-darker: #abb0bd; + --bug-color: #2e1917; + --bug-color-dark: #ad2617; + --bug-color-darker: #f5b1aa; + --invariant-color: #303a35; + --invariant-color-dark: #76ce96; + --invariant-color-darker: #cceed5; + + --fragment-background: #282c34; + --fragment-foreground: #dbe4eb; + --fragment-keyword: #cc99cd; + --fragment-keywordtype: #ab99cd; + --fragment-keywordflow: #e08000; + --fragment-token: #7ec699; + --fragment-comment: #999999; + --fragment-link: #98c0e3; + --fragment-preprocessor: #65cabe; + --fragment-linenumber-color: #cccccc; + --fragment-linenumber-background: #35393c; + --fragment-linenumber-border: #1f1f1f; + } +} + +/* dark mode variables are defined twice, to support both the dark-mode without and with doxygen-awesome-darkmode-toggle.js */ +html.dark-mode { + color-scheme: dark; + + --primary-color: #1982d2; + --primary-dark-color: #86a9c4; + --primary-light-color: #4779ac; + + --box-shadow: 0 2px 8px 0 rgba(0,0,0,.30); + + --odd-color: rgba(100,100,100,.06); + + --menu-selected-background: rgba(0,0,0,.4); + + --page-background-color: #1C1D1F; + --page-foreground-color: #d2dbde; + --page-secondary-foreground-color: #859399; + --separator-color: #38393b; + --side-nav-background: #252628; + + --code-background: #2a2c2f; + + --tablehead-background: #2a2c2f; + + --blockquote-background: #222325; + --blockquote-foreground: #7e8c92; + + --warning-color: #3b2e04; + --warning-color-dark: #f1b602; + --warning-color-darker: #ceb670; + --note-color: #163750; + --note-color-dark: #1982D2; + --note-color-darker: #dcf0fa; + --todo-color: #2a2536; + --todo-color-dark: #7661b3; + --todo-color-darker: #ae9ed6; + --deprecated-color: #2e323b; + --deprecated-color-dark: #738396; + --deprecated-color-darker: #abb0bd; + --bug-color: #2e1917; + --bug-color-dark: #ad2617; + --bug-color-darker: #f5b1aa; + --invariant-color: #303a35; + --invariant-color-dark: #76ce96; + --invariant-color-darker: #cceed5; + + --fragment-background: #282c34; + --fragment-foreground: #dbe4eb; + --fragment-keyword: #cc99cd; + --fragment-keywordtype: #ab99cd; + --fragment-keywordflow: #e08000; + --fragment-token: #7ec699; + --fragment-comment: #999999; + --fragment-link: #98c0e3; + --fragment-preprocessor: #65cabe; + --fragment-linenumber-color: #cccccc; + --fragment-linenumber-background: #35393c; + --fragment-linenumber-border: #1f1f1f; +} + +body { + color: var(--page-foreground-color); + background-color: var(--page-background-color); + font-size: var(--page-font-size); +} + +body, table, div, p, dl, #nav-tree .label, .title, +.sm-dox a, .sm-dox a:hover, .sm-dox a:focus, #projectname, +.SelectItem, #MSearchField, .navpath li.navelem a, +.navpath li.navelem a:hover, p.reference, p.definition, div.toc li, div.toc h3 { + font-family: var(--font-family); +} + +h1, h2, h3, h4, h5 { + margin-top: 1em; + font-weight: 600; + line-height: initial; +} + +p, div, table, dl, p.reference, p.definition { + font-size: var(--page-font-size); +} + +p.reference, p.definition { + color: var(--page-secondary-foreground-color); +} + +a:link, a:visited, a:hover, a:focus, a:active { + color: var(--primary-color) !important; + font-weight: 500; + background: none; +} + +a.anchor { + scroll-margin-top: var(--spacing-large); + display: block; +} + +/* + Title and top navigation + */ + +#top { + background: var(--header-background); + border-bottom: 1px solid var(--separator-color); +} + +@media screen and (min-width: 768px) { + #top { + display: flex; + flex-wrap: wrap; + justify-content: space-between; + align-items: center; + } +} + +#main-nav { + flex-grow: 5; + padding: var(--spacing-small) var(--spacing-medium); +} + +#titlearea { + width: auto; + padding: var(--spacing-medium) var(--spacing-large); + background: none; + color: var(--header-foreground); + border-bottom: none; +} + +@media screen and (max-width: 767px) { + #titlearea { + padding-bottom: var(--spacing-small); + } +} + +#titlearea table tbody tr { + height: auto !important; +} + +#projectname { + font-size: var(--title-font-size); + font-weight: 600; +} + +#projectnumber { + font-family: inherit; + font-size: 60%; +} + +#projectbrief { + font-family: inherit; + font-size: 80%; +} + +#projectlogo { + vertical-align: middle; +} + +#projectlogo img { + max-height: calc(var(--title-font-size) * 2); + margin-right: var(--spacing-small); +} + +.sm-dox, .tabs, .tabs2, .tabs3 { + background: none; + padding: 0; +} + +.tabs, .tabs2, .tabs3 { + border-bottom: 1px solid var(--separator-color); + margin-bottom: -1px; +} + +.main-menu-btn-icon, .main-menu-btn-icon:before, .main-menu-btn-icon:after { + background: var(--page-secondary-foreground-color); +} + +@media screen and (max-width: 767px) { + .sm-dox a span.sub-arrow { + background: var(--code-background); + } + + #main-menu a.has-submenu span.sub-arrow { + color: var(--page-secondary-foreground-color); + border-radius: var(--border-radius-medium); + } + + #main-menu a.has-submenu:hover span.sub-arrow { + color: var(--page-foreground-color); + } +} + +@media screen and (min-width: 768px) { + .sm-dox li, .tablist li { + display: var(--menu-display); + } + + .sm-dox a span.sub-arrow { + border-color: var(--header-foreground) transparent transparent transparent; + } + + .sm-dox a:hover span.sub-arrow { + border-color: var(--menu-focus-foreground) transparent transparent transparent; + } + + .sm-dox ul a span.sub-arrow { + border-color: transparent transparent transparent var(--page-foreground-color); + } + + .sm-dox ul a:hover span.sub-arrow { + border-color: transparent transparent transparent var(--menu-focus-foreground); + } +} + +.sm-dox ul { + background: var(--page-background-color); + box-shadow: var(--box-shadow); + border: 1px solid var(--separator-color); + border-radius: var(--border-radius-medium) !important; + padding: var(--spacing-small); + animation: ease-out 150ms slideInMenu; +} + +@keyframes slideInMenu { + from { + opacity: 0; + transform: translate(0px, -2px); + } + + to { + opacity: 1; + transform: translate(0px, 0px); + } +} + +.sm-dox ul a { + color: var(--page-foreground-color) !important; + background: var(--page-background-color); + font-size: var(--navigation-font-size); +} + +.sm-dox>li>ul:after { + border-bottom-color: var(--page-background-color) !important; +} + +.sm-dox>li>ul:before { + border-bottom-color: var(--separator-color) !important; +} + +.sm-dox ul a:hover, .sm-dox ul a:active, .sm-dox ul a:focus { + font-size: var(--navigation-font-size) !important; + color: var(--menu-focus-foreground) !important; + text-shadow: none; + background-color: var(--menu-focus-background); + border-radius: var(--border-radius-small) !important; +} + +.sm-dox a, .sm-dox a:focus, .tablist li, .tablist li a, .tablist li.current a { + text-shadow: none; + background: transparent; + background-image: none !important; + color: var(--header-foreground) !important; + font-weight: normal; + font-size: var(--navigation-font-size); + border-radius: var(--border-radius-small) !important; +} + +.sm-dox a:focus { + outline: auto; +} + +.sm-dox a:hover, .sm-dox a:active, .tablist li a:hover { + text-shadow: none; + font-weight: normal; + background: var(--menu-focus-background); + color: var(--menu-focus-foreground) !important; + border-radius: var(--border-radius-small) !important; + font-size: var(--navigation-font-size); +} + +.tablist li.current { + border-radius: var(--border-radius-small); + background: var(--menu-selected-background); +} + +.tablist li { + margin: var(--spacing-small) 0 var(--spacing-small) var(--spacing-small); +} + +.tablist a { + padding: 0 var(--spacing-large); +} + + +/* + Search box + */ + +#MSearchBox { + height: var(--searchbar-height); + background: var(--searchbar-background); + border-radius: var(--searchbar-border-radius); + border: 1px solid var(--separator-color); + overflow: hidden; + width: var(--searchbar-width); + position: relative; + box-shadow: none; + display: block; + margin-top: 0; +} + +/* until Doxygen 1.9.4 */ +.left img#MSearchSelect { + left: 0; + user-select: none; + padding-left: 8px; +} + +/* Doxygen 1.9.5 */ +.left span#MSearchSelect { + left: 0; + user-select: none; + margin-left: 8px; + padding: 0; +} + +.left #MSearchSelect[src$=".png"] { + padding-left: 0 +} + +.SelectionMark { + user-select: none; +} + +.tabs .left #MSearchSelect { + padding-left: 0; +} + +.tabs #MSearchBox { + position: absolute; + right: var(--spacing-medium); +} + +@media screen and (max-width: 767px) { + .tabs #MSearchBox { + position: relative; + right: 0; + margin-left: var(--spacing-medium); + margin-top: 0; + } +} + +#MSearchSelectWindow, #MSearchResultsWindow { + z-index: 9999; +} + +#MSearchBox.MSearchBoxActive { + border-color: var(--primary-color); + box-shadow: inset 0 0 0 1px var(--primary-color); +} + +#main-menu > li:last-child { + margin-right: 0; +} + +@media screen and (max-width: 767px) { + #main-menu > li:last-child { + height: 50px; + } +} + +#MSearchField { + font-size: var(--navigation-font-size); + height: calc(var(--searchbar-height) - 2px); + background: transparent; + width: calc(var(--searchbar-width) - 64px); +} + +.MSearchBoxActive #MSearchField { + color: var(--searchbar-foreground); +} + +#MSearchSelect { + top: calc(calc(var(--searchbar-height) / 2) - 11px); +} + +#MSearchBox span.left, #MSearchBox span.right { + background: none; + background-image: none; +} + +#MSearchBox span.right { + padding-top: calc(calc(var(--searchbar-height) / 2) - 12px); + position: absolute; + right: var(--spacing-small); +} + +.tabs #MSearchBox span.right { + top: calc(calc(var(--searchbar-height) / 2) - 12px); +} + +@keyframes slideInSearchResults { + from { + opacity: 0; + transform: translate(0, 15px); + } + + to { + opacity: 1; + transform: translate(0, 20px); + } +} + +#MSearchResultsWindow { + left: auto !important; + right: var(--spacing-medium); + border-radius: var(--border-radius-large); + border: 1px solid var(--separator-color); + transform: translate(0, 20px); + box-shadow: var(--box-shadow); + animation: ease-out 280ms slideInSearchResults; + background: var(--page-background-color); +} + +iframe#MSearchResults { + margin: 4px; +} + +iframe { + color-scheme: normal; +} + +@media (prefers-color-scheme: dark) { + html:not(.light-mode) iframe#MSearchResults { + filter: invert() hue-rotate(180deg); + } +} + +html.dark-mode iframe#MSearchResults { + filter: invert() hue-rotate(180deg); +} + +#MSearchResults .SRPage { + background-color: transparent; +} + +#MSearchResults .SRPage .SREntry { + font-size: 10pt; + padding: var(--spacing-small) var(--spacing-medium); +} + +#MSearchSelectWindow { + border: 1px solid var(--separator-color); + border-radius: var(--border-radius-medium); + box-shadow: var(--box-shadow); + background: var(--page-background-color); + padding-top: var(--spacing-small); + padding-bottom: var(--spacing-small); +} + +#MSearchSelectWindow a.SelectItem { + font-size: var(--navigation-font-size); + line-height: var(--content-line-height); + margin: 0 var(--spacing-small); + border-radius: var(--border-radius-small); + color: var(--page-foreground-color) !important; + font-weight: normal; +} + +#MSearchSelectWindow a.SelectItem:hover { + background: var(--menu-focus-background); + color: var(--menu-focus-foreground) !important; +} + +@media screen and (max-width: 767px) { + #MSearchBox { + margin-top: var(--spacing-medium); + margin-bottom: var(--spacing-medium); + width: calc(100vw - 30px); + } + + #main-menu > li:last-child { + float: none !important; + } + + #MSearchField { + width: calc(100vw - 110px); + } + + @keyframes slideInSearchResultsMobile { + from { + opacity: 0; + transform: translate(0, 15px); + } + + to { + opacity: 1; + transform: translate(0, 20px); + } + } + + #MSearchResultsWindow { + left: var(--spacing-medium) !important; + right: var(--spacing-medium); + overflow: auto; + transform: translate(0, 20px); + animation: ease-out 280ms slideInSearchResultsMobile; + width: auto !important; + } + + /* + * Overwrites for fixing the searchbox on mobile in doxygen 1.9.2 + */ + label.main-menu-btn ~ #searchBoxPos1 { + top: 3px !important; + right: 6px !important; + left: 45px; + display: flex; + } + + label.main-menu-btn ~ #searchBoxPos1 > #MSearchBox { + margin-top: 0; + margin-bottom: 0; + flex-grow: 2; + float: left; + } +} + +/* + Tree view + */ + +#side-nav { + padding: 0 !important; + background: var(--side-nav-background); + min-width: 8px; + max-width: 50vw; +} + +@media screen and (max-width: 767px) { + #side-nav { + display: none; + } + + #doc-content { + margin-left: 0 !important; + } +} + +#nav-tree { + background: transparent; + margin-right: 1px; +} + +#nav-tree .label { + font-size: var(--navigation-font-size); +} + +#nav-tree .item { + height: var(--tree-item-height); + line-height: var(--tree-item-height); + overflow: hidden; + text-overflow: ellipsis; +} + +#nav-tree .item > a:focus { + outline: none; +} + +#nav-sync { + bottom: 12px; + right: 12px; + top: auto !important; + user-select: none; +} + +#nav-tree .selected { + text-shadow: none; + background-image: none; + background-color: transparent; + position: relative; + color: var(--primary-color) !important; + font-weight: 500; +} + +#nav-tree .selected::after { + content: ""; + position: absolute; + top: 1px; + bottom: 1px; + left: 0; + width: 4px; + border-radius: 0 var(--border-radius-small) var(--border-radius-small) 0; + background: var(--primary-color); +} + + +#nav-tree a { + color: var(--side-nav-foreground) !important; + font-weight: normal; +} + +#nav-tree a:focus { + outline-style: auto; +} + +#nav-tree .arrow { + opacity: var(--side-nav-arrow-opacity); + background: none; +} + +.arrow { + color: inherit; + cursor: pointer; + font-size: 45%; + vertical-align: middle; + margin-right: 2px; + font-family: serif; + height: auto; + text-align: right; +} + +#nav-tree div.item:hover .arrow, #nav-tree a:focus .arrow { + opacity: var(--side-nav-arrow-hover-opacity); +} + +#nav-tree .selected a { + color: var(--primary-color) !important; + font-weight: bolder; + font-weight: 600; +} + +.ui-resizable-e { + width: 4px; + background: transparent; + box-shadow: inset -1px 0 0 0 var(--separator-color); +} + +/* + Contents + */ + +div.header { + border-bottom: 1px solid var(--separator-color); + background-color: var(--page-background-color); + background-image: none; +} + +@media screen and (min-width: 1000px) { + #doc-content > div > div.contents, + .PageDoc > div.contents { + display: flex; + flex-direction: row-reverse; + flex-wrap: nowrap; + align-items: flex-start; + } + + div.contents .textblock { + min-width: 200px; + flex-grow: 1; + } +} + +div.contents, div.header .title, div.header .summary { + max-width: var(--content-maxwidth); +} + +div.contents, div.header .title { + line-height: initial; + margin: calc(var(--spacing-medium) + .2em) auto var(--spacing-medium) auto; +} + +div.header .summary { + margin: var(--spacing-medium) auto 0 auto; +} + +div.headertitle { + padding: 0; +} + +div.header .title { + font-weight: 600; + font-size: 225%; + padding: var(--spacing-medium) var(--spacing-large); + word-break: break-word; +} + +div.header .summary { + width: auto; + display: block; + float: none; + padding: 0 var(--spacing-large); +} + +td.memSeparator { + border-color: var(--separator-color); +} + +span.mlabel { + background: var(--primary-color); + color: var(--on-primary-color); + border: none; + padding: 4px 9px; + border-radius: 12px; + margin-right: var(--spacing-medium); +} + +span.mlabel:last-of-type { + margin-right: 2px; +} + +div.contents { + padding: 0 var(--spacing-large); +} + +div.contents p, div.contents li { + line-height: var(--content-line-height); +} + +div.contents div.dyncontent { + margin: var(--spacing-medium) 0; +} + +@media (prefers-color-scheme: dark) { + html:not(.light-mode) div.contents div.dyncontent img, + html:not(.light-mode) div.contents center img, + html:not(.light-mode) div.contents > table img, + html:not(.light-mode) div.contents div.dyncontent iframe, + html:not(.light-mode) div.contents center iframe, + html:not(.light-mode) div.contents table iframe, + html:not(.light-mode) div.contents .dotgraph iframe { + filter: brightness(89%) hue-rotate(180deg) invert(); + } +} + +html.dark-mode div.contents div.dyncontent img, +html.dark-mode div.contents center img, +html.dark-mode div.contents > table img, +html.dark-mode div.contents div.dyncontent iframe, +html.dark-mode div.contents center iframe, +html.dark-mode div.contents table iframe, +html.dark-mode div.contents .dotgraph iframe + { + filter: brightness(89%) hue-rotate(180deg) invert(); +} + +h2.groupheader { + border-bottom: 0px; + color: var(--page-foreground-color); + box-shadow: + 100px 0 var(--page-background-color), + -100px 0 var(--page-background-color), + 100px 0.75px var(--separator-color), + -100px 0.75px var(--separator-color), + 500px 0 var(--page-background-color), + -500px 0 var(--page-background-color), + 500px 0.75px var(--separator-color), + -500px 0.75px var(--separator-color), + 900px 0 var(--page-background-color), + -900px 0 var(--page-background-color), + 900px 0.75px var(--separator-color), + -900px 0.75px var(--separator-color), + 1400px 0 var(--page-background-color), + -1400px 0 var(--page-background-color), + 1400px 0.75px var(--separator-color), + -1400px 0.75px var(--separator-color), + 1900px 0 var(--page-background-color), + -1900px 0 var(--page-background-color), + 1900px 0.75px var(--separator-color), + -1900px 0.75px var(--separator-color); +} + +blockquote { + margin: 0 var(--spacing-medium) 0 var(--spacing-medium); + padding: var(--spacing-small) var(--spacing-large); + background: var(--blockquote-background); + color: var(--blockquote-foreground); + border-left: 0; + overflow: visible; + border-radius: var(--border-radius-medium); + overflow: visible; + position: relative; +} + +blockquote::before, blockquote::after { + font-weight: bold; + font-family: serif; + font-size: 360%; + opacity: .15; + position: absolute; +} + +blockquote::before { + content: "“"; + left: -10px; + top: 4px; +} + +blockquote::after { + content: "”"; + right: -8px; + bottom: -25px; +} + +blockquote p { + margin: var(--spacing-small) 0 var(--spacing-medium) 0; +} +.paramname, .paramname em { + font-weight: 600; + color: var(--primary-dark-color); +} + +.paramname > code { + border: 0; +} + +table.params .paramname { + font-weight: 600; + font-family: var(--font-family-monospace); + font-size: var(--code-font-size); + padding-right: var(--spacing-small); + line-height: var(--table-line-height); +} + +h1.glow, h2.glow, h3.glow, h4.glow, h5.glow, h6.glow { + text-shadow: 0 0 15px var(--primary-light-color); +} + +.alphachar a { + color: var(--page-foreground-color); +} + +.dotgraph { + max-width: 100%; + overflow-x: scroll; +} + +.dotgraph .caption { + position: sticky; + left: 0; +} + +/* Wrap Graphviz graphs with the `interactive_dotgraph` class if `INTERACTIVE_SVG = YES` */ +.interactive_dotgraph .dotgraph iframe { + max-width: 100%; +} + +/* + Table of Contents + */ + +div.contents .toc { + max-height: var(--toc-max-height); + min-width: var(--toc-width); + border: 0; + border-left: 1px solid var(--separator-color); + border-radius: 0; + background-color: var(--page-background-color); + box-shadow: none; + position: sticky; + top: var(--toc-sticky-top); + padding: 0 var(--spacing-large); + margin: var(--spacing-small) 0 var(--spacing-large) var(--spacing-large); +} + +div.toc h3 { + color: var(--toc-foreground); + font-size: var(--navigation-font-size); + margin: var(--spacing-large) 0 var(--spacing-medium) 0; +} + +div.toc li { + padding: 0; + background: none; + line-height: var(--toc-font-size); + margin: var(--toc-font-size) 0 0 0; +} + +div.toc li::before { + display: none; +} + +div.toc ul { + margin-top: 0 +} + +div.toc li a { + font-size: var(--toc-font-size); + color: var(--page-foreground-color) !important; + text-decoration: none; +} + +div.toc li a:hover, div.toc li a.active { + color: var(--primary-color) !important; +} + +div.toc li a.aboveActive { + color: var(--page-secondary-foreground-color) !important; +} + + +@media screen and (max-width: 999px) { + div.contents .toc { + max-height: 45vh; + float: none; + width: auto; + margin: 0 0 var(--spacing-medium) 0; + position: relative; + top: 0; + position: relative; + border: 1px solid var(--separator-color); + border-radius: var(--border-radius-medium); + background-color: var(--toc-background); + box-shadow: var(--box-shadow); + } + + div.contents .toc.interactive { + max-height: calc(var(--navigation-font-size) + 2 * var(--spacing-large)); + overflow: hidden; + } + + div.contents .toc > h3 { + -webkit-tap-highlight-color: transparent; + cursor: pointer; + position: sticky; + top: 0; + background-color: var(--toc-background); + margin: 0; + padding: var(--spacing-large) 0; + display: block; + } + + div.contents .toc.interactive > h3::before { + content: ""; + width: 0; + height: 0; + border-left: 4px solid transparent; + border-right: 4px solid transparent; + border-top: 5px solid var(--primary-color); + display: inline-block; + margin-right: var(--spacing-small); + margin-bottom: calc(var(--navigation-font-size) / 4); + transform: rotate(-90deg); + transition: transform var(--animation-duration) ease-out; + } + + div.contents .toc.interactive.open > h3::before { + transform: rotate(0deg); + } + + div.contents .toc.interactive.open { + max-height: 45vh; + overflow: auto; + transition: max-height 0.2s ease-in-out; + } + + div.contents .toc a, div.contents .toc a.active { + color: var(--primary-color) !important; + } + + div.contents .toc a:hover { + text-decoration: underline; + } +} + +/* + Code & Fragments + */ + +code, div.fragment, pre.fragment { + border-radius: var(--border-radius-small); + border: 1px solid var(--separator-color); + overflow: hidden; +} + +code { + display: inline; + background: var(--code-background); + color: var(--code-foreground); + padding: 2px 6px; +} + +div.fragment, pre.fragment { + margin: var(--spacing-medium) 0; + padding: calc(var(--spacing-large) - (var(--spacing-large) / 6)) var(--spacing-large); + background: var(--fragment-background); + color: var(--fragment-foreground); + overflow-x: auto; +} + +@media screen and (max-width: 767px) { + div.fragment, pre.fragment { + border-top-right-radius: 0; + border-bottom-right-radius: 0; + border-right: 0; + } + + .contents > div.fragment, + .textblock > div.fragment, + .textblock > pre.fragment, + .textblock > .tabbed > ul > li > div.fragment, + .textblock > .tabbed > ul > li > pre.fragment, + .contents > .doxygen-awesome-fragment-wrapper > div.fragment, + .textblock > .doxygen-awesome-fragment-wrapper > div.fragment, + .textblock > .doxygen-awesome-fragment-wrapper > pre.fragment, + .textblock > .tabbed > ul > li > .doxygen-awesome-fragment-wrapper > div.fragment, + .textblock > .tabbed > ul > li > .doxygen-awesome-fragment-wrapper > pre.fragment { + margin: var(--spacing-medium) calc(0px - var(--spacing-large)); + border-radius: 0; + border-left: 0; + } + + .textblock li > .fragment, + .textblock li > .doxygen-awesome-fragment-wrapper > .fragment { + margin: var(--spacing-medium) calc(0px - var(--spacing-large)); + } + + .memdoc li > .fragment, + .memdoc li > .doxygen-awesome-fragment-wrapper > .fragment { + margin: var(--spacing-medium) calc(0px - var(--spacing-medium)); + } + + .textblock ul, .memdoc ul { + overflow: initial; + } + + .memdoc > div.fragment, + .memdoc > pre.fragment, + dl dd > div.fragment, + dl dd pre.fragment, + .memdoc > .doxygen-awesome-fragment-wrapper > div.fragment, + .memdoc > .doxygen-awesome-fragment-wrapper > pre.fragment, + dl dd > .doxygen-awesome-fragment-wrapper > div.fragment, + dl dd .doxygen-awesome-fragment-wrapper > pre.fragment { + margin: var(--spacing-medium) calc(0px - var(--spacing-medium)); + border-radius: 0; + border-left: 0; + } +} + +code, code a, pre.fragment, div.fragment, div.fragment .line, div.fragment span, div.fragment .line a, div.fragment .line span { + font-family: var(--font-family-monospace); + font-size: var(--code-font-size) !important; +} + +div.line:after { + margin-right: var(--spacing-medium); +} + +div.fragment .line, pre.fragment { + white-space: pre; + word-wrap: initial; + line-height: var(--fragment-lineheight); +} + +div.fragment span.keyword { + color: var(--fragment-keyword); +} + +div.fragment span.keywordtype { + color: var(--fragment-keywordtype); +} + +div.fragment span.keywordflow { + color: var(--fragment-keywordflow); +} + +div.fragment span.stringliteral { + color: var(--fragment-token) +} + +div.fragment span.comment { + color: var(--fragment-comment); +} + +div.fragment a.code { + color: var(--fragment-link) !important; +} + +div.fragment span.preprocessor { + color: var(--fragment-preprocessor); +} + +div.fragment span.lineno { + display: inline-block; + width: 27px; + border-right: none; + background: var(--fragment-linenumber-background); + color: var(--fragment-linenumber-color); +} + +div.fragment span.lineno a { + background: none; + color: var(--fragment-link) !important; +} + +div.fragment > .line:first-child .lineno { + box-shadow: -999999px 0px 0 999999px var(--fragment-linenumber-background), -999998px 0px 0 999999px var(--fragment-linenumber-border); + background-color: var(--fragment-linenumber-background) !important; +} + +div.line { + border-radius: var(--border-radius-small); +} + +div.line.glow { + background-color: var(--primary-light-color); + box-shadow: none; +} + +/* + dl warning, attention, note, deprecated, bug, ... + */ + +dl.bug dt a, dl.deprecated dt a, dl.todo dt a { + font-weight: bold !important; +} + +dl.warning, dl.attention, dl.note, dl.deprecated, dl.bug, dl.invariant, dl.pre, dl.post, dl.todo, dl.remark { + padding: var(--spacing-medium); + margin: var(--spacing-medium) 0; + color: var(--page-background-color); + overflow: hidden; + margin-left: 0; + border-radius: var(--border-radius-small); +} + +dl.section dd { + margin-bottom: 2px; +} + +dl.warning, dl.attention { + background: var(--warning-color); + border-left: 8px solid var(--warning-color-dark); + color: var(--warning-color-darker); +} + +dl.warning dt, dl.attention dt { + color: var(--warning-color-dark); +} + +dl.note, dl.remark { + background: var(--note-color); + border-left: 8px solid var(--note-color-dark); + color: var(--note-color-darker); +} + +dl.note dt, dl.remark dt { + color: var(--note-color-dark); +} + +dl.todo { + background: var(--todo-color); + border-left: 8px solid var(--todo-color-dark); + color: var(--todo-color-darker); +} + +dl.todo dt a { + color: var(--todo-color-dark) !important; +} + +dl.bug dt a { + color: var(--todo-color-dark) !important; +} + +dl.bug { + background: var(--bug-color); + border-left: 8px solid var(--bug-color-dark); + color: var(--bug-color-darker); +} + +dl.bug dt a { + color: var(--bug-color-dark) !important; +} + +dl.deprecated { + background: var(--deprecated-color); + border-left: 8px solid var(--deprecated-color-dark); + color: var(--deprecated-color-darker); +} + +dl.deprecated dt a { + color: var(--deprecated-color-dark) !important; +} + +dl.section dd, dl.bug dd, dl.deprecated dd, dl.todo dd { + margin-inline-start: 0px; +} + +dl.invariant, dl.pre, dl.post { + background: var(--invariant-color); + border-left: 8px solid var(--invariant-color-dark); + color: var(--invariant-color-darker); +} + +dl.invariant dt, dl.pre dt, dl.post dt { + color: var(--invariant-color-dark); +} + +/* + memitem + */ + +div.memdoc, div.memproto, h2.memtitle { + box-shadow: none; + background-image: none; + border: none; +} + +div.memdoc { + padding: 0 var(--spacing-medium); + background: var(--page-background-color); +} + +h2.memtitle, div.memitem { + border: 1px solid var(--separator-color); + box-shadow: var(--box-shadow); +} + +h2.memtitle { + box-shadow: 0px var(--spacing-medium) 0 -1px var(--fragment-background), var(--box-shadow); +} + +div.memitem { + transition: none; +} + +div.memproto, h2.memtitle { + background: var(--fragment-background); +} + +h2.memtitle { + font-weight: 500; + font-size: var(--memtitle-font-size); + font-family: var(--font-family-monospace); + border-bottom: none; + border-top-left-radius: var(--border-radius-medium); + border-top-right-radius: var(--border-radius-medium); + word-break: break-all; + position: relative; +} + +h2.memtitle:after { + content: ""; + display: block; + background: var(--fragment-background); + height: var(--spacing-medium); + bottom: calc(0px - var(--spacing-medium)); + left: 0; + right: -14px; + position: absolute; + border-top-right-radius: var(--border-radius-medium); +} + +h2.memtitle > span.permalink { + font-size: inherit; +} + +h2.memtitle > span.permalink > a { + text-decoration: none; + padding-left: 3px; + margin-right: -4px; + user-select: none; + display: inline-block; + margin-top: -6px; +} + +h2.memtitle > span.permalink > a:hover { + color: var(--primary-dark-color) !important; +} + +a:target + h2.memtitle, a:target + h2.memtitle + div.memitem { + border-color: var(--primary-light-color); +} + +div.memitem { + border-top-right-radius: var(--border-radius-medium); + border-bottom-right-radius: var(--border-radius-medium); + border-bottom-left-radius: var(--border-radius-medium); + overflow: hidden; + display: block !important; +} + +div.memdoc { + border-radius: 0; +} + +div.memproto { + border-radius: 0 var(--border-radius-small) 0 0; + overflow: auto; + border-bottom: 1px solid var(--separator-color); + padding: var(--spacing-medium); + margin-bottom: -1px; +} + +div.memtitle { + border-top-right-radius: var(--border-radius-medium); + border-top-left-radius: var(--border-radius-medium); +} + +div.memproto table.memname { + font-family: var(--font-family-monospace); + color: var(--page-foreground-color); + font-size: var(--memname-font-size); + text-shadow: none; +} + +div.memproto div.memtemplate { + font-family: var(--font-family-monospace); + color: var(--primary-dark-color); + font-size: var(--memname-font-size); + margin-left: 2px; + text-shadow: none; +} + +table.mlabels, table.mlabels > tbody { + display: block; +} + +td.mlabels-left { + width: auto; +} + +td.mlabels-right { + margin-top: 3px; + position: sticky; + left: 0; +} + +table.mlabels > tbody > tr:first-child { + display: flex; + justify-content: space-between; + flex-wrap: wrap; +} + +.memname, .memitem span.mlabels { + margin: 0 +} + +/* + reflist + */ + +dl.reflist { + box-shadow: var(--box-shadow); + border-radius: var(--border-radius-medium); + border: 1px solid var(--separator-color); + overflow: hidden; + padding: 0; +} + + +dl.reflist dt, dl.reflist dd { + box-shadow: none; + text-shadow: none; + background-image: none; + border: none; + padding: 12px; +} + + +dl.reflist dt { + font-weight: 500; + border-radius: 0; + background: var(--code-background); + border-bottom: 1px solid var(--separator-color); + color: var(--page-foreground-color) +} + + +dl.reflist dd { + background: none; +} + +/* + Table + */ + +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname), +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody { + display: inline-block; + max-width: 100%; +} + +.contents > table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname):not(.classindex) { + margin-left: calc(0px - var(--spacing-large)); + margin-right: calc(0px - var(--spacing-large)); + max-width: calc(100% + 2 * var(--spacing-large)); +} + +table.fieldtable, +table.markdownTable tbody, +table.doxtable tbody { + border: none; + margin: var(--spacing-medium) 0; + box-shadow: 0 0 0 1px var(--separator-color); + border-radius: var(--border-radius-small); +} + +table.markdownTable, table.doxtable, table.fieldtable { + padding: 1px; +} + +table.doxtable caption { + display: block; +} + +table.fieldtable { + border-collapse: collapse; + width: 100%; +} + +th.markdownTableHeadLeft, +th.markdownTableHeadRight, +th.markdownTableHeadCenter, +th.markdownTableHeadNone, +table.doxtable th { + background: var(--tablehead-background); + color: var(--tablehead-foreground); + font-weight: 600; + font-size: var(--page-font-size); +} + +th.markdownTableHeadLeft:first-child, +th.markdownTableHeadRight:first-child, +th.markdownTableHeadCenter:first-child, +th.markdownTableHeadNone:first-child, +table.doxtable tr th:first-child { + border-top-left-radius: var(--border-radius-small); +} + +th.markdownTableHeadLeft:last-child, +th.markdownTableHeadRight:last-child, +th.markdownTableHeadCenter:last-child, +th.markdownTableHeadNone:last-child, +table.doxtable tr th:last-child { + border-top-right-radius: var(--border-radius-small); +} + +table.markdownTable td, +table.markdownTable th, +table.fieldtable td, +table.fieldtable th, +table.doxtable td, +table.doxtable th { + border: 1px solid var(--separator-color); + padding: var(--spacing-small) var(--spacing-medium); +} + +table.markdownTable td:last-child, +table.markdownTable th:last-child, +table.fieldtable td:last-child, +table.fieldtable th:last-child, +table.doxtable td:last-child, +table.doxtable th:last-child { + border-right: none; +} + +table.markdownTable td:first-child, +table.markdownTable th:first-child, +table.fieldtable td:first-child, +table.fieldtable th:first-child, +table.doxtable td:first-child, +table.doxtable th:first-child { + border-left: none; +} + +table.markdownTable tr:first-child td, +table.markdownTable tr:first-child th, +table.fieldtable tr:first-child td, +table.fieldtable tr:first-child th, +table.doxtable tr:first-child td, +table.doxtable tr:first-child th { + border-top: none; +} + +table.markdownTable tr:last-child td, +table.markdownTable tr:last-child th, +table.fieldtable tr:last-child td, +table.fieldtable tr:last-child th, +table.doxtable tr:last-child td, +table.doxtable tr:last-child th { + border-bottom: none; +} + +table.markdownTable tr, table.doxtable tr { + border-bottom: 1px solid var(--separator-color); +} + +table.markdownTable tr:last-child, table.doxtable tr:last-child { + border-bottom: none; +} + +.full_width_table table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) { + display: block; +} + +.full_width_table table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody { + display: table; + width: 100%; +} + +table.fieldtable th { + font-size: var(--page-font-size); + font-weight: 600; + background-image: none; + background-color: var(--tablehead-background); + color: var(--tablehead-foreground); +} + +table.fieldtable td.fieldtype, .fieldtable td.fieldname, .fieldtable td.fieldinit, .fieldtable td.fielddoc, .fieldtable th { + border-bottom: 1px solid var(--separator-color); + border-right: 1px solid var(--separator-color); +} + +table.fieldtable tr:last-child td:first-child { + border-bottom-left-radius: var(--border-radius-small); +} + +table.fieldtable tr:last-child td:last-child { + border-bottom-right-radius: var(--border-radius-small); +} + +.memberdecls td.glow, .fieldtable tr.glow { + background-color: var(--primary-light-color); + box-shadow: none; +} + +table.memberdecls { + display: block; + -webkit-tap-highlight-color: transparent; +} + +table.memberdecls tr[class^='memitem'] { + font-family: var(--font-family-monospace); + font-size: var(--code-font-size); +} + +table.memberdecls tr[class^='memitem'] .memTemplParams { + font-family: var(--font-family-monospace); + font-size: var(--code-font-size); + color: var(--primary-dark-color); + white-space: normal; +} + +table.memberdecls .memItemLeft, +table.memberdecls .memItemRight, +table.memberdecls .memTemplItemLeft, +table.memberdecls .memTemplItemRight, +table.memberdecls .memTemplParams { + transition: none; + padding-top: var(--spacing-small); + padding-bottom: var(--spacing-small); + border-top: 1px solid var(--separator-color); + border-bottom: 1px solid var(--separator-color); + background-color: var(--fragment-background); +} + +table.memberdecls .memTemplItemLeft, +table.memberdecls .memTemplItemRight { + padding-top: 2px; +} + +table.memberdecls .memTemplParams { + border-bottom: 0; + border-left: 1px solid var(--separator-color); + border-right: 1px solid var(--separator-color); + border-radius: var(--border-radius-small) var(--border-radius-small) 0 0; + padding-bottom: var(--spacing-small); +} + +table.memberdecls .memTemplItemLeft { + border-radius: 0 0 0 var(--border-radius-small); + border-left: 1px solid var(--separator-color); + border-top: 0; +} + +table.memberdecls .memTemplItemRight { + border-radius: 0 0 var(--border-radius-small) 0; + border-right: 1px solid var(--separator-color); + padding-left: 0; + border-top: 0; +} + +table.memberdecls .memItemLeft { + border-radius: var(--border-radius-small) 0 0 var(--border-radius-small); + border-left: 1px solid var(--separator-color); + padding-left: var(--spacing-medium); + padding-right: 0; +} + +table.memberdecls .memItemRight { + border-radius: 0 var(--border-radius-small) var(--border-radius-small) 0; + border-right: 1px solid var(--separator-color); + padding-right: var(--spacing-medium); + padding-left: 0; + +} + +table.memberdecls .mdescLeft, table.memberdecls .mdescRight { + background: none; + color: var(--page-foreground-color); + padding: var(--spacing-small) 0; +} + +table.memberdecls .memItemLeft, +table.memberdecls .memTemplItemLeft { + padding-right: var(--spacing-medium); +} + +table.memberdecls .memSeparator { + background: var(--page-background-color); + height: var(--spacing-large); + border: 0; + transition: none; +} + +table.memberdecls .groupheader { + margin-bottom: var(--spacing-large); +} + +table.memberdecls .inherit_header td { + padding: 0 0 var(--spacing-medium) 0; + text-indent: -12px; + color: var(--page-secondary-foreground-color); +} + +table.memberdecls img[src="closed.png"], +table.memberdecls img[src="open.png"], +div.dynheader img[src="open.png"], +div.dynheader img[src="closed.png"] { + width: 0; + height: 0; + border-left: 4px solid transparent; + border-right: 4px solid transparent; + border-top: 5px solid var(--primary-color); + margin-top: 8px; + display: block; + float: left; + margin-left: -10px; + transition: transform var(--animation-duration) ease-out; +} + +table.memberdecls img { + margin-right: 10px; +} + +table.memberdecls img[src="closed.png"], +div.dynheader img[src="closed.png"] { + transform: rotate(-90deg); + +} + +.compoundTemplParams { + font-family: var(--font-family-monospace); + color: var(--primary-dark-color); + font-size: var(--code-font-size); +} + +@media screen and (max-width: 767px) { + + table.memberdecls .memItemLeft, + table.memberdecls .memItemRight, + table.memberdecls .mdescLeft, + table.memberdecls .mdescRight, + table.memberdecls .memTemplItemLeft, + table.memberdecls .memTemplItemRight, + table.memberdecls .memTemplParams { + display: block; + text-align: left; + padding-left: var(--spacing-large); + margin: 0 calc(0px - var(--spacing-large)) 0 calc(0px - var(--spacing-large)); + border-right: none; + border-left: none; + border-radius: 0; + white-space: normal; + } + + table.memberdecls .memItemLeft, + table.memberdecls .mdescLeft, + table.memberdecls .memTemplItemLeft { + border-bottom: 0; + padding-bottom: 0; + } + + table.memberdecls .memTemplItemLeft { + padding-top: 0; + } + + table.memberdecls .mdescLeft { + margin-bottom: calc(0px - var(--page-font-size)); + } + + table.memberdecls .memItemRight, + table.memberdecls .mdescRight, + table.memberdecls .memTemplItemRight { + border-top: 0; + padding-top: 0; + padding-right: var(--spacing-large); + overflow-x: auto; + } + + table.memberdecls tr[class^='memitem']:not(.inherit) { + display: block; + width: calc(100vw - 2 * var(--spacing-large)); + } + + table.memberdecls .mdescRight { + color: var(--page-foreground-color); + } + + table.memberdecls tr.inherit { + visibility: hidden; + } + + table.memberdecls tr[style="display: table-row;"] { + display: block !important; + visibility: visible; + width: calc(100vw - 2 * var(--spacing-large)); + animation: fade .5s; + } + + @keyframes fade { + 0% { + opacity: 0; + max-height: 0; + } + + 100% { + opacity: 1; + max-height: 200px; + } + } +} + + +/* + Horizontal Rule + */ + +hr { + margin-top: var(--spacing-large); + margin-bottom: var(--spacing-large); + height: 1px; + background-color: var(--separator-color); + border: 0; +} + +.contents hr { + box-shadow: 100px 0 var(--separator-color), + -100px 0 var(--separator-color), + 500px 0 var(--separator-color), + -500px 0 var(--separator-color), + 900px 0 var(--separator-color), + -900px 0 var(--separator-color), + 1400px 0 var(--separator-color), + -1400px 0 var(--separator-color), + 1900px 0 var(--separator-color), + -1900px 0 var(--separator-color); +} + +.contents img, .contents .center, .contents center, .contents div.image object { + max-width: 100%; + overflow: auto; +} + +@media screen and (max-width: 767px) { + .contents .dyncontent > .center, .contents > center { + margin-left: calc(0px - var(--spacing-large)); + margin-right: calc(0px - var(--spacing-large)); + max-width: calc(100% + 2 * var(--spacing-large)); + } +} + +/* + Directories + */ +div.directory { + border-top: 1px solid var(--separator-color); + border-bottom: 1px solid var(--separator-color); + width: auto; +} + +table.directory { + font-family: var(--font-family); + font-size: var(--page-font-size); + font-weight: normal; + width: 100%; +} + +table.directory td.entry, table.directory td.desc { + padding: calc(var(--spacing-small) / 2) var(--spacing-small); + line-height: var(--table-line-height); +} + +table.directory tr.even td:last-child { + border-radius: 0 var(--border-radius-small) var(--border-radius-small) 0; +} + +table.directory tr.even td:first-child { + border-radius: var(--border-radius-small) 0 0 var(--border-radius-small); +} + +table.directory tr.even:last-child td:last-child { + border-radius: 0 var(--border-radius-small) 0 0; +} + +table.directory tr.even:last-child td:first-child { + border-radius: var(--border-radius-small) 0 0 0; +} + +table.directory td.desc { + min-width: 250px; +} + +table.directory tr.even { + background-color: var(--odd-color); +} + +table.directory tr.odd { + background-color: transparent; +} + +.icona { + width: auto; + height: auto; + margin: 0 var(--spacing-small); +} + +.icon { + background: var(--primary-color); + border-radius: var(--border-radius-small); + font-size: var(--page-font-size); + padding: calc(var(--page-font-size) / 5); + line-height: var(--page-font-size); + transform: scale(0.8); + height: auto; + width: var(--page-font-size); + user-select: none; +} + +.iconfopen, .icondoc, .iconfclosed { + background-position: center; + margin-bottom: 0; + height: var(--table-line-height); +} + +.icondoc { + filter: saturate(0.2); +} + +@media screen and (max-width: 767px) { + div.directory { + margin-left: calc(0px - var(--spacing-large)); + margin-right: calc(0px - var(--spacing-large)); + } +} + +@media (prefers-color-scheme: dark) { + html:not(.light-mode) .iconfopen, html:not(.light-mode) .iconfclosed { + filter: hue-rotate(180deg) invert(); + } +} + +html.dark-mode .iconfopen, html.dark-mode .iconfclosed { + filter: hue-rotate(180deg) invert(); +} + +/* + Class list + */ + +.classindex dl.odd { + background: var(--odd-color); + border-radius: var(--border-radius-small); +} + +.classindex dl.even { + background-color: transparent; +} + +/* + Class Index Doxygen 1.8 +*/ + +table.classindex { + margin-left: 0; + margin-right: 0; + width: 100%; +} + +table.classindex table div.ah { + background-image: none; + background-color: initial; + border-color: var(--separator-color); + color: var(--page-foreground-color); + box-shadow: var(--box-shadow); + border-radius: var(--border-radius-large); + padding: var(--spacing-small); +} + +div.qindex { + background-color: var(--odd-color); + border-radius: var(--border-radius-small); + border: 1px solid var(--separator-color); + padding: var(--spacing-small) 0; +} + +/* + Footer and nav-path + */ + +#nav-path { + width: 100%; +} + +#nav-path ul { + background-image: none; + background: var(--page-background-color); + border: none; + border-top: 1px solid var(--separator-color); + border-bottom: 1px solid var(--separator-color); + border-bottom: 0; + box-shadow: 0 0.75px 0 var(--separator-color); + font-size: var(--navigation-font-size); +} + +img.footer { + width: 60px; +} + +.navpath li.footer { + color: var(--page-secondary-foreground-color); +} + +address.footer { + color: var(--page-secondary-foreground-color); + margin-bottom: var(--spacing-large); +} + +#nav-path li.navelem { + background-image: none; + display: flex; + align-items: center; +} + +.navpath li.navelem a { + text-shadow: none; + display: inline-block; + color: var(--primary-color) !important; +} + +.navpath li.navelem b { + color: var(--primary-dark-color); + font-weight: 500; +} + +li.navelem { + padding: 0; + margin-left: -8px; +} + +li.navelem:first-child { + margin-left: var(--spacing-large); +} + +li.navelem:first-child:before { + display: none; +} + +#nav-path li.navelem:after { + content: ''; + border: 5px solid var(--page-background-color); + border-bottom-color: transparent; + border-right-color: transparent; + border-top-color: transparent; + transform: translateY(-1px) scaleY(4.2); + z-index: 10; + margin-left: 6px; +} + +#nav-path li.navelem:before { + content: ''; + border: 5px solid var(--separator-color); + border-bottom-color: transparent; + border-right-color: transparent; + border-top-color: transparent; + transform: translateY(-1px) scaleY(3.2); + margin-right: var(--spacing-small); +} + +.navpath li.navelem a:hover { + color: var(--primary-color); +} + +/* + Scrollbars for Webkit +*/ + +#nav-tree::-webkit-scrollbar, +div.fragment::-webkit-scrollbar, +pre.fragment::-webkit-scrollbar, +div.memproto::-webkit-scrollbar, +.contents center::-webkit-scrollbar, +.contents .center::-webkit-scrollbar, +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody::-webkit-scrollbar, +div.contents .toc::-webkit-scrollbar, +.contents .dotgraph::-webkit-scrollbar, +.contents .tabs-overview-container::-webkit-scrollbar { + background: transparent; + width: calc(var(--webkit-scrollbar-size) + var(--webkit-scrollbar-padding) + var(--webkit-scrollbar-padding)); + height: calc(var(--webkit-scrollbar-size) + var(--webkit-scrollbar-padding) + var(--webkit-scrollbar-padding)); +} + +#nav-tree::-webkit-scrollbar-thumb, +div.fragment::-webkit-scrollbar-thumb, +pre.fragment::-webkit-scrollbar-thumb, +div.memproto::-webkit-scrollbar-thumb, +.contents center::-webkit-scrollbar-thumb, +.contents .center::-webkit-scrollbar-thumb, +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody::-webkit-scrollbar-thumb, +div.contents .toc::-webkit-scrollbar-thumb, +.contents .dotgraph::-webkit-scrollbar-thumb, +.contents .tabs-overview-container::-webkit-scrollbar-thumb { + background-color: transparent; + border: var(--webkit-scrollbar-padding) solid transparent; + border-radius: calc(var(--webkit-scrollbar-padding) + var(--webkit-scrollbar-padding)); + background-clip: padding-box; +} + +#nav-tree:hover::-webkit-scrollbar-thumb, +div.fragment:hover::-webkit-scrollbar-thumb, +pre.fragment:hover::-webkit-scrollbar-thumb, +div.memproto:hover::-webkit-scrollbar-thumb, +.contents center:hover::-webkit-scrollbar-thumb, +.contents .center:hover::-webkit-scrollbar-thumb, +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody:hover::-webkit-scrollbar-thumb, +div.contents .toc:hover::-webkit-scrollbar-thumb, +.contents .dotgraph:hover::-webkit-scrollbar-thumb, +.contents .tabs-overview-container:hover::-webkit-scrollbar-thumb { + background-color: var(--webkit-scrollbar-color); +} + +#nav-tree::-webkit-scrollbar-track, +div.fragment::-webkit-scrollbar-track, +pre.fragment::-webkit-scrollbar-track, +div.memproto::-webkit-scrollbar-track, +.contents center::-webkit-scrollbar-track, +.contents .center::-webkit-scrollbar-track, +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody::-webkit-scrollbar-track, +div.contents .toc::-webkit-scrollbar-track, +.contents .dotgraph::-webkit-scrollbar-track, +.contents .tabs-overview-container::-webkit-scrollbar-track { + background: transparent; +} + +#nav-tree::-webkit-scrollbar-corner { + background-color: var(--side-nav-background); +} + +#nav-tree, +div.fragment, +pre.fragment, +div.memproto, +.contents center, +.contents .center, +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody, +div.contents .toc { + overflow-x: auto; + overflow-x: overlay; +} + +#nav-tree { + overflow-x: auto; + overflow-y: auto; + overflow-y: overlay; +} + +/* + Scrollbars for Firefox +*/ + +#nav-tree, +div.fragment, +pre.fragment, +div.memproto, +.contents center, +.contents .center, +.contents table:not(.memberdecls):not(.mlabels):not(.fieldtable):not(.memname) tbody, +div.contents .toc, +.contents .dotgraph, +.contents .tabs-overview-container { + scrollbar-width: thin; +} + +/* + Optional Dark mode toggle button +*/ + +doxygen-awesome-dark-mode-toggle { + display: inline-block; + margin: 0 0 0 var(--spacing-small); + padding: 0; + width: var(--searchbar-height); + height: var(--searchbar-height); + background: none; + border: none; + border-radius: var(--searchbar-height); + vertical-align: middle; + text-align: center; + line-height: var(--searchbar-height); + font-size: 22px; + display: flex; + align-items: center; + justify-content: center; + user-select: none; + cursor: pointer; +} + +doxygen-awesome-dark-mode-toggle > svg { + transition: transform var(--animation-duration) ease-in-out; +} + +doxygen-awesome-dark-mode-toggle:active > svg { + transform: scale(.5); +} + +doxygen-awesome-dark-mode-toggle:hover { + background-color: rgba(0,0,0,.03); +} + +html.dark-mode doxygen-awesome-dark-mode-toggle:hover { + background-color: rgba(0,0,0,.18); +} + +/* + Optional fragment copy button +*/ +.doxygen-awesome-fragment-wrapper { + position: relative; +} + +doxygen-awesome-fragment-copy-button { + opacity: 0; + background: var(--fragment-background); + width: 28px; + height: 28px; + position: absolute; + right: calc(var(--spacing-large) - (var(--spacing-large) / 2.5)); + top: calc(var(--spacing-large) - (var(--spacing-large) / 2.5)); + border: 1px solid var(--fragment-foreground); + cursor: pointer; + border-radius: var(--border-radius-small); + display: flex; + justify-content: center; + align-items: center; +} + +.doxygen-awesome-fragment-wrapper:hover doxygen-awesome-fragment-copy-button, doxygen-awesome-fragment-copy-button.success { + opacity: .28; +} + +doxygen-awesome-fragment-copy-button:hover, doxygen-awesome-fragment-copy-button.success { + opacity: 1 !important; +} + +doxygen-awesome-fragment-copy-button:active:not([class~=success]) svg { + transform: scale(.91); +} + +doxygen-awesome-fragment-copy-button svg { + fill: var(--fragment-foreground); + width: 18px; + height: 18px; +} + +doxygen-awesome-fragment-copy-button.success svg { + fill: rgb(14, 168, 14); +} + +doxygen-awesome-fragment-copy-button.success { + border-color: rgb(14, 168, 14); +} + +@media screen and (max-width: 767px) { + .textblock > .doxygen-awesome-fragment-wrapper > doxygen-awesome-fragment-copy-button, + .textblock li > .doxygen-awesome-fragment-wrapper > doxygen-awesome-fragment-copy-button, + .memdoc li > .doxygen-awesome-fragment-wrapper > doxygen-awesome-fragment-copy-button, + .memdoc > .doxygen-awesome-fragment-wrapper > doxygen-awesome-fragment-copy-button, + dl dd > .doxygen-awesome-fragment-wrapper > doxygen-awesome-fragment-copy-button { + right: 0; + } +} + +/* + Optional paragraph link button +*/ + +a.anchorlink { + font-size: 90%; + margin-left: var(--spacing-small); + color: var(--page-foreground-color) !important; + text-decoration: none; + opacity: .15; + display: none; + transition: opacity var(--animation-duration) ease-in-out, color var(--animation-duration) ease-in-out; +} + +a.anchorlink svg { + fill: var(--page-foreground-color); +} + +h3 a.anchorlink svg, h4 a.anchorlink svg { + margin-bottom: -3px; + margin-top: -4px; +} + +a.anchorlink:hover { + opacity: .45; +} + +h2:hover a.anchorlink, h1:hover a.anchorlink, h3:hover a.anchorlink, h4:hover a.anchorlink { + display: inline-block; +} + +/* + Optional tab feature +*/ + +.tabbed > ul { + padding-inline-start: 0px; + margin: 0; + padding: var(--spacing-small) 0; +} + +.tabbed > ul > li { + display: none; +} + +.tabbed > ul > li.selected { + display: block; +} + +.tabs-overview-container { + overflow-x: auto; + display: block; + overflow-y: visible; +} + +.tabs-overview { + border-bottom: 1px solid var(--separator-color); + display: flex; + flex-direction: row; +} + +@media screen and (max-width: 767px) { + .tabs-overview-container { + margin: 0 calc(0px - var(--spacing-large)); + } + .tabs-overview { + padding: 0 var(--spacing-large) + } +} + +.tabs-overview button.tab-button { + color: var(--page-foreground-color); + margin: 0; + border: none; + background: transparent; + padding: calc(var(--spacing-large) / 2) 0; + display: inline-block; + font-size: var(--page-font-size); + cursor: pointer; + box-shadow: 0 1px 0 0 var(--separator-color); + position: relative; + + -webkit-tap-highlight-color: transparent; +} + +.tabs-overview button.tab-button .tab-title::before { + display: block; + content: attr(title); + font-weight: 600; + height: 0; + overflow: hidden; + visibility: hidden; +} + +.tabs-overview button.tab-button .tab-title { + float: left; + white-space: nowrap; + font-weight: normal; + padding: calc(var(--spacing-large) / 2) var(--spacing-large); + border-radius: var(--border-radius-medium); + transition: background-color var(--animation-duration) ease-in-out, font-weight var(--animation-duration) ease-in-out; +} + +.tabs-overview button.tab-button:not(:last-child) .tab-title { + box-shadow: 8px 0 0 -7px var(--separator-color); +} + +.tabs-overview button.tab-button:hover .tab-title { + background: var(--separator-color); + box-shadow: none; +} + +.tabs-overview button.tab-button.active .tab-title { + font-weight: 600; +} + +.tabs-overview button.tab-button::after { + content: ''; + display: block; + position: absolute; + left: 0; + bottom: 0; + right: 0; + height: 0; + width: 0%; + margin: 0 auto; + border-radius: var(--border-radius-small) var(--border-radius-small) 0 0; + background-color: var(--primary-color); + transition: width var(--animation-duration) ease-in-out, height var(--animation-duration) ease-in-out; +} + +.tabs-overview button.tab-button.active::after { + width: 100%; + box-sizing: border-box; + height: 3px; +} + + +/* + Navigation Buttons +*/ + +.section_buttons:not(:empty) { + margin-top: calc(var(--spacing-large) * 3); +} + +.section_buttons table.markdownTable { + display: block; + width: 100%; +} + +.section_buttons table.markdownTable tbody { + display: table !important; + width: 100%; + box-shadow: none; + border-spacing: 10px; +} + +.section_buttons table.markdownTable td { + padding: 0; +} + +.section_buttons table.markdownTable th { + display: none; +} + +.section_buttons table.markdownTable tr.markdownTableHead { + border: none; +} + +.section_buttons tr th, .section_buttons tr td { + background: none; + border: none; + padding: var(--spacing-large) 0 var(--spacing-small); +} + +.section_buttons a { + display: inline-block; + border: 1px solid var(--separator-color); + border-radius: var(--border-radius-medium); + color: var(--page-secondary-foreground-color) !important; + text-decoration: none; + transition: color var(--animation-duration) ease-in-out, background-color var(--animation-duration) ease-in-out; +} + +.section_buttons a:hover { + color: var(--page-foreground-color) !important; + background-color: var(--odd-color); +} + +.section_buttons tr td.markdownTableBodyLeft a { + padding: var(--spacing-medium) var(--spacing-large) var(--spacing-medium) calc(var(--spacing-large) / 2); +} + +.section_buttons tr td.markdownTableBodyRight a { + padding: var(--spacing-medium) calc(var(--spacing-large) / 2) var(--spacing-medium) var(--spacing-large); +} + +.section_buttons tr td.markdownTableBodyLeft a::before, +.section_buttons tr td.markdownTableBodyRight a::after { + color: var(--page-secondary-foreground-color) !important; + display: inline-block; + transition: color .08s ease-in-out, transform .09s ease-in-out; +} + +.section_buttons tr td.markdownTableBodyLeft a::before { + content: '〈'; + padding-right: var(--spacing-large); +} + + +.section_buttons tr td.markdownTableBodyRight a::after { + content: '〉'; + padding-left: var(--spacing-large); +} + + +.section_buttons tr td.markdownTableBodyLeft a:hover::before { + color: var(--page-foreground-color) !important; + transform: translateX(-3px); +} + +.section_buttons tr td.markdownTableBodyRight a:hover::after { + color: var(--page-foreground-color) !important; + transform: translateX(3px); +} + +@media screen and (max-width: 450px) { + .section_buttons a { + width: 100%; + box-sizing: border-box; + } + + .section_buttons tr td:nth-of-type(1).markdownTableBodyLeft a { + border-radius: var(--border-radius-medium) 0 0 var(--border-radius-medium); + border-right: none; + } + + .section_buttons tr td:nth-of-type(2).markdownTableBodyRight a { + border-radius: 0 var(--border-radius-medium) var(--border-radius-medium) 0; + } +} diff --git a/doc/header.html b/doc/header.html index d0e27869b3..b6ddef3ffc 100644 --- a/doc/header.html +++ b/doc/header.html @@ -1,54 +1,82 @@ - - - + + + - + + $projectname: $title $title + + + - + + + + + + + + $treeview $search $mathjax +$darkmode $extrastylesheet + + + + +
+ + +
- + - + - - - + + + + + + + +
-
$projectname -  $projectnumber +
+
$projectname $projectnumber
$projectbrief
+
$projectbrief
$searchbox$searchbox
$searchbox
diff --git a/doc/outline.txt b/doc/outline.txt deleted file mode 100644 index 26c41d815f..0000000000 --- a/doc/outline.txt +++ /dev/null @@ -1,120 +0,0 @@ -*** Overview -- ABSTRACT (taken from SII paper) -- Installation link -- Simplest example with compilation command (load urdf and run rnea) -- More complete example with C++ and Python (load model and run a loop for an IK with 3D task) - # @GabrieleBndn I don't think it's needed. It can go in the tutorials - # @nmansard Eigen copy-paste. It might be nice for visibility. Let's try, it is not much work. -- About Python wrapings (philosphy and example) -- How to cite Pinocchio -- Presentation of the content of the documentation. - -*** List of features -# Take the list from SII, shorten the description and add url links to the doc. -# This should act as an index for the "Features" part -# Normally, it should be contained in a single page -# It should contain url links for each page contained in "Features", possibly with short descriptions taken from SII -# As an alternative, it may be directly moved to the next section as an introductory page - -*** Features -# This section will be modeled on Eigen's "long tutorial". -# It contains a description of all most important features of Pinocchio, from the user's point of view -# Each section consists of a page and it teaches the user how to use a certain feature, using code snippets. -- Spatial Algebra module -- Model and data - # just explain the concept of model and data and what they contain. The explanation on how to build and/or load a model is delayed to the two following pages (explicitely say so from the start). Just use buildModels::humanoid(model) in the snippets [pending v2.0] -- Joints [pending v2.0] - # Or: Building the model: joints and bodies. Maybe merge this section with previous one? - # @nmansard : I prefer this way of separing models of joint models. -- Loading the model # how to load from an external file -- Dealing with Lie group geometry -- Kinematic algorithms [pending v2.0] -- Dynamic algorithms [pending v2.0] -- Operational frames - # as frames are not necessary to understand the previous sections, it could be a good idea to treat them separately. Introduce them here together with the related algorithms - # @ nmansard good idea -- Geometric models # with related algos -- Analytical derivatives [pending v2.0] -- Automatic differentiation and source code generation [pending v2.0] -- Python bindings -- Unit test - -*** Examples -# These should be a bunch of simple examples in Python and C++ doing key functionnalities. -# They should be chosen so that the documentation is evident. -# The code example both in C++ and Python should be in a stand-alone plain .cpp and .py file, -# possibly added in unittest/doc/*.cpp and unittest/doc/python/*.py (to be defined). -# It would then be straight forward to check at commit time that the .cpp are respecting -# the current API of Pinocchio. If adding .py test feature in our build test, extending -# to .py file test would be easy as well. -- Loading the model -- Computing the dynamics RNEA, bias forces b(q,v), gravity g(q), CRBA M(q) -- Contact dynamics -- Loading and displaying the model -- Collision detection and distances -- Derivatives of the dynamics (with finite diff checking) -- Code generation -- Inverse geometry -- Inverse kinematics (clik) -- Task space inverse dynamics -- QP (normal forces) unilateral contact dynamics (if we can write it concise enough) -- Posture generation using derivatives (if we can write it concise enough) -- A RRT planner for a robot arm (if we can write it concise enough) -- A RL tensorflow example (if we can write it concise enough) - -*** Mathematics -# For each subpart, add the list of "main related topics" toward algo description, specification, etc -# and add the direct url toward corresponding pages of the doc. -- Overview: rigid dynamics, joint dynamics, articulated dynamics, algorithms -- Rigid bodies: geomtry, kinematics and dynamics -- Joint dynamics: geometry, configuration space, kinematics, tangent space, list of joints -- Articulated dynamics: kinematic tree, configuration and velocity, geometry, kinematics and jacobian, inverse and direct dynamics -- Collision volums -- Main algorithm: list taken from SII -- Templatization, autodiff, code gen - -*** Practical exercises -# Documented exercises, could be followed by a newcomer to learn py-based Pinocchio -# Based on @nmansard class -- Intro -- Inverse geometry -- Inverse kinematics -- Contact dynamics -- Optimal control and reinforcement learning - -*** Implementation / Technical details -- Overview: what is making Pinocchio efficient -- Handling the sparsity -- CRTP concept -- Templatization, autodiff, code gen - -*** Benchmarks -- Overview of algo with plots -- Description of how to run the benchmarks - -*** Success stories -# List of projects succesfully using pinocchio -- TSID -- HPP -- DDP -- Supaero class -- WAN demonstration -- List of papers with videos based on Pinocchio - -*** Modules -# Main classes and functions (functions are yet missing) -- Spatial -- Multibody [pending v2.0] -- Joint [pending v2.0] -- Parsers -- Algorithms [pending v2.0] -# We also yet have benchmarks and unittests in the list. Better put then otherwise, is it not? - -*** Python "cheat sheet" -# Main functionalities and commands to be used in python. -# No clear ideas yet about how to present that info. - -*** Python Sphinx documentation -# To be added once Sphinx doc of Pinocchio is mature. -# OStasse suggests a new project that allows inserting sphinx in doxygen. -# We first have to generate a stand-alone sphinx of pinocchio and double check that we are happy with it. diff --git a/doc/treeview.dox b/doc/treeview.dox index 43b63a370d..84f90c1d80 100644 --- a/doc/treeview.dox +++ b/doc/treeview.dox @@ -105,7 +105,4 @@ namespace pinocchio { /// \namespace pinocchio::srdf /// \brief SRDF parsing - - /// \namespace pinocchio::lua - /// \brief Lua parsing } diff --git a/examples/candlewick-viewer-solo.py b/examples/candlewick-viewer-solo.py new file mode 100644 index 0000000000..b4e069080c --- /dev/null +++ b/examples/candlewick-viewer-solo.py @@ -0,0 +1,96 @@ +""" +See also: meshcat-viewer-solo.py +""" + +import time +from pathlib import Path + +import numpy as np +import pinocchio as pin +from candlewick.multibody import Visualizer, VisualizerConfig + +# Load the URDF model. +# Conversion with str seems to be necessary when executing this file with ipython +pinocchio_model_dir = Path(__file__).parent.parent / "models" + +model_path = pinocchio_model_dir / "example-robot-data/robots" +mesh_dir = pinocchio_model_dir +urdf_filename = "solo12.urdf" +urdf_model_path = model_path / "solo_description/robots" / urdf_filename + +model, collision_model, visual_model = pin.buildModelsFromUrdf( + urdf_model_path, mesh_dir, pin.JointModelFreeFlyer() +) +visual_model: pin.GeometryModel + +config = VisualizerConfig() +config.width = 1920 +config.height = 1080 + + +def ground(xy): + return ( + np.sin(xy[0] * 3) / 5 + + np.cos(xy[1] ** 2 * 3) / 20 + + np.sin(xy[1] * xy[0] * 5) / 10 + ) + + +def vizGround(elevation_fn, space, name="ground", color=np.array([1.0, 1.0, 0.6, 0.8])): + xg = np.arange(-2, 2, space) + nx = xg.shape[0] + xy_g = np.meshgrid(xg, xg) + xy_g = np.stack(xy_g) + elev_g = np.zeros((nx, nx)) + elev_g[:, :] = elevation_fn(xy_g) + + sx = xg[-1] - xg[0] + sy = xg[-1] - xg[0] + elev_g[:, :] = elev_g[::-1, :] + import coal + + heightField = coal.HeightFieldAABB(sx, sy, elev_g, np.min(elev_g)) + pl = pin.SE3.Identity() + obj = pin.GeometryObject(name, 0, pl, heightField) + obj.meshColor[:] = color + obj.overrideMaterial = True + visual_model.addGeometryObject(obj) + + +colorrgb = [128, 149, 255, 200] +colorrgb = np.array(colorrgb) / 255.0 +vizGround(ground, 0.02, color=colorrgb) + +viz = Visualizer(config, model, geomModel=visual_model) +print( + "Candlewick visualizer: opened on device driver", viz.renderer.device.driverName() +) + +q_ref = np.array( + [ + [0.09906518], + [0.20099078], + [0.32502457], + [0.19414175], + [-0.00524735], + [-0.97855773], + [0.06860185], + [0.00968163], + [0.60963582], + [-1.61206407], + [-0.02543309], + [0.66709088], + [-1.50870083], + [0.32405118], + [-1.15305599], + [1.56867351], + [-0.39097222], + [-1.29675892], + [1.39741073], + ] +) + +while not viz.shouldExit: + viz.display(q_ref) + +time.sleep(1.0) diff --git a/examples/meshcat-viewer-solo.py b/examples/meshcat-viewer-solo.py index c7dbfd1943..2fa8297ce6 100644 --- a/examples/meshcat-viewer-solo.py +++ b/examples/meshcat-viewer-solo.py @@ -60,7 +60,9 @@ def ground(xy): ) -def vizGround(viz, elevation_fn, space, name="ground", color=[1.0, 1.0, 0.6, 0.8]): +def vizGround( + viz, elevation_fn, space, name="ground", color=np.array([1.0, 1.0, 0.6, 0.8]) +): xg = np.arange(-2, 2, space) nx = xg.shape[0] xy_g = np.meshgrid(xg, xg) @@ -75,7 +77,7 @@ def vizGround(viz, elevation_fn, space, name="ground", color=[1.0, 1.0, 0.6, 0.8 heightField = hppfcl.HeightFieldAABB(sx, sy, elev_g, np.min(elev_g)) pl = pin.SE3.Identity() - obj = pin.GeometryObject("ground", 0, pl, heightField) + obj = pin.GeometryObject(name, 0, pl, heightField) obj.meshColor[:] = color viz.addGeometryObject(obj) diff --git a/examples/panda3d-viewer-play.py b/examples/panda3d-viewer-play.py index a05101f0c5..c354633efd 100644 --- a/examples/panda3d-viewer-play.py +++ b/examples/panda3d-viewer-play.py @@ -23,6 +23,7 @@ talos.setVisualizer(Panda3dVisualizer()) talos.initViewer() talos.loadViewerModel(group_name="talos", color=(1, 1, 1, 1)) +record_video = False # Play a sample trajectory in a loop @@ -43,9 +44,24 @@ def play_sample_trajectory(): -0.1 - beta * 1.56, ) + if record_video: + dt = 1 / 60 + fps = 1.0 / dt + filename = "talos.mp4" + ctx = talos.viz.create_video_ctx(filename, fps=fps) + print(f"[video will be recorded @ {filename}]") + else: + from contextlib import nullcontext + + ctx = nullcontext() + print("[no recording]") + while True: - talos.play(traj.T, 1.0 / update_rate) - traj = np.flip(traj, 1) + with ctx: + talos.play(traj.T, 1.0 / update_rate) + traj = np.flip(traj, 1) + if record_video: + break try: diff --git a/flake.lock b/flake.lock index d28337e1f0..4be2b274fe 100644 --- a/flake.lock +++ b/flake.lock @@ -5,11 +5,11 @@ "nixpkgs-lib": "nixpkgs-lib" }, "locked": { - "lastModified": 1743550720, - "narHash": "sha256-hIshGgKZCgWh6AYJpJmRgFdR3WUbkY04o82X05xqQiY=", + "lastModified": 1762040540, + "narHash": "sha256-z5PlZ47j50VNF3R+IMS9LmzI5fYRGY/Z5O5tol1c9I4=", "owner": "hercules-ci", "repo": "flake-parts", - "rev": "c621e8422220273271f52058f618c94e405bb0f5", + "rev": "0010412d62a25d959151790968765a70c436598b", "type": "github" }, "original": { @@ -20,11 +20,11 @@ }, "nixpkgs": { "locked": { - "lastModified": 1743583204, - "narHash": "sha256-F7n4+KOIfWrwoQjXrL2wD9RhFYLs2/GGe/MQY1sSdlE=", + "lastModified": 1762111121, + "narHash": "sha256-4vhDuZ7OZaZmKKrnDpxLZZpGIJvAeMtK6FKLJYUtAdw=", "owner": "NixOS", "repo": "nixpkgs", - "rev": "2c8d3f48d33929642c1c12cd243df4cc7d2ce434", + "rev": "b3d51a0365f6695e7dd5cdf3e180604530ed33b4", "type": "github" }, "original": { @@ -36,11 +36,11 @@ }, "nixpkgs-lib": { "locked": { - "lastModified": 1743296961, - "narHash": "sha256-b1EdN3cULCqtorQ4QeWgLMrd5ZGOjLSLemfa00heasc=", + "lastModified": 1761765539, + "narHash": "sha256-b0yj6kfvO8ApcSE+QmA6mUfu8IYG6/uU28OFn4PaC8M=", "owner": "nix-community", "repo": "nixpkgs.lib", - "rev": "e4822aea2a6d1cdd36653c134cacfd64c97ff4fa", + "rev": "719359f4562934ae99f5443f20aa06c2ffff91fc", "type": "github" }, "original": { diff --git a/include/pinocchio/algorithm/aba-derivatives.hpp b/include/pinocchio/algorithm/aba-derivatives.hpp index 152e4a9063..b3d48b1d6f 100644 --- a/include/pinocchio/algorithm/aba-derivatives.hpp +++ b/include/pinocchio/algorithm/aba-derivatives.hpp @@ -1,5 +1,6 @@ // -// Copyright (c) 2018-2021 CNRS INRIA +// Copyright (c) 2018 CNRS +// Copyright (c) 2018-2024 INRIA // #ifndef __pinocchio_algorithm_aba_derivatives_hpp__ @@ -93,6 +94,8 @@ namespace pinocchio typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2, + typename SpatialForce, + typename SpatialForceAllocator, typename MatrixType1, typename MatrixType2, typename MatrixType3> @@ -102,7 +105,7 @@ namespace pinocchio const Eigen::MatrixBase & q, const Eigen::MatrixBase & v, const Eigen::MatrixBase & tau, - const container::aligned_vector> & fext, + const std::vector & fext, const Eigen::MatrixBase & aba_partial_dq, const Eigen::MatrixBase & aba_partial_dv, const Eigen::MatrixBase & aba_partial_dtau); @@ -177,14 +180,16 @@ namespace pinocchio template class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType1, - typename TangentVectorType2> + typename TangentVectorType2, + typename SpatialForce, + typename SpatialForceAllocator> void computeABADerivatives( const ModelTpl & model, DataTpl & data, const Eigen::MatrixBase & q, const Eigen::MatrixBase & v, const Eigen::MatrixBase & tau, - const container::aligned_vector> & fext); + const std::vector & fext); /// /// \brief The derivatives of the Articulated-Body algorithm. @@ -272,13 +277,15 @@ namespace pinocchio typename Scalar, int Options, template class JointCollectionTpl, + typename SpatialForce, + typename SpatialForceAllocator, typename MatrixType1, typename MatrixType2, typename MatrixType3> void computeABADerivatives( const ModelTpl & model, DataTpl & data, - const container::aligned_vector> & fext, + const std::vector & fext, const Eigen::MatrixBase & aba_partial_dq, const Eigen::MatrixBase & aba_partial_dv, const Eigen::MatrixBase & aba_partial_dtau); @@ -300,11 +307,16 @@ namespace pinocchio /// /// \sa pinocchio::aba /// - template class JointCollectionTpl> + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename SpatialForce, + typename SpatialForceAllocator> void computeABADerivatives( const ModelTpl & model, DataTpl & data, - const container::aligned_vector> & fext); + const std::vector & fext); } // namespace pinocchio diff --git a/include/pinocchio/algorithm/aba-derivatives.hxx b/include/pinocchio/algorithm/aba-derivatives.hxx index c50cb74eef..de56349cfd 100644 --- a/include/pinocchio/algorithm/aba-derivatives.hxx +++ b/include/pinocchio/algorithm/aba-derivatives.hxx @@ -1,5 +1,6 @@ // -// Copyright (c) 2018-2021 CNRS INRIA +// Copyright (c) 2018 CNRS +// Copyright (c) 2018-2024 INRIA // #ifndef __pinocchio_algorithm_aba_derivatives_hxx__ @@ -128,7 +129,7 @@ namespace pinocchio jdata.StU().diagonal() += jmodel.jointVelocitySelector(model.armature); - ::pinocchio::internal::PerformStYSInversion::run(jdata.StU(), jdata.Dinv()); + ::pinocchio::matrix_inversion(jdata.StU(), jdata.Dinv()); jdata.UDinv().noalias() = jdata.U() * jdata.Dinv(); MatrixType & Minv_ = PINOCCHIO_EIGEN_CONST_CAST(MatrixType, Minv); @@ -459,6 +460,8 @@ namespace pinocchio typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2, + typename SpatialForce, + typename SpatialForceAllocator, typename MatrixType1, typename MatrixType2, typename MatrixType3> @@ -468,7 +471,7 @@ namespace pinocchio const Eigen::MatrixBase & q, const Eigen::MatrixBase & v, const Eigen::MatrixBase & tau, - const container::aligned_vector> & fext, + const std::vector & fext, const Eigen::MatrixBase & aba_partial_dq, const Eigen::MatrixBase & aba_partial_dv, const Eigen::MatrixBase & aba_partial_dtau) @@ -770,13 +773,15 @@ namespace pinocchio typename Scalar, int Options, template class JointCollectionTpl, + typename SpatialForce, + typename SpatialForceAllocator, typename MatrixType1, typename MatrixType2, typename MatrixType3> void computeABADerivatives( const ModelTpl & model, DataTpl & data, - const container::aligned_vector> & fext, + const std::vector & fext, const Eigen::MatrixBase & aba_partial_dq, const Eigen::MatrixBase & aba_partial_dv, const Eigen::MatrixBase & aba_partial_dtau) @@ -864,14 +869,16 @@ namespace pinocchio template class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType1, - typename TangentVectorType2> + typename TangentVectorType2, + typename SpatialForce, + typename SpatialForceAllocator> void computeABADerivatives( const ModelTpl & model, DataTpl & data, const Eigen::MatrixBase & q, const Eigen::MatrixBase & v, const Eigen::MatrixBase & tau, - const container::aligned_vector> & fext) + const std::vector & fext) { ::pinocchio::impl::computeABADerivatives( model, data, q, v, tau, fext, data.ddq_dq, data.ddq_dv, data.Minv); @@ -885,11 +892,16 @@ namespace pinocchio ::pinocchio::impl::computeABADerivatives(model, data, data.ddq_dq, data.ddq_dv, data.Minv); } - template class JointCollectionTpl> + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename SpatialForce, + typename SpatialForceAllocator> void computeABADerivatives( const ModelTpl & model, DataTpl & data, - const container::aligned_vector> & fext) + const std::vector & fext) { ::pinocchio::impl::computeABADerivatives( model, data, fext, data.ddq_dq, data.ddq_dv, data.Minv); @@ -929,6 +941,8 @@ namespace pinocchio typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2, + typename SpatialForce, + typename SpatialForceAllocator, typename MatrixType1, typename MatrixType2, typename MatrixType3> @@ -938,7 +952,7 @@ namespace pinocchio const Eigen::MatrixBase & q, const Eigen::MatrixBase & v, const Eigen::MatrixBase & tau, - const container::aligned_vector> & fext, + const std::vector & fext, const Eigen::MatrixBase & aba_partial_dq, const Eigen::MatrixBase & aba_partial_dv, const Eigen::MatrixBase & aba_partial_dtau) @@ -976,14 +990,16 @@ namespace pinocchio template class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType1, - typename TangentVectorType2> + typename TangentVectorType2, + typename SpatialForce, + typename SpatialForceAllocator> void computeABADerivatives( const ModelTpl & model, DataTpl & data, const Eigen::MatrixBase & q, const Eigen::MatrixBase & v, const Eigen::MatrixBase & tau, - const container::aligned_vector> & fext) + const std::vector & fext) { impl::computeABADerivatives( model, data, make_const_ref(q), make_const_ref(v), make_const_ref(tau), fext); @@ -1024,13 +1040,15 @@ namespace pinocchio typename Scalar, int Options, template class JointCollectionTpl, + typename SpatialForce, + typename SpatialForceAllocator, typename MatrixType1, typename MatrixType2, typename MatrixType3> void computeABADerivatives( const ModelTpl & model, DataTpl & data, - const container::aligned_vector> & fext, + const std::vector & fext, const Eigen::MatrixBase & aba_partial_dq, const Eigen::MatrixBase & aba_partial_dv, const Eigen::MatrixBase & aba_partial_dtau) @@ -1040,11 +1058,16 @@ namespace pinocchio make_ref(aba_partial_dtau)); } - template class JointCollectionTpl> + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename SpatialForce, + typename SpatialForceAllocator> void computeABADerivatives( const ModelTpl & model, DataTpl & data, - const container::aligned_vector> & fext) + const std::vector & fext) { impl::computeABADerivatives( model, data, fext, make_ref(data.ddq_dq), make_ref(data.ddq_dv), make_ref(data.Minv)); diff --git a/include/pinocchio/algorithm/aba-derivatives.txx b/include/pinocchio/algorithm/aba-derivatives.txx index 7bc0fd161f..ee3fcf8464 100644 --- a/include/pinocchio/algorithm/aba-derivatives.txx +++ b/include/pinocchio/algorithm/aba-derivatives.txx @@ -1,5 +1,5 @@ // -// Copyright (c) 2022 INRIA +// Copyright (c) 2022-2024 INRIA // #ifndef __pinocchio_algorithm_aba_derivatives_txx__ @@ -55,6 +55,8 @@ namespace pinocchio Eigen::Ref, Eigen::Ref, Eigen::Ref, + context::Force, + Eigen::aligned_allocator, Eigen::Ref, Eigen::Ref, Eigen::Ref>( @@ -63,7 +65,7 @@ namespace pinocchio const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, - const container::aligned_vector> &, + const std::vector> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &); @@ -75,6 +77,8 @@ namespace pinocchio Eigen::Ref, Eigen::Ref, Eigen::Ref, + context::Force, + Eigen::aligned_allocator, Eigen::Ref, Eigen::Ref, Eigen::Ref>( @@ -83,7 +87,7 @@ namespace pinocchio const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, - const container::aligned_vector> &, + const std::vector> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &); @@ -107,13 +111,15 @@ namespace pinocchio JointCollectionDefaultTpl, Eigen::Ref, Eigen::Ref, - Eigen::Ref>( + Eigen::Ref, + context::Force, + Eigen::aligned_allocator>( const context::Model &, context::Data &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, - const container::aligned_vector> &); + const std::vector> &); extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void computeABADerivatives< context::Scalar, @@ -139,22 +145,28 @@ namespace pinocchio context::Scalar, context::Options, JointCollectionDefaultTpl, + context::Force, + Eigen::aligned_allocator, Eigen::Ref, Eigen::Ref, Eigen::Ref>( const context::Model &, context::Data &, - const container::aligned_vector> &, + const std::vector> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &); } // namespace impl - extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void - computeABADerivatives( + extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void computeABADerivatives< + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + context::Force, + Eigen::aligned_allocator>( const context::Model &, context::Data &, - const container::aligned_vector> &); + const std::vector> &); } // namespace pinocchio #endif // ifndef __pinocchio_algorithm_aba_derivatives_txx__ diff --git a/include/pinocchio/algorithm/aba.hpp b/include/pinocchio/algorithm/aba.hpp index c782d0c25e..6c1e24af8d 100644 --- a/include/pinocchio/algorithm/aba.hpp +++ b/include/pinocchio/algorithm/aba.hpp @@ -1,5 +1,6 @@ // -// Copyright (c) 2016-2021 CNRS INRIA +// Copyright (c) 2016-2018 CNRS +// Copyright (c) 2018-2024 INRIA // #ifndef __pinocchio_algorithm_aba_hpp__ @@ -75,14 +76,15 @@ namespace pinocchio typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2, - typename ForceDerived> + typename SpatialForce, + typename SpatialForceAllocator> const typename DataTpl::TangentVectorType & aba( const ModelTpl & model, DataTpl & data, const Eigen::MatrixBase & q, const Eigen::MatrixBase & v, const Eigen::MatrixBase & tau, - const container::aligned_vector & fext, + const std::vector & fext, const Convention rf = Convention::LOCAL); /// diff --git a/include/pinocchio/algorithm/aba.hxx b/include/pinocchio/algorithm/aba.hxx index f03c2e2205..ca95326b04 100644 --- a/include/pinocchio/algorithm/aba.hxx +++ b/include/pinocchio/algorithm/aba.hxx @@ -1,5 +1,6 @@ // -// Copyright (c) 2016-2021 CNRS INRIA +// Copyright (c) 2016-2018 CNRS +// Copyright (c) 2018-2024 INRIA // #ifndef __pinocchio_algorithm_aba_hxx__ @@ -177,7 +178,7 @@ namespace pinocchio // Account for the rotor inertia contribution jdata.StU().diagonal() += jmodel.jointVelocitySelector(model.armature); - ::pinocchio::internal::PerformStYSInversion::run(jdata.StU(), jdata.Dinv()); + ::pinocchio::matrix_inversion(jdata.StU(), jdata.Dinv()); jdata.UDinv().noalias() = jdata.U() * jdata.Dinv(); if (parent > 0) @@ -299,7 +300,8 @@ namespace pinocchio typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2, - typename ForceDerived> + typename SpatialForce, + typename SpatialForceAllocator> const typename DataTpl::TangentVectorType & abaWorldConvention( const ModelTpl & model, @@ -307,7 +309,7 @@ namespace pinocchio const Eigen::MatrixBase & q, const Eigen::MatrixBase & v, const Eigen::MatrixBase & tau, - const container::aligned_vector & fext) + const std::vector & fext) { assert(model.check(data) && "data is not consistent with model."); @@ -546,7 +548,8 @@ namespace pinocchio typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2, - typename ForceDerived> + typename SpatialForce, + typename SpatialForceAllocator> const typename DataTpl::TangentVectorType & abaLocalConvention( const ModelTpl & model, @@ -554,7 +557,7 @@ namespace pinocchio const Eigen::MatrixBase & q, const Eigen::MatrixBase & v, const Eigen::MatrixBase & tau, - const container::aligned_vector & fext) + const std::vector & fext) { assert(model.check(data) && "data is not consistent with model."); @@ -689,7 +692,7 @@ namespace pinocchio // Account for the rotor inertia contribution jdata.StU().diagonal() += jmodel.jointVelocitySelector(model.armature); - ::pinocchio::internal::PerformStYSInversion::run(jdata.StU(), jdata.Dinv()); + ::pinocchio::matrix_inversion(jdata.StU(), jdata.Dinv()); jdata.UDinv().noalias() = jdata.U() * jdata.Dinv(); Minv.block(jmodel.idx_v(), jmodel.idx_v(), jmodel.nv(), jmodel.nv()) = jdata.Dinv(); @@ -954,14 +957,15 @@ namespace pinocchio typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2, - typename ForceDerived> + typename SpatialForce, + typename SpatialForceAllocator> const typename DataTpl::TangentVectorType & aba( const ModelTpl & model, DataTpl & data, const Eigen::MatrixBase & q, const Eigen::MatrixBase & v, const Eigen::MatrixBase & tau, - const container::aligned_vector & fext, + const std::vector & fext, const Convention convention) { switch (convention) diff --git a/include/pinocchio/algorithm/aba.txx b/include/pinocchio/algorithm/aba.txx index 3152c99cdd..dda1664699 100644 --- a/include/pinocchio/algorithm/aba.txx +++ b/include/pinocchio/algorithm/aba.txx @@ -1,5 +1,5 @@ // -// Copyright (c) 2022 INRIA +// Copyright (c) 2022-2024 INRIA // #ifndef __pinocchio_algorithm_aba_txx__ @@ -28,13 +28,14 @@ namespace pinocchio Eigen::Ref, Eigen::Ref, Eigen::Ref, - ForceTpl>( + context::Force, + Eigen::aligned_allocator>( const context::Model &, context::Data &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, - const container::aligned_vector> &, + const std::vector> &, const Convention); extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI const context::RowMatrixXs & diff --git a/include/pinocchio/algorithm/admm-solver.hpp b/include/pinocchio/algorithm/admm-solver.hpp index 2c120b3a6e..100dd81808 100644 --- a/include/pinocchio/algorithm/admm-solver.hpp +++ b/include/pinocchio/algorithm/admm-solver.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2022-2024 INRIA +// Copyright (c) 2022-2025 INRIA // #ifndef __pinocchio_algorithm_admm_solver_hpp__ @@ -13,10 +13,164 @@ #include "pinocchio/algorithm/contact-solver-base.hpp" #include "pinocchio/algorithm/delassus-operator-base.hpp" +#include "pinocchio/math/lanczos-decomposition.hpp" + +#include "pinocchio/algorithm/diagonal-preconditioner.hpp" + #include namespace pinocchio { + template + struct ADMMContactSolverTpl; + typedef ADMMContactSolverTpl ADMMContactSolver; + + template + struct ADMMSpectralUpdateRuleTpl + { + typedef _Scalar Scalar; + + ADMMSpectralUpdateRuleTpl( + const Scalar ratio_primal_dual, const Scalar L, const Scalar m, const Scalar rho_power_factor) + : ratio_primal_dual(ratio_primal_dual) + , rho_increment(std::pow(L / m, rho_power_factor)) + { + PINOCCHIO_CHECK_INPUT_ARGUMENT(m > Scalar(0), "m should be positive."); + } + + Scalar getRatioPrimalDual() const + { + return ratio_primal_dual; + } + void setRatioPrimalDual(const Scalar ratio_primal_dual) + { + this->ratio_primal_dual = ratio_primal_dual; + } + + Scalar getRhoIncrement() const + { + return rho_increment; + } + void setRhoIncrement(const Scalar cond, const Scalar rho_power_factor) + { + rho_increment = std::pow(cond, rho_power_factor); + } + + bool eval(const Scalar primal_feasibility, const Scalar dual_feasibility, Scalar & rho) const + { + bool rho_has_changed = false; + if (primal_feasibility > ratio_primal_dual * dual_feasibility) + { + rho *= rho_increment; + // rho *= math::pow(cond,rho_power_factor); + // rho_power += rho_power_factor; + rho_has_changed = true; + } + else if (dual_feasibility > ratio_primal_dual * primal_feasibility) + { + rho /= rho_increment; + // rho *= math::pow(cond,-rho_power_factor); + // rho_power -= rho_power_factor; + rho_has_changed = true; + } + + return rho_has_changed; + } + + /// \brief Compute the penalty ADMM value from the current largest and lowest eigenvalues and + /// the scaling spectral factor. + static inline Scalar computeRho(const Scalar L, const Scalar m, const Scalar rho_power) + { + const Scalar cond = L / m; + const Scalar rho = math::sqrt(L * m) * math::pow(cond, rho_power); + return rho; + } + + /// \brief Compute the scaling spectral factor of the ADMM penalty term from the current + /// largest and lowest eigenvalues and the ADMM penalty term. + static inline Scalar computeRhoPower(const Scalar L, const Scalar m, const Scalar rho) + { + const Scalar cond = L / m; + const Scalar sqrt_L_m = math::sqrt(L * m); + const Scalar rho_power = math::log(rho / sqrt_L_m) / math::log(cond); + return rho_power; + } + + protected: + Scalar ratio_primal_dual; + Scalar rho_increment; + }; + + template + struct ADMMLinearUpdateRuleTpl + { + typedef _Scalar Scalar; + + ADMMLinearUpdateRuleTpl( + const Scalar ratio_primal_dual, const Scalar increase_factor, const Scalar decrease_factor) + : ratio_primal_dual(ratio_primal_dual) + , increase_factor(increase_factor) + , decrease_factor(decrease_factor) + { + PINOCCHIO_CHECK_INPUT_ARGUMENT( + increase_factor > Scalar(1), "increase_factor should be greater than one."); + PINOCCHIO_CHECK_INPUT_ARGUMENT( + decrease_factor > Scalar(1), "decrease_factor should be greater than one."); + } + + ADMMLinearUpdateRuleTpl(const Scalar ratio_primal_dual, const Scalar factor) + : ratio_primal_dual(ratio_primal_dual) + , increase_factor(factor) + , decrease_factor(factor) + { + PINOCCHIO_CHECK_INPUT_ARGUMENT(factor > Scalar(1), "factor should be greater than one."); + } + + bool eval(const Scalar primal_feasibility, const Scalar dual_feasibility, Scalar & rho) const + { + bool rho_has_changed = false; + if (primal_feasibility > ratio_primal_dual * dual_feasibility) + { + rho *= increase_factor; + rho_has_changed = true; + } + else if (dual_feasibility > ratio_primal_dual * primal_feasibility) + { + rho /= decrease_factor; + rho_has_changed = true; + } + + return rho_has_changed; + } + + protected: + Scalar ratio_primal_dual; + Scalar increase_factor, decrease_factor; + }; + + enum class ADMMUpdateRule : char + { + SPECTRAL = 'S', + LINEAR = 'L', + CONSTANT = 'C', + }; + + template + union ADMMUpdateRuleContainerTpl { + ADMMUpdateRuleContainerTpl() + : dummy() {}; + ADMMSpectralUpdateRuleTpl spectral_rule; + ADMMLinearUpdateRuleTpl linear_rule; + + protected: + struct Dummy + { + Dummy() {}; + }; + + Dummy dummy{}; + }; + template struct PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") ADMMContactSolverTpl : ContactSolverBaseTpl<_Scalar> @@ -24,9 +178,12 @@ namespace pinocchio typedef _Scalar Scalar; typedef ContactSolverBaseTpl<_Scalar> Base; typedef Eigen::Matrix VectorXs; + typedef Eigen::Ref RefVectorXs; + typedef Eigen::Ref RefConstVectorXs; typedef const Eigen::Ref ConstRefVectorXs; typedef Eigen::Matrix MatrixXs; - typedef PowerIterationAlgoTpl PowerIterationAlgo; + typedef LanczosDecompositionTpl LanczosDecomposition; + typedef DiagonalPreconditionerTpl DiagonalPreconditioner; using Base::problem_size; @@ -55,54 +212,49 @@ namespace pinocchio // boost::optional L_vector; // }; // - struct SolverStats + struct ADMMSolverStats : Base::SolverStats { - explicit SolverStats(const int max_it) - : it(0) + ADMMSolverStats() + : Base::SolverStats() , cholesky_update_count(0) { - primal_feasibility.reserve(size_t(max_it)); - dual_feasibility.reserve(size_t(max_it)); - dual_feasibility_ncp.reserve(size_t(max_it)); - complementarity.reserve(size_t(max_it)); - rho.reserve(size_t(max_it)); } - void reset() + explicit ADMMSolverStats(const int max_it) + : Base::SolverStats(max_it) + , cholesky_update_count(0) { - primal_feasibility.clear(); - dual_feasibility.clear(); - complementarity.clear(); - dual_feasibility_ncp.clear(); - rho.clear(); - it = 0; - cholesky_update_count = 0; + reserve(max_it); } - size_t size() const + void reserve(const int max_it) { - return primal_feasibility.size(); + dual_feasibility_admm.reserve(size_t(max_it)); + dual_feasibility_constraint.reserve(size_t(max_it)); + rho.reserve(size_t(max_it)); } - ///  \brief Number of total iterations. - int it; + void reset() + { + Base::SolverStats::reset(); + dual_feasibility_admm.clear(); + dual_feasibility_constraint.clear(); + rho.clear(); + cholesky_update_count = 0; + } ///  \brief Number of Cholesky updates. int cholesky_update_count; - /// \brief History of primal feasibility values. - std::vector primal_feasibility; - - /// \brief History of dual feasibility values. - std::vector dual_feasibility; - std::vector dual_feasibility_ncp; - - /// \brief History of complementarity values. - std::vector complementarity; + /// \brief ADMM dual feasibility + std::vector dual_feasibility_admm; + /// \brief ADMM dual feasibility + std::vector dual_feasibility_constraint; /// \brief History of rho values. std::vector rho; }; + // // struct SolverResults // { @@ -123,31 +275,46 @@ namespace pinocchio Scalar tau = Scalar(0.5), Scalar rho_power = Scalar(0.2), Scalar rho_power_factor = Scalar(0.05), + Scalar linear_update_rule_factor = Scalar(2), Scalar ratio_primal_dual = Scalar(10), - int max_it_largest_eigen_value_solver = 20) + int lanczos_size = int(3)) : Base(problem_dim) , is_initialized(false) , mu_prox(mu_prox) , tau(tau) - , rho(Scalar(-1)) + , rho(10.) , rho_power(rho_power) , rho_power_factor(rho_power_factor) + , linear_update_rule_factor(linear_update_rule_factor) , ratio_primal_dual(ratio_primal_dual) - , max_it_largest_eigen_value_solver(max_it_largest_eigen_value_solver) - , power_iteration_algo(problem_dim) + , lanczos_decomposition( + static_cast(math::max(2, problem_dim)), + static_cast(math::max(2, math::min(lanczos_size, problem_dim)))) , x_(VectorXs::Zero(problem_dim)) , y_(VectorXs::Zero(problem_dim)) - , x_previous(VectorXs::Zero(problem_dim)) - , y_previous(VectorXs::Zero(problem_dim)) - , z_previous(VectorXs::Zero(problem_dim)) + , x_bar_(VectorXs::Zero(problem_dim)) + , y_bar_(VectorXs::Zero(problem_dim)) + , x_bar_previous(VectorXs::Zero(problem_dim)) + , y_bar_previous(VectorXs::Zero(problem_dim)) + , z_bar_previous(VectorXs::Zero(problem_dim)) , z_(VectorXs::Zero(problem_dim)) + , z_constraint_(VectorXs::Zero(problem_dim)) + , z_bar_(VectorXs::Zero(problem_dim)) , s_(VectorXs::Zero(problem_dim)) + , s_constraint_(VectorXs::Zero(problem_dim)) + , s_bar_(VectorXs::Zero(problem_dim)) + , preconditioner_(VectorXs::Ones(problem_dim)) + , g_bar_(VectorXs::Zero(problem_dim)) + , time_scaling_acc_to_constraints(VectorXs::Zero(problem_dim)) + , time_scaling_constraints_to_pos(VectorXs::Zero(problem_dim)) + , gs(VectorXs::Zero(problem_dim)) , rhs(problem_dim) , primal_feasibility_vector(VectorXs::Zero(problem_dim)) + , primal_feasibility_vector_bar(VectorXs::Zero(problem_dim)) , dual_feasibility_vector(VectorXs::Zero(problem_dim)) - , stats(Base::max_it) + , dual_feasibility_vector_bar(VectorXs::Zero(problem_dim)) + , stats() { - power_iteration_algo.max_it = max_it_largest_eigen_value_solver; } /// \brief Set the ADMM penalty value. @@ -177,12 +344,24 @@ namespace pinocchio { this->rho_power_factor = rho_power_factor; } - /// \brief Get the power factor associated to the problem conditionning. + /// \brief Get the value of the increase/decrease factor associated to the problem + /// conditionning. Scalar getRhoPowerFactor() const { return rho_power_factor; } + /// \brief Set the update factor of the Linear update rule + void setLinearUpdateRuleFactor(const Scalar linear_update_rule_factor) + { + this->linear_update_rule_factor = linear_update_rule_factor; + } + /// \brief Get the value of the increase/decrease factor of the Linear update rule + Scalar getLinearUpdateRuleFactor() const + { + return linear_update_rule_factor; + } + /// \brief Set the tau linear scaling factor. void setTau(const Scalar tau) { @@ -224,60 +403,176 @@ namespace pinocchio return cholesky_update_count; } + /// \brief Sets the size of triangular matrix of Lanczos decomposition. + /// The higher the size, the more accurate the estimation of min/max eigenvalues will be. + /// Note: the maximum size is the size of the problem + void setLanczosSize(int decomposition_size) + { + // TODO(lmontaut): should we throw if size > problem_size or instead take the min as done + // below? + int new_lanczos_size = math::max(2, this->problem_size); + int new_lanczos_decomposition_size = + math::max(2, math::min(decomposition_size, this->problem_size)); + if ( + new_lanczos_size != this->lanczos_decomposition.size() + || new_lanczos_decomposition_size != this->lanczos_decomposition.decompositionSize()) + { + this->lanczos_decomposition = LanczosDecomposition( + static_cast(new_lanczos_size), + static_cast(new_lanczos_decomposition_size)); + } + } + + /// \returns the Lanczos algorithm used for eigenvalues estimation. + const LanczosDecomposition & getLanczosDecomposition() const + { + return lanczos_decomposition; + } + + ADMMSolverStats & getStats() + { + return stats; + } + /// - /// \brief Solve the constrained conic problem composed of problem data (G,g,cones) and starting - /// from the initial guess. + /// \brief Solve the constraint problem composed of problem data (G,g,constraint_models) and + /// starting from the initial guess. /// - /// \param[in] G Symmetric PSD matrix representing the Delassus of the contact problem. - /// \param[in] g Free contact acceleration or velicity associted with the contact problem. - /// \param[in] cones Vector of conic constraints. - /// \param[in,out] x Initial guess and output solution of the problem - /// \param[in] mu_prox Proximal smoothing value associated to the algorithm. - /// \param[in] R Proximal regularization value associated to the compliant contacts (corresponds - /// to the lowest non-zero). \param[in] tau Over relaxation value + /// \param[in] G Symmetric PSD matrix representing the Delassus of the constraint problem. + /// \param[in] g Free constraint acceleration or velicity associted with the constraint problem. + /// \param[in] constraint_models Vector of constraints. + /// \param[in] preconditioner Precondtionner of the problem. + /// \param[in] primal_guess Optional initial guess of the primal solution (constrained forces). + /// \param[in] dual_guess Optinal Initial guess of the dual solution (constrained velocities). + /// \param[in] solve_ncp whether to solve the NCP (true) or CCP (false) + /// \param[in] admm_update_rule update rule for ADMM (linear or spectral) + /// \param[in] stat_record record solver metrics /// /// \returns True if the problem has converged. template< typename DelassusDerived, typename VectorLike, - typename ConstraintAllocator, - typename VectorLikeR> + template class Holder, + typename ConstraintModel, + typename ConstraintAllocator> + bool solve( + DelassusOperatorBase & delassus, + const Eigen::MatrixBase & g, + const std::vector, ConstraintAllocator> & constraint_models, + const Scalar dt, + const boost::optional preconditioner = boost::none, + const boost::optional primal_guess = boost::none, + const boost::optional dual_guess = boost::none, + const bool solve_ncp = true, + const ADMMUpdateRule admm_update_rule = ADMMUpdateRule::SPECTRAL, + const bool stat_record = false); + + /// + /// \brief Solve the constraint problem composed of problem data (G,g,constraint_models) and + /// starting from the initial guess. + /// + /// \param[in] G Symmetric PSD matrix representing the Delassus of the constraint problem. + /// \param[in] g Free constraint acceleration or velicity associted with the constraint problem. + /// \param[in] constraint_models Vector of constraints. + /// \param[in] preconditioner Precondtionner of the problem. + /// \param[in] primal_guess Optional initial guess of the primal solution (constrained forces). + /// \param[in] dual_guess Optinal Initial guess of the dual solution (constrained velocities). + /// \param[in] solve_ncp whether to solve the NCP (true) or CCP (false) + /// \param[in] admm_update_rule update rule for ADMM (linear or spectral) + /// \param[in] stat_record record solver metrics + /// + /// \returns True if the problem has converged. + template< + typename DelassusDerived, + typename VectorLike, + typename ConstraintModel, + typename ConstraintAllocator> bool solve( DelassusOperatorBase & delassus, const Eigen::MatrixBase & g, - const std::vector, ConstraintAllocator> & cones, - const Eigen::MatrixBase & R, - const boost::optional primal_guess = boost::none, - const boost::optional dual_guess = boost::none, - bool compute_largest_eigen_values = true, - bool stat_record = false); + const std::vector & constraint_models, + const Scalar dt, + const boost::optional preconditioner = boost::none, + const boost::optional primal_guess = boost::none, + const boost::optional dual_guess = boost::none, + const bool solve_ncp = true, + const ADMMUpdateRule admm_update_rule = ADMMUpdateRule::SPECTRAL, + const bool stat_record = false) + { + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + constraint_models.cbegin(), constraint_models.cend()); + + return solve( + delassus, g, wrapped_constraint_models, dt, preconditioner, primal_guess, dual_guess, + solve_ncp, admm_update_rule, stat_record); + } /// - /// \brief Solve the constrained conic problem composed of problem data (G,g,cones) and starting - /// from the initial guess. + /// \brief Solve the constraint problem composed of problem data (G,g,constraint_models) and + /// starting from the initial guess. /// - /// \param[in] G Symmetric PSD matrix representing the Delassus of the contact problem. - /// \param[in] g Free contact acceleration or velicity associted with the contact problem. - /// \param[in] cones Vector of conic constraints. - /// \param[in,out] x Initial guess and output solution of the problem - /// \param[in] mu_prox Proximal smoothing value associated to the algorithm. - /// \param[in] tau Over relaxation value + /// \param[in] G Symmetric PSD matrix representing the Delassus of the constraint problem. + /// \param[in] g Free constraint acceleration or velicity associted with the constraint problem. + /// \param[in] constraint_models Vector of constraints. + /// \param[in] primal_guess Optional initial guess of the primal solution (constrained forces). + /// \param[in] solve_ncp whether to solve the NCP (true) or CCP (false) /// /// \returns True if the problem has converged. template< typename DelassusDerived, typename VectorLike, + template class Holder, + typename ConstraintModel, typename ConstraintAllocator, typename VectorLikeOut> bool solve( DelassusOperatorBase & delassus, const Eigen::MatrixBase & g, - const std::vector, ConstraintAllocator> & cones, - const Eigen::DenseBase & x) + const std::vector, ConstraintAllocator> & constraint_models, + const Scalar dt, + const Eigen::DenseBase & primal_guess, + const bool solve_ncp = true) { return solve( - delassus.derived(), g.derived(), cones, x.const_cast_derived(), - VectorXs::Zero(problem_size)); + delassus.derived(), g.derived(), constraint_models, dt, boost::none, primal_guess.derived(), + boost::none, solve_ncp); + } + + /// + /// \brief Solve the constraint problem composed of problem data (G,g,constraint_models) and + /// starting from the initial guess. + /// + /// \param[in] G Symmetric PSD matrix representing the Delassus of the constraint problem. + /// \param[in] g Free constraint acceleration or velicity associted with the constraint problem. + /// \param[in] constraint_models Vector of constraints. + /// \param[in] primal_guess Optional initial guess of the primal solution (constrained forces). + /// \param[in] solve_ncp whether to solve the NCP (true) or CCP (false) + /// + /// \returns True if the problem has converged. + template< + typename DelassusDerived, + typename VectorLike, + typename ConstraintModel, + typename ConstraintAllocator, + typename VectorLikeOut> + bool solve( + DelassusOperatorBase & delassus, + const Eigen::MatrixBase & g, + const std::vector & constraint_models, + const Scalar dt, + const Eigen::DenseBase & primal_guess, + const bool solve_ncp = true) + { + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + constraint_models.cbegin(), constraint_models.cend()); + + return solve(delassus, g, wrapped_constraint_models, dt, primal_guess, solve_ncp); } /// \returns the primal solution of the problem @@ -288,41 +583,56 @@ namespace pinocchio /// \returns the dual solution of the problem const VectorXs & getDualSolution() const { - return z_; + return z_constraint_; } /// \returns the complementarity shift const VectorXs & getComplementarityShift() const { - return s_; + return s_constraint_; } - /// \brief Compute the penalty ADMM value from the current largest and lowest eigenvalues and - /// the scaling spectral factor. - static inline Scalar computeRho(const Scalar L, const Scalar m, const Scalar rho_power) + /// \returns the scaled primal solution of the problem + const VectorXs & getScaledPrimalSolution() const { - const Scalar cond = L / m; - const Scalar rho = math::sqrt(L * m) * math::pow(cond, rho_power); - return rho; + return y_bar_; + } + /// \returns the scaled dual solution of the problem + const VectorXs & getScaledDualSolution() const + { + return z_bar_; + } + /// \returns the scaled complementarity shift + const VectorXs & getScaledComplementarityShift() const + { + return s_bar_; } - /// \brief Compute the scaling spectral factor of the ADMM penalty term from the current - /// largest and lowest eigenvalues and the ADMM penalty term. - static inline Scalar computeRhoPower(const Scalar L, const Scalar m, const Scalar rho) + /// \returns use the preconditioner to scale a primal quantity x. + /// Typically, it allows to get x_bar from x. + void scalePrimalSolution(const VectorXs & x, VectorXs & x_bar) const { - const Scalar cond = L / m; - const Scalar sqtr_L_m = math::sqrt(L * m); - const Scalar rho_power = math::log(rho / sqtr_L_m) / math::log(cond); - return rho_power; + preconditioner_.scale(x, x_bar); } - PowerIterationAlgo & getPowerIterationAlgo() + /// \returns use the preconditioner to unscale a primal quantity x. + /// Typically, it allows to get x from x_bar. + void unscalePrimalSolution(const VectorXs & x_bar, VectorXs & x) const { - return power_iteration_algo; + preconditioner_.unscale(x_bar, x); } - SolverStats & getStats() + /// \returns use the preconditioner to scale a dual quantity z. + /// Typically, it allows to get z_bar from z. + void scaleDualSolution(const VectorXs & z, VectorXs & z_bar) const { - return stats; + preconditioner_.unscale(z, z_bar); + } + + /// \returns use the preconditioner to unscale a dual quantity z. + /// Typically, it allows to get z from z_bar. + void unscaleDualSolution(const VectorXs & z_bar, VectorXs & z) const + { + preconditioner_.scale(z_bar, z); } protected: @@ -333,42 +643,65 @@ namespace pinocchio /// \brief Linear scaling of the ADMM penalty term Scalar tau; - /// \brief Penalty term associated to the ADMM. Scalar rho; + + // Set of parameters associated with the Spectral update rule /// \brief Power value associated to rho. This quantity will be automatically updated. Scalar rho_power; /// \brief Update factor for the primal/dual update of rho. Scalar rho_power_factor; + + // Set of parameters associated with the Linear update rule + /// \brief value of the increase/decrease factor + Scalar linear_update_rule_factor; + ///  \brief Ratio primal/dual Scalar ratio_primal_dual; - /// \brief Maximum number of iterarions called for the power iteration algorithm - int max_it_largest_eigen_value_solver; - - /// \brief Power iteration algo. - PowerIterationAlgo power_iteration_algo; + /// \brief Lanczos decomposition algorithm. + LanczosDecomposition lanczos_decomposition; - /// \brief Primal variables (corresponds to the contact forces) + /// \brief Primal variables (corresponds to the constraint impulses) VectorXs x_, y_; - /// \brief Previous value of y. - VectorXs x_previous, y_previous, z_previous; - /// \brief Dual varible of the ADMM (corresponds to the contact velocity or acceleration). + /// \brief Scaled primal variables (corresponds to the contact forces) + VectorXs x_bar_, y_bar_; + /// \brief Previous values of x_bar_, y_bar_ and z_bar_. + VectorXs x_bar_previous, y_bar_previous, z_bar_previous; + /// \brief Dual variable of the ADMM (corresponds to the contact velocity or acceleration). VectorXs z_; + VectorXs z_constraint_; + /// \brief Scaled dual variable of the ADMM (corresponds to the contact velocity or + /// acceleration). + VectorXs z_bar_; /// \brief De Saxé shift VectorXs s_; + VectorXs s_constraint_; + /// \brief Scaled De Saxé shift + VectorXs s_bar_; + + /// \brief the diagonal preconditioner of the problem + DiagonalPreconditioner preconditioner_; + /// \brief Preconditioned drift term + VectorXs g_bar_; - VectorXs rhs, primal_feasibility_vector, dual_feasibility_vector; + /// \brief Time scaling vector for constraints + VectorXs time_scaling_acc_to_constraints, time_scaling_constraints_to_pos; + /// \brief Vector g divided by time scaling (g / time_scaling_acc_to_constraints) + VectorXs gs; + + VectorXs rhs, primal_feasibility_vector, primal_feasibility_vector_bar, dual_feasibility_vector, + dual_feasibility_vector_bar; int cholesky_update_count; - /// \brief Stats of the solver - SolverStats stats; + ADMMSolverStats stats; #ifdef PINOCCHIO_WITH_HPP_FCL using Base::timer; #endif // PINOCCHIO_WITH_HPP_FCL }; // struct ADMMContactSolverTpl + } // namespace pinocchio #include "pinocchio/algorithm/admm-solver.hxx" diff --git a/include/pinocchio/algorithm/admm-solver.hxx b/include/pinocchio/algorithm/admm-solver.hxx index 1eed525c5b..10d7665c16 100644 --- a/include/pinocchio/algorithm/admm-solver.hxx +++ b/include/pinocchio/algorithm/admm-solver.hxx @@ -1,5 +1,5 @@ // -// Copyright (c) 2022-2024 INRIA +// Copyright (c) 2022-2025 INRIA // #ifndef __pinocchio_algorithm_admm_solver_hxx__ @@ -9,80 +9,244 @@ #include "pinocchio/algorithm/contact-solver-utils.hpp" #include "pinocchio/algorithm/constraints/coulomb-friction-cone.hpp" +#include "pinocchio/algorithm/constraints/visitors/constraint-model-visitor.hpp" +#include "pinocchio/algorithm/delassus-operator-preconditioned.hpp" + +#include "pinocchio/tracy.hpp" + +#include namespace pinocchio { + template + struct ZeroInitialGuessMaxConstraintViolationVisitor + : visitors::ConstraintUnaryVisitorBase< + ZeroInitialGuessMaxConstraintViolationVisitor> + { + using ArgsType = boost::fusion::vector; + using Base = visitors::ConstraintUnaryVisitorBase< + ZeroInitialGuessMaxConstraintViolationVisitor>; + + template + static void algo( + const ConstraintModelBase & cmodel, + const DriftVectorLike & drift, + Scalar & max_violation) + { + return algo_impl(cmodel.set(), drift, max_violation); + } + + template + static void algo_impl( + const CoulombFrictionConeTpl & set, + const Eigen::MatrixBase & drift, + Scalar & max_violation) + { + PINOCCHIO_UNUSED_VARIABLE(set); + const Scalar violation = -drift.coeff(2); + if (violation > max_violation) + { + max_violation = violation; + } + } + + template + static void algo_impl( + const UnboundedSetTpl & set, + const Eigen::MatrixBase & drift, + Scalar & max_violation) + { + PINOCCHIO_UNUSED_VARIABLE(set); + const Scalar violation = drift.template lpNorm(); + if (violation > max_violation) + { + max_violation = violation; + } + } + + template + static void algo_impl( + const BoxSetTpl & set, + const Eigen::MatrixBase & drift, + Scalar & max_violation) + { + PINOCCHIO_UNUSED_VARIABLE(set); + const Scalar violation = drift.template lpNorm(); + if (violation > max_violation) + { + max_violation = violation; + } + } + + template + static void algo_impl( + const JointLimitConstraintConeTpl & set, + const Eigen::MatrixBase & drift, + Scalar & max_violation) + { + Scalar negative_orthant_violation = 0; + if (set.getNegativeOrthant().size() > 0) + { + negative_orthant_violation = + math::max(Scalar(0), drift.head(set.getNegativeOrthant().size()).maxCoeff()); + } + Scalar positive_orthant_violation = 0; + if (set.getPositiveOrthant().size() > 0) + { + positive_orthant_violation = + -math::min(Scalar(0), drift.tail(set.getPositiveOrthant().size()).minCoeff()); + } + const Scalar violation = math::max(negative_orthant_violation, positive_orthant_violation); + if (violation > max_violation) + { + max_violation = violation; + } + } + + template + static void algo_impl( + const ConstraintSet & set, + const Eigen::MatrixBase & drift, + Scalar & max_violation) + { + // do nothing + PINOCCHIO_UNUSED_VARIABLE(set); + PINOCCHIO_UNUSED_VARIABLE(drift); + PINOCCHIO_UNUSED_VARIABLE(max_violation); + } + + /// ::run for individual constraints + template + static void run( + const pinocchio::ConstraintModelBase & cmodel, + const DriftVectorLike & drift, + Scalar & max_violation) + { + algo(cmodel.derived(), drift, max_violation); + } + + /// ::run for constraints variant + template class ConstraintCollectionTpl> + static void run( + const pinocchio::ConstraintModelTpl & cmodel, + const DriftVectorLike & drift, + Scalar & max_violation) + { + ArgsType args(drift, max_violation); + // Note: Base::run will call `algo` of this visitor + Base::run(cmodel.derived(), args); + } + }; // struct ZeroInitialGuessMaxConstraintViolationVisitor + + template< + template class Holder, + typename ConstraintModel, + typename ConstraintModelAllocator, + typename VectorLikeIn> + typename ConstraintModel::Scalar computeZeroInitialGuessMaxConstraintViolation( + const std::vector, ConstraintModelAllocator> & constraint_models, + const Eigen::DenseBase & drift) + { + PINOCCHIO_TRACY_ZONE_SCOPED_N("computeZeroInitialGuessMaxConstraintViolation"); + Eigen::DenseIndex cindex = 0; + + using SegmentType = typename VectorLikeIn::ConstSegmentReturnType; + using Scalar = typename ConstraintModel::Scalar; + + Scalar max_violation = Scalar(0); + for (const ConstraintModel & cmodel : constraint_models) + { + const auto csize = cmodel.activeSize(); + + SegmentType drift_segment = drift.segment(cindex, csize); + typedef ZeroInitialGuessMaxConstraintViolationVisitor Algo; + + Algo::run(cmodel, drift_segment, max_violation); + + cindex += csize; + } + return max_violation; + } + template template< typename DelassusDerived, typename VectorLike, - typename ConstraintAllocator, - typename VectorLikeR> + template class Holder, + typename ConstraintModel, + typename ConstraintModelAllocator> bool ADMMContactSolverTpl<_Scalar>::solve( DelassusOperatorBase & _delassus, const Eigen::MatrixBase & g, - const std::vector, ConstraintAllocator> & cones, - const Eigen::MatrixBase & R, - const boost::optional primal_guess, - const boost::optional dual_guess, - bool compute_largest_eigen_values, - bool stat_record) + const std::vector, ConstraintModelAllocator> & constraint_models, + const Scalar dt, + const boost::optional preconditioner, + const boost::optional primal_guess, + const boost::optional dual_guess, + const bool solve_ncp, + const ADMMUpdateRule admm_update_rule, + const bool stat_record) { - using namespace internal; + // Unused for now + PINOCCHIO_UNUSED_VARIABLE(dual_guess); + typedef ADMMSpectralUpdateRuleTpl ADMMSpectralUpdateRule; + typedef ADMMLinearUpdateRuleTpl ADMMLinearUpdateRule; + + typedef ADMMUpdateRuleContainerTpl ADMMUpdateRuleContainer; + + typedef DelassusOperatorPreconditionedTpl + DelassusOperatorPreconditioned; DelassusDerived & delassus = _delassus.derived(); - const Scalar mu_R = R.minCoeff(); + const Scalar mu_R = delassus.getCompliance().minCoeff(); + PINOCCHIO_CHECK_INPUT_ARGUMENT(dt >= Scalar(0), "dt should be positive."); PINOCCHIO_CHECK_INPUT_ARGUMENT(tau <= Scalar(1) && tau > Scalar(0), "tau should lie in ]0,1]."); PINOCCHIO_CHECK_INPUT_ARGUMENT(mu_prox >= 0, "mu_prox should be positive."); PINOCCHIO_CHECK_INPUT_ARGUMENT(mu_R >= Scalar(0), "R should be a positive vector."); - PINOCCHIO_CHECK_ARGUMENT_SIZE(R.size(), problem_size); - // PINOCCHIO_CHECK_INPUT_ARGUMENT(math::max(R.maxCoeff(),mu_prox) >= 0,"mu_prox and mu_R - // cannot be both equal to zero."); + PINOCCHIO_CHECK_ARGUMENT_SIZE(delassus.getCompliance().size(), problem_size); + + // First, we initialize the primal and dual variables + int it = 0; + cholesky_update_count = 0; - if (compute_largest_eigen_values) + Scalar complementarity, dx_bar_norm, dy_bar_norm, dz_bar_norm, // + primal_feasibility, dual_feasibility; + + if (stat_record) { - // const Scalar L = delassus.computeLargestEigenValue(20); // Largest eigen_value - // estimate. - power_iteration_algo.run(delassus); + stats.reserve(this->max_it); + stats.reset(); } - const Scalar L = power_iteration_algo.largest_eigen_value; - // const Scalar L = delassus.computeLargestEigenValue(20); - const Scalar m = mu_prox + mu_R; - const Scalar cond = L / m; - const Scalar rho_increment = std::pow(cond, rho_power_factor); - - Scalar complementarity, - proximal_metric, // proximal metric between two successive iterates. - primal_feasibility, dual_feasibility_ncp, dual_feasibility; - - // std::cout << std::setprecision(12); - - Scalar rho; - rho = computeRho(L, m, rho_power); - // if(!is_initialized) - // { - // rho = computeRho(L,m,rho_power); - // } - // else - // { - // rho = this->rho; - // } - // rho = computeRho(L,m,rho_power); - - // std::cout << "L: " << L << std::endl; - // std::cout << "m: " << m << std::endl; - // std::cout << "prox_value: " << prox_value << std::endl; - - PINOCCHIO_EIGEN_MALLOC_NOT_ALLOWED(); - - // Update the cholesky decomposition - Scalar prox_value = mu_prox + tau * rho; - rhs = R + VectorXs::Constant(this->problem_size, prox_value); - delassus.updateDamping(rhs); - cholesky_update_count = 1; + + // Then, we get the time_scaling_acc_to_constraints T from the constraints to construct gs, + // which is g time-scaled depending on the formulation of each constraint: gs = T^{-1} * g. The + // idea is that if we formulate a given constraint at the position/velocity/acceleration level, + // we want to measure constraint satisfaction for this constraint at the same + // position/velocity/acceleration level. + // However, to take admm steps, we work at the (force, acceleration) level for all constraints. + // In short: + // -> gs is used to perform optimization steps (we typically work on min_x x^TGx + gs^Tx). + // -> time_scaling_acc_to_constraints is used to check for constraint satisfaction (we typically + // want TGx + g = 0). It allows to go from accelerations to the units of each constraints. This + // way, x and y are always forces expressed in N. + // -> time_scaling_constraints_to_pos similarly allows to go from the units of the constraints + // to positions in m. Warning: this constraints time-scaling has (a priori) nothing to do with + // the pre-conditioner. + internal::getTimeScalingFromAccelerationToConstraints( + constraint_models, dt, time_scaling_acc_to_constraints); + internal::getTimeScalingFromConstraintsToPosition( + time_scaling_acc_to_constraints, dt, time_scaling_constraints_to_pos); + gs = g.array() / time_scaling_acc_to_constraints.array(); + const Scalar g_pos_norm_inf = + (g.cwiseProduct(time_scaling_constraints_to_pos)).template lpNorm(); + + // Initialize De Saxé shift to 0 + // For the CCP, there is no shift + // For the NCP, the shift will be initialized using z + s_.setZero(); // Initial update of the variables // Init x @@ -91,232 +255,393 @@ namespace pinocchio x_ = primal_guess.get(); PINOCCHIO_CHECK_ARGUMENT_SIZE(x_.size(), problem_size); } - else if (!is_initialized) - { - x_.setZero(); - } else { - x_ = y_; // takes the current value stored in the solver + x_.setZero(); } - // Init y - computeConeProjection(cones, x_, y_); - - // Init z - if (dual_guess) + // Retrieve the pre-conditioner + if (preconditioner) { - z_ = dual_guess.get(); - PINOCCHIO_CHECK_ARGUMENT_SIZE(z_.size(), problem_size); - } - else if (!is_initialized) - { - delassus.applyOnTheRight(y_, z_); // z = G * y - z_.noalias() += -prox_value * y_ + g; - computeComplementarityShift(cones, z_, s_); - z_ += s_; // Add De Saxé shift - computeDualConeProjection(cones, z_, z_); + PINOCCHIO_CHECK_ARGUMENT_SIZE(preconditioner_.rows(), problem_size); + PINOCCHIO_CHECK_INPUT_ARGUMENT( + preconditioner_.getDiagonal().minCoeff() > Scalar(0), + "Preconditioner should be a strictly positive vector."); + preconditioner_.setDiagonal(preconditioner.get()); } else { - // Keep z from the previous iteration + preconditioner_.setDiagonal(VectorXs::Ones(problem_size)); } - // std::cout << "x_: " << x_.transpose() << std::endl; - // std::cout << "y_: " << y_.transpose() << std::endl; - // std::cout << "z_: " << z_.transpose() << std::endl; + // Init y + internal::computeConeProjection(constraint_models, x_, y_); - if (stat_record) + // Init z -> z_ = (G + R) * y_ + g + delassus.applyOnTheRight(y_, z_); + z_ += gs; + z_ -= y_.cwiseProduct(delassus.getDamping()); + if (solve_ncp) { - stats.reset(); - - // Compute initial problem primal and dual feasibility - primal_feasibility_vector = x_ - y_; - primal_feasibility = primal_feasibility_vector.template lpNorm(); + internal::computeDeSaxeCorrection(constraint_models, z_, s_); + z_ += s_; // Add De Saxé shift } - is_initialized = true; - - // End of Initialization phase - - bool abs_prec_reached = false, rel_prec_reached = false; - - Scalar y_previous_norm_inf = y_.template lpNorm(); - int it = 1; -// Scalar res = 0; -#ifdef PINOCCHIO_WITH_HPP_FCL - timer.start(); -#endif // PINOCCHIO_WITH_HPP_FCL - for (; it <= Base::max_it; ++it) - { - // std::cout << "---" << std::endl; - // std::cout << "it: " << it << std::endl; - // std::cout << "tau*rho: " << tau*rho << std::endl; - - x_previous = x_; - y_previous = y_; - z_previous = z_; - complementarity = Scalar(0); - - // s-update - computeComplementarityShift(cones, z_, s_); - - // std::cout << "s_: " << s_.transpose() << std::endl; - - // std::cout << "x_: " << x_.transpose() << std::endl; - - // z-update - // const Scalar alpha = 1.; - // z_ -= (tau*rho) * (x_ - y_); - // std::cout << "intermediate z_: " << z_.transpose() << std::endl; - - // x-update - rhs = -(g + s_ - (rho * tau) * y_ - mu_prox * x_ - z_); - const VectorXs rhs_copy = rhs; - // x_ = rhs; - delassus.solveInPlace(rhs); - // VectorXs tmp = delassus * rhs - rhs_copy; - // res = math::max(res,tmp.template lpNorm()); - // std::cout << "residual = " << (delassus * rhs - x_).template lpNorm() - // << std::endl; - x_ = rhs; - - // y-update - // rhs *= alpha; - // rhs += (1-alpha)*y_previous; - rhs = x_; - rhs -= z_ / (tau * rho); - computeConeProjection(cones, rhs, y_); - // std::cout << "y_: " << y_.transpose() << std::endl; - - // z-update - z_ -= (tau * rho) * (x_ - y_); - // const Scalar gamma = Scalar(it) / Scalar(it + 300); - - // z_ += gamma * (z_ - z_previous).eval(); - // x_ += gamma * (x_ - x_previous).eval(); - // computeConeProjection(cones, y_, y_); - - // z_ -= (tau*rho) * (x_ * alpha + (1-alpha)*y_previous - y_); - // std::cout << "z_: " << z_.transpose() << std::endl; - // computeDualConeProjection(cones, z_, z_); - - // check termination criteria - primal_feasibility_vector = x_ - y_; - // delassus.applyOnTheRight(x_,dual_feasibility_vector); - // dual_feasibility_vector.noalias() += g + s_ - prox_value * x_ - z_; - + // Computing the convergence criterion of the initial guess + primal_feasibility = 0; // always feasible because y is projected + + // complementarity of the initial guess + // NB: complementarity is computed between a force y_ (in N) and z_ which unit is that of the + // constraint formulation level. + rhs = + z_.array() * time_scaling_acc_to_constraints.array(); // back to constraint formulation level + complementarity = internal::computeConicComplementarity(constraint_models, rhs, y_); + + // dual feasibility is computed in "position" on the z_ variable (and not on z_bar_). + dual_feasibility_vector = rhs; + internal::computeDualConeProjection(constraint_models, rhs, rhs); + dual_feasibility_vector -= rhs; + dual_feasibility = dual_feasibility_vector.template lpNorm(); + const Scalar absolute_residual_warm_start = math::max(complementarity, dual_feasibility); + + dual_feasibility_vector.array() *= time_scaling_constraints_to_pos.array(); + dual_feasibility = dual_feasibility_vector.template lpNorm(); + this->absolute_residual = math::max(complementarity, dual_feasibility); + + // Checking if the initial guess is better than 0. + // if instead of the x_ initial guess, x_ is set to 0, then z_ = g. + // -> we check how much constraints violation is induced by using g as the dual variable. + // note: here we work with g and not gs, because we check for constraints violation at the + // formulation level of each constraints. + const Scalar absolute_residual_zero_guess = + computeZeroInitialGuessMaxConstraintViolation(constraint_models, g); + + if (absolute_residual_zero_guess < absolute_residual_warm_start) + { // If true, this means that the zero value initial guess leads a better feasibility in the + // sense of the constraints satisfaction. + // So we set the primal variables to the 0 initial guess and the dual variable to g. + x_.setZero(); + y_.setZero(); + z_ = gs; + if (solve_ncp) { - VectorXs & dy = rhs; - dy = y_ - y_previous; - proximal_metric = dy.template lpNorm(); - dual_feasibility_vector.noalias() = (tau * rho) * dy; + { + PINOCCHIO_TRACY_ZONE_SCOPED_N( + "ADMMContactSolverTpl::solve - second computeDeSaxeCorrection"); + internal::computeDeSaxeCorrection(constraint_models, z_, s_); + } + z_ += s_; // Add De Saxé shift } - + rhs = z_.array() * time_scaling_acc_to_constraints.array(); + dual_feasibility_vector = rhs; + internal::computeDualConeProjection(constraint_models, rhs, rhs); + dual_feasibility_vector -= rhs; // Dual feasibility vector for the new null guess + dual_feasibility_vector.array() *= time_scaling_constraints_to_pos.array(); + // We set the new convergence criterion + this->absolute_residual = absolute_residual_zero_guess; + } + // We test convergence + bool abs_prec_reached = this->absolute_residual < this->absolute_precision; + + if (!abs_prec_reached) + { // the initial guess is not solution of the problem so we run the ADMM algorithm + // Applying the preconditioner to work on a problem with a better scaling + DelassusOperatorPreconditioned G_bar(_delassus, preconditioner_); + rhs = VectorXs::Constant(this->problem_size, mu_prox); + G_bar.updateDamping(rhs); // G_bar = P*(G+R)*P + mu_prox*Id + scaleDualSolution(gs, g_bar_); // g_bar = P * gs + scalePrimalSolution(x_, x_bar_); + scalePrimalSolution(y_, y_bar_); + scaleDualSolution(z_, z_bar_); + + // Setup ADMM update rules: + // Before running ADMM, we compute the largest and smallest eigenvalues of delassus in order + // to be able to use a spectral update rule for the proximal parameter (rho) + // TODO should we evaluate the eigenvalues of G or Gbar ? + Scalar L, m, rho; + ADMMUpdateRuleContainer admm_update_rule_container; + switch (admm_update_rule) { - VectorXs & dx = rhs; - dx = x_ - x_previous; - dual_feasibility_vector.noalias() += mu_prox * dx; + case (ADMMUpdateRule::SPECTRAL): { + if (this->problem_size > 1) + { + PINOCCHIO_TRACY_ZONE_SCOPED_N("ADMMContactSolverTpl::solve - lanczos"); + m = rhs.minCoeff(); + this->lanczos_decomposition.compute(G_bar); + L = ::pinocchio::computeLargestEigenvalue(this->lanczos_decomposition.Ts(), 1e-8); +#ifndef NDEBUG + const bool enforce_symmetry = true; + Eigen::MatrixXd delassus = G_bar.matrix(enforce_symmetry); + Eigen::SelfAdjointEigenSolver solver(delassus); + Eigen::VectorXd eigvals = solver.eigenvalues(); + // Scalar true_m = eigvals.minCoeff(); + Scalar true_L = eigvals.maxCoeff(); + // if (true_m > 0) + // { + // assert( + // math::fabs((true_m - m) / math::max(true_m, m)) < 0.01 + // && "true_m and m are too far apart."); + // } + assert( + math::fabs((true_L - L) / math::max(true_L, L)) < 0.01 + && "true_L and L are too far apart."); +#endif // NDEBUG + } + else + { + // TODO adapt this with Gbar + typedef Eigen::Matrix Vector1; + const Vector1 G = delassus * Vector1::Constant(1); + m = L = G.coeff(0); + } + admm_update_rule_container.spectral_rule = + ADMMSpectralUpdateRule(ratio_primal_dual, L, m, rho_power_factor); + rho = ADMMSpectralUpdateRule::computeRho(L, m, rho_power); + break; + } + case (ADMMUpdateRule::LINEAR): + admm_update_rule_container.linear_rule = + ADMMLinearUpdateRule(ratio_primal_dual, linear_update_rule_factor); + rho = this->rho; // use the rho value stored in the solver. + break; + case (ADMMUpdateRule::CONSTANT): + rho = this->rho; // use the rho value stored in the solver. + break; } - // delassus.applyOnTheRight(x_,dual_feasibility_vector); - // dual_feasibility_vector.noalias() += g; - // computeComplementarityShift(cones, z_, s_); - // dual_feasibility_vector.noalias() += s_ - prox_value * x_ - z_; + // clamp the rho + rho = math::max(1e-8, rho); - primal_feasibility = primal_feasibility_vector.template lpNorm(); - dual_feasibility = dual_feasibility_vector.template lpNorm(); - complementarity = computeConicComplementarity(cones, z_, y_); - // complementarity = z_.dot(y_)/cones.size(); + PINOCCHIO_EIGEN_MALLOC_NOT_ALLOWED(); - if (stat_record) - { - VectorXs tmp(rhs); - delassus.applyOnTheRight(y_, rhs); - rhs.noalias() += g - prox_value * y_; - computeComplementarityShift(cones, rhs, tmp); - rhs.noalias() += tmp; - - internal::computeDualConeProjection(cones, rhs, tmp); - tmp -= rhs; - - dual_feasibility_ncp = tmp.template lpNorm(); - - stats.primal_feasibility.push_back(primal_feasibility); - stats.dual_feasibility.push_back(dual_feasibility); - stats.dual_feasibility_ncp.push_back(dual_feasibility_ncp); - stats.complementarity.push_back(complementarity); - stats.rho.push_back(rho); - } + // Update the cholesky decomposition + Scalar prox_value = mu_prox + tau * rho; + rhs = VectorXs::Constant(this->problem_size, prox_value); + G_bar.updateDamping(rhs); + Scalar old_prox_value = prox_value; + cholesky_update_count = 1; - // std::cout << "primal_feasibility: " << primal_feasibility << std::endl; - // std::cout << "dual_feasibility: " << dual_feasibility << std::endl; - // std::cout << "complementarity: " << complementarity << std::endl; - - // Checking stopping residual - if ( - check_expression_if_real(complementarity <= this->absolute_precision) - && check_expression_if_real(dual_feasibility <= this->absolute_precision) - && check_expression_if_real(primal_feasibility <= this->absolute_precision)) - abs_prec_reached = true; - else - abs_prec_reached = false; - - const Scalar y_norm_inf = y_.template lpNorm(); - if (check_expression_if_real( - proximal_metric - <= this->relative_precision * math::max(y_norm_inf, y_previous_norm_inf))) - rel_prec_reached = true; - else - rel_prec_reached = false; - - // if(abs_prec_reached || rel_prec_reached) - if (abs_prec_reached) - break; + is_initialized = true; - // Account for potential update of rho - bool update_delassus_factorization = false; - if (primal_feasibility > ratio_primal_dual * dual_feasibility) - { - rho *= rho_increment; - // rho *= math::pow(cond,rho_power_factor); - // rho_power += rho_power_factor; - update_delassus_factorization = true; - } - else if (dual_feasibility > ratio_primal_dual * primal_feasibility) + // End of Initialization phase + abs_prec_reached = false; + bool rel_prec_reached = false; + + Scalar x_bar_norm_inf = x_bar_.template lpNorm(); + Scalar y_bar_norm_inf = y_bar_.template lpNorm(); + Scalar z_bar_norm_inf = z_bar_.template lpNorm(); + Scalar x_bar_previous_norm_inf = x_bar_norm_inf; + Scalar y_bar_previous_norm_inf = y_bar_norm_inf; + Scalar z_bar_previous_norm_inf = z_bar_norm_inf; + it = 1; +#ifdef PINOCCHIO_WITH_HPP_FCL + timer.start(); +#endif // PINOCCHIO_WITH_HPP_FCL + for (; it <= Base::max_it; ++it) { - rho /= rho_increment; - // rho *= math::pow(cond,-rho_power_factor); - // rho_power -= rho_power_factor; - update_delassus_factorization = true; - } - if (update_delassus_factorization) + x_bar_previous = x_bar_; + y_bar_previous = y_bar_; + z_bar_previous = z_bar_; + complementarity = Scalar(0); + + if (solve_ncp) + { + // s-update + internal::computeDeSaxeCorrection(constraint_models, z_bar_, s_bar_); + } + + // x-update + rhs = -(g_bar_ + s_bar_ - (rho * tau) * y_bar_ - mu_prox * x_bar_ - z_bar_); + G_bar.solveInPlace(rhs); + x_bar_ = rhs; + + // y-update + rhs -= z_bar_ / (tau * rho); + internal::computeScaledConeProjection( + constraint_models, rhs, preconditioner_.getDiagonal(), y_bar_); + + // z-update + z_bar_ -= (tau * rho) * (x_bar_ - y_bar_); + + // check termination criteria + primal_feasibility_vector_bar = x_bar_ - y_bar_; + + { + VectorXs & dx_bar = rhs; + dx_bar = x_bar_ - x_bar_previous; + dx_bar_norm = + dx_bar.template lpNorm(); // check relative progress on x_bar + dual_feasibility_vector_bar = mu_prox * dx_bar; + } + + { + VectorXs & dy_bar = rhs; + dy_bar = y_bar_ - y_bar_previous; + dy_bar_norm = + dy_bar.template lpNorm(); // check relative progress on y_bar + dual_feasibility_vector_bar += (tau * rho) * dy_bar; + } + + { + VectorXs & dz_bar = rhs; + dz_bar = z_bar_ - z_bar_previous; + dz_bar_norm = + dz_bar.template lpNorm(); // check relative progress on z_bar + } + + // We unscale the quantities to work with stopping criterion from the original (unscaled) + // problem + unscalePrimalSolution(primal_feasibility_vector_bar, primal_feasibility_vector); + primal_feasibility = primal_feasibility_vector.template lpNorm(); + unscaleDualSolution(dual_feasibility_vector_bar, dual_feasibility_vector); + const Scalar dual_feasibility_admm = + dual_feasibility_vector.template lpNorm(); + dual_feasibility_vector.array() *= time_scaling_acc_to_constraints.array(); + const Scalar dual_feasibility_constraint = + dual_feasibility_vector.template lpNorm(); + dual_feasibility_vector.array() *= time_scaling_constraints_to_pos.array(); + dual_feasibility = dual_feasibility_vector.template lpNorm(); + unscalePrimalSolution(y_bar_, y_); + unscaleDualSolution(z_bar_, z_); + rhs = z_.array() * time_scaling_acc_to_constraints.array(); + complementarity = internal::computeConicComplementarity(constraint_models, rhs, y_); + + if (stat_record) + { + VectorXs tmp(rhs); + G_bar.applyOnTheRight(y_bar_, rhs); + rhs += g_bar_ - prox_value * y_bar_; + unscaleDualSolution(rhs, tmp); + if (solve_ncp) + { + internal::computeDeSaxeCorrection(constraint_models, tmp, rhs); + tmp += rhs; + } + + tmp.array() *= + time_scaling_acc_to_constraints.array(); // back to constraint formulation level + rhs = tmp; + internal::computeDualConeProjection(constraint_models, rhs, rhs); + tmp -= rhs; + + Scalar dual_feasibility_ncp = tmp.template lpNorm(); + + stats.primal_feasibility.push_back(primal_feasibility); + stats.dual_feasibility.push_back(dual_feasibility); + stats.dual_feasibility_admm.push_back(dual_feasibility_admm); + stats.dual_feasibility_ncp.push_back(dual_feasibility_ncp); + stats.dual_feasibility_constraint.push_back(dual_feasibility_constraint); + stats.complementarity.push_back(complementarity); + stats.rho.push_back(rho); + } + + // Checking stopping residual + const Scalar x_norm_inf = x_.template lpNorm(); + const Scalar y_norm_inf = y_.template lpNorm(); + const Scalar z_norm_inf = z_.template lpNorm(); + if ( + check_expression_if_real(complementarity <= this->absolute_precision) + && check_expression_if_real( + dual_feasibility + <= this->absolute_precision + + this->relative_precision * math::max(g_pos_norm_inf, z_norm_inf)) + && check_expression_if_real( + primal_feasibility <= this->absolute_precision + + this->relative_precision * math::max(x_norm_inf, y_norm_inf))) + abs_prec_reached = true; + else + abs_prec_reached = false; + + x_bar_norm_inf = x_bar_.template lpNorm(); + y_bar_norm_inf = y_bar_.template lpNorm(); + z_bar_norm_inf = z_bar_.template lpNorm(); + if ( + check_expression_if_real( + dx_bar_norm + <= this->relative_precision * math::max(x_bar_norm_inf, x_bar_previous_norm_inf)) + && check_expression_if_real( + dy_bar_norm + <= this->relative_precision * math::max(y_bar_norm_inf, y_bar_previous_norm_inf)) + && check_expression_if_real( + dz_bar_norm + <= this->relative_precision * math::max(z_bar_norm_inf, z_bar_previous_norm_inf))) + rel_prec_reached = true; + else + rel_prec_reached = false; + + if (abs_prec_reached || rel_prec_reached) + break; + + // Apply rho according to the primal_dual_ratio + bool update_delassus_factorization = false; + switch (admm_update_rule) + { + case (ADMMUpdateRule::SPECTRAL): + update_delassus_factorization = admm_update_rule_container.spectral_rule.eval( + primal_feasibility, dual_feasibility_constraint, rho); + break; + case (ADMMUpdateRule::LINEAR): + update_delassus_factorization = admm_update_rule_container.linear_rule.eval( + primal_feasibility, dual_feasibility_constraint, rho); + break; + case (ADMMUpdateRule::CONSTANT): + break; + } + + // clamp rho + rho = math::max(1e-8, rho); + + // Account for potential update of rho + if (update_delassus_factorization) + { + prox_value = mu_prox + tau * rho; + if (old_prox_value != prox_value) + { + rhs = VectorXs::Constant(this->problem_size, prox_value); + G_bar.updateDamping(rhs); + cholesky_update_count++; + old_prox_value = prox_value; + } + } + + x_bar_previous_norm_inf = x_bar_norm_inf; + y_bar_previous_norm_inf = y_bar_norm_inf; + z_bar_previous_norm_inf = z_bar_norm_inf; + } // end ADMM main for loop + + unscalePrimalSolution(x_bar_, x_); + unscalePrimalSolution(y_bar_, y_); + unscaleDualSolution(z_bar_, z_); + unscaleDualSolution(s_bar_, s_); + + this->relative_residual = math::max( + dx_bar_norm / math::max(x_bar_norm_inf, x_bar_previous_norm_inf), + dy_bar_norm / math::max(y_bar_norm_inf, y_bar_previous_norm_inf)); + this->relative_residual = math::max( + this->relative_residual, dz_bar_norm / math::max(z_bar_norm_inf, z_bar_previous_norm_inf)); + this->absolute_residual = + math::max(primal_feasibility, math::max(complementarity, dual_feasibility)); + + // Save values of spectral update rule + if (admm_update_rule == ADMMUpdateRule::SPECTRAL) { - prox_value = mu_prox + tau * rho; - rhs = R + VectorXs::Constant(this->problem_size, prox_value); - delassus.updateDamping(rhs); - cholesky_update_count++; + this->rho_power = ADMMSpectralUpdateRule::computeRhoPower(L, m, rho); + this->rho = rho; } - - y_previous_norm_inf = y_norm_inf; - // std::cout << "rho_power: " << rho_power << std::endl; - // std::cout << "rho: " << rho << std::endl; - // std::cout << "---" << std::endl; } - PINOCCHIO_EIGEN_MALLOC_ALLOWED(); - this->absolute_residual = - math::max(primal_feasibility, math::max(complementarity, dual_feasibility)); - this->relative_residual = proximal_metric; - this->it = it; - // std::cout << "max linalg res: " << res << std::endl; - // y_sol.const_cast_derived() = y_; +#ifdef PINOCCHIO_WITH_HPP_FCL + timer.stop(); +#endif // PINOCCHIO_WITH_HPP_FCL + // - // Save values - this->rho_power = computeRhoPower(L, m, rho); - this->rho = rho; + this->it = it; + // we time-rescale dual solution and desaxe correction + // so that z_ and s_ are back at the constraints formulations levels + z_constraint_ = z_.array() * time_scaling_acc_to_constraints.array(); + s_constraint_ = s_.array() * time_scaling_acc_to_constraints.array(); if (stat_record) { @@ -324,11 +649,6 @@ namespace pinocchio stats.cholesky_update_count = cholesky_update_count; } -#ifdef PINOCCHIO_WITH_HPP_FCL - timer.stop(); -#endif // PINOCCHIO_WITH_HPP_FCL - - // if(abs_prec_reached || rel_prec_reached) if (abs_prec_reached) return true; diff --git a/include/pinocchio/algorithm/check-data.hxx b/include/pinocchio/algorithm/check-data.hxx index dfd8e88060..077bb542e9 100644 --- a/include/pinocchio/algorithm/check-data.hxx +++ b/include/pinocchio/algorithm/check-data.hxx @@ -78,7 +78,6 @@ namespace pinocchio CHECK_DATA((int)data.oMf.size() == model.nframes); - CHECK_DATA((int)data.lastChild.size() == model.njoints); CHECK_DATA((int)data.nvSubtree.size() == model.njoints); CHECK_DATA((int)data.parents_fromRow.size() == model.nvExtended); CHECK_DATA((int)data.mimic_parents_fromRow.size() == model.nvExtended); @@ -101,7 +100,7 @@ namespace pinocchio } for (JointIndex j = 1; int(j) < model.njoints; ++j) { - JointIndex c = (JointIndex)data.lastChild[j]; + const JointIndex c = model.subtrees[j].back(); CHECK_DATA((int)c < model.njoints); int nv; // For mimic, since in nvSubtree we're using the idx_vExtended, we need to do the same here @@ -174,8 +173,7 @@ namespace pinocchio } template class JointCollectionTpl> - inline bool ModelTpl::check( - const DataTpl & data) const + bool ModelTpl::check(const Data & data) const { return checkData(*this, data); } diff --git a/include/pinocchio/algorithm/constrained-dynamics-derivatives.hxx b/include/pinocchio/algorithm/constrained-dynamics-derivatives.hxx index 1ce9fdae2e..97f467962b 100644 --- a/include/pinocchio/algorithm/constrained-dynamics-derivatives.hxx +++ b/include/pinocchio/algorithm/constrained-dynamics-derivatives.hxx @@ -449,6 +449,7 @@ namespace pinocchio const RigidConstraintModel & cmodel = contact_models[k]; RigidConstraintData & cdata = contact_data[k]; // const BooleanVector & joint1_indexes = cmodel.colwise_joint1_sparsity; + const BooleanVector & joint1_indexes = cmodel.colwise_joint1_sparsity; const BooleanVector & joint2_indexes = cmodel.colwise_joint2_sparsity; switch (cmodel.type) @@ -501,43 +502,38 @@ namespace pinocchio const Motion v2_in_c1 = cdata.c1Mc2.act(cdata.contact2_velocity); const Motion a2_in_c1 = cdata.oMc1.actInv(data.oa[cmodel.joint2_id]); - Eigen::DenseIndex k = Eigen::DenseIndex(cmodel.colwise_span_indexes.size()) - 1; - Eigen::DenseIndex col_id(0); - while (cmodel.reference_frame == LOCAL && cmodel.colwise_span_indexes.size() > 0) + if (cmodel.reference_frame == LOCAL) { - if (k >= 0) - { - col_id = cmodel.colwise_span_indexes[size_t(k)]; - k--; - } - else + Eigen::DenseIndex col_id(0); + const auto & colwise_span_indexes = cmodel.getRowActiveIndexes(0); + for (Eigen::DenseIndex k = 0; k < Eigen::DenseIndex(colwise_span_indexes.size()); k++) { - col_id = data.parents_fromRow[size_t(col_id)]; - if (col_id < 0) - break; + col_id = colwise_span_indexes[size_t(k)]; + + const MotionRef dvc_dv_col(contact_dac_da.col(col_id)); + const MotionRef da2_da_col( + cdata.da2_da.col(col_id)); + const MotionRef dv2_dq_col( + cdata.dv2_dq.col(col_id)); + + // dv/dq + const Motion v2_in_c1_cross_dvc_dv_col = v2_in_c1.cross(dvc_dv_col); + contact_dvc_dq.col(col_id) -= v2_in_c1_cross_dvc_dv_col.toVector(); + + // da/dv + contact_dac_dv.col(col_id) -= v2_in_c1_cross_dvc_dv_col.toVector(); + contact_dac_dv.col(col_id) += + cdata.contact_velocity_error.cross(da2_da_col).toVector(); + + // da/dq + const MotionRef dvc_dq_col(contact_dvc_dq.col(col_id)); + + contact_dac_dq.col(col_id) -= a2_in_c1.cross(dvc_dv_col).toVector(); + contact_dac_dq.col(col_id) -= v2_in_c1.cross(dvc_dq_col).toVector(); + contact_dac_dq.col(col_id) += + cdata.contact_velocity_error.cross(v2_in_c1_cross_dvc_dv_col + dv2_dq_col) + .toVector(); } - - const MotionRef dvc_dv_col(contact_dac_da.col(col_id)); - const MotionRef da2_da_col( - cdata.da2_da.col(col_id)); - const MotionRef dv2_dq_col( - cdata.dv2_dq.col(col_id)); - - // dv/dq - const Motion v2_in_c1_cross_dvc_dv_col = v2_in_c1.cross(dvc_dv_col); - contact_dvc_dq.col(col_id) -= v2_in_c1_cross_dvc_dv_col.toVector(); - - // da/dv - contact_dac_dv.col(col_id) -= v2_in_c1_cross_dvc_dv_col.toVector(); - contact_dac_dv.col(col_id) += cdata.contact_velocity_error.cross(da2_da_col).toVector(); - - // da/dq - const MotionRef dvc_dq_col(contact_dvc_dq.col(col_id)); - - contact_dac_dq.col(col_id) -= a2_in_c1.cross(dvc_dv_col).toVector(); - contact_dac_dq.col(col_id) -= v2_in_c1.cross(dvc_dq_col).toVector(); - contact_dac_dq.col(col_id) += - cdata.contact_velocity_error.cross(v2_in_c1_cross_dvc_dv_col + dv2_dq_col).toVector(); } cdata.dvc_dq = contact_dvc_dq; @@ -637,21 +633,21 @@ namespace pinocchio } // d./dq - for (Eigen::DenseIndex k = 0; k < Eigen::DenseIndex(cmodel.colwise_span_indexes.size()); - ++k) + const auto & colwise_span_indexes = cmodel.getRowActiveIndexes(0); + for (size_t k = 0; k < colwise_span_indexes.size(); ++k) { - const Eigen::DenseIndex col_id = cmodel.colwise_span_indexes[size_t(k)]; + const Eigen::DenseIndex col_id = colwise_span_indexes[k]; const MotionRef J_col(data.J.col(col_id)); const Force J_col_cross_contact_force_in_WORLD = J_col.cross(contact_force_in_WORLD); for (Eigen::DenseIndex j = colRef2; j >= 0; j = data.parents_fromRow[(size_t)j]) { - if (joint2_indexes[col_id]) + if (!joint1_indexes[col_id] && joint2_indexes[col_id]) { data.dtau_dq(j, col_id) -= data.J.col(j).dot(J_col_cross_contact_force_in_WORLD.toVector()); } - else + else if (joint1_indexes[col_id] && !joint2_indexes[col_id]) { data.dtau_dq(j, col_id) += data.J.col(j).dot(J_col_cross_contact_force_in_WORLD.toVector()); @@ -771,10 +767,10 @@ namespace pinocchio contact_dac_dq += cmodel.corrector.Kd.asDiagonal() * contact_dvc_dq; contact_dac_dv += cmodel.corrector.Kd.asDiagonal() * contact_dac_da; // d./dq - for (Eigen::DenseIndex k = 0; k < Eigen::DenseIndex(cmodel.colwise_span_indexes.size()); - ++k) + const auto & colwise_span_indexes = cmodel.getRowActiveIndexes(0); + for (size_t k = 0; k < colwise_span_indexes.size(); ++k) { - const Eigen::DenseIndex row_id = cmodel.colwise_span_indexes[size_t(k)]; + const Eigen::DenseIndex row_id = cmodel.colwise_span_indexes[k]; // contact_dac_dq.col(row_id) += cmodel.corrector.Kd * contact_dvc_dq.col(row_id); contact_dac_dq.col(row_id).noalias() += cmodel.corrector.Kp.asDiagonal() * Jlog * contact_dac_da.col(row_id); diff --git a/include/pinocchio/algorithm/constrained-dynamics.hpp b/include/pinocchio/algorithm/constrained-dynamics.hpp index 90922c00e7..e8671ed97b 100644 --- a/include/pinocchio/algorithm/constrained-dynamics.hpp +++ b/include/pinocchio/algorithm/constrained-dynamics.hpp @@ -29,13 +29,15 @@ namespace pinocchio template< typename Scalar, int Options, - template class JointCollectionTpl, + class ConstraintModel, + template + class JointCollectionTpl, class Allocator> PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") inline void initConstraintDynamics( const ModelTpl & model, DataTpl & data, - const std::vector, Allocator> & contact_models); + const std::vector & contact_models); /// /// \brief Computes the forward dynamics with contact constraints according to a given list of @@ -79,7 +81,8 @@ namespace pinocchio template< typename Scalar, int Options, - template class JointCollectionTpl, + template + class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2, @@ -136,7 +139,8 @@ namespace pinocchio template< typename Scalar, int Options, - template class JointCollectionTpl, + template + class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2, @@ -161,7 +165,8 @@ namespace pinocchio template< typename Scalar, int Options, - template class JointCollectionTpl, + template + class JointCollectionTpl, typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2, diff --git a/include/pinocchio/algorithm/constrained-dynamics.hxx b/include/pinocchio/algorithm/constrained-dynamics.hxx index 629dda0d75..724980e33d 100644 --- a/include/pinocchio/algorithm/constrained-dynamics.hxx +++ b/include/pinocchio/algorithm/constrained-dynamics.hxx @@ -22,14 +22,15 @@ namespace pinocchio template< typename Scalar, int Options, + class ConstraintModel, template class JointCollectionTpl, class Allocator> inline void initConstraintDynamics( const ModelTpl & model, DataTpl & data, - const std::vector, Allocator> & contact_models) + const std::vector & contact_models) { - data.contact_chol.allocate(model, contact_models); + data.contact_chol.resize(model, contact_models); data.primal_dual_contact_solution.resize(data.contact_chol.size()); data.primal_rhs_contact.resize(data.contact_chol.constraintDim()); @@ -293,7 +294,7 @@ namespace pinocchio RigidConstraintData & contact_data = contact_datas[contact_id]; const int contact_dim = contact_model.size(); - const typename RigidConstraintModel::BaumgarteCorrectorParameters & corrector = + const typename RigidConstraintModel::BaumgarteCorrectorVectorParameters & corrector = contact_model.corrector; const typename RigidConstraintData::Motion & contact_acceleration_desired = contact_data.contact_acceleration_desired; @@ -408,12 +409,9 @@ namespace pinocchio if (contact_model.type == CONTACT_3D) { - coriolis_centrifugal_acc2.linear().noalias() = - oMc1.rotation().transpose() - * (data.oa[joint2_id].linear() + data.oa[joint2_id].angular().cross(oMc2.translation()) - + data.ov[joint2_id].angular().cross( - data.ov[joint2_id].linear() - + data.ov[joint2_id].angular().cross(oMc2.translation()))); + coriolis_centrifugal_acc2.linear().noalias() + = oMc1.rotation().transpose()*(data.oa[joint2_id].linear() + data.oa[joint2_id].angular().cross(oMc2.translation()) + + data.ov[joint2_id].angular().cross(data.ov[joint2_id].linear() + data.ov[joint2_id].angular().cross(oMc2.translation()))); coriolis_centrifugal_acc2.angular().setZero(); } else @@ -635,7 +633,7 @@ namespace pinocchio // Account for the rotor inertia contribution jdata.StU().diagonal() += jmodel.jointVelocitySelector(model.armature); - internal::PerformStYSInversion::run(jdata.StU(), jdata.Dinv()); + matrix_inversion(jdata.StU(), jdata.Dinv()); jdata.UDinv().noalias() = jdata.U() * jdata.Dinv(); if (parent > 0) @@ -733,7 +731,7 @@ namespace pinocchio jmodel.jointVelocitySelector(data.ddq).noalias() = jdata.Dinv() * jmodel.jointVelocitySelector(data.u) - jdata.UDinv().transpose() * data.oa_augmented[i].toVector(); - data.oa_augmented[i].toVector() += Jcols * jmodel.jointVelocitySelector(data.ddq); + data.oa_augmented[i].toVector().noalias() += Jcols * jmodel.jointVelocitySelector(data.ddq); } }; diff --git a/include/pinocchio/algorithm/constrained-dynamics.txx b/include/pinocchio/algorithm/constrained-dynamics.txx index 16191dc4d8..c10e7218d9 100644 --- a/include/pinocchio/algorithm/constrained-dynamics.txx +++ b/include/pinocchio/algorithm/constrained-dynamics.txx @@ -13,6 +13,7 @@ namespace pinocchio extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void initConstraintDynamics< context::Scalar, context::Options, + RigidConstraintModel, JointCollectionDefaultTpl, typename context::RigidConstraintModelVector::allocator_type>( const context::Model &, context::Data &, const context::RigidConstraintModelVector &); diff --git a/include/pinocchio/algorithm/constraints/baumgarte-corrector-parameters.hpp b/include/pinocchio/algorithm/constraints/baumgarte-corrector-parameters.hpp new file mode 100644 index 0000000000..ebea4855c9 --- /dev/null +++ b/include/pinocchio/algorithm/constraints/baumgarte-corrector-parameters.hpp @@ -0,0 +1,80 @@ +// +// Copyright (c) 2020-2025 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_baumgarte_corrector_parameters_hpp__ +#define __pinocchio_algorithm_constraints_baumgarte_corrector_parameters_hpp__ + +#include "pinocchio/fwd.hpp" + +namespace pinocchio +{ + + template + struct BaumgarteCorrectorParametersTpl; + + template + struct CastType> + { + typedef BaumgarteCorrectorParametersTpl type; + }; + + template + struct traits> + { + typedef _Scalar Scalar; + }; + + template + struct BaumgarteCorrectorParametersTpl : NumericalBase> + { + typedef _Scalar Scalar; + + /// \brief Default constructor initializes Kp and Kd to 0 (no correction). + /// It is needed for constraints that don't have baumgarte correction. + BaumgarteCorrectorParametersTpl() + : Kp(Scalar(0)) + , Kd(Scalar(0)) + { + } + + /// \brief Constructor from Kp and Kd. + BaumgarteCorrectorParametersTpl(const Scalar Kp, const Scalar Kd) + : Kp(Kp) + , Kd(Kd) + { + } + + bool operator==(const BaumgarteCorrectorParametersTpl & other) const + { + if (this == &other) + return true; + return Kp == other.Kp && Kd == other.Kd; + } + + bool operator!=(const BaumgarteCorrectorParametersTpl & other) const + { + return !(*this == other); + } + + // parameters + /// \brief Proportional corrector values. + Scalar Kp; + + /// \brief Damping corrector values. + Scalar Kd; + + template + typename CastType::type cast() const + { + typedef typename CastType::type ReturnType; + ReturnType res; + res.Kp = NewScalar(Kp); + res.Kd = NewScalar(Kd); + return res; + } + + }; // struct BaumgarteCorrectorParametersTpl +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_baumgarte_corrector_parameters_hpp__ diff --git a/include/pinocchio/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp b/include/pinocchio/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp new file mode 100644 index 0000000000..72fa882ee5 --- /dev/null +++ b/include/pinocchio/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp @@ -0,0 +1,136 @@ +// +// Copyright (c) 2020-2025 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_baumgarte_corrector_vector_parameters_hpp__ +#define __pinocchio_algorithm_constraints_baumgarte_corrector_vector_parameters_hpp__ + +#include "pinocchio/algorithm/fwd.hpp" + +namespace pinocchio +{ + + template + struct BaumgarteCorrectorVectorParametersTpl; + + template + struct CastType> + { + enum + { + RowsAtCompileTime = VectorType::RowsAtCompileTime, + ColsAtCompileTime = VectorType::ColsAtCompileTime, + Options = VectorType::Options + }; + + typedef Eigen::Matrix NewVectorType; + typedef BaumgarteCorrectorVectorParametersTpl type; + }; + + template + struct traits> + { + typedef _VectorType VectorType; + typedef typename VectorType::Scalar Scalar; + }; + + template + struct BaumgarteCorrectorVectorParametersTpl + : NumericalBase> + { + typedef _VectorType VectorType; + typedef typename VectorType::Scalar Scalar; + + template + friend struct BaumgarteCorrectorVectorParametersTpl; + + /// \brief Default constructor with 0-size Kp and Kd. + /// It is needed for constraints that don't have baumgarte correction. + BaumgarteCorrectorVectorParametersTpl() + { + } + + explicit BaumgarteCorrectorVectorParametersTpl(int size) + : Kp(size) + , Kd(size) + { + Kp.setZero(); + Kd.setZero(); + } + + /// \brief Constructor from VectorType. + /// It is needed for the generic constraint model. + template + BaumgarteCorrectorVectorParametersTpl( + const Eigen::MatrixBase & Kp, const Eigen::MatrixBase & Kd) + : Kp(Kp) + , Kd(Kd) + { + PINOCCHIO_CHECK_INPUT_ARGUMENT( + (this->Kp.array() >= Scalar(0)).all(), "Kp should only contain non negative quantities."); + PINOCCHIO_CHECK_INPUT_ARGUMENT( + (this->Kd.array() >= Scalar(0)).all(), "Kp should only contain non negative quantities."); + } + + /// \brief Get reference to baumgarte parameters. + /// It is needed for the generic constraint model. + template + BaumgarteCorrectorVectorParametersTpl> ref() + { + typedef BaumgarteCorrectorVectorParametersTpl> ReturnType; + ReturnType res(::pinocchio::make_ref(Kp), ::pinocchio::make_ref(Kd)); + return res; + } + + /// \brief Get const reference to baumgarte parameters. + /// It is needed for the generic constraint model. + template + BaumgarteCorrectorVectorParametersTpl> ref() const + { + typedef BaumgarteCorrectorVectorParametersTpl> ReturnType; + ReturnType res(::pinocchio::make_const_ref(Kp), ::pinocchio::make_const_ref(Kd)); + return res; + } + + bool operator==(const BaumgarteCorrectorVectorParametersTpl & other) const + { + if (this == &other) + return true; + return Kp == other.Kp && Kd == other.Kd; + } + + bool operator!=(const BaumgarteCorrectorVectorParametersTpl & other) const + { + return !(*this == other); + } + + template + BaumgarteCorrectorVectorParametersTpl & + operator=(const BaumgarteCorrectorVectorParametersTpl & other) + { + Kp = other.Kp; + Kd = other.Kd; + return *this; + } + + // parameters + /// \brief Proportional corrector values. + VectorType Kp; + + /// \brief Damping corrector values. + VectorType Kd; + + template + typename CastType::type cast() const + { + typedef typename CastType::type ReturnType; + ReturnType res; + res.Kp = Kp.template cast(); + res.Kd = Kd.template cast(); + return res; + } + + }; // struct BaumgarteCorrectorVectorParametersTpl +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_baumgarte_corrector_vector_parameters_hpp__ diff --git a/include/pinocchio/algorithm/constraints/box-set.hpp b/include/pinocchio/algorithm/constraints/box-set.hpp new file mode 100644 index 0000000000..5cb7ebddc3 --- /dev/null +++ b/include/pinocchio/algorithm/constraints/box-set.hpp @@ -0,0 +1,209 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_box_set_hpp__ +#define __pinocchio_algorithm_constraints_box_set_hpp__ + +#include "pinocchio/math/fwd.hpp" +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/set-base.hpp" + +namespace pinocchio +{ + + template + struct CastType> + { + typedef BoxSetTpl type; + }; + + template + struct traits> + { + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + }; + + ///  \brief Box set defined by a lower and an upper bounds [lb;ub]. + template + struct BoxSetTpl : SetBase> + { + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + typedef Eigen::Matrix Vector; + typedef SetBase Base; + + /// \brief Default constructor + /// + BoxSetTpl() + { + } + + /// \brief Constructor from a given size + /// + explicit BoxSetTpl(const Eigen::DenseIndex size) + : m_lb(Vector::Constant(size, -std::numeric_limits::infinity())) + , m_ub(Vector::Constant(size, +std::numeric_limits::infinity())) + { + } + + template + BoxSetTpl(const Eigen::MatrixBase & lb, const Eigen::MatrixBase & ub) + : m_lb(lb) + , m_ub(ub) + { + PINOCCHIO_CHECK_INPUT_ARGUMENT( + (m_lb.array() <= m_ub.array()).all(), "Some components of lb are greater than ub"); + } + + /// \brief Copy constructor. + BoxSetTpl(const BoxSetTpl & other) = default; + + /// \brief Cast operator + template + BoxSetTpl cast() const + { + typedef BoxSetTpl ReturnType; + return ReturnType( + this->m_lb.template cast(), this->m_ub.template cast()); + } + + /// \brief Copy operator + BoxSetTpl & operator=(const BoxSetTpl & other) = default; + + /// \brief Comparison operator + bool operator==(const BoxSetTpl & other) const + { + return base() == other.base() && m_lb == other.m_lb && m_ub == other.m_ub; + } + + /// \brief Difference operator + bool operator!=(const BoxSetTpl & other) const + { + return !(*this == other); + } + + /// \brief Resize by calling the resize method of Eigen. + void resize(Eigen::DenseIndex new_size) + { + m_lb.resize(new_size); + m_ub.resize(new_size); + } + + /// \brief Resize by calling the conservativeResize method of Eigen. + void conservativeResize(Eigen::DenseIndex new_size) + { + m_lb.conservativeResize(new_size); + m_ub.conservativeResize(new_size); + } + + /// \brief Check whether a vector x lies within the box. + /// + /// \param[in] f vector to check (assimilated to a force vector). + /// + template + bool isInside(const Eigen::MatrixBase & x, const Scalar prec = Scalar(0)) const + { + assert(prec >= 0 && "prec should be positive"); + return (x - project(x)).norm() <= prec; + } + + using Base::project; + + /// \brief Project a vector x into the box. + /// + /// \param[in] x a vector to project. + /// \param[in] res result of the projection. + /// + template + void project( + const Eigen::MatrixBase & x, + const Eigen::MatrixBase & res_) const + { + res_.const_cast_derived() = x.array().max(m_lb.array()).min(m_ub.array()); + } + + /// \brief Project a vector x such that scale * res is in the box. + /// + /// \param[in] x a vector to project. + /// \param[in] scale the scaling vector. + /// \param[in] res result of the projection. + /// + template + void scaledProject_impl( + const Eigen::MatrixBase & x, + const Eigen::MatrixBase & scale, + const Eigen::MatrixBase & res_) const + { + PINOCCHIO_EIGEN_MALLOC_NOT_ALLOWED(); + assert((scale.array() > 0).all() && "scale vector should be positive"); + res_.const_cast_derived() = + x.array().max(m_lb.array() / scale.array()).min(m_ub.array() / scale.array()); + PINOCCHIO_EIGEN_MALLOC_ALLOWED(); + } + + /// \brief Returns the dimension of the box. + Eigen::DenseIndex dim() const + { + return m_lb.size(); + } + + Eigen::DenseIndex size() const + { + return m_lb.size(); + } + + const Vector & lb() const + { + return m_lb; + } + Vector & lb() + { + return m_lb; + } + + const Vector & ub() const + { + return m_ub; + } + Vector & ub() + { + return m_ub; + } + + /// \brief Check whether lb <= ub for all components + bool isValid() const + { + return (m_lb.array() <= m_ub.array()).all(); + } + + /// \brief Project the value given as input for the given row index. + Scalar rowiseProject(const Eigen::DenseIndex row_id, const Scalar value) const + { + assert(row_id < size()); + return math::max(m_lb[row_id], math::min(m_ub[row_id], value)); + } + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + protected: + Vector m_lb, m_ub; + }; // BoxSetTpl + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_box_set_hpp__ diff --git a/include/pinocchio/algorithm/constraints/cone-base.hpp b/include/pinocchio/algorithm/constraints/cone-base.hpp new file mode 100644 index 0000000000..49e750aa04 --- /dev/null +++ b/include/pinocchio/algorithm/constraints/cone-base.hpp @@ -0,0 +1,69 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_cone_base_hpp__ +#define __pinocchio_algorithm_constraints_cone_base_hpp__ + +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/set-base.hpp" + +namespace pinocchio +{ + + template + struct ConeBase : SetBase + { + typedef typename traits::Scalar Scalar; + typedef typename traits::DualCone DualCone; + + typedef SetBase Base; + + using Base::derived; + using Base::dim; + using Base::isInside; + using Base::project; + + DualCone dual() const + { + return derived().dual(); + } + + template + void scaledProject_impl( + const Eigen::MatrixBase & x, + const Eigen::MatrixBase & scale, + const Eigen::MatrixBase & x_proj) const + { + assert(x.size() == scale.size() && " x and scale should have the same size."); + assert( + scale.isApprox(scale(0) * VectorLikeIn2::Ones(scale.size())) + && "Only scalar scaling are supported."); + PINOCCHIO_UNUSED_VARIABLE(scale); // the cone is preserved when scaled by a scalar + return project(x, x_proj); + } + + bool operator==(const ConeBase & other) const + { + return base() == other.base(); + } + + bool operator!=(const ConeBase & other) const + { + return !(*this == other); + } + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + }; // struct ConeBase + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_cone_base_hpp__ diff --git a/include/pinocchio/algorithm/constraints/constraint-collection-default.hpp b/include/pinocchio/algorithm/constraints/constraint-collection-default.hpp new file mode 100644 index 0000000000..e27943b475 --- /dev/null +++ b/include/pinocchio/algorithm/constraints/constraint-collection-default.hpp @@ -0,0 +1,66 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_constraint_collection_default_hpp__ +#define __pinocchio_algorithm_constraints_constraint_collection_default_hpp__ + +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include + +namespace pinocchio +{ + template + struct ConstraintCollectionDefaultTpl + { + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + + // typedef FictiousConstraintModelTpl FictiousConstraintModel; + // typedef FictiousConstraintDataTpl FictiousConstraintData; + + typedef BilateralPointConstraintModelTpl BilateralPointConstraintModel; + typedef BilateralPointConstraintDataTpl BilateralPointConstraintData; + + typedef FrictionalPointConstraintModelTpl FrictionalPointConstraintModel; + typedef FrictionalPointConstraintDataTpl FrictionalPointConstraintData; + + typedef FrictionalJointConstraintModelTpl FrictionalJointConstraintModel; + typedef FrictionalJointConstraintDataTpl FrictionalJointConstraintData; + + typedef JointLimitConstraintModelTpl JointLimitConstraintModel; + typedef JointLimitConstraintDataTpl JointLimitConstraintData; + + typedef WeldConstraintModelTpl WeldConstraintModel; + typedef WeldConstraintDataTpl WeldConstraintData; + + typedef boost::variant< + boost::blank, + // FictiousConstraintModel, + BilateralPointConstraintModel, + FrictionalPointConstraintModel, + FrictionalJointConstraintModel, + JointLimitConstraintModel, + WeldConstraintModel> + ConstraintModelVariant; + + typedef boost::variant< + boost::blank, + // FictiousConstraintData, + BilateralPointConstraintData, + FrictionalPointConstraintData, + FrictionalJointConstraintData, + JointLimitConstraintData, + WeldConstraintData> + ConstraintDataVariant; + }; // struct ConstraintCollectionDefaultTpl + + typedef ConstraintCollectionDefault::ConstraintModelVariant ConstraintModelVariant; + typedef ConstraintCollectionDefault::ConstraintDataVariant ConstraintDataVariant; + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_constraint_collection_default_hpp__ diff --git a/include/pinocchio/algorithm/constraints/constraint-data-base.hpp b/include/pinocchio/algorithm/constraints/constraint-data-base.hpp index d9beca98be..0d9923aae3 100644 --- a/include/pinocchio/algorithm/constraints/constraint-data-base.hpp +++ b/include/pinocchio/algorithm/constraints/constraint-data-base.hpp @@ -1,20 +1,24 @@ // -// Copyright (c) 2023 INRIA +// Copyright (c) 2023-2024 INRIA // #ifndef __pinocchio_algorithm_constraint_data_base_hpp__ #define __pinocchio_algorithm_constraint_data_base_hpp__ #include "pinocchio/algorithm/fwd.hpp" +#include "pinocchio/common/data-entity.hpp" namespace pinocchio { template - struct ConstraintDataBase : NumericalBase + struct ConstraintDataBase + : NumericalBase + , DataEntity { typedef typename traits::Scalar Scalar; typedef typename traits::ConstraintModel ConstraintModel; + typedef DataEntity Base; Derived & derived() { @@ -24,8 +28,46 @@ namespace pinocchio { return static_cast(*this); } - }; + std::string shortname() const + { + return derived().shortname(); + } + static std::string classname() + { + return Derived::classname(); + } + + void disp(std::ostream & os) const + { + using namespace std; + os << shortname() << endl; + } + + friend std::ostream & operator<<(std::ostream & os, const ConstraintDataBase & constraint) + { + constraint.disp(os); + return os; + } + + template + bool operator==(const ConstraintDataBase &) const + { + return true; + } + + template + bool operator!=(const ConstraintDataBase & other) const + { + return !(*this == other); + } + + protected: + /// \brief Default constructor + ConstraintDataBase() + { + } + }; } // namespace pinocchio #endif // ifndef __pinocchio_algorithm_constraint_data_base_hpp__ diff --git a/include/pinocchio/algorithm/constraints/constraint-data-generic.hpp b/include/pinocchio/algorithm/constraints/constraint-data-generic.hpp index 0d5c44e703..9f697f8777 100644 --- a/include/pinocchio/algorithm/constraints/constraint-data-generic.hpp +++ b/include/pinocchio/algorithm/constraints/constraint-data-generic.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2023 INRIA +// Copyright (c) 2023-2024 INRIA // #ifndef __pinocchio_algorithm_constraint_data_generic_hpp__ @@ -25,6 +25,8 @@ namespace pinocchio Options = _Options }; typedef ConstraintModelTpl ConstraintModel; + typedef ConstraintModel Model; + typedef boost::blank ConstraintSet; }; template< @@ -34,8 +36,9 @@ namespace pinocchio struct ConstraintDataTpl : ConstraintDataBase> , ConstraintCollectionTpl<_Scalar, _Options>::ConstraintDataVariant + , serialization::Serializable> { - typedef ConstraintDataBase> Base; + typedef ConstraintDataBase> Base; typedef _Scalar Scalar; enum { @@ -74,6 +77,15 @@ namespace pinocchio return static_cast(*this); } + static std::string classname() + { + return "ConstraintData"; + } + std::string shortname() const + { + return ::pinocchio::visitors::shortname(*this); + } + template bool isEqual(const ConstraintDataBase & other) const { diff --git a/include/pinocchio/algorithm/constraints/constraint-model-base.hpp b/include/pinocchio/algorithm/constraints/constraint-model-base.hpp index b075a04a12..0ac00cc066 100644 --- a/include/pinocchio/algorithm/constraints/constraint-model-base.hpp +++ b/include/pinocchio/algorithm/constraints/constraint-model-base.hpp @@ -1,29 +1,58 @@ // -// Copyright (c) 2023 INRIA +// Copyright (c) 2023-2025 INRIA // -#ifndef __pinocchio_algorithm_constraint_model_base_hpp__ -#define __pinocchio_algorithm_constraint_model_base_hpp__ +#ifndef __pinocchio_algorithm_constraints_constraint_model_base_hpp__ +#define __pinocchio_algorithm_constraints_constraint_model_base_hpp__ #include "pinocchio/multibody/model.hpp" #include "pinocchio/algorithm/fwd.hpp" +#include "pinocchio/common/model-entity.hpp" +#include "pinocchio/algorithm/constraints/baumgarte-corrector-parameters.hpp" +#include "pinocchio/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp" namespace pinocchio { + template + struct BaumgarteCorrectorParametersTpl; + + enum struct ConstraintFormulationLevel + { + POSITION_LEVEL, // scaling dt^2 + VELOCITY_LEVEL, // scaling dt + ACCELERATION_LEVEL // scaling 1 + }; template - struct ConstraintModelBase : NumericalBase + struct ConstraintModelBase + : NumericalBase + , ModelEntity { typedef typename traits::Scalar Scalar; enum { Options = traits::Options }; + + typedef ModelEntity Base; + typedef typename traits::ConstraintData ConstraintData; + typedef typename traits::ConstraintSet ConstraintSet; + typedef typename traits::ComplianceVectorTypeRef ComplianceVectorTypeRef; + typedef typename traits::ComplianceVectorTypeConstRef ComplianceVectorTypeConstRef; + typedef typename traits::ActiveComplianceVectorTypeRef ActiveComplianceVectorTypeRef; + typedef typename traits::ActiveComplianceVectorTypeConstRef + ActiveComplianceVectorTypeConstRef; + typedef typename traits::BaumgarteCorrectorVectorParametersRef + BaumgarteCorrectorVectorParametersRef; + typedef typename traits::BaumgarteCorrectorVectorParametersConstRef + BaumgarteCorrectorVectorParametersConstRef; + typedef BaumgarteCorrectorParametersTpl BaumgarteCorrectorParameters; typedef Eigen::Matrix BooleanVector; - // typedef Eigen::Matrix IndexVector; - typedef std::vector IndexVector; + typedef std::vector EigenIndexVector; + + using Base::createData; Derived & derived() { @@ -40,6 +69,23 @@ namespace pinocchio return derived().template cast(); } + template + void cast(ConstraintModelBase & other) const + { + other.name = name; + } + + /// \brief Resize the constraint if needed at the current state given by data and store the + /// results in cdata. + template class JointCollectionTpl> + void resize( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata) + { + derived().resize_impl(model, data, cdata); + } + /// \brief Evaluate the constraint values at the current state given by data and store the /// results in cdata. template class JointCollectionTpl> @@ -51,7 +97,7 @@ namespace pinocchio derived().calc(model, data, cdata); } - template class JointCollectionTpl> + template class JointCollectionTpl, typename JacobianMatrix> void jacobian( const ModelTpl & model, const DataTpl & data, @@ -61,30 +107,164 @@ namespace pinocchio derived().jacobian(model, data, cdata, jacobian_matrix.const_cast_derived()); } + template class JointCollectionTpl> + typename traits::JacobianMatrixType jacobian( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata) const + { + typedef typename traits::JacobianMatrixType ReturnType; + ReturnType res = ReturnType::Zero(activeSize(), model.nv); + + jacobian(model, data, cdata, res); + + return res; + } + + template class JointCollectionTpl> + typename traits::template JacobianMatrixProductReturnType::type + jacobianMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat) const + { + return derived().jacobianMatrixProduct(model, data, cdata, mat.derived()); + } + + template< + typename InputMatrix, + typename OutputMatrix, + template class JointCollectionTpl, + AssignmentOperatorType op = SETTO> + void jacobianMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat, + const Eigen::MatrixBase & res, + AssignmentOperatorTag aot = SetTo()) const + { + derived().jacobianMatrixProduct( + model, data, cdata, mat.derived(), res.const_cast_derived(), aot); + } + + template class JointCollectionTpl> + typename traits::template JacobianTransposeMatrixProductReturnType::type + jacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat) const + { + return derived().jacobianTransposeMatrixProduct(model, data, cdata, mat.derived()); + } + + template< + typename InputMatrix, + typename OutputMatrix, + template class JointCollectionTpl, + AssignmentOperatorType op = SETTO> + void jacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat, + const Eigen::MatrixBase & res, + AssignmentOperatorTag aot = SetTo()) const + { + derived().jacobianTransposeMatrixProduct( + model, data, cdata, mat.derived(), res.const_cast_derived(), aot); + } + + /// + /// \brief Map the constraint forces (aka constraint Lagrange multipliers) to joint space (e.g., + /// joint forces, joint torque vector). + /// + /// \param[in] model The model of the rigid body system. + /// \param[in] data The data associated with model. + /// \param[in] cdata The constraint data associated with the constraint model. + /// \param[in] constraint_forces Input constraint forces (Lagrange multipliers) associated with + /// the constraint. + /// \param[out] joint_forces Output joint forces associated with each joint of the model. + /// \param[out] joint_torques Output joint torques associated with the model. + /// \param[in] reference_frame Input reference frame in which the forces are expressed. + /// + /// \note The results will be added to the joint_forces and joint_torques ouput argument. + /// + template< + template class JointCollectionTpl, + typename ConstraintForceLike, + typename ForceAllocator, + typename JointTorquesLike, + ReferenceFrame rf> + void mapConstraintForceToJointSpace( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & constraint_forces, + std::vector, ForceAllocator> & joint_forces, + const Eigen::MatrixBase & joint_torques, + ReferenceFrameTag reference_frame) const + { + derived().mapConstraintForceToJointSpace( + model, data, cdata, constraint_forces, joint_forces, joint_torques.const_cast_derived(), + reference_frame); + } + + /// + /// \brief Map the joint space quantities (e.g., + /// joint motions, joint motion vector) to the constraint motions. + /// + /// \param[in] model The model of the rigid body system. + /// \param[in] data The data associated with model. + /// \param[in] cdata The constraint data associated with the constraint model. + /// \param[in] joint_motions Input joint motions associated with the model. + /// \param[in] joint_generalized_velocity Input joint motions associated with the model. + /// \param[out] constraint_motions Output constraint motions. + /// \param[in] reference_frame Input reference frame in which the joint motions are expressed. + /// + template< + template class JointCollectionTpl, + typename MotionAllocator, + typename JointMotionsLike, + typename VectorLike, + ReferenceFrame rf> + void mapJointSpaceToConstraintMotion( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const std::vector, MotionAllocator> & joint_motions, + const Eigen::MatrixBase & joint_generalized_velocity, + const Eigen::MatrixBase & constraint_motions, + ReferenceFrameTag reference_frame) const + { + derived().mapJointSpaceToConstraintMotion( + model, data, cdata, joint_motions, joint_generalized_velocity, constraint_motions, + reference_frame); + } + // Attributes common to all constraints /// \brief Name of the constraint std::string name; - /// \brief Sparsity pattern associated to the constraint; - BooleanVector colwise_sparsity; - - /// \brief Indexes of the columns spanned by the constraints. - IndexVector colwise_span_indexes; - template bool operator==(const ConstraintModelBase & other) const { - return name == other.name && colwise_sparsity == other.colwise_sparsity - && colwise_span_indexes == other.colwise_span_indexes; + return name == other.name; + } + + template + bool operator!=(const ConstraintModelBase & other) const + { + return !(*this == other); } template ConstraintModelBase & operator=(const ConstraintModelBase & other) { name = other.name; - colwise_sparsity = other.colwise_sparsity; - colwise_span_indexes = other.colwise_span_indexes; return *this; } @@ -94,30 +274,172 @@ namespace pinocchio return derived().createData(); } - protected: - template class JointCollectionTpl> - ConstraintModelBase(const ModelTpl & model) - : colwise_sparsity(model.nv) + /// \brief Returns the colwise sparsity associated with a given row + const BooleanVector & getRowActivableSparsityPattern(const Eigen::Index row_id) const { - static const bool default_sparsity_value = false; - colwise_sparsity.fill(default_sparsity_value); + return derived().getRowActivableSparsityPattern(row_id); } - /// \brief Default constructor - ConstraintModelBase() + /// \brief Returns the colwise sparsity associated with a given row of the active set of + /// cosntraints + const BooleanVector & getRowActiveSparsityPattern(const Eigen::Index row_id) const { + return derived().getRowActiveSparsityPattern(row_id); + } + + /// \brief Returns the vector of the activable indexes associated with a given row + const EigenIndexVector & getRowActivableIndexes(const Eigen::DenseIndex row_id) const + { + return derived().getRowActivableIndexes(row_id); + } + + /// \brief Returns the vector of the active indexes associated with a given row + const EigenIndexVector & getRowActiveIndexes(const Eigen::DenseIndex row_id) const + { + return derived().getRowActiveIndexes(row_id); + } + + /// \brief Returns the active compliance internally stored in the constraint and corresponding + /// to the active set contained in cdata + ActiveComplianceVectorTypeConstRef getActiveCompliance() const + { + return derived().getActiveCompliance_impl(); + } + + /// \brief Returns the active compliance internally stored in the constraint and corresponding + /// to the active set contained in cdata + ActiveComplianceVectorTypeRef getActiveCompliance() + { + return derived().getActiveCompliance_impl(); + } + + int size() const + { + return derived().size(); + } + + int activeSize() const + { + return derived().activeSize(); + } + + ConstraintSet & set() + { + return derived().set(); + } + const ConstraintSet & set() const + { + return derived().set(); + } + + template< + template class JointCollectionTpl, + typename VectorNLike, + ReferenceFrame rf> + void appendCouplingConstraintInertias( + const ModelTpl & model, + DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & diagonal_constraint_inertia, + const ReferenceFrameTag reference_frame) const + { + derived().appendCouplingConstraintInertias( + model, data, cdata, diagonal_constraint_inertia.derived(), reference_frame); + } + + /// \brief Returns the compliance internally stored in the constraint model + ComplianceVectorTypeConstRef compliance() const + { + return derived().compliance_impl(); + } + + /// \brief Returns the compliance internally stored in the constraint model + ComplianceVectorTypeRef compliance() + { + return derived().compliance_impl(); + } + + // CHOICE: right now we use the scalar Baumgarte + // /// \brief Returns the Baumgarte vector parameters internally stored in the constraint model + // BaumgarteCorrectorVectorParametersConstRef baumgarte_corrector_vector_parameters() const + // { + // return derived().baumgarte_corrector_vector_parameters_impl(); + // } + + // /// \brief Returns the Baumgarte vector parameters internally stored in the constraint model + // BaumgarteCorrectorVectorParametersRef baumgarte_corrector_vector_parameters() + // { + // return derived().baumgarte_corrector_vector_parameters_impl(); + // } + + /// \brief Returns the Baumgarte parameters internally stored in the constraint model + const BaumgarteCorrectorParameters & baumgarte_corrector_parameters() const + { + return derived().baumgarte_corrector_parameters_impl(); + } + + /// \brief Returns the Baumgarte parameters internally stored in the constraint model + BaumgarteCorrectorParameters & baumgarte_corrector_parameters() + { + return derived().baumgarte_corrector_parameters_impl(); + } + + /// \brief Default implementation: do nothing + template class JointCollectionTpl> + void resize_impl( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata) + { + PINOCCHIO_UNUSED_VARIABLE(model); + PINOCCHIO_UNUSED_VARIABLE(data); + PINOCCHIO_UNUSED_VARIABLE(cdata); } ConstraintModelBase & base() { return *this; } + const ConstraintModelBase & base() const { return *this; } + + std::string shortname() const + { + return derived().shortname(); + } + static std::string classname() + { + return Derived::classname(); + } + + void disp(std::ostream & os) const + { + using namespace std; + os << shortname() << endl; + } + + friend std::ostream & + operator<<(std::ostream & os, const ConstraintModelBase & constraint) + { + constraint.disp(os); + return os; + } + + protected: + template class JointCollectionTpl> + explicit ConstraintModelBase(const ModelTpl & /*model*/) + { + } + + /// \brief Default constructor + ConstraintModelBase() + { + } }; } // namespace pinocchio -#endif // ifndef __pinocchio_algorithm_constraint_model_base_hpp__ +#endif // ifndef __pinocchio_algorithm_constraints_constraint_model_base_hpp__ diff --git a/include/pinocchio/algorithm/constraints/constraint-model-common-parameters.hpp b/include/pinocchio/algorithm/constraints/constraint-model-common-parameters.hpp new file mode 100644 index 0000000000..9ccf0ca9ae --- /dev/null +++ b/include/pinocchio/algorithm/constraints/constraint-model-common-parameters.hpp @@ -0,0 +1,118 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_constraint_model_common_parameters_hpp__ +#define __pinocchio_algorithm_constraints_constraint_model_common_parameters_hpp__ + +namespace pinocchio +{ + + template + struct BaumgarteCorrectorVectorParametersTpl; + + template + struct BaumgarteCorrectorParametersTpl; + + template + struct ConstraintModelCommonParameters + { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + template + friend struct ConstraintModelCommonParameters; + + typedef ConstraintModelCommonParameters Self; + typedef typename traits::Scalar Scalar; + typedef typename traits::ComplianceVectorType ComplianceVectorType; + typedef typename traits::ComplianceVectorTypeRef ComplianceVectorTypeRef; + typedef typename traits::ComplianceVectorTypeConstRef ComplianceVectorTypeConstRef; + typedef typename traits::BaumgarteVectorType BaumgarteVectorType; + typedef typename traits::BaumgarteCorrectorVectorParameters + BaumgarteCorrectorVectorParameters; + typedef typename traits::BaumgarteCorrectorVectorParametersRef + BaumgarteCorrectorVectorParametersRef; + typedef typename traits::BaumgarteCorrectorVectorParametersConstRef + BaumgarteCorrectorVectorParametersConstRef; + typedef BaumgarteCorrectorParametersTpl BaumgarteCorrectorParameters; + + /// \brief Cast to NewScalar + template + void cast(ConstraintModelCommonParameters & other) const + { + other.m_compliance = m_compliance.template cast(); + + // CHOICE: right now we use the scalar Baumgarte + // other.m_baumgarte_vector_parameters = m_baumgarte_vector_parameters.template + // cast(); + other.m_baumgarte_parameters = m_baumgarte_parameters.template cast(); + } + + /// \brief Comparison operator + bool operator==(const Self & other) const + { + // CHOICE: right now we use the scalar Baumgarte + // return m_compliance == other.m_compliance + // && m_baumgarte_vector_parameters == other.m_baumgarte_vector_parameters; + return m_compliance == other.m_compliance + && m_baumgarte_parameters == other.m_baumgarte_parameters; + } + + /// \brief Comparison operator + bool operator!=(const Self & other) const + { + return !(*this == other); + } + + /// \brief Returns the compliance internally stored in the constraint model + ComplianceVectorTypeConstRef compliance_impl() const + { + return m_compliance; + } + + /// \brief Returns the compliance internally stored in the constraint model + ComplianceVectorTypeRef compliance_impl() + { + return m_compliance; + } + + // CHOICE: right now we use the scalar Baumgarte + // /// \brief Returns the Baumgarte vector parameters internally stored in the constraint model + // BaumgarteCorrectorVectorParametersConstRef baumgarte_corrector_vector_parameters_impl() const + // { + // return m_baumgarte_vector_parameters; + // } + + // /// \brief Returns the Baumgarte vector parameters internally stored in the constraint model + // BaumgarteCorrectorVectorParametersRef baumgarte_corrector_vector_parameters_impl() + // { + // return m_baumgarte_vector_parameters; + // } + + /// \brief Returns the Baumgarte parameters internally stored in the constraint model + const BaumgarteCorrectorParameters & baumgarte_corrector_parameters_impl() const + { + return m_baumgarte_parameters; + } + + /// \brief Returns the Baumgarte parameters internally stored in the constraint model + BaumgarteCorrectorParameters & baumgarte_corrector_parameters_impl() + { + return m_baumgarte_parameters; + } + + protected: + /// \brief Default constructor - protected so that the class cannot be instanciated on its own. + ConstraintModelCommonParameters() + { + } + + ComplianceVectorType m_compliance; + // CHOICE: right now we use the scalar Baumgarte + // BaumgarteCorrectorVectorParameters m_baumgarte_vector_parameters; + BaumgarteCorrectorParameters m_baumgarte_parameters; + }; + +} // namespace pinocchio + +#endif // __pinocchio_algorithm_constraints_constraint_model_common_parameters_hpp__ diff --git a/include/pinocchio/algorithm/constraints/constraint-model-generic.hpp b/include/pinocchio/algorithm/constraints/constraint-model-generic.hpp index 1b8ff1604c..8be3006d15 100644 --- a/include/pinocchio/algorithm/constraints/constraint-model-generic.hpp +++ b/include/pinocchio/algorithm/constraints/constraint-model-generic.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2023 INRIA +// Copyright (c) 2023-2025 INRIA // #ifndef __pinocchio_algorithm_constraint_model_generic_hpp__ @@ -9,6 +9,8 @@ #include "pinocchio/algorithm/constraints/constraint-model-base.hpp" #include "pinocchio/algorithm/constraints/constraint-data-generic.hpp" #include "pinocchio/algorithm/constraints/visitors/constraint-model-visitor.hpp" +#include "pinocchio/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp" +#include "pinocchio/algorithm/constraints/baumgarte-corrector-parameters.hpp" namespace pinocchio { @@ -24,7 +26,56 @@ namespace pinocchio { Options = _Options }; + + static constexpr bool has_baumgarte_corrector = true; + static constexpr bool has_baumgarte_corrector_vector = true; + typedef ConstraintDataTpl ConstraintData; + typedef ConstraintData Data; + typedef boost::blank ConstraintSet; + + typedef Eigen::Matrix VectorXs; + typedef Eigen::Matrix JacobianMatrixType; + typedef VectorXs VectorConstraintSize; + + typedef VectorXs ComplianceVectorType; + typedef Eigen::Ref ComplianceVectorTypeRef; + typedef Eigen::Ref ComplianceVectorTypeConstRef; + + typedef ComplianceVectorTypeRef ActiveComplianceVectorTypeRef; + typedef ComplianceVectorTypeConstRef ActiveComplianceVectorTypeConstRef; + + typedef VectorXs BaumgarteVectorType; + typedef Eigen::Ref BaumgarteVectorTypeRef; + typedef BaumgarteCorrectorVectorParametersTpl + BaumgarteCorrectorVectorParameters; + typedef BaumgarteCorrectorVectorParameters BaumgarteCorrectorVectorParametersRef; + typedef Eigen::Ref BaumgarteVectorTypeConstRef; + typedef BaumgarteCorrectorVectorParametersTpl + BaumgarteCorrectorVectorParametersConstRef; + + template + struct JacobianMatrixProductReturnType + { + typedef typename InputMatrix::Scalar Scalar; + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(InputMatrix) InputMatrixPlain; + typedef Eigen:: + Matrix + type; + }; + + template + struct JacobianTransposeMatrixProductReturnType + { + typedef typename InputMatrix::Scalar Scalar; + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(InputMatrix) InputMatrixPlain; + typedef Eigen::Matrix< + Scalar, + Eigen::Dynamic, + InputMatrixPlain::ColsAtCompileTime, + InputMatrixPlain::Options> + type; + }; }; template< @@ -34,6 +85,7 @@ namespace pinocchio struct ConstraintModelTpl : ConstraintModelBase> , ConstraintCollectionTpl<_Scalar, _Options>::ConstraintModelVariant + , serialization::Serializable> { typedef _Scalar Scalar; enum @@ -41,12 +93,31 @@ namespace pinocchio Options = _Options }; - typedef ConstraintModelBase> - Base; + typedef ConstraintModelTpl Self; + typedef ConstraintModelBase Base; + typedef ConstraintModelBase RootBase; + typedef ConstraintDataTpl ConstraintData; typedef ConstraintCollectionTpl ConstraintCollection; typedef typename ConstraintCollection::ConstraintDataVariant ConstraintDataVariant; typedef typename ConstraintCollection::ConstraintModelVariant ConstraintModelVariant; + typedef typename traits::ComplianceVectorType ComplianceVectorType; + typedef typename traits::ComplianceVectorTypeRef ComplianceVectorTypeRef; + typedef typename traits::ComplianceVectorTypeConstRef ComplianceVectorTypeConstRef; + typedef typename traits::ActiveComplianceVectorTypeRef ActiveComplianceVectorTypeRef; + typedef + typename traits::ActiveComplianceVectorTypeConstRef ActiveComplianceVectorTypeConstRef; + typedef + typename traits::BaumgarteCorrectorVectorParameters BaumgarteCorrectorVectorParameters; + typedef typename traits::BaumgarteCorrectorVectorParametersRef + BaumgarteCorrectorVectorParametersRef; + typedef typename traits::BaumgarteCorrectorVectorParametersConstRef + BaumgarteCorrectorVectorParametersConstRef; + typedef BaumgarteCorrectorParametersTpl BaumgarteCorrectorParameters; + + using RootBase::jacobian; + using typename Base::BooleanVector; + using typename Base::EigenIndexVector; ConstraintModelTpl() : ConstraintModelVariant() @@ -68,10 +139,308 @@ namespace pinocchio ConstraintData createData() const { - return ::pinocchio::createData(*this); + return ::pinocchio::visitors::createData(*this); + } + + template class JointCollectionTpl> + void calc( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata) const + { + ::pinocchio::visitors::calc(*this, model, data, cdata); + } + + template class JointCollectionTpl> + void resize_impl( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata) + { + ::pinocchio::visitors::resize(*this, model, data, cdata); + } + + template class JointCollectionTpl, typename JacobianMatrix> + void jacobian( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata, + const Eigen::MatrixBase & jacobian_matrix) const + { + ::pinocchio::visitors::jacobian( + *this, model, data, cdata, jacobian_matrix.const_cast_derived()); + } + + /// \brief Returns the vector of the active indexes associated with a given row + const EigenIndexVector & getRowActivableIndexes(const Eigen::DenseIndex row_id) const + { + return ::pinocchio::visitors::getRowActivableIndexes(*this, row_id); + } + + /// \brief Returns the vector of the active indexes associated with a given row + const EigenIndexVector & getRowActiveIndexes(const Eigen::DenseIndex row_id) const + { + return ::pinocchio::visitors::getRowActiveIndexes(*this, row_id); + } + + /// \brief Returns the sparsity pattern associated with a given row + const BooleanVector & getRowActivableSparsityPattern(const Eigen::DenseIndex row_id) const + { + return ::pinocchio::visitors::getRowActivableSparsityPattern(*this, row_id); + } + + /// \brief Returns the sparsity pattern associated with a given row + const BooleanVector & getRowActiveSparsityPattern(const Eigen::DenseIndex row_id) const + { + return ::pinocchio::visitors::getRowActiveSparsityPattern(*this, row_id); + } + + /// \brief Returns the compliance associated to the current active set + ActiveComplianceVectorTypeConstRef getActiveCompliance_impl() const + { + return ::pinocchio::visitors::getActiveCompliance(*this); + } + + /// \brief Returns the compliance associated to the current active set + ActiveComplianceVectorTypeRef getActiveCompliance_impl() + { + return ::pinocchio::visitors::getActiveCompliance(*this); } - }; + /// \brief Runs the underlying jacobian multiplication with a matrix. + template< + template class JointCollectionTpl, + typename InputMatrix, + typename OutputMatrix> + typename traits::template JacobianMatrixProductReturnType::type + jacobianMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & input_matrix) const + { + typedef typename traits::template JacobianMatrixProductReturnType::type + ReturnType; + ReturnType res(size(), input_matrix.cols()); + jacobianMatrixProduct(model, data, cdata, input_matrix.derived(), res); + return res; + } + + /// \brief Runs the underlying jacobian multiplication with a matrix. + template< + template class JointCollectionTpl, + typename InputMatrix, + typename OutputMatrix, + AssignmentOperatorType op = SETTO> + void jacobianMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & input_matrix, + const Eigen::MatrixBase & result_matrix, + AssignmentOperatorTag aot = SetTo()) const + { + ::pinocchio::visitors::jacobianMatrixProduct( + *this, model, data, cdata, input_matrix.derived(), result_matrix.const_cast_derived(), aot); + } + + /// \brief Runs the underlying jacobian transpose multiplication with a matrix. + template< + template class JointCollectionTpl, + typename InputMatrix, + typename OutputMatrix> + typename traits::template JacobianTransposeMatrixProductReturnType::type + jacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & input_matrix) const + { + typedef + typename traits::template JacobianTransposeMatrixProductReturnType::type + ReturnType; + ReturnType res(model.nv, input_matrix.cols()); + jacobianTransposeMatrixProduct(*this, model, data, cdata, input_matrix.derived(), res); + return res; + } + + template< + typename InputMatrix, + typename OutputMatrix, + template class JointCollectionTpl, + AssignmentOperatorType op = SETTO> + void jacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & input_matrix, + const Eigen::MatrixBase & result_matrix, + AssignmentOperatorTag aot = SetTo()) const + { + ::pinocchio::visitors::jacobianTransposeMatrixProduct( + *this, model, data, cdata, input_matrix.derived(), result_matrix.const_cast_derived(), aot); + } + + template< + template class JointCollectionTpl, + typename VectorNLike, + ReferenceFrame rf> + void appendCouplingConstraintInertias( + const ModelTpl & model, + DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & diagonal_constraint_inertia, + const ReferenceFrameTag reference_frame) const + { + ::pinocchio::visitors::appendCouplingConstraintInertias( + *this, model, data, cdata, diagonal_constraint_inertia.derived(), reference_frame); + } + + template< + template class JointCollectionTpl, + typename ConstraintForceLike, + typename ForceAllocator, + typename JointTorquesLike, + ReferenceFrame rf> + void mapConstraintForceToJointSpace( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & constraint_forces, + std::vector, ForceAllocator> & joint_forces, + const Eigen::MatrixBase & joint_torques, + ReferenceFrameTag reference_frame) const + { + ::pinocchio::visitors::mapConstraintForceToJointSpace( + *this, model, data, cdata, constraint_forces, joint_forces, + joint_torques.const_cast_derived(), reference_frame); + } + + template< + template class JointCollectionTpl, + typename MotionAllocator, + typename JointMotionsLike, + typename VectorLike, + ReferenceFrame rf> + void mapJointSpaceToConstraintMotion( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const std::vector, MotionAllocator> & joint_motions, + const Eigen::MatrixBase & joint_generalized_velocity, + const Eigen::MatrixBase & constraint_motions, + ReferenceFrameTag reference_frame) const + { + ::pinocchio::visitors::mapJointSpaceToConstraintMotion( + *this, model, data, cdata, joint_motions, joint_generalized_velocity, + constraint_motions.const_cast_derived(), reference_frame); + } + + static std::string classname() + { + return "ConstraintModel"; + } + std::string shortname() const + { + return ::pinocchio::visitors::shortname(*this); + } + + /// \brief Returns the compliance internally stored in the constraint model + ComplianceVectorTypeConstRef compliance_impl() const + { + return ::pinocchio::visitors::compliance(*this); + } + + /// \brief Returns the compliance internally stored in the constraint model + ComplianceVectorTypeRef compliance_impl() + { + return ::pinocchio::visitors::compliance(*this); + } + + // CHOICE: right now we use the scalar Baumgarte + // /// \brief Returns the Baumgarte vector parameters internally stored in the constraint model + // BaumgarteCorrectorVectorParametersConstRef baumgarte_corrector_vector_parameters_impl() const + // { + // return ::pinocchio::visitors::getBaumgarteCorrectorVectorParameters(*this); + // } + + // /// \brief Returns the Baumgarte vector parameters internally stored in the constraint model + // BaumgarteCorrectorVectorParametersRef baumgarte_corrector_vector_parameters_impl() + // { + // return ::pinocchio::visitors::getBaumgarteCorrectorVectorParameters(*this); + // } + + /// \brief Returns the Baumgarte parameters internally stored in the constraint model + const BaumgarteCorrectorParameters & baumgarte_corrector_parameters_impl() const + { + return ::pinocchio::visitors::getBaumgarteCorrectorParameters(*this); + } + + /// \brief Returns the Baumgarte parameters internally stored in the constraint model + BaumgarteCorrectorParameters & baumgarte_corrector_parameters_impl() + { + return ::pinocchio::visitors::getBaumgarteCorrectorParameters(*this); + } + + /// \brief Returns the size of the constraint + int size() const + { + return ::pinocchio::visitors::size(*this); + } + + /// \brief Returns the size of the active constraints + int activeSize() const + { + return ::pinocchio::visitors::activeSize(*this); + } + + boost::blank & set() + { + static boost::blank val; + PINOCCHIO_THROW_PRETTY( + std::runtime_error, "Set method is not accessible for ConstraintModelTpl."); + return val; + } + + const boost::blank & set() const + { + static boost::blank val; + PINOCCHIO_THROW_PRETTY( + std::runtime_error, "Set method is not accessible for ConstraintModelTpl."); + return val; + } + + ConstraintModelVariant & toVariant() + { + return static_cast(*this); + } + + const ConstraintModelVariant & toVariant() const + { + return static_cast(*this); + } + + template + bool isEqual(const ConstraintModelBase & other) const + { + return ::pinocchio::isEqual(*this, other.derived()); + } + + bool isEqual(const ConstraintModelTpl & other) const + { + return toVariant() == other.toVariant(); + } + + bool operator==(const ConstraintModelTpl & other) const + { + return isEqual(other); + } + + bool operator!=(const ConstraintModelTpl & other) const + { + return !(*this == other); + } + }; // struct ConstraintModelTpl } // namespace pinocchio #endif // ifndef __pinocchio_algorithm_constraint_model_generic_hpp__ diff --git a/include/pinocchio/algorithm/constraints/constraint-ordering.hpp b/include/pinocchio/algorithm/constraints/constraint-ordering.hpp new file mode 100644 index 0000000000..b84c6b3fd2 --- /dev/null +++ b/include/pinocchio/algorithm/constraints/constraint-ordering.hpp @@ -0,0 +1,42 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_constraint_ordering_hpp__ +#define __pinocchio_algorithm_constraints_constraint_ordering_hpp__ + +#include "pinocchio/multibody/model.hpp" +#include "pinocchio/multibody/data.hpp" + +#include "pinocchio/algorithm/check.hpp" +#include "pinocchio/algorithm/constraints/constraints.hpp" + +namespace pinocchio +{ + + /// + /// \brief Init the data according to the contact information contained in constraint_models. + /// + /// \tparam JointCollection Collection of Joint types. + /// \tparam Allocator Allocator class for the std::vector. + /// + /// \param[in] model The model structure of the rigid body system. + /// \param[in] data The data structure of the rigid body system. + /// \param[in] constraint_models Vector of contact information related to the problem. + /// + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + class ConstraintModelAllocator> + inline void computeJointMinimalOrdering( + const ModelTpl & model, + DataTpl & data, + const std::vector & constraint_models); + +} // namespace pinocchio + +#include "pinocchio/algorithm/constraints/constraint-ordering.hxx" + +#endif // ifndef __pinocchio_algorithm_constraints_constraint_ordering_hpp__ diff --git a/include/pinocchio/algorithm/constraints/constraint-ordering.hxx b/include/pinocchio/algorithm/constraints/constraint-ordering.hxx new file mode 100644 index 0000000000..b6433c143b --- /dev/null +++ b/include/pinocchio/algorithm/constraints/constraint-ordering.hxx @@ -0,0 +1,255 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_constraint_ordering_hxx__ +#define __pinocchio_algorithm_constraints_constraint_ordering_hxx__ + +#include "pinocchio/algorithm/constraints/visitors/constraint-model-visitor.hpp" +#include "pinocchio/utils/reference.hpp" + +/// @cond DEV + +namespace pinocchio +{ + + template class JointCollectionTpl> + struct MinimalOrderingConstraintStepVisitor + : visitors::ConstraintUnaryVisitorBase< + MinimalOrderingConstraintStepVisitor> + { + typedef ModelTpl Model; + typedef DataTpl Data; + + typedef boost::fusion::vector ArgsType; + + typedef visitors::ConstraintUnaryVisitorBase< + MinimalOrderingConstraintStepVisitor> + Base; + + template + static void + algo(const ConstraintModelBase & cmodel, const Model & model, Data & data) + { + algo_step(cmodel.derived(), model, data); + } + + template + static void algo_step( + const KinematicsConstraintModelBase & cmodel, + const Model & model, + Data & data) + { + typedef std::pair JointPair; + typedef typename Data::Matrix6 Matrix6; + + PINOCCHIO_UNUSED_VARIABLE(model); + + const JointIndex joint1_id = cmodel.joint1_id; + const JointIndex joint2_id = cmodel.joint2_id; + auto & neighbours = data.neighbour_links; + + const auto constraint_size = cmodel.size(); + data.constraints_supported_dim[joint1_id] += constraint_size; + data.constraints_supported_dim[joint2_id] += constraint_size; + + if (joint2_id > 0 && joint1_id > 0) + { + const JointPair joint_pair = + joint1_id > joint2_id ? JointPair{joint2_id, joint1_id} : JointPair{joint1_id, joint2_id}; + + if (!data.joint_cross_coupling.exist(joint_pair)) + data.joint_cross_coupling[joint_pair] = Matrix6::Zero(); + + auto & joint1_neighbours = neighbours[joint1_id]; + auto & joint2_neighbours = neighbours[joint2_id]; + + if ( + std::find(joint1_neighbours.begin(), joint1_neighbours.end(), joint2_id) + == joint1_neighbours.end()) + joint1_neighbours.push_back(joint2_id); + if ( + std::find(joint2_neighbours.begin(), joint2_neighbours.end(), joint1_id) + == joint2_neighbours.end()) + joint2_neighbours.push_back(joint1_id); + } + } + + template + static void algo_step( + const FrictionalJointConstraintModelTpl<_Scalar, _Options> & cmodel, + const Model & model, + Data & data) + { + for (const JointIndex joint_id : cmodel.getActiveJoints()) + { + data.constraints_supported_dim[joint_id] += model.nvs[joint_id]; + } + } + + template + static void algo_step( + const JointLimitConstraintModelTpl<_Scalar, _Options> & cmodel, + const Model & model, + Data & data) + { + PINOCCHIO_UNUSED_VARIABLE(cmodel); + PINOCCHIO_UNUSED_VARIABLE(model); + PINOCCHIO_UNUSED_VARIABLE(data); + } + + using Base::run; + + template + static void run( + const pinocchio::ConstraintModelBase & cmodel, + const Model & model, + Data & data) + { + algo(cmodel.derived(), model, data); + } + + template< + typename _Scalar, + int _Options, + template class ConstraintCollectionTpl> + static void run( + const pinocchio::ConstraintModelTpl<_Scalar, _Options, ConstraintCollectionTpl> & cmodel, + const Model & model, + Data & data) + { + ArgsType args(model, data); + run(cmodel.derived(), args); + } + }; // struct MinimalOrderingConstraintStepVisitor + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + class ConstraintModelAllocator> + inline void computeJointMinimalOrdering( + const ModelTpl & model, + DataTpl & data, + const std::vector & constraint_models) + { + typedef ModelTpl Model; + typedef DataTpl Data; + + typedef typename Model::JointIndex JointIndex; + typedef std::pair JointPair; + typedef typename Data::Matrix6 Matrix6; + + // First step: for each joint, collect their neighbourds + auto & neighbours = data.neighbour_links; + for (auto & neighbour_elt : neighbours) + neighbour_elt.clear(); + data.joint_cross_coupling.clear(); + + // Get links supporting constraints + std::fill(data.constraints_supported_dim.begin(), data.constraints_supported_dim.end(), 0); + typedef MinimalOrderingConstraintStepVisitor Step; + for (std::size_t i = 0; i < constraint_models.size(); ++i) + { + const auto & cmodel = helper::get_ref(constraint_models[i]); + Step::run(cmodel, model, data); + } + + // Second step: order the joints according to the minimum degree heuristic + auto & elimination_order = data.elimination_order; + elimination_order.clear(); // clearing in case inited once more + + std::vector num_children(size_t(model.njoints), 0); + std::list leaf_vertices; + + for (JointIndex joint_id = JointIndex(model.njoints - 1); joint_id > 0; --joint_id) + { + num_children[joint_id] = model.children[joint_id].size(); + if (num_children[joint_id] == 0) + leaf_vertices.push_back(joint_id); + } + + while (leaf_vertices.size() > 0) + { + JointIndex joint_id_with_least_neighbors = std::numeric_limits::max(); + size_t least_neighbours = std::numeric_limits::max(); + + for (const auto joint_id : leaf_vertices) + { + assert(joint_id != 0); + const auto leaf_num_neighours = neighbours[joint_id].size(); + if (leaf_num_neighours < least_neighbours) + { + least_neighbours = leaf_num_neighours; + joint_id_with_least_neighbors = joint_id; + } + } + + const JointIndex joint_id = joint_id_with_least_neighbors; + assert(joint_id != 0); + leaf_vertices.remove(joint_id); + elimination_order.push_back(joint_id); + + const JointIndex parent_id = model.parents[joint_id]; + num_children[parent_id]--; + // If the number of children joints of parent is reaching zero, this means that parent is now + // a leaf node. + if (num_children[parent_id] == 0 && parent_id != 0) + leaf_vertices.push_front(parent_id); + + data.constraints_supported_dim[parent_id] += data.constraints_supported_dim[joint_id]; + const auto & joint_neighbours = neighbours[joint_id]; + auto & parent_neighbours = neighbours[parent_id]; + for (size_t j = 0; j < joint_neighbours.size(); j++) + { + const JointIndex neighbour_j = joint_neighbours[j]; + auto & neighbour_j_neighbours = neighbours[neighbour_j]; + if (neighbour_j != parent_id) + { + const JointPair jp_pair = neighbour_j < parent_id ? JointPair(neighbour_j, parent_id) + : JointPair(parent_id, neighbour_j); + + if (!data.joint_cross_coupling.exist(jp_pair)) + { + data.joint_cross_coupling[jp_pair] = Matrix6::Zero(); // add joint_cross_coupling + + if ( + std::find(parent_neighbours.begin(), parent_neighbours.end(), neighbour_j) + == parent_neighbours.end()) + { + parent_neighbours.push_back(neighbour_j); + neighbour_j_neighbours.push_back(parent_id); + } + } + } + + // Remove joint_id from the list of neighbours for neighbour_j_neighbours + neighbour_j_neighbours.erase( + std::remove(neighbour_j_neighbours.begin(), neighbour_j_neighbours.end(), joint_id), + neighbour_j_neighbours.end()); + + for (size_t k = j + 1; k < joint_neighbours.size(); ++k) + { + const JointIndex neighbour_k = joint_neighbours[k]; + auto & neighbour_k_neighbours = neighbours[neighbour_k]; + assert(neighbour_k != neighbour_j && "Must never happen!"); + const JointPair cross_coupling = neighbour_j < neighbour_k + ? JointPair{neighbour_j, neighbour_k} + : JointPair{neighbour_k, neighbour_j}; + + if (!data.joint_cross_coupling.exist(cross_coupling)) + { + data.joint_cross_coupling[cross_coupling] = Matrix6::Zero(); // add edge + neighbour_j_neighbours.push_back(neighbour_k); + neighbour_k_neighbours.push_back(neighbour_j); + } + } + } + } + } +} // namespace pinocchio + +/// @endcond + +#endif // ifndef __pinocchio_algorithm_constraints_constraint_ordering_hxx__ diff --git a/include/pinocchio/algorithm/constraints/constraints.hpp b/include/pinocchio/algorithm/constraints/constraints.hpp index 3203321a55..e0aee896fe 100644 --- a/include/pinocchio/algorithm/constraints/constraints.hpp +++ b/include/pinocchio/algorithm/constraints/constraints.hpp @@ -1,14 +1,24 @@ // -// Copyright (c) 2023 INRIA +// Copyright (c) 2023-2024 INRIA // #ifndef __pinocchio_algorithm_constraints_constraints_hpp__ #define __pinocchio_algorithm_constraints_constraints_hpp__ #include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/contact-info.hpp" +#include "pinocchio/algorithm/constraints/joint-frictional-constraint.hpp" +#include "pinocchio/algorithm/constraints/point-frictional-constraint.hpp" +#include "pinocchio/algorithm/constraints/point-bilateral-constraint.hpp" +#include "pinocchio/algorithm/constraints/joint-limit-constraint.hpp" +#include "pinocchio/algorithm/constraints/weld-constraint.hpp" +// #include "pinocchio/algorithm/constraints/fictious-constraint.hpp" -namespace pinocchio -{ -} +#include "pinocchio/algorithm/constraints/constraint-collection-default.hpp" + +#include "pinocchio/algorithm/constraints/constraint-model-generic.hpp" +#include "pinocchio/algorithm/constraints/constraint-data-generic.hpp" + +#include "pinocchio/algorithm/constraints/sets.hpp" #endif // ifndef __pinocchio_algorithm_constraints_constraints_hpp__ diff --git a/include/pinocchio/algorithm/constraints/coulomb-friction-cone.hpp b/include/pinocchio/algorithm/constraints/coulomb-friction-cone.hpp index 2c121a6c1f..79ccc627d1 100644 --- a/include/pinocchio/algorithm/constraints/coulomb-friction-cone.hpp +++ b/include/pinocchio/algorithm/constraints/coulomb-friction-cone.hpp @@ -1,11 +1,12 @@ // -// Copyright (c) 2022 INRIA +// Copyright (c) 2022-2024 INRIA // #ifndef __pinocchio_algorithm_constraints_coulomb_friction_cone_hpp__ #define __pinocchio_algorithm_constraints_coulomb_friction_cone_hpp__ #include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/cone-base.hpp" #include "pinocchio/math/fwd.hpp" #include "pinocchio/math/comparison-operators.hpp" @@ -15,17 +16,54 @@ namespace pinocchio template struct DualCoulombFrictionConeTpl; - ///  \brief 3d Coulomb friction cone. + template + struct CastType> + { + typedef CoulombFrictionConeTpl type; + }; + + template + struct CastType> + { + typedef DualCoulombFrictionConeTpl type; + }; + template - struct CoulombFrictionConeTpl + struct traits> { typedef _Scalar Scalar; typedef DualCoulombFrictionConeTpl DualCone; + }; + + template + struct traits> + { + typedef _Scalar Scalar; + typedef CoulombFrictionConeTpl DualCone; + }; + + ///  \brief 3d Coulomb friction cone. + template + struct CoulombFrictionConeTpl : ConeBase> + { + typedef _Scalar Scalar; + typedef typename traits::DualCone DualCone; typedef Eigen::Matrix Vector3; + typedef ConeBase Base; + /// /// \brief Default constructor /// - /// \param[in] mu Friction coefficient + CoulombFrictionConeTpl() + : mu(+std::numeric_limits::infinity()) + { + } + + /// + /// \brief Constructor from a friction coefficient mu + /// + /// \param[in] mu Friction coefficient. + /// explicit CoulombFrictionConeTpl(const Scalar mu) : mu(mu) { @@ -38,10 +76,18 @@ namespace pinocchio /// \brief Copy operator CoulombFrictionConeTpl & operator=(const CoulombFrictionConeTpl & other) = default; + /// \brief Cast operator + template + CoulombFrictionConeTpl cast() const + { + typedef CoulombFrictionConeTpl ReturnType; + return ReturnType(NewScalar(this->mu)); + } + /// \brief Comparison operator bool operator==(const CoulombFrictionConeTpl & other) const { - return mu == other.mu; + return base() == other.base() && mu == other.mu; } /// \brief Difference operator @@ -59,64 +105,80 @@ namespace pinocchio { assert(mu >= 0 && "mu must be positive"); assert(prec >= 0 && "prec should be positive"); - EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3); - return f.template head<2>().norm() <= mu * f[2] + prec; + // EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3); + assert(f.size() == 3 && "The input vector is of wrong size."); + const Vector3 f_normalized = f.normalized(); + return f_normalized.template head<2>().norm() <= mu * f_normalized[2] + prec; } + using Base::project; + /// \brief Project a vector x onto the cone. /// /// \param[in] x a 3d vector to project. /// - template - typename PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like) - project(const Eigen::MatrixBase & x) const + template + void project( + const Eigen::MatrixBase & x, + const Eigen::MatrixBase & res_) const { assert(mu >= 0 && "mu must be positive"); - EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3); - typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like) Vector3Plain; + // EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3); + assert(x.size() == 3 && "The input vector is of wrong size."); + typedef Eigen::Matrix Vector2Plain; + const Scalar & z = x[2]; const Scalar mu_z = mu * z; - const Eigen::Matrix t = x.template head<2>(); + auto & res = res_.const_cast_derived(); + + const Vector2Plain t = x.template head<2>(); const Scalar t_norm = t.norm(); if (mu * t_norm <= -z) - return Vector3Plain::Zero(); + { + res.setZero(); + return; + } else if (t_norm <= mu_z) { - return x; + res = x; + return; } else { - Vector3Plain res; res.template head<2>() = (mu / t_norm) * t; res[2] = 1; res.normalize(); const Scalar scale = x.dot(res); res *= scale; - return res; + return; } } /// \brief Project a vector x onto the cone with a matric specified by the diagonal matrix R. /// /// \param[in] x a 3d vector to project. - /// \param[in] R a 3d vector representing the diagonal of the weights matrix. The tangential - /// components (the first two) of R should be equal. + /// \param[in] R a 3d vector representing the diagonal of the weight matrix. The tangential + /// components (the first two) of R should be equal, assuming an isotropic scaling. /// - template - typename PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like) weightedProject( - const Eigen::MatrixBase & x, const Eigen::MatrixBase & R) const + template + typename PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like1) weightedProject( + const Eigen::MatrixBase & x, const Eigen::MatrixBase & R) const { assert(mu >= 0 && "mu must be positive"); - EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3); - typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like) Vector3Plain; + // EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3); + assert(x.size() == 3 && "The input vector is of wrong size."); assert(R(2) > 0 && "R(2) must be strictly positive"); - Scalar weighted_mu = mu * math::sqrt(R(0) / R(2)); - CoulombFrictionConeTpl weighted_cone(weighted_mu); - Vector3Plain R_sqrt = R.cwiseSqrt(); - Vector3Plain R_sqrt_times_x = (R_sqrt.array() * x.array()).matrix(); - Vector3Plain res = (weighted_cone.project(R_sqrt_times_x).array() / R_sqrt.array()).matrix(); + assert(R(0) == R(1) && "R(0) must be equal to R(1)"); + + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like1) Vector3Plain; + + const Scalar weighted_mu = mu * math::sqrt(R(0) / R(2)); + const CoulombFrictionConeTpl weighted_cone(weighted_mu); + const Vector3Plain R_sqrt = R.cwiseSqrt(); + const Vector3Plain R_sqrt_times_x = R_sqrt.array() * x.array(); + Vector3Plain res = weighted_cone.project(R_sqrt_times_x).array() / R_sqrt.array(); return res; } @@ -126,11 +188,12 @@ namespace pinocchio /// \param[in] v a dual vector. /// template - typename PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like) - computeNormalCorrection(const Eigen::MatrixBase & v) const + typename Eigen::Matrix + computeNormalCorrection(const Eigen::MatrixBase & v) const { - EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3); - typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like) Vector3Plain; + // EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3); + assert(v.size() == 3); + typedef Eigen::Matrix Vector3Plain; Vector3Plain res; res.template head<2>().setZero(); @@ -147,7 +210,8 @@ namespace pinocchio typename PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like) computeRadialProjection(const Eigen::MatrixBase & f) const { - EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3); + // EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3); + assert(f.size() == 3 && "The input vector is of wrong size."); typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like) Vector3Plain; Vector3Plain res; @@ -170,7 +234,7 @@ namespace pinocchio Scalar computeContactComplementarity( const Eigen::MatrixBase & v, const Eigen::MatrixBase & f) const { - typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like1) Vector3Plain; + typedef Eigen::Matrix Vector3Plain; return math::fabs(f.dot(Vector3Plain(v + computeNormalCorrection(v)))); } @@ -193,20 +257,46 @@ namespace pinocchio return 3; } + int size() const + { + return dim(); + } + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + /// \var Friction coefficient Scalar mu; }; // CoulombFrictionConeTpl ///  \brief Dual of the 3d Coulomb friction cone. template - struct DualCoulombFrictionConeTpl + struct DualCoulombFrictionConeTpl : ConeBase> { typedef _Scalar Scalar; - typedef CoulombFrictionConeTpl DualCone; + typedef typename traits::DualCone DualCone; + typedef Eigen::Matrix Vector3; + typedef ConeBase Base; + /// /// \brief Default constructor /// - /// \param[in] mu Friction coefficient + DualCoulombFrictionConeTpl() + : mu(+std::numeric_limits::infinity()) + { + } + + /// + /// \brief Constructor from a friction coefficient mu + /// + /// \param[in] mu Friction coefficient. + /// explicit DualCoulombFrictionConeTpl(const Scalar mu) : mu(mu) { @@ -222,7 +312,7 @@ namespace pinocchio /// \brief Comparison operator bool operator==(const DualCoulombFrictionConeTpl & other) const { - return mu == other.mu; + return base() == other.base() && mu == other.mu; } /// \brief Difference operator @@ -239,38 +329,47 @@ namespace pinocchio bool isInside(const Eigen::MatrixBase & v, const Scalar prec = Scalar(0)) const { assert(mu >= 0 && "mu must be positive"); - EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3); - return mu * v.template head<2>().norm() <= v[2] + prec; + // EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3); + assert(v.size() == 3 && "The input vector is of wrong size."); + const Vector3 v_normalized = v.normalized(); + return mu * v_normalized.template head<2>().norm() <= v_normalized[2] + prec; } + using Base::project; /// \brief Project a vector x onto the cone - template - typename PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like) - project(const Eigen::MatrixBase & x) const + template + void project( + const Eigen::MatrixBase & x, + const Eigen::MatrixBase & res_) const { assert(mu >= 0 && "mu must be positive"); - EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3); - typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(Vector3Like) Vector3Plain; + // EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3Like, 3); + assert(x.size() == 3 && "The input vector is of wrong size."); const Scalar & z = x[2]; + auto & res = res_.const_cast_derived(); + const Eigen::Matrix t = x.template head<2>(); const Scalar t_norm = t.norm(); if (t_norm <= -mu * z) - return Vector3Plain::Zero(); + { + res.setZero(); + return; + } else if (mu * t_norm <= z) { - return x; + res = x; + return; } else { - Vector3Plain res; res.template head<2>() = t; res[2] = mu * t_norm; res.normalize(); const Scalar scale = x.dot(res); res *= scale; - return res; + return; } } @@ -280,12 +379,26 @@ namespace pinocchio return 3; } + int size() const + { + return dim(); + } + /// \brief Returns the dual cone associated to this. /// DualCone dual() const { return DualCone(mu); } + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + /// \var Friction coefficient Scalar mu; diff --git a/include/pinocchio/algorithm/constraints/fictious-constraint.hpp b/include/pinocchio/algorithm/constraints/fictious-constraint.hpp new file mode 100644 index 0000000000..abbcc45f8c --- /dev/null +++ b/include/pinocchio/algorithm/constraints/fictious-constraint.hpp @@ -0,0 +1,112 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_fictious_constraint_hpp__ +#define __pinocchio_algorithm_constraints_fictious_constraint_hpp__ + +#include "pinocchio/algorithm/constraints/fwd.hpp" + +namespace pinocchio +{ + + template + struct CastType> + { + typedef FictiousConstraintModelTpl type; + }; + + template + struct traits> + { + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + typedef FictiousConstraintModelTpl ConstraintModel; + typedef FictiousConstraintDataTpl ConstraintData; + typedef void ConstraintSet; + }; + + template + struct traits> + { + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + typedef FictiousConstraintModelTpl ConstraintModel; + typedef FictiousConstraintDataTpl ConstraintData; + typedef void ConstraintSet; + }; + + /// \brief Fictious constraint model used for variant definition + template + struct FictiousConstraintModelTpl + : ConstraintModelBase> + { + FictiousConstraintModelTpl() + { + } + + bool operator==(const FictiousConstraintModelTpl &) const + { + return true; + } + + inline FictiousConstraintDataTpl createData() const; + }; + + /// \brief Fictious constraint data used for variant definition + template + struct FictiousConstraintDataTpl : ConstraintDataBase> + { + FictiousConstraintDataTpl() + { + } + + bool operator==(const FictiousConstraintDataTpl &) const + { + return true; + } + }; + + template + inline FictiousConstraintDataTpl + FictiousConstraintModelTpl::createData() const + { + return FictiousConstraintDataTpl(); + } + +} // namespace pinocchio + +namespace boost +{ + template + struct has_nothrow_constructor<::pinocchio::FictiousConstraintModelTpl> + : public integral_constant + { + }; + + template + struct has_nothrow_copy<::pinocchio::FictiousConstraintModelTpl> + : public integral_constant + { + }; + + template + struct has_nothrow_constructor<::pinocchio::FictiousConstraintDataTpl> + : public integral_constant + { + }; + + template + struct has_nothrow_copy<::pinocchio::FictiousConstraintDataTpl> + : public integral_constant + { + }; +} // namespace boost + +#endif // ifndef __pinocchio_algorithm_constraints_fictious_constraint_hpp__ diff --git a/include/pinocchio/algorithm/constraints/frame-constraint-data-base.hpp b/include/pinocchio/algorithm/constraints/frame-constraint-data-base.hpp new file mode 100644 index 0000000000..2a7b2ef1cf --- /dev/null +++ b/include/pinocchio/algorithm/constraints/frame-constraint-data-base.hpp @@ -0,0 +1,159 @@ +// +// Copyright (c) 2019-2024 INRIA CNRS +// + +#ifndef __pinocchio_algorithm_constraints_frame_constraint_data_hpp__ +#define __pinocchio_algorithm_constraints_frame_constraint_data_hpp__ + +#include "pinocchio/algorithm/fwd.hpp" +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/constraint-data-base.hpp" + +namespace pinocchio +{ + + /// + ///  \brief Data structure associated with FrameConstraint + /// + template + struct FrameConstraintDataBase : ConstraintDataBase + { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef typename traits::Scalar Scalar; + enum + { + Options = traits::Options + }; + + typedef typename traits::ConstraintModel ConstraintModel; + typedef typename traits::ConstraintData ConstraintData; + typedef ConstraintDataBase Base; + + typedef SE3Tpl SE3; + typedef MotionTpl Motion; + typedef ForceTpl Force; + typedef Eigen::Matrix Vector3; + typedef Eigen::Matrix Vector6; + typedef Eigen::Matrix Matrix6; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(Matrix6) VectorOfMatrix6; + typedef Eigen::Matrix Matrix6x; + typedef Eigen::Matrix MatrixX; + + // data + + /// \brief Resulting contact forces + Vector6 constraint_force; + + /// \brief Placement of the constraint frame 1 with respect to the WORLD frame + SE3 oMc1; + + /// \brief Placement of the constraint frame 2 with respect to the WORLD frame + SE3 oMc2; + + /// \brief Relative displacement between the two frames + SE3 c1Mc2; + + /// \brief Constraint position error + Vector6 constraint_position_error; + + /// \brief Constraint velocity error + Vector6 constraint_velocity_error; + + /// \brief Constraint acceleration error + Vector6 constraint_acceleration_error; + + /// \brief Constraint acceleration biais + Vector6 constraint_acceleration_biais_term; + + Matrix6 A1_world; + Matrix6 A2_world; + Matrix6 A_world; // A1 + A2 + + Matrix6 A1_local; + Matrix6 A2_local; + Matrix6 A_local; // A1 + A2 + + // VectorOfMatrix6 extended_motion_propagators_joint1; + // VectorOfMatrix6 lambdas_joint1; + // VectorOfMatrix6 extended_motion_propagators_joint2; + + // Matrix6x dv1_dq, da1_dq, da1_dv, da1_da; + // Matrix6x dv2_dq, da2_dq, da2_dv, da2_da; + // MatrixX dvc_dq, dac_dq, dac_dv, dac_da; + + /// \brief Default constructor + FrameConstraintDataBase() + { + } + + explicit FrameConstraintDataBase(const ConstraintModel & constraint_model) + : constraint_force(Vector6::Zero()) + , oMc1(SE3::Identity()) + , oMc2(SE3::Identity()) + , c1Mc2(SE3::Identity()) + , constraint_position_error(Vector6::Zero()) + , constraint_velocity_error(Vector6::Zero()) + , constraint_acceleration_error(Vector6::Zero()) + , constraint_acceleration_biais_term(Vector6::Zero()) + // , extended_motion_propagators_joint1(constraint_model.depth_joint1, Matrix6::Zero()) + // , lambdas_joint1(constraint_model.depth_joint1, Matrix6::Zero()) + // , extended_motion_propagators_joint2(constraint_model.depth_joint2, Matrix6::Zero()) + // , dv1_dq(6, constraint_model.nv) + // , da1_dq(6, constraint_model.nv) + // , da1_dv(6, constraint_model.nv) + // , da1_da(6, constraint_model.nv) + // , dv2_dq(6, constraint_model.nv) + // , da2_dq(6, constraint_model.nv) + // , da2_dv(6, constraint_model.nv) + // , da2_da(6, constraint_model.nv) + // , dvc_dq(constraint_model.size(), constraint_model.nv) + // , dac_dq(constraint_model.size(), constraint_model.nv) + // , dac_dv(constraint_model.size(), constraint_model.nv) + // , dac_da(constraint_model.size(), constraint_model.nv) + { + PINOCCHIO_UNUSED_VARIABLE(constraint_model); + } + + bool operator==(const FrameConstraintDataBase & other) const + { + return constraint_force == other.constraint_force && oMc1 == other.oMc1 && oMc2 == other.oMc2 + && c1Mc2 == other.c1Mc2 && constraint_position_error == other.constraint_position_error + && constraint_velocity_error == other.constraint_velocity_error + && constraint_acceleration_error == other.constraint_acceleration_error + && constraint_acceleration_biais_term == other.constraint_acceleration_biais_term + // && extended_motion_propagators_joint1 == other.extended_motion_propagators_joint1 + // && lambdas_joint1 == other.lambdas_joint1 + // && extended_motion_propagators_joint2 == other.extended_motion_propagators_joint2 + // + // && dv1_dq == other.dv1_dq && da1_dq == other.da1_dq && da1_dv == other.da1_dv + // && da1_da == other.da1_da + // // + // && dv2_dq == other.dv2_dq && da2_dq == other.da2_dq && da2_dv == other.da2_dv + // && da2_da == other.da2_da + // // + // && dvc_dq == other.dvc_dq && dac_dq == other.dac_dq && dac_dv == other.dac_dv + // && dac_da == other.dac_da + ; + } + + bool operator!=(const FrameConstraintDataBase & other) const + { + return !(*this == other); + } + + using Base::derived; + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + }; + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_frame_constraint_data_hpp__ diff --git a/include/pinocchio/algorithm/constraints/frame-constraint-model-base.hpp b/include/pinocchio/algorithm/constraints/frame-constraint-model-base.hpp new file mode 100644 index 0000000000..d7269504dd --- /dev/null +++ b/include/pinocchio/algorithm/constraints/frame-constraint-model-base.hpp @@ -0,0 +1,1061 @@ +// +// Copyright (c) 2019-2025 INRIA CNRS +// + +#ifndef __pinocchio_algorithm_constraints_frame_constraint_model_base_hpp__ +#define __pinocchio_algorithm_constraints_frame_constraint_model_base_hpp__ + +#include + +#include "pinocchio/multibody/model.hpp" +#include "pinocchio/spatial/skew.hpp" +#include "pinocchio/algorithm/fwd.hpp" +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/kinematics-constraint-base.hpp" +#include "pinocchio/algorithm/constraints/constraint-data-base.hpp" +#include "pinocchio/algorithm/constraints/constraint-model-common-parameters.hpp" +#include "pinocchio/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp" +#include "pinocchio/algorithm/constraints/baumgarte-corrector-parameters.hpp" + +namespace pinocchio +{ + + template + struct FrameConstraintModelBase; + + template + struct traits> + { + static constexpr ConstraintFormulationLevel constraint_formulation_level = + ConstraintFormulationLevel::VELOCITY_LEVEL; + static constexpr bool has_baumgarte_corrector = true; + static constexpr bool has_baumgarte_corrector_vector = true; + + template + struct JacobianMatrixProductReturnType + { + typedef typename InputMatrix::Scalar Scalar; + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(InputMatrix) InputMatrixPlain; + typedef Eigen::Matrix + type; + }; + + template + struct JacobianTransposeMatrixProductReturnType + { + typedef typename InputMatrix::Scalar Scalar; + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(InputMatrix) InputMatrixPlain; + typedef Eigen::Matrix< + Scalar, + Eigen::Dynamic, + InputMatrixPlain::ColsAtCompileTime, + InputMatrixPlain::Options> + type; + }; + }; + + /// + ///  \brief Contact model structure containg all the info describing the rigid contact model + /// + template + struct FrameConstraintModelBase + : KinematicsConstraintModelBase + , ConstraintModelCommonParameters + { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef typename traits::Scalar Scalar; + enum + { + Options = traits::Options + }; + + typedef KinematicsConstraintModelBase Base; + typedef ConstraintModelCommonParameters BaseCommonParameters; + typedef ConstraintModelBase RootBase; + + template + friend struct FrameConstraintModelBase; + + static const ConstraintFormulationLevel constraint_formulation_level = + traits::constraint_formulation_level; + typedef typename traits::ConstraintData ConstraintData; + typedef typename traits::ComplianceVectorType ComplianceVectorType; + typedef typename traits::ActiveComplianceVectorTypeRef ActiveComplianceVectorTypeRef; + typedef typename traits::ActiveComplianceVectorTypeConstRef + ActiveComplianceVectorTypeConstRef; + typedef typename traits::BaumgarteCorrectorVectorParameters + BaumgarteCorrectorVectorParameters; + typedef BaumgarteCorrectorParametersTpl BaumgarteCorrectorParameters; + + using Base::derived; + using Base::joint1_id; + using Base::joint2_id; + using typename Base::BooleanVector; + using typename Base::EigenIndexVector; + + typedef SE3Tpl SE3; + typedef MotionTpl Motion; + typedef ForceTpl Force; + typedef Eigen::Matrix Matrix6; + typedef Eigen::Matrix Vector6; + typedef Vector6 VectorConstraintSize; + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + BaseCommonParameters & base_common_parameters() + { + return static_cast(*this); + } + const BaseCommonParameters & base_common_parameters() const + { + return static_cast(*this); + } + + /// \brief Position of attached point with respect to the frame of joint1. + SE3 joint1_placement; + + /// \brief Position of attached point with respect to the frame of joint2. + SE3 joint2_placement; + + /// \brief Desired constraint shift at position level + Vector6 desired_constraint_offset; + + /// \brief Desired constraint velocity at velocity level + Vector6 desired_constraint_velocity; + + /// \brief Desired constraint velocity at acceleration level + Vector6 desired_constraint_acceleration; + + /// \brief Colwise sparsity pattern associated with joint 1. + BooleanVector colwise_joint1_sparsity; + + /// \brief Colwise sparsity pattern associated with joint 2. + BooleanVector colwise_joint2_sparsity; + + /// \brief Jointwise span indexes associated with joint 1. + EigenIndexVector joint1_span_indexes; + + /// \brief Jointwise span indexes associated with joint 2. + EigenIndexVector joint2_span_indexes; + + EigenIndexVector loop_span_indexes; + + /// \brief Sparsity pattern associated to the constraint; + BooleanVector colwise_sparsity; + + /// \brief Indexes of the columns spanned by the constraints. + EigenIndexVector colwise_span_indexes; + + /// \brief Dimensions of the model + int nv; + + ///  \brief Depth of the kinematic tree for joint1 and joint2 + size_t depth_joint1, depth_joint2; + + protected: + using BaseCommonParameters::m_compliance; + // CHOICE: right now we use the scalar Baumgarte + // using BaseCommonParameters::m_baumgarte_vector_parameters; + using BaseCommonParameters::m_baumgarte_parameters; + + public: + /// + ///  \brief Default constructor + /// + FrameConstraintModelBase() + : nv(-1) + , depth_joint1(0) + , depth_joint2(0) + { + } + + /// + ///  \brief Contructor with from a given type, joint indexes and placements. + /// + /// \param[in] type Type of the contact. + /// \param[in] model Model associated to the constraint. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// \param[in] joint2_id Index of the joint 2 in the model tree. + /// \param[in] joint1_placement Placement of the constraint w.r.t the frame of joint1. + /// \param[in] joint2_placement Placement of the constraint w.r.t the frame of joint2. + /// \param[in] reference_frame Reference frame in which the constraints quantities are + /// expressed. + /// + template class JointCollectionTpl> + FrameConstraintModelBase( + const ModelTpl & model, + const JointIndex joint1_id, + const SE3 & joint1_placement, + const JointIndex joint2_id, + const SE3 & joint2_placement) + : Base(model, joint1_id, joint2_id) + , joint1_placement(joint1_placement) + , joint2_placement(joint2_placement) + , desired_constraint_offset(Vector6::Zero()) + , desired_constraint_velocity(Vector6::Zero()) + , desired_constraint_acceleration(Vector6::Zero()) + , colwise_joint1_sparsity(model.nv) + , colwise_joint2_sparsity(model.nv) + , loop_span_indexes((size_t)model.nv) + { + init(model); + } + + /// + ///  \brief Contructor with from a given type, joint1_id and placement. + /// + /// \param[in] type Type of the contact. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// \param[in] joint1_placement Placement of the constraint w.r.t the frame of joint1. + /// \param[in] reference_frame Reference frame in which the constraints quantities are + /// expressed. + /// + template class JointCollectionTpl> + FrameConstraintModelBase( + const ModelTpl & model, + const JointIndex joint1_id, + const SE3 & joint1_placement) + : Base(model, joint1_id, 0) + , joint1_placement(joint1_placement) + , joint2_placement(SE3::Identity()) + , desired_constraint_offset(Vector6::Zero()) + , desired_constraint_velocity(Vector6::Zero()) + , desired_constraint_acceleration(Vector6::Zero()) + , colwise_joint1_sparsity(model.nv) + , colwise_joint2_sparsity(model.nv) + , loop_span_indexes((size_t)model.nv) + { + init(model); + } + + /// + ///  \brief Contructor with from a given type and the joint ids. + /// + /// \param[in] model Kinematic tree. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// \param[in] joint2_id Index of the joint 2 in the model tree. + /// + template class JointCollectionTpl> + FrameConstraintModelBase( + const ModelTpl & model, + const JointIndex joint1_id, + const JointIndex joint2_id) + : Base(model, joint1_id, joint2_id) + , joint1_placement(SE3::Identity()) + , joint2_placement(SE3::Identity()) + , desired_constraint_offset(Vector6::Zero()) + , desired_constraint_velocity(Vector6::Zero()) + , desired_constraint_acceleration(Vector6::Zero()) + , colwise_joint1_sparsity(model.nv) + , colwise_joint2_sparsity(model.nv) + , loop_span_indexes((size_t)model.nv) + { + init(model); + } + + /// + ///  \brief Contructor with from a given type and . + /// + /// \param[in] model Kinematic tree. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// + /// \remarks The second joint id (joint2_id) is set to be 0 (corresponding to the index of the + /// universe). + /// + template class JointCollectionTpl> + FrameConstraintModelBase( + const ModelTpl & model, const JointIndex joint1_id) + : Base(model, joint1_id, 0) + , joint1_placement(SE3::Identity()) + , joint2_placement(SE3::Identity()) + , desired_constraint_offset(Vector6::Zero()) + , desired_constraint_velocity(Vector6::Zero()) + , desired_constraint_acceleration(Vector6::Zero()) + , colwise_joint1_sparsity(model.nv) + , colwise_joint2_sparsity(model.nv) + , loop_span_indexes((size_t)model.nv) + { + init(model); + } + + /// + /// \brief Create data storage associated to the constraint + /// + ConstraintData createData() const + { + return ConstraintData(*this); + } + + /// \brief Returns the colwise sparsity associated with a given row + const BooleanVector & getRowActivableSparsityPattern(const Eigen::DenseIndex row_id) const + { + PINOCCHIO_CHECK_INPUT_ARGUMENT(row_id < size()); + return colwise_sparsity; + } + + /// \brief Returns the sparsity associated with a given row + const BooleanVector & getRowActiveSparsityPattern(const Eigen::DenseIndex row_id) const + { + return getRowActivableSparsityPattern(row_id); + } + + /// \brief Returns the vector of the active indexes associated with a given row + const EigenIndexVector & getRowActivableIndexes(const Eigen::DenseIndex row_id) const + { + PINOCCHIO_CHECK_INPUT_ARGUMENT(row_id < size()); + return colwise_span_indexes; + } + + /// \brief Returns the vector of the active indexes associated with a given row + const EigenIndexVector & getRowActiveIndexes(const Eigen::DenseIndex row_id) const + { + return getRowActivableIndexes(row_id); + } + + /// \brief Returns the compliance internally stored in the constraint model + ActiveComplianceVectorTypeConstRef getActiveCompliance_impl() const + { + return this->compliance(); + } + + /// \brief Returns the compliance internally stored in the constraint model + ActiveComplianceVectorTypeRef getActiveCompliance_impl() + { + return this->compliance(); + } + + /// + ///  \brief Comparison operator + /// + /// \param[in] other Other FrameConstraintModelBase to compare with. + /// + /// \returns true if the two *this is equal to other (type, joint1_id and placement attributs + /// must be the same). + /// + bool operator==(const FrameConstraintModelBase & other) const + { + if (this == &other) + return true; + return base() == other.base() && base_common_parameters() == other.base_common_parameters() + && joint1_id == other.joint1_id && joint2_id == other.joint2_id + && joint1_placement == other.joint1_placement + && joint2_placement == other.joint2_placement && nv == other.nv + && desired_constraint_offset == other.desired_constraint_offset + && desired_constraint_velocity == other.desired_constraint_velocity + && desired_constraint_acceleration == other.desired_constraint_acceleration + && colwise_joint1_sparsity == other.colwise_joint1_sparsity + && colwise_joint2_sparsity == other.colwise_joint2_sparsity + && joint1_span_indexes == other.joint1_span_indexes + && joint2_span_indexes == other.joint2_span_indexes && nv == other.nv + && depth_joint1 == other.depth_joint1 && depth_joint2 == other.depth_joint2 + && colwise_sparsity == other.colwise_sparsity + && colwise_span_indexes == other.colwise_span_indexes + && loop_span_indexes == other.loop_span_indexes; + } + + /// + ///  \brief Oposite of the comparison operator. + /// + /// \param[in] other Other FrameConstraintModelBase to compare with. + /// + /// \returns false if the two *this is not equal to other (at least type, joint1_id or placement + /// attributs is different). + /// + bool operator!=(const FrameConstraintModelBase & other) const + { + return !(*this == other); + } + + /// \brief Evaluate the constraint values at the current state given by data and store the + /// results in cdata. + template class JointCollectionTpl> + void calc( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata) const + { + PINOCCHIO_UNUSED_VARIABLE(model); + + if (joint1_id > 0) + cdata.oMc1 = data.oMi[joint1_id] * joint1_placement; + else + cdata.oMc1 = joint1_placement; + + if (joint2_id > 0) + cdata.oMc2 = data.oMi[joint2_id] * joint2_placement; + else + cdata.oMc2 = joint2_placement; + + // Compute relative placement + cdata.c1Mc2 = cdata.oMc1.actInv(cdata.oMc2); + + // Compute errors + auto & position_error = cdata.constraint_position_error; + position_error = log6(cdata.c1Mc2).toVector(); + + const auto vf1 = joint1_placement.actInv(data.v[this->joint1_id]); + const auto vf2 = joint2_placement.actInv(data.v[this->joint2_id]); + + auto & velocity_error = cdata.constraint_velocity_error; + const Motion vf2_in_frame1 = cdata.c1Mc2.act(vf2); + const Motion motion_velocity_error = vf2_in_frame1 - vf1; + velocity_error = motion_velocity_error.toVector(); + + const auto af1 = joint1_placement.actInv(data.a[this->joint1_id]); + const auto af2 = joint2_placement.actInv(data.a[this->joint2_id]); + const Motion af2_in_frame1 = cdata.c1Mc2.act(af2); + auto & acceleration_error = cdata.constraint_acceleration_error; + + acceleration_error = af2_in_frame1 - af1 + motion_velocity_error.cross(vf2_in_frame1); + + cdata.A1_world = this->getA1(cdata, WorldFrameTag()); + cdata.A2_world = this->getA2(cdata, WorldFrameTag()); + cdata.A_world = cdata.A1_world + cdata.A2_world; + + cdata.A1_local = this->getA1(cdata, LocalFrameTag()); + cdata.A2_local = this->getA2(cdata, LocalFrameTag()); + cdata.A_local = cdata.A1_local + cdata.A2_local; + } + + /// \brief Returns the constraint projector associated with joint 1. + /// This matrix transforms a spatial velocity expressed at the origin to the first component of + /// the constraint associated with joint 1. + template + Matrix6 getA1(const ConstraintData & cdata, ReferenceFrameTag) const + { + Matrix6 res; + + if (std::is_same, WorldFrameTag>::value) + { + const SE3 & oM1 = cdata.oMc1; + res = -oM1.toActionMatrixInverse(); + } + else if (std::is_same, LocalFrameTag>::value) + { + const SE3 & j1Mc1 = this->joint1_placement; + res = -j1Mc1.toActionMatrixInverse(); + } + + return res; + } + + /// \brief Returns the constraint projector associated with joint 2. + /// This matrix transforms a spatial velocity expressed at the origin to the first component of + /// the constraint associated with joint 2. + template + Matrix6 getA2(const ConstraintData & cdata, ReferenceFrameTag) const + { + Matrix6 res; + + if (std::is_same, WorldFrameTag>::value) + { + const SE3 & oM1 = cdata.oMc1; + res = oM1.toActionMatrixInverse(); + } + else if (std::is_same, LocalFrameTag>::value) + { + const SE3 & j2Mc2 = this->joint2_placement; + const SE3 & c1Mc2 = cdata.c1Mc2; + const SE3 c1Mj2 = c1Mc2.act(j2Mc2.inverse()); + res = c1Mj2.toActionMatrix(); + } + + return res; + } + + template< + typename Matrix6LikeOut1, + typename Matrix6LikeOut2, + typename Matrix6LikeOut3, + ReferenceFrame rf> + void computeConstraintInertias( + const ConstraintData & cdata, + const Scalar & constraint_inertia_value, + const Eigen::MatrixBase & I11, + const Eigen::MatrixBase & I12, + const Eigen::MatrixBase & I22, + const ReferenceFrameTag reference_frame) const + { + computeConstraintInertias( + cdata, Vector6::Constant(constraint_inertia_value), I11.const_cast_derived(), + I12.const_cast_derived(), I22.const_cast_derived(), reference_frame); + } + + template< + typename Vector6Like, + typename Matrix6LikeOut1, + typename Matrix6LikeOut2, + typename Matrix6LikeOut3, + ReferenceFrame rf> + void computeConstraintInertias( + const ConstraintData & cdata, + const Eigen::MatrixBase & diagonal_constraint_inertia, + const Eigen::MatrixBase & I11, + const Eigen::MatrixBase & I12, + const Eigen::MatrixBase & I22, + const ReferenceFrameTag reference_frame) const + { + EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Vector6Like, Vector6); + EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Matrix6LikeOut1, Matrix6); + EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Matrix6LikeOut2, Matrix6); + EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Matrix6LikeOut3, Matrix6); + + PINOCCHIO_UNUSED_VARIABLE(reference_frame); + // assert((check_expression_if_real(diagonal_constraint_inertia.isZero(Scalar(0))))); + + const auto & A1 = + std::is_same, WorldFrameTag>::value ? cdata.A1_world : cdata.A1_local; + const auto & A2 = + std::is_same, WorldFrameTag>::value ? cdata.A2_world : cdata.A2_local; + + Matrix6 diagonal_constraint_inertia_time_A; + if (joint1_id > 0) + { + diagonal_constraint_inertia_time_A = diagonal_constraint_inertia.asDiagonal() * A1; + I11.const_cast_derived().noalias() = A1.transpose() * diagonal_constraint_inertia_time_A; + } + else + I11.const_cast_derived().setZero(); + + if (joint2_id > 0) + { + diagonal_constraint_inertia_time_A = diagonal_constraint_inertia.asDiagonal() * A2; + I22.const_cast_derived().noalias() = A2.transpose() * diagonal_constraint_inertia_time_A; + } + else + I22.const_cast_derived().setZero(); + + // Compute the cross coupling term + if (joint1_id > 0 && joint2_id > 0) + { + I12.const_cast_derived().noalias() = A1.transpose() * diagonal_constraint_inertia_time_A; + } + else + I12.const_cast_derived().setZero(); + } + + template< + template class JointCollectionTpl, + typename Vector6Like, + ReferenceFrame rf> + void appendCouplingConstraintInertias( + const ModelTpl & model, + DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & diagonal_constraint_inertia, + const ReferenceFrameTag reference_frame) const + { + PINOCCHIO_UNUSED_VARIABLE(model); + + Matrix6 I11, I12, I22; + computeConstraintInertias(cdata, diagonal_constraint_inertia, I11, I12, I22, reference_frame); + assert( + (std::is_same, WorldFrameTag>::value + || std::is_same, LocalFrameTag>::value) + && "must never happened"); + + Matrix6 & Y1 = std::is_same, WorldFrameTag>::value + ? data.oYaba_augmented[joint1_id] + : data.oYaba_augmented[joint1_id]; + + if (joint1_id > 0) + Y1 += I11; + + Matrix6 & Y2 = std::is_same, WorldFrameTag>::value + ? data.oYaba_augmented[joint2_id] + : data.oYaba_augmented[joint2_id]; + + if (joint2_id > 0) + Y2 += I22; + + if (joint1_id > 0 && joint2_id > 0) + { + if (joint1_id < joint2_id) + { + data.joint_cross_coupling.get({joint1_id, joint2_id}) += I12; + } + else + { + data.joint_cross_coupling.get({joint2_id, joint1_id}) += I12.transpose(); + } + } + } + + // /// + // /// @brief This function computes the spatial inertia associated with the constraint. + // /// This function is useful to express the constraint inertia associated with the + // constraint for + // /// AL settings. + // /// + // template + // Matrix6 computeConstraintSpatialInertia( + // const SE3Tpl & placement, + // const Eigen::MatrixBase & + // diagonal_constraint_inertia) const + // { + // EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Vector3Like, Vector3); + // Matrix6 res; + // + // const auto & R = placement.rotation(); + // const auto & t = placement.translation(); + // + // typedef Eigen::Matrix Matrix3; + // const Matrix3 R_Sigma = R * diagonal_constraint_inertia.asDiagonal(); + // const Matrix3 t_skew = skew(t); + // + // auto block_LL = res.template block<3, 3>(SE3::LINEAR, SE3::LINEAR); + // auto block_LA = res.template block<3, 3>(SE3::LINEAR, SE3::ANGULAR); + // auto block_AL = res.template block<3, 3>(SE3::ANGULAR, SE3::LINEAR); + // auto block_AA = res.template block<3, 3>(SE3::ANGULAR, SE3::ANGULAR); + // + // block_LL.noalias() = R_Sigma * R.transpose(); + // block_LA.noalias() = -block_LL * t_skew; + // block_AL.noalias() = block_LA.transpose(); + // block_AA.noalias() = t_skew * block_LA; + // + // return res; + // } + + // template< + // template + // class JointCollectionTpl, + // typename Vector3Like, + // typename Matrix6Like, + // typename Matrix6LikeAllocator> + // void appendCouplingConstraintInertias( + // const ModelTpl & model, const + // DataTpl & data, const + // BilateralFrameConstraintDataTpl & cdata, const + // Eigen::MatrixBase & + // diagonal_constraint_inertia, + // std::vector & inertias) + // const + // { + // EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Vector3Like, Vector3); + // PINOCCHIO_UNUSED_VARIABLE(data); + // PINOCCHIO_UNUSED_VARIABLE(cdata); + // PINOCCHIO_CHECK_ARGUMENT_SIZE(inertias.size(), size_t(model.njoints)); + // assert( + // ((joint1_id > 0 && joint2_id == 0) || (joint1_id == 0 && joint2_id > 0)) + // && "The behavior is only defined for this context"); + // + // if (this->joint1_id != 0) + // { + // const SE3 & placement = this->joint1_placement; + // inertias[this->joint1_id] += + // computeConstraintSpatialInertia(placement, diagonal_constraint_inertia); + // } + // + // if (this->joint2_id != 0) + // { + // const SE3 & placement = this->joint2_placement; + // inertias[this->joint2_id] += + // computeConstraintSpatialInertia(placement, diagonal_constraint_inertia); + // } + // } + + template class JointCollectionTpl> + typename traits::template JacobianMatrixProductReturnType::type + jacobianMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat) const + { + typedef typename traits::template JacobianMatrixProductReturnType::type + ReturnType; + ReturnType res(6, mat.cols()); + jacobianMatrixProduct(model, data, cdata, mat.derived(), res); + return res; + } + + template< + typename InputMatrix, + typename OutputMatrix, + template class JointCollectionTpl, + AssignmentOperatorType op = SETTO> + void jacobianMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat, + const Eigen::MatrixBase & _res, + AssignmentOperatorTag aot = SetTo()) const + { + typedef DataTpl Data; + typedef typename Data::Vector6 Vector6; + OutputMatrix & res = _res.const_cast_derived(); + + PINOCCHIO_CHECK_ARGUMENT_SIZE(mat.rows(), model.nv); + PINOCCHIO_CHECK_ARGUMENT_SIZE(mat.cols(), res.cols()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res.rows(), size()); + PINOCCHIO_UNUSED_VARIABLE(aot); + + if (std::is_same, SetTo>::value) + res.setZero(); + + // const Eigen::DenseIndex constraint_dim = size(); + // + // const Eigen::DenseIndex + // complexity_strategy_1 = 6 * res.cols() * 36 + constraint_dim * 36 * res.cols(), + // complexity_strategy_2 = 36 * constraint_dim * 6 + constraint_dim * 36 * res.cols(); + + const Matrix6 A = getA2(cdata, WorldFrameTag()); + + for (Eigen::DenseIndex jj = 0; jj < model.nv; ++jj) + { + if (!(colwise_joint1_sparsity[jj] || colwise_joint2_sparsity[jj])) + continue; + if (colwise_joint1_sparsity[jj] == colwise_joint2_sparsity[jj]) + continue; + Vector6 AxSi; + + typedef typename Data::Matrix6x::ConstColXpr ConstColXpr; + const ConstColXpr Jcol = data.J.col(jj); + + if (colwise_joint1_sparsity[jj]) + AxSi.noalias() = -A * Jcol; + else + AxSi.noalias() = A * Jcol; + + if (std::is_same, RmTo>::value) + res.noalias() -= AxSi * mat.row(jj); + else // AddTo, SetTo + res.noalias() += AxSi * mat.row(jj); + } + } + + template class JointCollectionTpl> + typename traits::template JacobianTransposeMatrixProductReturnType::type + jacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat) const + { + typedef typename traits::template JacobianTransposeMatrixProductReturnType< + InputMatrix>::type ReturnType; + ReturnType res(model.nv, mat.cols()); + jacobianTransposeMatrixProduct(model, data, cdata, mat.derived(), res); + return res; + } + + template< + typename InputMatrix, + typename OutputMatrix, + template class JointCollectionTpl, + AssignmentOperatorType op = SETTO> + void jacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat, + const Eigen::MatrixBase & _res, + AssignmentOperatorTag aot = SetTo()) const + { + typedef DataTpl Data; + typedef typename Data::Vector6 Vector6; + OutputMatrix & res = _res.const_cast_derived(); + + PINOCCHIO_CHECK_ARGUMENT_SIZE(mat.rows(), size()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res.cols(), mat.cols()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res.rows(), model.nv); + PINOCCHIO_UNUSED_VARIABLE(aot); + + if (std::is_same, SetTo>::value) + res.setZero(); + + const Matrix6 A = getA2(cdata, WorldFrameTag()); + + for (Eigen::DenseIndex jj = 0; jj < model.nv; ++jj) + { + if (!(colwise_joint1_sparsity[jj] || colwise_joint2_sparsity[jj])) + continue; + if (colwise_joint1_sparsity[jj] == colwise_joint2_sparsity[jj]) + continue; + Vector6 AxSi; + + typedef typename Data::Matrix6x::ConstColXpr ConstColXpr; + const ConstColXpr Jcol = data.J.col(jj); + + if (colwise_joint1_sparsity[jj]) + AxSi.noalias() = -A * Jcol; + else + AxSi.noalias() = A * Jcol; + + if (std::is_same, RmTo>::value) + res.row(jj).noalias() -= AxSi.transpose() * mat; + else + res.row(jj).noalias() += AxSi.transpose() * mat; + } + } + + using RootBase::jacobian; + + ///  \brief Evaluate the Jacobian associated to the constraint at the given state stored in data + /// and cdata.  The results Jacobian is evaluated in the jacobian input/output matrix. + template class JointCollectionTpl, typename JacobianMatrix> + void jacobian( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata, + const Eigen::MatrixBase & _jacobian_matrix) const + { + typedef DataTpl Data; + JacobianMatrix & jacobian_matrix = _jacobian_matrix.const_cast_derived(); + + // const FrameConstraintModelBase & cmodel = *this; + + const SE3 & oMc1 = cdata.oMc1; + + for (Eigen::DenseIndex j = 0; j < model.nv; ++j) + { + if (colwise_joint1_sparsity[j] || colwise_joint2_sparsity[j]) + { + typedef typename Data::Matrix6x::ConstColXpr ConstColXpr; + const ConstColXpr Jcol = data.J.col(j); + const MotionRef Jcol_motion(Jcol); + + // TODO: simplify computations + if (colwise_joint1_sparsity[j] == colwise_joint2_sparsity[j]) + jacobian_matrix.col(j).setZero(); + else + { + const Motion Jcol_local(oMc1.actInv(Jcol_motion)); + if (colwise_joint1_sparsity[j]) + jacobian_matrix.col(j) = -Jcol_local.toVector(); + else + jacobian_matrix.col(j) = Jcol_local.toVector(); + } + } + } + } + + /// + /// \copydoc Base::mapConstraintForceToJointForces(const ModelTpl &, const DataTpl &, const + /// ConstraintData &, const Eigen::MatrixBase &, std::vector, ForceAllocator> &, ReferenceFrameTag) + /// + template< + template class JointCollectionTpl, + typename ForceLike, + typename ForceAllocator, + ReferenceFrame rf> + void mapConstraintForceToJointForces( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & constraint_forces, + std::vector, ForceAllocator> & joint_forces, + ReferenceFrameTag reference_frame) const + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(joint_forces.size(), size_t(model.njoints)); + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_forces.rows(), size()); + PINOCCHIO_UNUSED_VARIABLE(data); + PINOCCHIO_UNUSED_VARIABLE(reference_frame); + + // Todo: optimize code + const auto & A1 = + std::is_same, WorldFrameTag>::value ? cdata.A1_world : cdata.A1_local; + const auto & A2 = + std::is_same, WorldFrameTag>::value ? cdata.A2_world : cdata.A2_local; + + if (joint1_id > 0) + joint_forces[this->joint1_id].toVector().noalias() += A1.transpose() * constraint_forces; + if (joint2_id > 0) + joint_forces[this->joint2_id].toVector().noalias() += A2.transpose() * constraint_forces; + } + + /// + /// \copydoc Base::mapJointMotionsToConstraintMotion(const ModelTpl &, const DataTpl &, const + /// ConstraintData &, const std::vector, MotionAllocator> &, const + /// Eigen::MatrixBase &, ReferenceFrameTag) + /// + template< + template class JointCollectionTpl, + typename MotionAllocator, + typename VectorLike, + ReferenceFrame rf> + void mapJointMotionsToConstraintMotion( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const std::vector, MotionAllocator> & joint_accelerations, + const Eigen::MatrixBase & constraint_motion, + ReferenceFrameTag reference_frame) const + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(joint_accelerations.size(), size_t(model.njoints)); + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_motion.rows(), activeSize()); + PINOCCHIO_UNUSED_VARIABLE(data); + PINOCCHIO_UNUSED_VARIABLE(reference_frame); + + const auto & A1 = + std::is_same, WorldFrameTag>::value ? cdata.A1_world : cdata.A1_local; + const auto & A2 = + std::is_same, WorldFrameTag>::value ? cdata.A2_world : cdata.A2_local; + + if (joint1_id > 0 && joint2_id > 0) + constraint_motion.const_cast_derived().noalias() = + A1 * joint_accelerations[this->joint1_id].toVector() + + A2 * joint_accelerations[this->joint2_id].toVector(); + else if (joint1_id > 0) + constraint_motion.const_cast_derived().noalias() = + A1 * joint_accelerations[this->joint1_id].toVector(); + else if (joint2_id > 0) + constraint_motion.const_cast_derived().noalias() = + A2 * joint_accelerations[this->joint2_id].toVector(); + else + constraint_motion.const_cast_derived().setZero(); + } + + static int size() + { + return 6; + } + + static int activeSize() + { + return size(); + } + + /// \returns An expression of *this with the Scalar type casted to NewScalar. + template + void cast(FrameConstraintModelBase & res) const + { + Base::cast(res); + BaseCommonParameters::template cast(res); + + res.joint1_id = joint1_id; + res.joint2_id = joint2_id; + res.joint1_placement = joint1_placement.template cast(); + res.joint2_placement = joint2_placement.template cast(); + res.desired_constraint_offset = desired_constraint_offset.template cast(); + res.desired_constraint_velocity = desired_constraint_velocity.template cast(); + res.desired_constraint_acceleration = + desired_constraint_acceleration.template cast(); + res.colwise_joint1_sparsity = colwise_joint1_sparsity; + res.colwise_joint2_sparsity = colwise_joint2_sparsity; + res.joint1_span_indexes = joint1_span_indexes; + res.joint2_span_indexes = joint2_span_indexes; + res.colwise_sparsity = colwise_sparsity; + res.colwise_span_indexes = colwise_span_indexes; + res.nv = nv; + res.depth_joint1 = depth_joint1; + res.depth_joint2 = depth_joint2; + res.loop_span_indexes = loop_span_indexes; + } + + protected: + template class JointCollectionTpl> + void init(const ModelTpl & model) + { + nv = model.nv; + depth_joint1 = static_cast(model.supports[joint1_id].size()); + depth_joint2 = static_cast(model.supports[joint2_id].size()); + + typedef ModelTpl Model; + typedef typename Model::JointModel JointModel; + static const bool default_sparsity_value = false; + colwise_joint1_sparsity.fill(default_sparsity_value); + colwise_joint2_sparsity.fill(default_sparsity_value); + + joint1_span_indexes.reserve(size_t(model.njoints)); + joint2_span_indexes.reserve(size_t(model.njoints)); + + JointIndex current1_id = 0; + if (joint1_id > 0) + current1_id = joint1_id; + + JointIndex current2_id = 0; + if (joint2_id > 0) + current2_id = joint2_id; + + while (current1_id != current2_id) + { + if (current1_id > current2_id) + { + const JointModel & joint1 = model.joints[current1_id]; + joint1_span_indexes.push_back((Eigen::DenseIndex)current1_id); + Eigen::DenseIndex current1_col_id = joint1.idx_v(); + for (int k = 0; k < joint1.nv(); ++k, ++current1_col_id) + { + colwise_joint1_sparsity[current1_col_id] = true; + } + current1_id = model.parents[current1_id]; + } + else + { + const JointModel & joint2 = model.joints[current2_id]; + joint2_span_indexes.push_back((Eigen::DenseIndex)current2_id); + Eigen::DenseIndex current2_col_id = joint2.idx_v(); + for (int k = 0; k < joint2.nv(); ++k, ++current2_col_id) + { + colwise_joint2_sparsity[current2_col_id] = true; + } + current2_id = model.parents[current2_id]; + } + } + assert(current1_id == current2_id && "current1_id should be equal to current2_id"); + + { + JointIndex current_id = current1_id; + while (current_id > 0) + { + const JointModel & joint = model.joints[current_id]; + joint1_span_indexes.push_back((Eigen::DenseIndex)current_id); + joint2_span_indexes.push_back((Eigen::DenseIndex)current_id); + Eigen::DenseIndex current_row_id = joint.idx_v(); + for (int k = 0; k < joint.nv(); ++k, ++current_row_id) + { + colwise_joint1_sparsity[current_row_id] = true; + colwise_joint2_sparsity[current_row_id] = true; + } + current_id = model.parents[current_id]; + } + } + std::reverse(joint1_span_indexes.begin(), joint1_span_indexes.end()); + std::reverse(joint2_span_indexes.begin(), joint2_span_indexes.end()); + colwise_span_indexes.reserve((size_t)model.nv); + colwise_sparsity.resize(model.nv); + colwise_sparsity.setZero(); + loop_span_indexes.reserve((size_t)model.nv); + for (Eigen::DenseIndex col_id = 0; col_id < model.nv; ++col_id) + { + if (colwise_joint1_sparsity[col_id] || colwise_joint2_sparsity[col_id]) + { + colwise_span_indexes.push_back(col_id); + colwise_sparsity[col_id] = true; + } + + if (colwise_joint1_sparsity[col_id] != colwise_joint2_sparsity[col_id]) + { + loop_span_indexes.push_back(col_id); + } + } + + // Set compliance and baumgarte parameters + m_compliance = ComplianceVectorType::Zero(size()); + // CHOICE: right now we use the scalar Baumgarte + // m_baumgarte_vector_parameters = BaumgarteCorrectorVectorParameters(size()); + m_baumgarte_parameters = BaumgarteCorrectorParameters(); + } + }; // FrameConstraintModelBase + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_frame_constraint_model_base_hpp__ diff --git a/include/pinocchio/algorithm/constraints/fwd.hpp b/include/pinocchio/algorithm/constraints/fwd.hpp index 9de5c0902f..69621a205a 100644 --- a/include/pinocchio/algorithm/constraints/fwd.hpp +++ b/include/pinocchio/algorithm/constraints/fwd.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2022-2023 INRIA +// Copyright (c) 2022-2024 INRIA // #ifndef __pinocchio_algorithm_constraints_fwd_hpp__ @@ -10,39 +10,90 @@ namespace pinocchio { + // Constraints template struct RigidConstraintModelTpl; template struct RigidConstraintDataTpl; - template - struct ConstraintCollectionTpl - { - typedef _Scalar Scalar; - enum - { - Options = _Options - }; + template + struct FictiousConstraintModelTpl; + template + struct FictiousConstraintDataTpl; + + template + struct FrictionalJointConstraintModelTpl; + typedef FrictionalJointConstraintModelTpl FrictionalJointConstraintModel; + + template + struct FrictionalJointConstraintDataTpl; + typedef FrictionalJointConstraintDataTpl FrictionalJointConstraintData; + + template + struct JointLimitConstraintModelTpl; + typedef JointLimitConstraintModelTpl JointLimitConstraintModel; + + template + struct JointLimitConstraintDataTpl; + typedef JointLimitConstraintDataTpl JointLimitConstraintData; + + template + struct BilateralPointConstraintModelTpl; + typedef BilateralPointConstraintModelTpl BilateralPointConstraintModel; + template + struct BilateralPointConstraintDataTpl; + typedef BilateralPointConstraintDataTpl BilateralPointConstraintData; + + template + struct FrictionalPointConstraintModelTpl; + typedef FrictionalPointConstraintModelTpl FrictionalPointConstraintModel; + template + struct FrictionalPointConstraintDataTpl; + typedef FrictionalPointConstraintDataTpl FrictionalPointConstraintData; - typedef RigidConstraintModelTpl RigidConstraintModel; - typedef RigidConstraintDataTpl RigidConstraintData; + template + struct WeldConstraintModelTpl; + typedef WeldConstraintModelTpl WeldConstraintModel; + template + struct WeldConstraintDataTpl; + typedef WeldConstraintDataTpl WeldConstraintData; - typedef boost::variant ConstraintModelVariant; - typedef boost::variant ConstraintDataVariant; - }; + template + struct ConstraintCollectionDefaultTpl; - typedef ConstraintCollectionTpl ConstraintCollection; + typedef ConstraintCollectionDefaultTpl + ConstraintCollectionDefault; - template class ConstraintCollectionTpl> + template< + typename Scalar, + int _Options, + template class ConstraintCollectionTpl = ConstraintCollectionDefaultTpl> struct ConstraintModelTpl; - typedef ConstraintModelTpl + typedef ConstraintModelTpl ConstraintModel; - template class ConstraintCollectionTpl> + template< + typename Scalar, + int _Options, + template class ConstraintCollectionTpl = ConstraintCollectionDefaultTpl> struct ConstraintDataTpl; - typedef ConstraintDataTpl + typedef ConstraintDataTpl ConstraintData; + // Sets + template + struct BoxSetTpl; + typedef BoxSetTpl BoxSet; + + // Cone sets + template + struct UnboundedSetTpl; + typedef UnboundedSetTpl UnboundedSet; + + template + struct NullSetTpl; + typedef NullSetTpl NullSet; + template struct CoulombFrictionConeTpl; typedef CoulombFrictionConeTpl CoulombFrictionCone; @@ -50,6 +101,19 @@ namespace pinocchio template struct DualCoulombFrictionConeTpl; typedef DualCoulombFrictionConeTpl DualCoulombFrictionCone; + + template + struct PositiveOrthantConeTpl; + typedef PositiveOrthantConeTpl PositiveOrthantCone; + + template + struct NegativeOrthantConeTpl; + typedef NegativeOrthantConeTpl NegativeOrthantCone; + + template + struct JointLimitConstraintConeTpl; + typedef JointLimitConstraintConeTpl JointLimitConstraintCone; + } // namespace pinocchio #endif // ifndef __pinocchio_algorithm_constraints_fwd_hpp__ diff --git a/include/pinocchio/algorithm/constraints/joint-frictional-constraint.hpp b/include/pinocchio/algorithm/constraints/joint-frictional-constraint.hpp new file mode 100644 index 0000000000..8f9213c04f --- /dev/null +++ b/include/pinocchio/algorithm/constraints/joint-frictional-constraint.hpp @@ -0,0 +1,461 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_frictional_joint_constraint_hpp__ +#define __pinocchio_algorithm_constraints_frictional_joint_constraint_hpp__ + +#include "pinocchio/math/fwd.hpp" + +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/box-set.hpp" +#include "pinocchio/algorithm/constraints/jointwise-constraint-base.hpp" +#include "pinocchio/algorithm/constraints/constraint-data-base.hpp" +#include "pinocchio/algorithm/constraints/constraint-model-common-parameters.hpp" + +namespace pinocchio +{ + + template + struct CastType> + { + typedef FrictionalJointConstraintModelTpl type; + }; + + template + struct traits> + { + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + + static constexpr ConstraintFormulationLevel constraint_formulation_level = + ConstraintFormulationLevel::VELOCITY_LEVEL; + static constexpr bool has_baumgarte_corrector = false; + static constexpr bool has_baumgarte_corrector_vector = false; + + typedef FrictionalJointConstraintModelTpl ConstraintModel; + typedef FrictionalJointConstraintDataTpl ConstraintData; + typedef BoxSetTpl ConstraintSet; + + typedef ConstraintModel Model; + typedef ConstraintData Data; + + typedef Eigen::Matrix VectorXs; + typedef Eigen::Matrix JacobianMatrixType; + typedef VectorXs VectorConstraintSize; + + typedef VectorXs ComplianceVectorType; + typedef ComplianceVectorType & ComplianceVectorTypeRef; + typedef const ComplianceVectorType & ComplianceVectorTypeConstRef; + + typedef ComplianceVectorTypeRef ActiveComplianceVectorTypeRef; + typedef ComplianceVectorTypeConstRef ActiveComplianceVectorTypeConstRef; + + typedef Eigen::Matrix BaumgarteVectorType; // empty vector + typedef BaumgarteCorrectorVectorParametersTpl + BaumgarteCorrectorVectorParameters; + typedef BaumgarteCorrectorVectorParameters & BaumgarteCorrectorVectorParametersRef; + typedef const BaumgarteCorrectorVectorParameters & BaumgarteCorrectorVectorParametersConstRef; + + template + struct JacobianMatrixProductReturnType + { + typedef typename InputMatrix::Scalar Scalar; + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(InputMatrix) InputMatrixPlain; + typedef Eigen:: + Matrix + type; + }; + + template + struct JacobianTransposeMatrixProductReturnType + { + typedef typename InputMatrix::Scalar Scalar; + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(InputMatrix) InputMatrixPlain; + typedef Eigen::Matrix< + Scalar, + Eigen::Dynamic, + InputMatrixPlain::ColsAtCompileTime, + InputMatrixPlain::Options> + type; + }; + }; + + template + struct traits> + : traits> + { + }; + + template + struct FrictionalJointConstraintModelTpl + : JointWiseConstraintModelBase> + , ConstraintModelCommonParameters> + { + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + + typedef FrictionalJointConstraintModelTpl Self; + typedef JointWiseConstraintModelBase Base; + typedef ConstraintModelCommonParameters BaseCommonParameters; + typedef ConstraintModelBase RootBase; + + template + friend struct FrictionalJointConstraintModelTpl; + + static const ConstraintFormulationLevel constraint_formulation_level = + traits::constraint_formulation_level; + typedef typename traits::ComplianceVectorTypeRef ComplianceVectorTypeRef; + typedef typename traits::ComplianceVectorTypeConstRef ComplianceVectorTypeConstRef; + typedef typename traits::ActiveComplianceVectorTypeRef ActiveComplianceVectorTypeRef; + typedef + typename traits::ActiveComplianceVectorTypeConstRef ActiveComplianceVectorTypeConstRef; + typedef typename traits::ComplianceVectorType ComplianceVectorType; + + typedef FrictionalJointConstraintDataTpl ConstraintData; + typedef BoxSetTpl ConstraintSet; + + using RootBase::jacobian; + using typename Base::BooleanVector; + using typename Base::EigenIndexVector; + + typedef std::vector VectorOfBooleanVector; + typedef std::vector VectofOfEigenIndexVector; + typedef std::vector JointIndexVector; + typedef Eigen::Matrix VectorXs; + typedef VectorXs VectorConstraintSize; + + FrictionalJointConstraintModelTpl() + { + } + + template class JointCollectionTpl> + FrictionalJointConstraintModelTpl( + const ModelTpl & model, + const JointIndexVector & active_joints) + : active_joints(active_joints) + { + init(model, active_joints); + } + + /// \brief Cast operator + template + typename CastType::type cast() const + { + typedef typename CastType::type ReturnType; + ReturnType res; + Base::cast(res); + BaseCommonParameters::template cast(res); + + res.active_joints = active_joints; + res.active_dofs = active_dofs; + res.row_sparsity_pattern = row_sparsity_pattern; + res.row_active_indexes = row_active_indexes; + + res.m_set = m_set.template cast(); + return res; + } + + ConstraintData createData() const + { + return ConstraintData(*this); + } + + int size() const + { + return int(active_dofs.size()); + } + + int activeSize() const + { + return size(); + } + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + BaseCommonParameters & base_common_parameters() + { + return static_cast(*this); + } + const BaseCommonParameters & base_common_parameters() const + { + return static_cast(*this); + } + + template class JointCollectionTpl> + void calc( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata) const + { + PINOCCHIO_UNUSED_VARIABLE(model); + PINOCCHIO_UNUSED_VARIABLE(data); + PINOCCHIO_UNUSED_VARIABLE(cdata); + } + + template class JointCollectionTpl, typename JacobianMatrix> + void jacobian( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata, + const Eigen::MatrixBase & _jacobian_matrix) const; + + template class JointCollectionTpl> + typename traits::template JacobianMatrixProductReturnType::type + jacobianMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat) const + { + typedef typename traits::template JacobianMatrixProductReturnType::type + ReturnType; + ReturnType res(size(), mat.cols()); + jacobianMatrixProduct(model, data, cdata, mat.derived(), res); + return res; + } + + template< + typename InputMatrix, + typename OutputMatrix, + template class JointCollectionTpl, + AssignmentOperatorType op = SETTO> + void jacobianMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat, + const Eigen::MatrixBase & _res, + AssignmentOperatorTag aot = SetTo()) const; + + template class JointCollectionTpl> + typename traits::template JacobianTransposeMatrixProductReturnType::type + jacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat) const + { + typedef + typename traits::template JacobianTransposeMatrixProductReturnType::type + ReturnType; + ReturnType res(model.nv, mat.cols()); + jacobianTransposeMatrixProduct(model, data, cdata, mat.derived(), res); + return res; + } + + template< + typename InputMatrix, + typename OutputMatrix, + template class JointCollectionTpl, + AssignmentOperatorType op = SETTO> + void jacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat, + const Eigen::MatrixBase & _res, + AssignmentOperatorTag aot = SetTo()) const; + + /// \brief Returns the sparsity associated with a given row + const BooleanVector & getRowActivableSparsityPattern(const Eigen::DenseIndex row_id) const + { + PINOCCHIO_CHECK_INPUT_ARGUMENT(row_id < size()); + return row_sparsity_pattern[size_t(row_id)]; + } + + /// \brief Returns the sparsity associated with a given row + const BooleanVector & getRowActiveSparsityPattern(const Eigen::DenseIndex row_id) const + { + return getRowActivableSparsityPattern(row_id); + } + + /// \brief Returns the vector of the active indexes associated with a given row + const EigenIndexVector & getRowActivableIndexes(const Eigen::DenseIndex row_id) const + { + PINOCCHIO_CHECK_INPUT_ARGUMENT(row_id < size()); + return row_active_indexes[size_t(row_id)]; + } + // row_active_indexes[size_t(row_id)] + + /// \brief Returns the vector of the active indexes associated with a given row + const EigenIndexVector & getRowActiveIndexes(const Eigen::DenseIndex row_id) const + { + return getRowActivableIndexes(row_id); + } + + /// \brief Returns the compliance internally stored in the constraint model + ActiveComplianceVectorTypeConstRef getActiveCompliance_impl() const + { + return this->compliance(); + } + + /// \brief Returns the compliance internally stored in the constraint model + ActiveComplianceVectorTypeRef getActiveCompliance_impl() + { + return this->compliance(); + } + + /// \brief Returns the vector of active joints + const JointIndexVector & getActiveJoints() const + { + return active_joints; + } + + /// \brief Returns the vector of active rows + const EigenIndexVector & getActiveDofs() const + { + return active_dofs; + } + + const ConstraintSet & set() const + { + return m_set; + } + + ConstraintSet & set() + { + return m_set; + } + + template< + template class JointCollectionTpl, + typename VectorNLike, + ReferenceFrame rf> + void appendCouplingConstraintInertias( + const ModelTpl & model, + DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & diagonal_constraint_inertia, + const ReferenceFrameTag reference_frame) const; + + /// \copydoc Base::mapConstraintForcesToJointTorques + template< + template class JointCollectionTpl, + typename ConstraintForcesLike, + typename JointTorquesLike> + void mapConstraintForceToJointTorques( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & constraint_forces, + const Eigen::MatrixBase & joint_torques) const; + + /// \copydoc Base::mapJointMotionsToConstraintMotions + template< + template class JointCollectionTpl, + typename JointMotionsLike, + typename ConstraintMotionsLike> + void mapJointMotionsToConstraintMotion( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & joint_motions, + const Eigen::MatrixBase & constraint_motions) const; + + /// + ///  \brief Comparison operator + /// + /// \param[in] other Other FrictionalJointConstraintModelTpl to compare with. + /// + /// \returns true if the two *this is equal to other (type, joint1_id and placement attributs + /// must be the same). + /// + bool operator==(const FrictionalJointConstraintModelTpl & other) const + { + if (this == &other) + return true; + return base() == other.base() && base_common_parameters() == other.base_common_parameters() + && active_dofs == other.active_dofs + && row_sparsity_pattern == other.row_sparsity_pattern + && row_active_indexes == other.row_active_indexes && m_set == other.m_set; + } + + static std::string classname() + { + return std::string("FrictionalJointConstraintModel"); + } + std::string shortname() const + { + return classname(); + } + + bool operator!=(const FrictionalJointConstraintModelTpl & other) const + { + return !(*this == other); + } + + protected: + template class JointCollectionTpl> + void init( + const ModelTpl & model, + const JointIndexVector & active_joints); + + JointIndexVector active_joints; + EigenIndexVector active_dofs; + VectorOfBooleanVector row_sparsity_pattern; + VectofOfEigenIndexVector row_active_indexes; + + ConstraintSet m_set; + using BaseCommonParameters::m_compliance; + }; + + template + struct FrictionalJointConstraintDataTpl + : ConstraintDataBase> + { + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + typedef ConstraintDataBase Base; + typedef std::vector JointIndexVector; + + typedef FrictionalJointConstraintModelTpl ConstraintModel; + + FrictionalJointConstraintDataTpl() + { + } + + explicit FrictionalJointConstraintDataTpl(const ConstraintModel & /*constraint_model*/) + { + } + + bool operator==(const FrictionalJointConstraintDataTpl & /*other*/) const + { + return true; + } + + bool operator!=(const FrictionalJointConstraintDataTpl & other) const + { + return !(*this == other); + } + + static std::string classname() + { + return std::string("FrictionalJointConstraintData"); + } + std::string shortname() const + { + return classname(); + } + }; +} // namespace pinocchio + +#include "pinocchio/algorithm/constraints/joint-frictional-constraint.hxx" + +#endif // ifndef __pinocchio_algorithm_constraints_frictional_joint_constraint_hpp__ diff --git a/include/pinocchio/algorithm/constraints/joint-frictional-constraint.hxx b/include/pinocchio/algorithm/constraints/joint-frictional-constraint.hxx new file mode 100644 index 0000000000..c85d48d35a --- /dev/null +++ b/include/pinocchio/algorithm/constraints/joint-frictional-constraint.hxx @@ -0,0 +1,270 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_frictional_joint_constraint_hxx__ +#define __pinocchio_algorithm_constraints_frictional_joint_constraint_hxx__ + +namespace pinocchio +{ + template + template class JointCollectionTpl> + void FrictionalJointConstraintModelTpl::init( + const ModelTpl & model, + const JointIndexVector & active_joints) + { + active_dofs.reserve(size_t(model.nv)); + for (const JointIndex joint_id : active_joints) + { + PINOCCHIO_CHECK_INPUT_ARGUMENT( + joint_id < model.joints.size(), + "joint_id is larger than the total number of joints contained in the model."); + const auto & jsupport = model.supports[joint_id]; + + const auto nv = model.nvs[joint_id]; + const auto idx_v = model.idx_vs[joint_id]; + + for (int k = 0; k < nv; ++k) + { + const int row_id = idx_v + k; + active_dofs.push_back(row_id); + } + + EigenIndexVector extended_support; + extended_support.reserve(size_t(model.nv)); + for (size_t j = 1; j < jsupport.size() - 1; ++j) + { + const JointIndex jsupport_id = jsupport[j]; + + const int jsupport_nv = model.nvs[jsupport_id]; + const int jsupport_idx_v = model.idx_vs[jsupport_id]; + + for (int k = 0; k < jsupport_nv; ++k) + { + const int extended_row_id = jsupport_idx_v + k; + extended_support.push_back(extended_row_id); + } + } + + for (int k = 0; k < nv; ++k) + { + const int row_id = idx_v + k; + extended_support.push_back(row_id); + row_active_indexes.push_back(extended_support); + } + } + + const size_t total_size = active_dofs.size(); + assert( + row_active_indexes.size() == total_size && "The two vectors should be of the same size."); + + // Fill row_sparsity_pattern from row_active_indexes content + row_sparsity_pattern.resize(total_size, BooleanVector::Zero(model.nv)); + for (size_t row_id = 0; row_id < total_size; ++row_id) + { + auto & sparsity_pattern = row_sparsity_pattern[row_id]; + const auto & extended_support = row_active_indexes[row_id]; + + for (const auto val : extended_support) + sparsity_pattern[val] = true; + } + + m_compliance = ComplianceVectorType::Zero(activeSize()); + m_set = ConstraintSet(activeSize()); + } + + template + template class JointCollectionTpl, typename JacobianMatrix> + void FrictionalJointConstraintModelTpl::jacobian( + const ModelTpl & model, + const DataTpl & /*data*/, + ConstraintData & /*cdata*/, + const Eigen::MatrixBase & _jacobian_matrix) const + { + JacobianMatrix & jacobian_matrix = _jacobian_matrix.const_cast_derived(); + + const FrictionalJointConstraintModelTpl & cmodel = *this; + PINOCCHIO_CHECK_ARGUMENT_SIZE( + jacobian_matrix.rows(), cmodel.activeSize(), + "The input/output Jacobian matrix does not have the right number of rows."); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + jacobian_matrix.cols(), model.nv, + "The input/output Jacobian matrix does not have the right number of cols."); + + jacobian_matrix.setZero(); + for (size_t row_id = 0; row_id < active_dofs.size(); ++row_id) + { + const auto col_id = active_dofs[row_id]; + jacobian_matrix(Eigen::DenseIndex(row_id), col_id) = Scalar(1); + } + } + + template + template< + typename InputMatrix, + typename OutputMatrix, + template class JointCollectionTpl, + AssignmentOperatorType op> + void FrictionalJointConstraintModelTpl::jacobianMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat, + const Eigen::MatrixBase & _res, + AssignmentOperatorTag aot) const + { + OutputMatrix & res = _res.const_cast_derived(); + + PINOCCHIO_CHECK_ARGUMENT_SIZE(mat.rows(), model.nv); + PINOCCHIO_CHECK_ARGUMENT_SIZE(mat.cols(), res.cols()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res.rows(), activeSize()); + PINOCCHIO_UNUSED_VARIABLE(data); + PINOCCHIO_UNUSED_VARIABLE(cdata); + PINOCCHIO_UNUSED_VARIABLE(aot); + + if (std::is_same, SetTo>::value) + res.setZero(); + + for (size_t row_id = 0; row_id < active_dofs.size(); ++row_id) + { + const auto col_id = active_dofs[row_id]; + + if (std::is_same, RmTo>::value) + res.row(Eigen::DenseIndex(row_id)) -= mat.row(col_id); + else + res.row(Eigen::DenseIndex(row_id)) += mat.row(col_id); + } + } + + template + template< + typename InputMatrix, + typename OutputMatrix, + template class JointCollectionTpl, + AssignmentOperatorType op> + void FrictionalJointConstraintModelTpl::jacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat, + const Eigen::MatrixBase & _res, + AssignmentOperatorTag aot) const + { + OutputMatrix & res = _res.const_cast_derived(); + + PINOCCHIO_CHECK_ARGUMENT_SIZE(mat.rows(), activeSize()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res.cols(), mat.cols()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res.rows(), model.nv); + PINOCCHIO_UNUSED_VARIABLE(data); + PINOCCHIO_UNUSED_VARIABLE(cdata); + PINOCCHIO_UNUSED_VARIABLE(aot); + + if (std::is_same, SetTo>::value) + res.setZero(); + + for (size_t row_id = 0; row_id < active_dofs.size(); ++row_id) + { + const auto col_id = active_dofs[row_id]; + + if (std::is_same, RmTo>::value) + res.row(col_id) -= mat.row(Eigen::DenseIndex(row_id)); + else + res.row(col_id) += mat.row(Eigen::DenseIndex(row_id)); + } + } + + template + template< + template class JointCollectionTpl, + typename VectorNLike, + ReferenceFrame rf> + void FrictionalJointConstraintModelTpl::appendCouplingConstraintInertias( + const ModelTpl & model, + DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & diagonal_constraint_inertia, + const ReferenceFrameTag reference_frame) const + { + PINOCCHIO_UNUSED_VARIABLE(cdata); + PINOCCHIO_UNUSED_VARIABLE(reference_frame); + + PINOCCHIO_CHECK_ARGUMENT_SIZE( + diagonal_constraint_inertia.size(), activeSize(), + "The diagonal_constraint_inertia is of wrong size."); + + typedef DataTpl Data; + using Matrix6 = typename Data::Inertia::Matrix6; + + Eigen::DenseIndex row_id = 0; + Matrix6 SI; + for (const JointIndex joint_id : active_joints) + { + const auto joint_nv = model.nvs[joint_id]; + const auto joint_idx_v = model.idx_vs[joint_id]; + const auto joint_diagonal_constraint_inertia = + diagonal_constraint_inertia.segment(row_id, joint_nv); + + data.joint_apparent_inertia.segment(joint_idx_v, joint_nv) += + joint_diagonal_constraint_inertia; + + row_id += joint_nv; + } + } + + template + template< + template class JointCollectionTpl, + typename ConstraintForcesLike, + typename JointTorquesLike> + void FrictionalJointConstraintModelTpl::mapConstraintForceToJointTorques( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & constraint_forces, + const Eigen::MatrixBase & joint_torques_) const + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_forces.rows(), activeSize()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(joint_torques_.rows(), model.nv); + PINOCCHIO_UNUSED_VARIABLE(data); + PINOCCHIO_UNUSED_VARIABLE(cdata); + + auto & joint_torques = joint_torques_.const_cast_derived(); + + for (size_t dof_id = 0; dof_id < active_dofs.size(); ++dof_id) + { + const auto row_id = active_dofs[dof_id]; + + joint_torques.row(row_id) += constraint_forces.row(Eigen::DenseIndex(dof_id)); + } + } + + template + template< + template class JointCollectionTpl, + typename JointMotionsLike, + typename ConstraintMotionsLike> + void FrictionalJointConstraintModelTpl::mapJointMotionsToConstraintMotion( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & joint_motions, + const Eigen::MatrixBase & constraint_motions_) const + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_motions_.rows(), activeSize()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(joint_motions.rows(), model.nv); + PINOCCHIO_UNUSED_VARIABLE(data); + PINOCCHIO_UNUSED_VARIABLE(cdata); + + auto & constraint_motions = constraint_motions_.const_cast_derived(); + + for (size_t dof_id = 0; dof_id < active_dofs.size(); ++dof_id) + { + const auto row_id = active_dofs[dof_id]; + + constraint_motions.row(Eigen::DenseIndex(dof_id)) = joint_motions.row(row_id); + } + } + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_frictional_joint_constraint_hxx__ diff --git a/include/pinocchio/algorithm/constraints/joint-limit-constraint-cone.hpp b/include/pinocchio/algorithm/constraints/joint-limit-constraint-cone.hpp new file mode 100644 index 0000000000..2122198223 --- /dev/null +++ b/include/pinocchio/algorithm/constraints/joint-limit-constraint-cone.hpp @@ -0,0 +1,176 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_joint_limit_constraint_set_hpp__ +#define __pinocchio_algorithm_constraints_joint_limit_constraint_set_hpp__ + +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/orthant-cone.hpp" + +namespace pinocchio +{ + + template + struct JointLimitConstraintConeTpl; + + template + struct CastType> + { + typedef JointLimitConstraintConeTpl type; + }; + + template + struct traits> + { + typedef _Scalar Scalar; + typedef JointLimitConstraintConeTpl DualCone; + }; + + template + struct JointLimitConstraintConeTpl : ConeBase> + { + typedef _Scalar Scalar; + typedef ConeBase Base; + typedef typename traits::DualCone DualCone; + + typedef PositiveOrthantConeTpl PositiveOrthantCone; + typedef NegativeOrthantConeTpl NegativeOrthantCone; + typedef Eigen::Matrix Vector; + + using Base::project; + + JointLimitConstraintConeTpl() = default; + + JointLimitConstraintConeTpl( + const Eigen::DenseIndex negative_orthant_size, const Eigen::DenseIndex positive_orthant_size) + : negative_orthant(negative_orthant_size) + , positive_orthant(positive_orthant_size) + { + } + + void resize( + const Eigen::DenseIndex negative_orthant_size, const Eigen::DenseIndex positive_orthant_size) + { + negative_orthant.resize(negative_orthant_size); + positive_orthant.resize(positive_orthant_size); + } + + void conservativeResize( + const Eigen::DenseIndex negative_orthant_size, const Eigen::DenseIndex positive_orthant_size) + { + negative_orthant.conservativeResize(negative_orthant_size); + positive_orthant.conservativeResize(positive_orthant_size); + } + + /// \brief Cast operator + template + JointLimitConstraintConeTpl cast() const + { + typedef JointLimitConstraintConeTpl ReturnType; + return ReturnType(negative_orthant.size(), positive_orthant.size()); + } + + /// \brief Returns the dual cone associated with this. + /// + /// \remarks Orthant cones are by definition self dual. + DualCone dual() const + { + return JointLimitConstraintConeTpl(*this); + } + + /// \brief Returns the dimension of the box. + Eigen::DenseIndex dim() const + { + return negative_orthant.size() + positive_orthant.size(); + } + + Eigen::DenseIndex size() const + { + return dim(); + } + + /// \brief Comparison operator + bool operator==(const JointLimitConstraintConeTpl & other) const + { + return base() == other.base() && negative_orthant == other.negative_orthant + && positive_orthant == other.positive_orthant; + } + + /// \brief Difference operator + bool operator!=(const JointLimitConstraintConeTpl & other) const + { + return !(*this == other); + } + + /// \brief Check whether a vector x lies within the orthant. + /// + /// \param[in] x vector to check . + /// + template + bool isInside(const Eigen::MatrixBase & x, const Scalar prec = Scalar(0)) const + { + assert(x.size() == size()); + return negative_orthant.isInside(x.head(negative_orthant.size()), prec) + && positive_orthant.isInside(x.tail(positive_orthant.size()), prec); + } + + /// \brief Project a vector x into orthant. + /// + /// \param[in] x a vector to project. + /// \param[in] res result of the projection. + /// + template + void project( + const Eigen::MatrixBase & x, + const Eigen::MatrixBase & res_) const + { + auto & res = res_.const_cast_derived(); + negative_orthant.project(x.head(negative_orthant.size()), res.head(negative_orthant.size())); + positive_orthant.project(x.tail(positive_orthant.size()), res.tail(positive_orthant.size())); + } + + /// \brief Project the value given as input for the given row index. + Scalar rowiseProject(const Eigen::DenseIndex row_id, const Scalar value) const + { + assert(row_id < size()); + if (row_id < negative_orthant.size()) + { + return negative_orthant.rowiseProject(row_id, value); + } + else + { + return positive_orthant.rowiseProject(row_id - negative_orthant.size(), value); + } + } + + /// \brief Returns a const reference to the negative orthant. + /// + const NegativeOrthantCone & getNegativeOrthant() const + { + return negative_orthant; + } + + /// \brief Returns a const reference to the positive orthant. + /// + const PositiveOrthantCone & getPositiveOrthant() const + { + return positive_orthant; + } + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + protected: + NegativeOrthantCone negative_orthant; + PositiveOrthantCone positive_orthant; + }; +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_joint_limit_constraint_set_hpp__ diff --git a/include/pinocchio/algorithm/constraints/joint-limit-constraint.hpp b/include/pinocchio/algorithm/constraints/joint-limit-constraint.hpp new file mode 100644 index 0000000000..260ce8b5ee --- /dev/null +++ b/include/pinocchio/algorithm/constraints/joint-limit-constraint.hpp @@ -0,0 +1,721 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_joint_limit_constraint_hpp__ +#define __pinocchio_algorithm_constraints_joint_limit_constraint_hpp__ + +#include "pinocchio/math/fwd.hpp" + +#include + +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/joint-limit-constraint-cone.hpp" +#include "pinocchio/algorithm/constraints/jointwise-constraint-base.hpp" +#include "pinocchio/algorithm/constraints/constraint-data-base.hpp" +#include "pinocchio/algorithm/constraints/constraint-model-common-parameters.hpp" +#include "pinocchio/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp" +#include "pinocchio/algorithm/constraints/baumgarte-corrector-parameters.hpp" +#include "pinocchio/container/storage.hpp" + +namespace pinocchio +{ + + template + struct CastType> + { + typedef JointLimitConstraintModelTpl type; + }; + + template + struct traits> + { + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + + static constexpr ConstraintFormulationLevel constraint_formulation_level = + ConstraintFormulationLevel::POSITION_LEVEL; + static constexpr bool has_baumgarte_corrector = true; + static constexpr bool has_baumgarte_corrector_vector = false; + + typedef JointLimitConstraintModelTpl ConstraintModel; + typedef JointLimitConstraintDataTpl ConstraintData; + typedef JointLimitConstraintConeTpl ConstraintSet; + + typedef ConstraintModel Model; + typedef ConstraintData Data; + + typedef Eigen::Matrix VectorXs; + typedef Eigen::Matrix JacobianMatrixType; + typedef VectorXs VectorConstraintSize; + + typedef VectorXs ComplianceVectorType; + typedef ComplianceVectorType & ComplianceVectorTypeRef; + typedef const ComplianceVectorType & ComplianceVectorTypeConstRef; + + typedef EigenStorageTpl EigenStorageVector; + typedef typename EigenStorageVector::RefMapType ActiveComplianceVectorTypeRef; + typedef typename EigenStorageVector::ConstRefMapType ActiveComplianceVectorTypeConstRef; + + typedef VectorXs BaumgarteVectorType; + typedef BaumgarteCorrectorVectorParametersTpl + BaumgarteCorrectorVectorParameters; + typedef BaumgarteCorrectorVectorParameters & BaumgarteCorrectorVectorParametersRef; + typedef const BaumgarteCorrectorVectorParameters & BaumgarteCorrectorVectorParametersConstRef; + + template + struct JacobianMatrixProductReturnType + { + typedef typename InputMatrix::Scalar Scalar; + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(InputMatrix) InputMatrixPlain; + typedef Eigen:: + Matrix + type; + }; + + template + struct JacobianTransposeMatrixProductReturnType + { + typedef typename InputMatrix::Scalar Scalar; + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(InputMatrix) InputMatrixPlain; + typedef Eigen::Matrix< + Scalar, + Eigen::Dynamic, + InputMatrixPlain::ColsAtCompileTime, + InputMatrixPlain::Options> + type; + }; + }; + + template + struct traits> + : traits> + { + }; + + template + struct JointLimitConstraintModelTpl + : JointWiseConstraintModelBase> + , ConstraintModelCommonParameters> + { + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + + typedef JointLimitConstraintModelTpl Self; + typedef JointWiseConstraintModelBase Base; + typedef ConstraintModelBase RootBase; + + typedef ConstraintModelCommonParameters BaseCommonParameters; + + template + friend struct JointLimitConstraintModelTpl; + + static const ConstraintFormulationLevel constraint_formulation_level = + traits::constraint_formulation_level; + typedef typename traits::ComplianceVectorType ComplianceVectorType; + typedef typename traits::EigenStorageVector EigenStorageVector; + typedef typename traits::ActiveComplianceVectorTypeRef ActiveComplianceVectorTypeRef; + typedef + typename traits::ActiveComplianceVectorTypeConstRef ActiveComplianceVectorTypeConstRef; + typedef + typename traits::BaumgarteCorrectorVectorParameters BaumgarteCorrectorVectorParameters; + typedef BaumgarteCorrectorParametersTpl BaumgarteCorrectorParameters; + + typedef JointLimitConstraintDataTpl ConstraintData; + typedef JointLimitConstraintConeTpl ConstraintSet; + typedef BoxSetTpl BoxSet; + + using RootBase::jacobian; + using typename Base::BooleanVector; + using typename Base::EigenIndexVector; + + typedef std::vector VectorOfBooleanVector; + typedef std::vector VectofOfEigenIndexVector; + typedef std::vector VectorOfSize; + typedef std::vector JointIndexVector; + typedef Eigen::Matrix VectorXs; + typedef VectorXs VectorConstraintSize; + typedef Eigen::Matrix + CompactTangentMap_t; + + JointLimitConstraintModelTpl() + : active_compliance(active_compliance_storage.map()) + { + } + + JointLimitConstraintModelTpl(const JointLimitConstraintModelTpl & other) + : active_compliance(active_compliance_storage.map()) + { + *this = other; + } + + template class JointCollectionTpl> + JointLimitConstraintModelTpl( + const ModelTpl & model, + const JointIndexVector & _activable_joints) + : active_compliance(active_compliance_storage.map()) + { + init( + model, _activable_joints, model.lowerPositionLimit, model.upperPositionLimit, + model.positionLimitMargin); + } + + template< + template class JointCollectionTpl, + typename VectorLowerConfiguration, + typename VectorUpperConfiguration> + JointLimitConstraintModelTpl( + const ModelTpl & model, + const JointIndexVector & _activable_joints, + const Eigen::MatrixBase & lb, + const Eigen::MatrixBase & ub) + : active_compliance(active_compliance_storage.map()) + { + init(model, _activable_joints, lb, ub, model.positionLimitMargin); + } + + template< + template class JointCollectionTpl, + typename VectorLowerConfiguration, + typename VectorUpperConfiguration, + typename VectorMarginConfiguration> + JointLimitConstraintModelTpl( + const ModelTpl & model, + const JointIndexVector & _activable_joints, + const Eigen::MatrixBase & lb, + const Eigen::MatrixBase & ub, + const Eigen::MatrixBase & marg) + : active_compliance(active_compliance_storage.map()) + { + init(model, _activable_joints, lb, ub, marg); + } + + /// \brief Cast operator + template + typename CastType::type cast() const + { + typedef typename CastType::type ReturnType; + ReturnType res; + Base::cast(res); + BaseCommonParameters::template cast(res); + + res.activable_joints = activable_joints; + res.nq_reduce = nq_reduce; + res.nv_max_atom = nv_max_atom; + res.lower_activable_size = lower_activable_size; + res.lower_active_size = lower_active_size; + res.row_sparsity_pattern = row_sparsity_pattern; + res.row_indexes = row_indexes; + res.bound_position_limit = bound_position_limit.template cast(); + res.bound_position_margin = bound_position_margin.template cast(); + res.activable_idx_qs = activable_idx_qs; + res.active_set_indexes = active_set_indexes; + res.activable_idx_rows = activable_idx_rows; + res.activable_idx_qs_reduce = activable_idx_qs_reduce; + res.activable_nvs = activable_nvs; + res.activable_idx_vs = activable_idx_vs; + res.active_idx_rows = active_idx_rows; + res.active_idx_qs_reduce = active_idx_qs_reduce; + res.active_nvs = active_nvs; + res.active_idx_vs = active_idx_vs; + res.m_set = m_set.template cast(); + res.active_compliance_storage = active_compliance_storage.template cast(); + res.active_compliance = res.active_compliance_storage.map(); + + return res; + } + + ConstraintData createData() const + { + return ConstraintData(*this); + } + + int size() const + { + return int(activable_idx_rows.size()); + } + + int activeSize() const + { + return int(active_idx_rows.size()); + } + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + BaseCommonParameters & base_common_parameters() + { + return static_cast(*this); + } + const BaseCommonParameters & base_common_parameters() const + { + return static_cast(*this); + } + + /// \brief Resize the constraint by computing the current active set. + template class JointCollectionTpl> + void resize_impl( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata); + + /// \brief Compute the constraint residual for the active constraints. It assumes that the + /// active set has been computed by calling `resize` beforehand. + template class JointCollectionTpl> + void calc( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata) const; + + /// \brief Returns the sparsity associated with a given row + const BooleanVector & getRowActivableSparsityPattern(const Eigen::DenseIndex row_id) const + { + PINOCCHIO_CHECK_INPUT_ARGUMENT(row_id < size()); + return row_sparsity_pattern[activable_idx_rows[static_cast(row_id)]]; + } + + /// \brief Returns the sparsity associated with a given row + /// This vector is computed when calling the calc method. + const BooleanVector & getRowActiveSparsityPattern(const Eigen::DenseIndex row_id) const + { + PINOCCHIO_CHECK_INPUT_ARGUMENT(row_id < activeSize()); + return row_sparsity_pattern[active_idx_rows[static_cast(row_id)]]; + } + + /// \brief Returns the vector of the activable indexes associated with a given row + const EigenIndexVector & getRowActivableIndexes(const Eigen::DenseIndex row_id) const + { + PINOCCHIO_CHECK_INPUT_ARGUMENT(row_id < size()); + return row_indexes[activable_idx_rows[static_cast(row_id)]]; + } + + /// \brief Returns the vector of the active indexes associated with a given row + /// This vector is computed when calling the calc method. + const EigenIndexVector & getRowActiveIndexes(const Eigen::DenseIndex row_id) const + { + PINOCCHIO_CHECK_INPUT_ARGUMENT(row_id < activeSize()); + return row_indexes[active_idx_rows[static_cast(row_id)]]; + } + + /// \brief Returns the compliance internally stored in the constraint model + ActiveComplianceVectorTypeConstRef getActiveCompliance_impl() const + { + return active_compliance; + } + + /// \brief Returns the compliance internally stored in the constraint model + ActiveComplianceVectorTypeRef getActiveCompliance_impl() + { + return active_compliance; + } + + const ConstraintSet & set() const + { + return m_set; + } + + ConstraintSet & set() + { + return m_set; + } + + template< + template class JointCollectionTpl, + typename VectorNLike, + ReferenceFrame rf> + void appendCouplingConstraintInertias( + const ModelTpl & model, + DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & diagonal_constraint_inertia, + const ReferenceFrameTag reference_frame) const; + + /// \brief Returns the vector of the active indexes associated with a given row + /// This vector is computed when calling the calc method. + const VectorOfSize & getActiveSetIndexes() const + { + return active_set_indexes; + } + + /// Specialized accessor + + const JointIndexVector & getActivableJoints() const + { + return activable_joints; + } + int getNqReduce() const + { + return nq_reduce; + } + int getNvMaxAtom() const + { + return nv_max_atom; + } + int lowerSize() const + { + return lower_activable_size; + } + int lowerActiveSize() const + { + return lower_active_size; + } + int upperSize() const + { + return size() - lowerSize(); + } + int upperActiveSize() const + { + return activeSize() - lowerActiveSize(); + } + + const VectorXs & getBoundPositionLimit() const + { + return bound_position_limit; + } + const VectorXs & getBoundPositionMargin() const + { + return bound_position_margin; + } + + const EigenIndexVector & getActivableIdxQs() const + { + return activable_idx_qs; + } + + const EigenIndexVector & getActivableIdxQsReduce() const + { + return activable_idx_qs_reduce; + } + const EigenIndexVector & getActiveIdxQsReduce() const + { + return active_idx_qs_reduce; + } + const EigenIndexVector & getActivableNvs() const + { + return activable_nvs; + } + const EigenIndexVector & getActiveNvs() const + { + return active_nvs; + } + const EigenIndexVector & getActivableIdxVs() const + { + return activable_idx_vs; + } + const EigenIndexVector & getActiveIdxVs() const + { + return active_idx_vs; + } + + // row_sparsity_pattern, row_indexes, activable_idx_rows, active_idx_rows are + // not exposed as they only privately allow getRowActiv[e/able]SparsityPattern and + // getRowActiv[e/able]Indexes + + /// + ///  \brief Comparison operator + /// + /// \param[in] other Other FrictionalJointConstraintModelTpl to compare with. + /// + /// \returns true if the two *this is equal to other (type, joint1_id and placement attributs + /// must be the same). + /// + bool operator==(const JointLimitConstraintModelTpl & other) const + { + return base() == other.base() && base_common_parameters() == other.base_common_parameters() + && activable_joints == other.activable_joints && nq_reduce == other.nq_reduce + && nv_max_atom == other.nv_max_atom + && lower_activable_size == other.lower_activable_size + && lower_active_size == other.lower_active_size + && row_sparsity_pattern == other.row_sparsity_pattern + && row_indexes == other.row_indexes + && bound_position_limit == other.bound_position_limit + && bound_position_margin == other.bound_position_margin + && activable_idx_qs == other.activable_idx_qs + && active_set_indexes == other.active_set_indexes + && activable_idx_rows == other.activable_idx_rows + && activable_idx_qs_reduce == other.activable_idx_qs_reduce + && activable_nvs == other.activable_nvs && activable_idx_vs == other.activable_idx_vs + && active_idx_rows == other.active_idx_rows + && active_idx_qs_reduce == other.active_idx_qs_reduce && active_nvs == other.active_nvs + && active_idx_vs == other.active_idx_vs && m_set == other.m_set + && active_compliance_storage == other.active_compliance_storage + && active_compliance == other.active_compliance; + } + + bool operator!=(const JointLimitConstraintModelTpl & other) const + { + return !(*this == other); + } + + JointLimitConstraintModelTpl & operator=(const JointLimitConstraintModelTpl & other) + { + if (this != &other) + { + base_common_parameters() = other.base_common_parameters(); + activable_joints = other.activable_joints; + nq_reduce = other.nq_reduce; + nv_max_atom = other.nv_max_atom; + lower_activable_size = other.lower_activable_size; + lower_active_size = other.lower_active_size; + row_sparsity_pattern = other.row_sparsity_pattern; + row_indexes = other.row_indexes; + bound_position_limit = other.bound_position_limit; + bound_position_margin = other.bound_position_margin; + activable_idx_qs = other.activable_idx_qs; + active_set_indexes = other.active_set_indexes; + activable_idx_rows = other.activable_idx_rows; + activable_idx_qs_reduce = other.activable_idx_qs_reduce; + activable_nvs = other.activable_nvs; + activable_idx_vs = other.activable_idx_vs; + active_idx_rows = other.active_idx_rows; + active_idx_qs_reduce = other.active_idx_qs_reduce; + active_nvs = other.active_nvs; + active_idx_vs = other.active_idx_vs; + m_set = other.m_set; + active_compliance_storage = other.active_compliance_storage; + active_compliance = active_compliance_storage.map(); + } + return *this; + } + + // Jacobian operations + + template class JointCollectionTpl, typename JacobianMatrix> + void jacobian( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata, + const Eigen::MatrixBase & _jacobian_matrix) const; + + template class JointCollectionTpl> + typename traits::template JacobianMatrixProductReturnType::type + jacobianMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat) const + { + typedef typename traits::template JacobianMatrixProductReturnType::type + ReturnType; + ReturnType res(size(), mat.cols()); + jacobianMatrixProduct(model, data, cdata, mat.derived(), res); + return res; + } + + template< + typename InputMatrix, + typename OutputMatrix, + template class JointCollectionTpl, + AssignmentOperatorType op = SETTO> + void jacobianMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat, + const Eigen::MatrixBase & _res, + AssignmentOperatorTag aot = SetTo()) const; + + template class JointCollectionTpl> + typename traits::template JacobianTransposeMatrixProductReturnType::type + jacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat) const + { + typedef + typename traits::template JacobianTransposeMatrixProductReturnType::type + ReturnType; + ReturnType res(model.nv, mat.cols()); + jacobianTransposeMatrixProduct(model, data, cdata, mat.derived(), res); + return res; + } + + template< + typename InputMatrix, + typename OutputMatrix, + template class JointCollectionTpl, + AssignmentOperatorType op = SETTO> + void jacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat, + const Eigen::MatrixBase & _res, + AssignmentOperatorTag aot = SetTo()) const; + + public: + static std::string classname() + { + return std::string("JointLimitConstraintModel"); + } + std::string shortname() const + { + return classname(); + } + + protected: + template< + template class JointCollectionTpl, + typename VectorLowerConfiguration, + typename VectorUpperConfiguration, + typename VectorMarginConfiguration> + void init( + const ModelTpl & model, + const JointIndexVector & _activable_joints, + const Eigen::MatrixBase & lb, + const Eigen::MatrixBase & ub, + const Eigen::MatrixBase & marg); + + /// @brief List of joints that are concerned by the constraint. size nja + JointIndexVector activable_joints; + /// @brief nq size given the considered joints + /// nq_reduce = SUM(j in activable_joints) j.nq + int nq_reduce; + /// @brief maximum nv size off all atomic (even if there is some composite) in all + /// activable_joints + int nv_max_atom; + /// @brief number of lower bound limite activable and active + int lower_activable_size, lower_active_size; + + /// @brief Sparsity pattern for each considered joint. size nja + VectorOfBooleanVector row_sparsity_pattern; + VectofOfEigenIndexVector row_indexes; + + /// @brief Limit value of lower and upper bound in the constraint (size size()=lsize+usize) + VectorXs bound_position_limit; + /// @brief Margin value of lower and upper bound in the constraint (size size()=lsize+usize) + VectorXs bound_position_margin; + + /// @brief give for each activable constraint the qs in the configuration vector + EigenIndexVector activable_idx_qs; + + /// \brief Vector containing the indexes of the constraints in the active set. + /// the size of the vector is activeSize() + /// each element have value < size() + VectorOfSize active_set_indexes; + + /// @brief give for each active/activable constraint the row_id of sparsity pattern + VectorOfSize activable_idx_rows, active_idx_rows; + /// @brief give for each active/activable constraint of sparsity pattern + EigenIndexVector activable_idx_qs_reduce, active_idx_qs_reduce; + /// @brief For each dof, the associated nv and idx_v to exploit tangent map sparsity + EigenIndexVector activable_nvs, active_nvs; + EigenIndexVector activable_idx_vs, active_idx_vs; + + ConstraintSet m_set; + using BaseCommonParameters::m_baumgarte_parameters; + using BaseCommonParameters::m_compliance; + + /// \brief Compliance of the active constraints + EigenStorageVector active_compliance_storage; + typename EigenStorageVector::RefMapType active_compliance; + }; + + template + struct JointLimitConstraintDataTpl + : ConstraintDataBase> + { + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + typedef ConstraintDataBase Base; + typedef std::vector JointIndexVector; + + typedef JointLimitConstraintModelTpl ConstraintModel; + + typedef typename ConstraintModel::VectorXs VectorXs; + typedef typename ConstraintModel::CompactTangentMap_t CompactTangentMap_t; + typedef typename ConstraintModel::EigenStorageVector EigenStorageVector; + typedef typename ConstraintModel::Base::BooleanVector BooleanVector; + typedef typename ConstraintModel::Base::EigenIndexVector EigenIndexVector; + + typedef std::vector VectorOfBooleanVector; + typedef std::vector VectofOfEigenIndexVector; + + JointLimitConstraintDataTpl() + : constraint_residual(constraint_residual_storage.map()) + { + } + + JointLimitConstraintDataTpl(const JointLimitConstraintDataTpl & other) + : constraint_residual(constraint_residual_storage.map()) + { + *this = other; + } + + explicit JointLimitConstraintDataTpl(const ConstraintModel & constraint_model) + : compact_tangent_map( + CompactTangentMap_t::Zero(constraint_model.getNqReduce(), constraint_model.getNvMaxAtom())) + , activable_constraint_residual(constraint_model.size()) + , constraint_residual_storage(constraint_model.size()) + , constraint_residual(constraint_residual_storage.map()) + { + constraint_residual_storage.resize(0); + } + + bool operator==(const JointLimitConstraintDataTpl & other) const + { + if (this == &other) + return true; + return ( + this->compact_tangent_map == other.compact_tangent_map + && this->constraint_residual_storage == other.constraint_residual_storage + && this->constraint_residual == other.constraint_residual); + } + + bool operator!=(const JointLimitConstraintDataTpl & other) const + { + return !(*this == other); + } + + JointLimitConstraintDataTpl & operator=(const JointLimitConstraintDataTpl & other) + { + if (this != &other) + { + compact_tangent_map = other.compact_tangent_map; + activable_constraint_residual = other.activable_constraint_residual; + constraint_residual_storage = other.constraint_residual_storage; + constraint_residual = constraint_residual_storage.map(); + } + return *this; + } + + /// @brief Compact storage of the tangent map + CompactTangentMap_t compact_tangent_map; + + /// \brief Residual of all the activable constraints + VectorXs activable_constraint_residual; + + /// \brief Residual of the active constraints + EigenStorageVector constraint_residual_storage; + typename EigenStorageVector::RefMapType constraint_residual; + + static std::string classname() + { + return std::string("JointLimitConstraintData"); + } + std::string shortname() const + { + return classname(); + } + }; +} // namespace pinocchio + +#include "pinocchio/algorithm/constraints/joint-limit-constraint.hxx" + +#endif // ifndef __pinocchio_algorithm_constraints_joint_limit_constraint_hpp__ diff --git a/include/pinocchio/algorithm/constraints/joint-limit-constraint.hxx b/include/pinocchio/algorithm/constraints/joint-limit-constraint.hxx new file mode 100644 index 0000000000..ba1e710133 --- /dev/null +++ b/include/pinocchio/algorithm/constraints/joint-limit-constraint.hxx @@ -0,0 +1,473 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_joint_limit_constraint_hxx__ +#define __pinocchio_algorithm_constraints_joint_limit_constraint_hxx__ + +#include +#include + +#include "pinocchio/multibody/joint/joint-basic-visitors.hpp" + +namespace pinocchio +{ + + template + template< + template class JointCollectionTpl, + typename VectorLowerConfiguration, + typename VectorUpperConfiguration, + typename VectorMarginConfiguration> + void JointLimitConstraintModelTpl::init( + const ModelTpl & model, + const JointIndexVector & _activable_joints, + const Eigen::MatrixBase & lb, + const Eigen::MatrixBase & ub, + const Eigen::MatrixBase & marg) + { + typedef ModelTpl Model; + typedef typename Model::JointModel JointModel; + + PINOCCHIO_CHECK_ARGUMENT_SIZE(lb.size(), model.nq); + PINOCCHIO_CHECK_ARGUMENT_SIZE(ub.size(), model.nq); + PINOCCHIO_CHECK_ARGUMENT_SIZE(marg.size(), model.nq); + + // Check validity of _activable_joints input + for (const JointIndex joint_id : _activable_joints) + { + PINOCCHIO_CHECK_INPUT_ARGUMENT( + joint_id < model.joints.size(), + "joint_id is larger than the total number of joints contained in the model."); + PINOCCHIO_CHECK_INPUT_ARGUMENT(joint_id > 0, "joint_id is not valid."); + } + + // PINOCCHIO_CHECK_INPUT_ARGUMENT( + // check__activable_joints(model, _activable_joints) == -1, + // "One of the joint is not supported by JointLimitConstraintModelTpl.") + + // TODO: Should we reserve some activable quantities ? + + // Loop on all q components of activable jointds to identify activable lower and upper + // constraints, and for each track row_id of related activable joint, idx_q in the configuration + // and idx_q_reduce in the subpart of q due to activable joints + VectorOfSize & activable_idx_rows_lower = activable_idx_rows; + VectorOfSize activable_idx_rows_upper; + + EigenIndexVector & activable_idx_qs_reduce_lower = activable_idx_qs_reduce; + EigenIndexVector activable_idx_qs_reduce_upper; + + EigenIndexVector & activable_idx_qs_lower = activable_idx_qs; + EigenIndexVector activable_idx_qs_upper; + + // Prepare the structure to compute sparsity pattern + EigenIndexVector extended_support; + extended_support.reserve(size_t(model.nv)); + + size_t idx_row = 0; + nq_reduce = 0; + for (const JointIndex joint_id : _activable_joints) + { + const JointModel & jmodel = model.joints[joint_id]; + + const int idx_q = jmodel.idx_q(); + const int idx_v = jmodel.idx_v(); + const int nq = jmodel.nq(); + const int nv = jmodel.nv(); + const auto has_configuration_limit = jmodel.hasConfigurationLimit(); + + bool is_joint_really_active = false; + for (int j_qi = 0; j_qi < nq; ++j_qi) + { + if (!has_configuration_limit[size_t(j_qi)]) + continue; + + const int q_index = idx_q + j_qi; + const int q_reduce_index = nq_reduce + j_qi; + + if (!(lb[q_index] == -std::numeric_limits::max() + || lb[q_index] == -std::numeric_limits::infinity())) + { + activable_idx_rows_lower.push_back(idx_row); + activable_idx_qs_lower.push_back(q_index); + activable_idx_qs_reduce_lower.push_back(q_reduce_index); + is_joint_really_active = true; + } + if (!(ub[q_index] == +std::numeric_limits::max() + || ub[q_index] == +std::numeric_limits::infinity())) + { + activable_idx_rows_upper.push_back(idx_row); + activable_idx_qs_upper.push_back(q_index); + activable_idx_qs_reduce_upper.push_back(q_reduce_index); + is_joint_really_active = true; + } + } + + // At least one lower or upper constraint for a component of the joint is active so update the + // quantity + if (is_joint_really_active) + { + activable_joints.push_back(joint_id); + idx_row += 1; + nq_reduce += nq; + + // Compute the sparsity pattern of the joint + const auto & jsupport = model.supports[joint_id]; + extended_support.clear(); + for (size_t i = 1; i < jsupport.size() - 1; ++i) + { + const JointIndex jsupport_id = jsupport[i]; + const JointModel & jsupport = model.joints[jsupport_id]; + const int jsupport_nv = jsupport.nv(); + const int jsupport_idx_v = jsupport.idx_v(); + for (int k = 0; k < jsupport_nv; ++k) + { + const int extended_row_id = jsupport_idx_v + k; + extended_support.push_back(extended_row_id); + } + } + for (int k = 0; k < nv; ++k) + { + const int extended_row_id = idx_v + k; + extended_support.push_back(extended_row_id); + } + row_indexes.push_back(extended_support); + } + } + + // Recover sizes of constraints + lower_activable_size = static_cast(activable_idx_rows_lower.size()); + int upper_activable_size = static_cast(activable_idx_rows_upper.size()); + int activable_size = lower_activable_size + upper_activable_size; + PINOCCHIO_UNUSED_VARIABLE(activable_size); + + // Recompose one vectors for all constraint with convention lower | upper + activable_idx_rows.insert( + activable_idx_rows.end(), activable_idx_rows_upper.begin(), activable_idx_rows_upper.end()); + activable_idx_qs_reduce.insert( + activable_idx_qs_reduce.end(), activable_idx_qs_reduce_upper.begin(), + activable_idx_qs_reduce_upper.end()); + activable_idx_qs.insert( + activable_idx_qs.end(), activable_idx_qs_upper.begin(), activable_idx_qs_upper.end()); + assert(size() == activable_size); + + // Fill bound limit and margin for lower and upper constraint + // Another strategy could be to query the model again but it is not coherent with the existing + // constructors. + bound_position_limit = VectorXs::Zero(Eigen::DenseIndex(size())); + bound_position_margin = VectorXs::Zero(Eigen::DenseIndex(size())); + Eigen::DenseIndex bound_row_id = 0; + for (std::size_t i = 0; i < static_cast(lowerSize()); i++) + { + const auto activable_idx_q = activable_idx_qs[i]; + bound_position_limit[bound_row_id] = lb[activable_idx_q]; + assert(marg[activable_idx_q] >= 0); + bound_position_margin[bound_row_id] = marg[activable_idx_q]; + bound_row_id++; + } + for (std::size_t i = static_cast(lowerSize()); + i < static_cast(size()); i++) + { + const auto activable_idx_q = activable_idx_qs[i]; + bound_position_limit[bound_row_id] = ub[activable_idx_q]; + assert(marg[activable_idx_q] >= 0); + bound_position_margin[bound_row_id] = marg[activable_idx_q]; + bound_row_id++; + } + assert(bound_row_id == static_cast(size())); + + // Get nvs and idx_vs of all actibale joints to compute nv_max_atom + // and activable_nvs, activable_idx_vs + std::vector reduce_nvs, reduce_idx_vs; + reduce_nvs.reserve(static_cast(nq_reduce)); + reduce_idx_vs.reserve(static_cast(nq_reduce)); + + pinocchio::indexvInfo(model, activable_joints, reduce_nvs, reduce_idx_vs); + assert(nq_reduce == static_cast(reduce_nvs.size())); + assert(nq_reduce == static_cast(reduce_idx_vs.size())); + auto nv_max_atom_iter = std::max_element(reduce_nvs.begin(), reduce_nvs.end()); + nv_max_atom = nv_max_atom_iter != reduce_nvs.end() ? *nv_max_atom_iter : 1; + assert(nv_max_atom <= MAX_JOINT_NV); + + std::size_t r_size = static_cast(size()); + activable_nvs.reserve(r_size); + activable_idx_vs.reserve(r_size); + for (const auto activable_idx_q_reduce : activable_idx_qs_reduce) + { + std::size_t idx_query = static_cast(activable_idx_q_reduce); + activable_nvs.push_back(static_cast(reduce_nvs[idx_query])); + activable_idx_vs.push_back(static_cast(reduce_idx_vs[idx_query])); + } + assert(r_size == activable_nvs.size()); + assert(r_size == activable_idx_vs.size()); + + // Fill row_activable_sparsity_pattern from row_activable_indexes content + row_sparsity_pattern.resize(row_indexes.size(), BooleanVector::Zero(model.nv)); + for (size_t joint_id = 0; joint_id < row_indexes.size(); ++joint_id) + { + auto & sparsity_pattern = row_sparsity_pattern[joint_id]; + const auto & extended_support = row_indexes[joint_id]; + for (const auto val : extended_support) + sparsity_pattern[val] = true; + } + + m_compliance = ComplianceVectorType::Zero(size()); + m_baumgarte_parameters = BaumgarteCorrectorParameters(); + + // Allocate the maximum size for the dynamic quantity + lower_active_size = 0; + active_set_indexes.reserve(r_size); + active_idx_rows.reserve(r_size); + active_idx_qs_reduce.reserve(r_size); + active_nvs.reserve(r_size); + active_idx_vs.reserve(r_size); + // active_compliance_storage.resize(size()) would allocate double size... + // active_compliance_storage.resize(0); and we resize again + active_compliance_storage.reserve(size()); + assert(activeSize() == lowerActiveSize() == upperActiveSize() == 0); + } + + template + template class JointCollectionTpl> + void JointLimitConstraintModelTpl::resize_impl( + const ModelTpl & /* model */, + const DataTpl & data, + ConstraintData & cdata) + { + // Compute notably the constraint constraint_residual + // This allows to compute which limits are active in the current configuration (data.q_in) which + // corresponds to the current active set. + auto & activable_constraint_residual = cdata.activable_constraint_residual; + + active_set_indexes.clear(); + active_idx_rows.clear(); + active_idx_qs_reduce.clear(); + active_nvs.clear(); + active_idx_vs.clear(); + lower_active_size = 0; + + // Fill the constraint residual for all activable constraints and detect the active ones. + // The convention is lower | upper, and negative | positive constraint so: + // q_l <= q + TMv <= q_up + // -TMv + (q_l - q) <= 0 + // -TMv + (q_u - q) >= 0 + + // We compute all active quanties + // active_[idx_rows|idx_qs_reduce|nvs|idx_vs] are store + // but they are not necessary as they are recoverable from active_set_indexes + // However it imply double referencing in all jacobian methods + // And for one call of resize/calc, their can be multiple call to jacobian methods ! + + // Lower + for (std::size_t i = 0; i < static_cast(lowerSize()); i++) + { + const Eigen::DenseIndex ie = static_cast(i); + const Eigen::DenseIndex idx_q = activable_idx_qs[i]; + activable_constraint_residual[ie] = bound_position_limit[ie] - data.q_in[idx_q]; + if (activable_constraint_residual[ie] >= -bound_position_margin[ie]) + { + active_set_indexes.push_back(i); + active_idx_rows.push_back(activable_idx_rows[i]); + active_idx_qs_reduce.push_back(activable_idx_qs_reduce[i]); + active_nvs.push_back(activable_nvs[i]); + active_idx_vs.push_back(activable_idx_vs[i]); + lower_active_size += 1; + } + } + // Upper + for (std::size_t i = static_cast(lowerSize()); + i < static_cast(size()); i++) + { + const Eigen::DenseIndex ie = static_cast(i); + const Eigen::DenseIndex idx_q = activable_idx_qs[i]; + activable_constraint_residual[ie] = bound_position_limit[ie] - data.q_in[idx_q]; + if (activable_constraint_residual[ie] <= bound_position_margin[ie]) + { + active_set_indexes.push_back(i); + active_idx_rows.push_back(activable_idx_rows[i]); + active_idx_qs_reduce.push_back(activable_idx_qs_reduce[i]); + active_nvs.push_back(activable_nvs[i]); + active_idx_vs.push_back(activable_idx_vs[i]); + } + } + + // Resize the constraint residual/compliance storage to the active set size. + const int active_size = activeSize(); + cdata.constraint_residual_storage.resize(active_size); + + // Update the active compliance + active_compliance_storage.resize(active_size); + for (int active_row_index = 0; active_row_index < active_size; active_row_index++) + { + active_compliance[active_row_index] = m_compliance[static_cast( + active_set_indexes[static_cast(active_row_index)])]; + } + + // Resize the constraint set so it corresponds to the active set. + m_set.resize(Eigen::DenseIndex(lowerActiveSize()), Eigen::DenseIndex(upperActiveSize())); + } + + template + template class JointCollectionTpl> + void JointLimitConstraintModelTpl::calc( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata) const + { + PINOCCHIO_UNUSED_VARIABLE(model); + PINOCCHIO_UNUSED_VARIABLE(data); + + const std::size_t active_size = static_cast(this->activeSize()); + auto & activable_constraint_residual = cdata.activable_constraint_residual; + auto & constraint_residual = cdata.constraint_residual; + + PINOCCHIO_CHECK_ARGUMENT_SIZE( + constraint_residual.size(), this->activeSize(), + "The active constraint_residual size in constraint data is different from the constraint " + "model active size. You should probably use cmodel.resize(model, data, cdata) first."); + + // Fill the constraint residual for all active constraints. + for (std::size_t active_row_index = 0; active_row_index < active_size; active_row_index++) + { + constraint_residual[int(active_row_index)] = + activable_constraint_residual[int(active_set_indexes[active_row_index])]; + } + + // Fill the compact tangent map + pinocchio::compactTangentMap(model, activable_joints, data.q_in, cdata.compact_tangent_map); + } + + template + template class JointCollectionTpl, typename JacobianMatrix> + void JointLimitConstraintModelTpl::jacobian( + const ModelTpl & model, + const DataTpl & /*data*/, + ConstraintData & cdata, + const Eigen::MatrixBase & _jacobian_matrix) const + { + JacobianMatrix & jacobian_matrix = _jacobian_matrix.const_cast_derived(); + + PINOCCHIO_CHECK_ARGUMENT_SIZE( + jacobian_matrix.rows(), this->activeSize(), + "The input/output Jacobian matrix does not have the right number of rows."); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + jacobian_matrix.cols(), model.nv, + "The input/output Jacobian matrix does not have the right number of cols."); + + jacobian_matrix.setZero(); + const CompactTangentMap_t & TMc = cdata.compact_tangent_map; + Eigen::DenseIndex row_id = 0; + for (size_t constraint_id = 0; constraint_id < static_cast(activeSize()); + ++constraint_id, ++row_id) + { + jacobian_matrix.block(row_id, active_idx_vs[constraint_id], 1, active_nvs[constraint_id]) = + -TMc.block(active_idx_qs_reduce[constraint_id], 0, 1, active_nvs[constraint_id]); + } + } + + template + template< + typename InputMatrix, + typename OutputMatrix, + template class JointCollectionTpl, + AssignmentOperatorType op> + void JointLimitConstraintModelTpl::jacobianMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat, + const Eigen::MatrixBase & _res, + AssignmentOperatorTag aot) const + { + OutputMatrix & res = _res.const_cast_derived(); + + PINOCCHIO_CHECK_ARGUMENT_SIZE(mat.rows(), model.nv); + PINOCCHIO_CHECK_ARGUMENT_SIZE(mat.cols(), res.cols()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res.rows(), this->activeSize()); + PINOCCHIO_UNUSED_VARIABLE(data); + PINOCCHIO_UNUSED_VARIABLE(aot); + + if (std::is_same, SetTo>::value) + res.setZero(); + + const CompactTangentMap_t & TMc = cdata.compact_tangent_map; + Eigen::DenseIndex row_id = 0; + for (size_t constraint_id = 0; constraint_id < static_cast(activeSize()); + ++constraint_id, ++row_id) + { + if (std::is_same, RmTo>::value) + res.row(row_id) -= + -TMc.block(active_idx_qs_reduce[constraint_id], 0, 1, active_nvs[constraint_id]) + * mat.middleRows(active_idx_vs[constraint_id], active_nvs[constraint_id]); + else + res.row(row_id) += + -TMc.block(active_idx_qs_reduce[constraint_id], 0, 1, active_nvs[constraint_id]) + * mat.middleRows(active_idx_vs[constraint_id], active_nvs[constraint_id]); + } + } + + template + template< + typename InputMatrix, + typename OutputMatrix, + template class JointCollectionTpl, + AssignmentOperatorType op> + void JointLimitConstraintModelTpl::jacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat, + const Eigen::MatrixBase & _res, + AssignmentOperatorTag aot) const + { + OutputMatrix & res = _res.const_cast_derived(); + + PINOCCHIO_CHECK_ARGUMENT_SIZE(mat.rows(), this->activeSize()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res.cols(), mat.cols()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res.rows(), model.nv); + PINOCCHIO_UNUSED_VARIABLE(data); + PINOCCHIO_UNUSED_VARIABLE(aot); + + if (std::is_same, SetTo>::value) + res.setZero(); + + const CompactTangentMap_t & TMc = cdata.compact_tangent_map; + Eigen::DenseIndex row_id = 0; + for (size_t constraint_id = 0; constraint_id < static_cast(activeSize()); + ++constraint_id, ++row_id) + { + if (std::is_same, RmTo>::value) + res.middleRows(active_idx_vs[constraint_id], active_nvs[constraint_id]) -= + -TMc.block(active_idx_qs_reduce[constraint_id], 0, 1, active_nvs[constraint_id]) + .transpose() + * mat.row(row_id); + else + res.middleRows(active_idx_vs[constraint_id], active_nvs[constraint_id]) += + -TMc.block(active_idx_qs_reduce[constraint_id], 0, 1, active_nvs[constraint_id]) + .transpose() + * mat.row(row_id); + } + } + + template + template< + template class JointCollectionTpl, + typename VectorNLike, + ReferenceFrame rf> + void JointLimitConstraintModelTpl::appendCouplingConstraintInertias( + const ModelTpl & model, + DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & diagonal_constraint_inertia, + const ReferenceFrameTag reference_frame) const + { + PINOCCHIO_UNUSED_VARIABLE(model); + PINOCCHIO_UNUSED_VARIABLE(data); + PINOCCHIO_UNUSED_VARIABLE(cdata); + PINOCCHIO_UNUSED_VARIABLE(diagonal_constraint_inertia); + PINOCCHIO_UNUSED_VARIABLE(reference_frame); + // TODO(jcarpent) + } +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_joint_limit_constraint_hxx__ diff --git a/include/pinocchio/algorithm/constraints/jointwise-constraint-base.hpp b/include/pinocchio/algorithm/constraints/jointwise-constraint-base.hpp new file mode 100644 index 0000000000..bedd09ccaf --- /dev/null +++ b/include/pinocchio/algorithm/constraints/jointwise-constraint-base.hpp @@ -0,0 +1,173 @@ +// +// Copyright (c) 2023-2025 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_jointwise_constraint_base_hpp__ +#define __pinocchio_algorithm_constraints_jointwise_constraint_base_hpp__ + +#include "pinocchio/algorithm/fwd.hpp" +#include "pinocchio/algorithm/constraints/constraint-model-base.hpp" + +namespace pinocchio +{ + + template + struct JointWiseConstraintModelBase : ConstraintModelBase + { + typedef typename traits::Scalar Scalar; + enum + { + Options = traits::Options + }; + typedef ConstraintModelBase Base; + + using Base::derived; + using typename Base::BooleanVector; + using typename Base::EigenIndexVector; + + typedef typename traits::ConstraintData ConstraintData; + typedef typename traits::ConstraintSet ConstraintSet; + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + template class JointCollectionTpl> + JointWiseConstraintModelBase(const ModelTpl & model) + : Base(model) + { + } + + template + bool operator==(const JointWiseConstraintModelBase & other) const + { + return base() == other.base(); + } + + template + bool operator!=(const JointWiseConstraintModelBase & other) const + { + return !(*this == other); + } + + /// \brief Map the constraint forces (aka constraint Lagrange multipliers) to the joint torques + /// associated to each independant constraint. This operation corresponds to the mapping of the + /// constraint multipliers on the joint torque. + /// + /// \param[in] model The model of the rigid body system. + /// \param[in] data The data associated with model. + /// \param[in] cdata The constraint data associated with the constraint model. + /// \param[in] constraint_forces Input constraint forces (Lagrange multipliers) associated with + /// the constraint. + /// \param[out] joint_torques Output joint torques associated with the model. + /// + /// \note The results will be added to the joint_torques ouput argument. + template< + template class JointCollectionTpl, + typename ConstraintForcesLike, + typename JointTorquesLike> + void mapConstraintForceToJointTorques( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & constraint_forces, + const Eigen::MatrixBase & joint_torques) const + { + derived().mapConstraintForceToJointTorques( + model, data, cdata, constraint_forces, joint_torques.const_cast_derived()); + } + + /// + /// \copydoc Base::mapConstraintForceToJointSpace(const ModelTpl &, const DataTpl , const + /// ConstraintData &, const Eigen::MatrixBase &, + /// std::vector, ForceAllocator> &, const + /// Eigen::MatrixBase &,ReferenceFrameTag) + /// + template< + template class JointCollectionTpl, + typename ConstraintForceLike, + typename ForceAllocator, + typename JointTorquesLike, + ReferenceFrame rf> + void mapConstraintForceToJointSpace( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & constraint_forces, + std::vector, ForceAllocator> & joint_forces, + const Eigen::MatrixBase & joint_torques, + ReferenceFrameTag reference_frame) const + { + PINOCCHIO_UNUSED_VARIABLE(joint_forces); + PINOCCHIO_UNUSED_VARIABLE(reference_frame); + mapConstraintForceToJointTorques(model, data, cdata, constraint_forces, joint_torques); + } + + /// \brief Map the joint motions to the constraint motions. + /// This operation corresponds to the dual mapping wrt mapConstraintForcesToJointTorques. + /// + /// \param[in] model The model of the rigid body system. + /// \param[in] data The data associated with model. + /// \param[in] cdata The constraint data associated with the constraint model. + /// \param[in] joint_generalized_velocity Input joint motions associated with the model. + /// \param[out] constraint_motions Output constraint motions. + /// + template< + template class JointCollectionTpl, + typename JointMotionsLike, + typename ConstraintMotionsLike> + void mapJointMotionsToConstraintMotion( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & joint_generalized_velocity, + const Eigen::MatrixBase & constraint_motions) const + { + derived().mapJointMotionsToConstraintMotion( + model, data, cdata, joint_generalized_velocity, constraint_motions.const_cast_derived()); + } + + /// + ///\copydoc Base::mapJointSpaceToConstraintMotion(const ModelTpl &, const DataTpl , const + /// ConstraintData &, + /// std::vector, MotionAllocator> &, const + /// Eigen::MatrixBase &, const Eigen::MatrixBase + /// &,ReferenceFrameTag) + /// + template< + template class JointCollectionTpl, + typename MotionAllocator, + typename JointMotionsLike, + typename VectorLike, + ReferenceFrame rf> + void mapJointSpaceToConstraintMotion( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const std::vector, MotionAllocator> & joint_motions, + const Eigen::MatrixBase & joint_generalized_velocity, + const Eigen::MatrixBase & constraint_motions, + ReferenceFrameTag reference_frame) const + { + PINOCCHIO_UNUSED_VARIABLE(joint_motions); + PINOCCHIO_UNUSED_VARIABLE(reference_frame); + mapJointMotionsToConstraintMotion( + model, data, cdata, joint_generalized_velocity, constraint_motions.const_cast_derived()); + } + + protected: + /// \brief Default constructor + JointWiseConstraintModelBase() + { + } + }; // struct JointWiseConstraintModelBase +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_jointwise_constraint_base_hpp__ diff --git a/include/pinocchio/algorithm/constraints/kinematics-constraint-base.hpp b/include/pinocchio/algorithm/constraints/kinematics-constraint-base.hpp new file mode 100644 index 0000000000..b90e2e649d --- /dev/null +++ b/include/pinocchio/algorithm/constraints/kinematics-constraint-base.hpp @@ -0,0 +1,246 @@ +// +// Copyright (c) 2023-2025 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_kinematics_constraint_base_hpp__ +#define __pinocchio_algorithm_constraints_kinematics_constraint_base_hpp__ + +#include "pinocchio/algorithm/fwd.hpp" +#include "pinocchio/algorithm/constraints/constraint-model-base.hpp" + +namespace pinocchio +{ + + template + struct KinematicsConstraintModelBase : ConstraintModelBase + { + typedef typename traits::Scalar Scalar; + enum + { + Options = traits::Options + }; + typedef ConstraintModelBase Base; + typedef typename traits::ConstraintData ConstraintData; + typedef typename traits::ConstraintSet ConstraintSet; + + using Base::derived; + using typename Base::BooleanVector; + using typename Base::EigenIndexVector; + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + template class JointCollectionTpl> + KinematicsConstraintModelBase( + const ModelTpl & model, + const JointIndex joint1_id, + const JointIndex joint2_id) + : Base(model) + , joint1_id(joint1_id) + , joint2_id(joint2_id) + { + } + + /// \brief Index of the first joint in the model tree + JointIndex joint1_id; + + /// \brief Index of the second joint in the model tree + JointIndex joint2_id; + + template + bool operator==(const KinematicsConstraintModelBase & other) const + { + return base() == other.base() && joint1_id == other.joint1_id && joint2_id == other.joint2_id; + } + + template + bool operator!=(const KinematicsConstraintModelBase & other) const + { + return !(*this == other); + } + + /// + /// \brief Map the constraint forces (aka constraint Lagrange multipliers) to the forces + /// supported by the joints expressed in the input reference_frame. + /// + /// \param[in] model The model of the rigid body system. + /// \param[in] data The data associated with model. + /// \param[in] cdata The constraint data associated with the constraint model. + /// \param[in] constraint_forces Input constraint forces (Lagrange multipliers) associated with + /// the constraint. + /// \param[out] joint_forces Output joint forces associated with each joint of the model. + /// \param[in] reference_frame Input reference frame in which the forces are expressed. + /// + /// \note The results will be added to the joint_torques ouput argument. + /// + template< + template class JointCollectionTpl, + typename ForceLike, + typename ForceAllocator, + ReferenceFrame rf> + void mapConstraintForceToJointForces( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & constraint_forces, + std::vector, ForceAllocator> & joint_forces, + ReferenceFrameTag reference_frame) const + { + derived().mapConstraintForceToJointForces( + model, data, cdata, constraint_forces.derived(), joint_forces, reference_frame); + } + + /// + /// \brief Map the constraint forces (aka constraint Lagrange multipliers) to the forces + /// supported by the joints expressed in the LOCAL frame of the joints. + /// + /// \param[in] model The model of the rigid body system. + /// \param[in] data The data associated with model. + /// \param[in] cdata The constraint data associated with the constraint model. + /// \param[in] constraint_forces Input constraint forces (Lagrange multipliers) associated with + /// the constraint. + /// \param[out] joint_forces Output joint forces associated with each joint of the model. + /// + /// \note The results will be added to the joint_torques ouput argument. + /// + template< + template class JointCollectionTpl, + typename ForceLike, + typename ForceAllocator> + void mapConstraintForceToJointForces( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & constraint_forces, + std::vector, ForceAllocator> & joint_forces) const + { + mapConstraintForceToJointForces( + model, data, cdata, constraint_forces, joint_forces.const_cast_derived(), LocalFrameTag()); + } + + /// + /// \brief Map the joint motions to the constraint motions. The joint motions are expressed in + /// the frame given by the input argument reference_frame. + /// + /// \param[in] model The model of the rigid body system. + /// \param[in] data The data associated with model. + /// \param[in] cdata The constraint data associated with the constraint model. + /// \param[in] joint_motions Input joint motions associated with each joint of the model. + /// \param[out] constraint_motions Output contraint motions. + /// \param[in] reference_frame Input reference frame in which the joint motion quantities are + /// expressed. + /// + template< + template class JointCollectionTpl, + typename MotionAllocator, + typename VectorLike, + ReferenceFrame rf> + void mapJointMotionsToConstraintMotion( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const std::vector, MotionAllocator> & joint_motions, + const Eigen::MatrixBase & constraint_motions, + ReferenceFrameTag reference_frame) const + { + derived().mapJointMotionsToConstraintMotion( + model, data, cdata, joint_motions, constraint_motions.const_cast_derived(), + reference_frame); + } + + /// + /// \brief Map the joint motions expressed in the LOCAL frame to the constraint motions. + /// + /// \param[in] model The model of the rigid body system. + /// \param[in] data The data associated with model. + /// \param[in] cdata The constraint data associated with the constraint model. + /// \param[in] joint_motions Input joint motions associated with each joint of the model. + /// \param[out] constraint_motions Output contraint motions. + /// + template< + template class JointCollectionTpl, + typename MotionAllocator, + typename VectorLike> + void mapJointMotionsToConstraintMotion( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const std::vector, MotionAllocator> & joint_motions, + const Eigen::MatrixBase & constraint_motions) const + { + derived().mapJointMotionsToConstraintMotion( + model, data, cdata, joint_motions, constraint_motions.const_cast_derived(), + LocalFrameTag()); + } + + /// + /// \copydoc Base::mapConstraintForceToJointSpace(const ModelTpl &, const DataTpl , const + /// ConstraintData &, const Eigen::MatrixBase &, + /// std::vector, ForceAllocator> &, const + /// Eigen::MatrixBase &,ReferenceFrameTag) + /// + template< + template class JointCollectionTpl, + typename ConstraintForceLike, + typename ForceAllocator, + typename JointTorquesLike, + ReferenceFrame rf> + void mapConstraintForceToJointSpace( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & constraint_forces, + std::vector, ForceAllocator> & joint_forces, + const Eigen::MatrixBase & joint_torques, + ReferenceFrameTag reference_frame) const + { + PINOCCHIO_UNUSED_VARIABLE(joint_torques); + mapConstraintForceToJointForces( + model, data, cdata, constraint_forces.derived(), joint_forces, reference_frame); + } + + /// + ///\copydoc Base::mapJointSpaceToConstraintMotion(const ModelTpl &, const DataTpl , const + /// ConstraintData &, + /// std::vector, MotionAllocator> &, const + /// Eigen::MatrixBase &, const Eigen::MatrixBase + /// &,ReferenceFrameTag) + /// + template< + template class JointCollectionTpl, + typename MotionAllocator, + typename JointMotionsLike, + typename VectorLike, + ReferenceFrame rf> + void mapJointSpaceToConstraintMotion( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const std::vector, MotionAllocator> & joint_motions, + const Eigen::MatrixBase & joint_generalized_velocity, + const Eigen::MatrixBase & constraint_motions, + ReferenceFrameTag reference_frame) const + { + PINOCCHIO_UNUSED_VARIABLE(joint_generalized_velocity); + mapJointMotionsToConstraintMotion( + model, data, cdata, joint_motions, constraint_motions.const_cast_derived(), + reference_frame); + } + + protected: + /// \brief Default constructor + KinematicsConstraintModelBase() + { + } + }; // struct KinematicsConstraintModelBase +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_kinematics_constraint_base_hpp__ diff --git a/include/pinocchio/algorithm/constraints/null-set.hpp b/include/pinocchio/algorithm/constraints/null-set.hpp new file mode 100644 index 0000000000..50c5879ac2 --- /dev/null +++ b/include/pinocchio/algorithm/constraints/null-set.hpp @@ -0,0 +1,149 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_null_set_hpp__ +#define __pinocchio_algorithm_constraints_null_set_hpp__ + +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/cone-base.hpp" + +namespace pinocchio +{ + + template + struct CastType> + { + typedef NullSetTpl type; + }; + + template + struct traits> + { + typedef _Scalar Scalar; + + enum + { + Options = _Options + }; + typedef UnboundedSetTpl DualCone; + }; + + ///  \brief Null set containing (0 singleton). + template + struct NullSetTpl : ConeBase> + { + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + typedef Eigen::Matrix Vector; + typedef ConeBase Base; + typedef typename traits::DualCone DualCone; + + /// \brief Constructor from a given size + /// + explicit NullSetTpl(const Eigen::DenseIndex size) + : m_size(size) + { + } + + /// \brief Copy constructor. + NullSetTpl(const NullSetTpl & other) = default; + + /// \brief Copy operator + NullSetTpl & operator=(const NullSetTpl & other) = default; + + /// \brief Cast operator + template + NullSetTpl cast() const + { + typedef NullSetTpl ReturnType; + return ReturnType(this->size()); + } + + /// \brief Comparison operator + bool operator==(const NullSetTpl & other) const + { + return base() == other.base() && m_size == other.m_size; + } + + /// \brief Difference operator + bool operator!=(const NullSetTpl & other) const + { + return !(*this == other); + } + + /// \brief Check whether a vector x is zero. + /// + /// \param[in] f vector to check (assimilated to a force vector). + /// + template + bool isInside(const Eigen::MatrixBase & x, const Scalar prec = Scalar(0)) const + { + assert(prec >= 0 && "prec should be positive"); + return x.isZero(prec); + } + + using Base::project; + + /// \brief Project a vector x into set. + /// + /// \param[in] x a vector to project. + /// \param[in] res result of the projection. + /// + template + void project( + const Eigen::MatrixBase & x, + const Eigen::MatrixBase & res_) const + { + PINOCCHIO_UNUSED_VARIABLE(x); + auto & res = res_.const_cast_derived(); + res.setZero(); + } + + /// \brief Returns the dimension of the ambiant space. + Eigen::DenseIndex dim() const + { + return m_size; + } + + Eigen::DenseIndex size() const + { + return m_size; + } + + /// \brief Resize by calling the resize method of Eigen. + void resize(Eigen::DenseIndex new_size) + { + m_size = new_size; + } + + /// \brief Resize by calling the conservativeResize method of Eigen. + void conservativeResize(Eigen::DenseIndex new_size) + { + this->resize(new_size); + } + + DualCone dual() const + { + return DualCone(m_size); + } + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + protected: + Eigen::DenseIndex m_size; + }; // NullSetTpl + +} // namespace pinocchio + +#endif // __pinocchio_algorithm_constraints_null_set_hpp__ diff --git a/include/pinocchio/algorithm/constraints/orthant-cone.hpp b/include/pinocchio/algorithm/constraints/orthant-cone.hpp new file mode 100644 index 0000000000..23bb4f1e6e --- /dev/null +++ b/include/pinocchio/algorithm/constraints/orthant-cone.hpp @@ -0,0 +1,245 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_orthant_cone_hpp__ +#define __pinocchio_algorithm_constraints_orthant_cone_hpp__ + +#include "pinocchio/math/fwd.hpp" +#include "pinocchio/algorithm/constraints/cone-base.hpp" + +namespace pinocchio +{ + + template + struct CastType> + { + typedef PositiveOrthantConeTpl type; + }; + + template + struct traits> + { + typedef _Scalar Scalar; + typedef PositiveOrthantConeTpl DualCone; + }; + + template + struct CastType> + { + typedef NegativeOrthantConeTpl type; + }; + + template + struct traits> + { + typedef _Scalar Scalar; + typedef NegativeOrthantConeTpl DualCone; + }; + + ///  \brief Box set defined by a lower and an upper bounds [lb;ub]. + template + struct OrthantConeBase : ConeBase + { + typedef typename traits::Scalar Scalar; + typedef typename traits::DualCone DualCone; + + typedef Eigen::Matrix Vector; + typedef ConeBase Base; + + const Base & base() const + { + return static_cast(*this); + } + Base & base() + { + return static_cast(*this); + } + + using Base::derived; + using Base::project; + + /// \brief Default constructor + /// + OrthantConeBase() + : m_size(0) + { + } + + /// \brief Constructor from a given size + /// + explicit OrthantConeBase(const Eigen::DenseIndex size) + : m_size(size) + { + } + + /// \brief Copy constructor. + OrthantConeBase(const OrthantConeBase & other) = default; + + /// \brief Cast operator + template + typename CastType::type cast() const + { + typedef typename CastType::type ReturnType; + return ReturnType(size()); + } + + /// \brief Copy operator + OrthantConeBase & operator=(const OrthantConeBase & other) = default; + + /// \brief Comparison operator + bool operator==(const OrthantConeBase & other) const + { + return base() == other.base() && m_size == other.m_size; + } + + /// \brief Difference operator + bool operator!=(const OrthantConeBase & other) const + { + return !(*this == other); + } + + /// \brief Resize by calling the resize method of Eigen. + void resize(Eigen::DenseIndex new_size) + { + m_size = new_size; + } + + /// \brief Resize by calling the conservativeResize method of Eigen. + void conservativeResize(Eigen::DenseIndex new_size) + { + this->resize(new_size); + } + + /// \brief Check whether a vector x lies within the orthant. + /// + /// \param[in] x vector to check . + /// + template + bool isInside(const Eigen::MatrixBase & x, const Scalar prec = Scalar(0)) const + { + assert(prec >= 0 && "prec should be positive"); + return (x - project(x)).norm() <= prec; + } + + /// \brief Returns the dual cone associated with this. + /// + /// \remarks Orthant cone are by definition self dual. + DualCone dual() const + { + return derived(); + } + + /// \brief Returns the dimension of the box. + Eigen::DenseIndex dim() const + { + return m_size; + } + + Eigen::DenseIndex size() const + { + return m_size; + } + + protected: + Eigen::DenseIndex m_size; + }; // OrthantConeBase + + template + struct PositiveOrthantConeTpl : OrthantConeBase> + { + typedef OrthantConeBase Base; + + typedef _Scalar Scalar; + + /// \brief Default constructor + /// + PositiveOrthantConeTpl() = default; + + /// \brief Constructor from a given size + /// + explicit PositiveOrthantConeTpl(const Eigen::DenseIndex size) + : Base(size) + { + } + + using Base::project; + using Base::operator==; + using Base::operator!=; + using Base::dim; + using Base::size; + + /// \brief Project a vector x into orthant. + /// + /// \param[in] x a vector to project. + /// \param[in] res result of the projection. + /// + template + void project( + const Eigen::MatrixBase & x, + const Eigen::MatrixBase & res_) const + { + res_.const_cast_derived() = x.array().max(Scalar(0)).matrix(); + } + + /// \brief Project the value given as input for the given row index. + Scalar rowiseProject(const Eigen::DenseIndex row_id, const Scalar value) const + { + assert(row_id < size()); + PINOCCHIO_ONLY_USED_FOR_DEBUG(row_id); + return math::max(Scalar(0), value); + } + + }; // struct PositiveOrthantTpl + + ///  \brief Negative orthant + template + struct NegativeOrthantConeTpl : OrthantConeBase> + { + typedef OrthantConeBase Base; + + typedef _Scalar Scalar; + + /// \brief Default constructor + /// + NegativeOrthantConeTpl() = default; + + /// \brief Constructor from a given size + /// + explicit NegativeOrthantConeTpl(const Eigen::DenseIndex size) + : Base(size) + { + } + + using Base::project; + using Base::operator==; + using Base::operator!=; + using Base::dim; + using Base::size; + + /// \brief Project a vector x into orthant. + /// + /// \param[in] x a vector to project. + /// \param[in] res result of the projection. + /// + template + void project( + const Eigen::MatrixBase & x, + const Eigen::MatrixBase & res_) const + { + res_.const_cast_derived() = x.array().min(Scalar(0)).matrix(); + } + + /// \brief Project the value given as input for the given row index. + Scalar rowiseProject(const Eigen::DenseIndex row_id, const Scalar value) const + { + assert(row_id < size()); + PINOCCHIO_ONLY_USED_FOR_DEBUG(row_id); + return math::min(Scalar(0), value); + } + + }; // struct PositiveOrthantTpl + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_orthant_cone_hpp__ diff --git a/include/pinocchio/algorithm/delassus-operartor-ref.hpp b/include/pinocchio/algorithm/constraints/patch-frictional-constraint.hpp similarity index 100% rename from include/pinocchio/algorithm/delassus-operartor-ref.hpp rename to include/pinocchio/algorithm/constraints/patch-frictional-constraint.hpp diff --git a/include/pinocchio/algorithm/constraints/point-bilateral-constraint.hpp b/include/pinocchio/algorithm/constraints/point-bilateral-constraint.hpp new file mode 100644 index 0000000000..4b0c6e95cd --- /dev/null +++ b/include/pinocchio/algorithm/constraints/point-bilateral-constraint.hpp @@ -0,0 +1,325 @@ +// +// Copyright (c) 2019-2024 INRIA CNRS +// + +#ifndef __pinocchio_algorithm_constraints_bilateral_point_constraint_hpp__ +#define __pinocchio_algorithm_constraints_bilateral_point_constraint_hpp__ + +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/unbounded-set.hpp" +#include "pinocchio/algorithm/constraints/point-constraint-model-base.hpp" +#include "pinocchio/algorithm/constraints/point-constraint-data-base.hpp" + +namespace pinocchio +{ + + template + struct CastType> + { + typedef BilateralPointConstraintModelTpl type; + }; + + template + struct traits> + : traits>> + { + typedef _Scalar Scalar; + + enum + { + Options = _Options + }; + + typedef BilateralPointConstraintModelTpl ConstraintModel; + typedef BilateralPointConstraintDataTpl ConstraintData; + typedef UnboundedSetTpl ConstraintSet; + + typedef ConstraintModel Model; + typedef ConstraintData Data; + + typedef Eigen::Matrix Vector3; + typedef Eigen::Matrix JacobianMatrixType; + typedef Vector3 VectorConstraintSize; + + typedef Vector3 ComplianceVectorType; + typedef ComplianceVectorType & ComplianceVectorTypeRef; + typedef const ComplianceVectorType & ComplianceVectorTypeConstRef; + + typedef ComplianceVectorTypeRef ActiveComplianceVectorTypeRef; + typedef ComplianceVectorTypeConstRef ActiveComplianceVectorTypeConstRef; + + typedef Vector3 BaumgarteVectorType; + typedef BaumgarteCorrectorVectorParametersTpl + BaumgarteCorrectorVectorParameters; + typedef BaumgarteCorrectorVectorParameters & BaumgarteCorrectorVectorParametersRef; + typedef const BaumgarteCorrectorVectorParameters & BaumgarteCorrectorVectorParametersConstRef; + }; + + template + struct traits> + : traits> + { + }; + + /// + ///  \brief Contact model structure containg all the info describing the rigid contact model + /// + template + struct BilateralPointConstraintModelTpl + : PointConstraintModelBase> + { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + + typedef PointConstraintModelBase Base; + typedef ConstraintModelBase RootBase; + + template + friend struct BilateralPointConstraintModelTpl; + + typedef BilateralPointConstraintDataTpl ConstraintData; + typedef UnboundedSetTpl ConstraintSet; + + using typename Base::BooleanVector; + using typename Base::EigenIndexVector; + using typename Base::Force; + using typename Base::Matrix36; + using typename Base::Matrix6; + using typename Base::Motion; + using typename Base::SE3; + using typename Base::Vector3; + using typename Base::Vector6; + using typename Base::VectorConstraintSize; + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + /// + ///  \brief Default constructor + /// + BilateralPointConstraintModelTpl() + : Base() + { + } + + /// + ///  \brief Contructor with from a given type, joint indexes and placements. + /// + /// \param[in] type Type of the contact. + /// \param[in] model Model associated to the constraint. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// \param[in] joint2_id Index of the joint 2 in the model tree. + /// \param[in] joint1_placement Placement of the constraint w.r.t the frame of joint1. + /// \param[in] joint2_placement Placement of the constraint w.r.t the frame of joint2. + /// expressed. + /// + template class JointCollectionTpl> + BilateralPointConstraintModelTpl( + const ModelTpl & model, + const JointIndex joint1_id, + const SE3 & joint1_placement, + const JointIndex joint2_id, + const SE3 & joint2_placement) + : Base(model, joint1_id, joint1_placement, joint2_id, joint2_placement) + { + } + + /// + ///  \brief Contructor with from a given type, joint1_id and placement. + /// + /// \param[in] type Type of the contact. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// \param[in] joint1_placement Placement of the constraint w.r.t the frame of joint1. + /// expressed. + /// + template class JointCollectionTpl> + BilateralPointConstraintModelTpl( + const ModelTpl & model, + const JointIndex joint1_id, + const SE3 & joint1_placement) + : Base(model, joint1_id, joint1_placement) + { + } + + /// + ///  \brief Contructor with from a given type and the joint ids. + /// + /// \param[in] type Type of the contact. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// \param[in] joint2_id Index of the joint 2 in the model tree. + /// + template class JointCollectionTpl> + BilateralPointConstraintModelTpl( + const ModelTpl & model, + const JointIndex joint1_id, + const JointIndex joint2_id) + : Base(model, joint1_id, joint2_id) + { + } + + /// + ///  \brief Contructor with from a given type and . + /// + /// \param[in] type Type of the contact. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// + /// \remarks The second joint id (joint2_id) is set to be 0 (corresponding to the index of the + /// universe). + /// + template class JointCollectionTpl> + BilateralPointConstraintModelTpl( + const ModelTpl & model, const JointIndex joint1_id) + : Base(model, joint1_id) + { + } + + /// + /// \brief Create data storage associated to the constraint + /// + ConstraintData createData() const + { + return ConstraintData(*this); + } + + /// \brief Cast operator + template + typename CastType::type cast() const + { + typedef typename CastType::type ReturnType; + ReturnType res; + Base::template cast(res); + res.m_set = m_set.template cast(); + return res; + } + + /// + ///  \brief Comparison operator + /// + /// \param[in] other Other BilateralPointConstraintModelTpl to compare with. + /// + /// \returns true if the two *this is equal to other (type, joint1_id and placement attributs + /// must be the same). + /// + bool operator==(const BilateralPointConstraintModelTpl & other) const + { + return base() == other.base() && m_set == other.m_set; + } + + /// + ///  \brief Oposite of the comparison operator. + /// + /// \param[in] other Other BilateralPointConstraintModelTpl to compare with. + /// + /// \returns false if the two *this is not equal to other (at least type, joint1_id or placement + /// attributs is different). + /// + bool operator!=(const BilateralPointConstraintModelTpl & other) const + { + return !(*this == other); + } + + const ConstraintSet & set() const + { + return m_set; + } + + ConstraintSet & set() + { + return m_set; + } + + static std::string classname() + { + return std::string("BilateralPointConstraintModel"); + } + std::string shortname() const + { + return classname(); + } + + protected: + ConstraintSet m_set = ConstraintSet(3); + + }; // struct BilateralPointConstraintModelTpl<_Scalar,_Options> + + /// + ///  \brief Contact model structure containg all the info describing the rigid contact model + /// + template + struct BilateralPointConstraintDataTpl + : PointConstraintDataBase> + { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + + typedef BilateralPointConstraintModelTpl ConstraintModel; + typedef BilateralPointConstraintDataTpl ConstraintData; + typedef PointConstraintDataBase Base; + + using typename Base::Force; + using typename Base::Matrix6; + using typename Base::Matrix6x; + using typename Base::MatrixX; + using typename Base::Motion; + using typename Base::SE3; + using typename Base::Vector3; + using typename Base::VectorOfMatrix6; + + /// \brief Default constructor + BilateralPointConstraintDataTpl() + { + } + + explicit BilateralPointConstraintDataTpl(const ConstraintModel & constraint_model) + : Base(constraint_model) + { + } + + bool operator==(const BilateralPointConstraintDataTpl & other) const + { + return base() == other.base(); + } + + bool operator!=(const BilateralPointConstraintDataTpl & other) const + { + return !(*this == other); + } + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + static std::string classname() + { + return std::string("BilateralPointConstraintData"); + } + std::string shortname() const + { + return classname(); + } + }; // struct BilateralPointConstraintDataTpl<_Scalar,_Options> + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_bilateral_point_constraint_hpp__ diff --git a/include/pinocchio/algorithm/constraints/point-constraint-data-base.hpp b/include/pinocchio/algorithm/constraints/point-constraint-data-base.hpp new file mode 100644 index 0000000000..4359db3c3c --- /dev/null +++ b/include/pinocchio/algorithm/constraints/point-constraint-data-base.hpp @@ -0,0 +1,189 @@ +// +// Copyright (c) 2019-2025 INRIA CNRS +// + +#ifndef __pinocchio_algorithm_constraints_point_constraint_data_hpp__ +#define __pinocchio_algorithm_constraints_point_constraint_data_hpp__ + +#include "pinocchio/algorithm/fwd.hpp" +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/constraint-data-base.hpp" + +namespace pinocchio +{ + + /// + ///  \brief Data structure associated with PointConstraint + /// + template + struct PointConstraintDataBase : ConstraintDataBase + { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef typename traits::Scalar Scalar; + enum + { + Options = traits::Options + }; + + typedef typename traits::ConstraintModel ConstraintModel; + typedef typename traits::ConstraintData ConstraintData; + typedef ConstraintDataBase Base; + + typedef SE3Tpl SE3; + typedef MotionTpl Motion; + typedef ForceTpl Force; + typedef Eigen::Matrix Vector3; + typedef Eigen::Matrix Matrix6; + typedef Eigen::Matrix Matrix36; + typedef Eigen::Matrix RowMatrix36; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(Matrix6) VectorOfMatrix6; + typedef Eigen::Matrix Matrix6x; + typedef Eigen::Matrix MatrixX; + + // data + + /// \brief Resulting contact forces + Vector3 constraint_force; + + /// \brief Placement of the constraint frame 1 with respect to the WORLD frame + SE3 oMc1; + + /// \brief Placement of the constraint frame 2 with respect to the WORLD frame + SE3 oMc2; + + /// \brief Relative displacement between the two frames + SE3 c1Mc2; + + /// \brief Constraint position error + Vector3 constraint_position_error; + + /// \brief Constraint velocity error + Vector3 constraint_velocity_error; + + /// \brief Constraint acceleration error + Vector3 constraint_acceleration_error; + + /// \brief Constraint acceleration biais + Vector3 constraint_acceleration_biais_term; + + Vector3 & contraint_residual = constraint_position_error; + Vector3 & dcontraint_residual = constraint_velocity_error; + Vector3 & ddcontraint_residual = constraint_acceleration_error; + + Matrix36 A1_world; + Matrix36 A2_world; + Matrix36 A_world; // A1 + A2 + + Matrix36 A1_local; + Matrix36 A2_local; + Matrix36 A_local; // A1 + A2 + + // VectorOfMatrix6 extended_motion_propagators_joint1; + // VectorOfMatrix6 lambdas_joint1; + // VectorOfMatrix6 extended_motion_propagators_joint2; + + // Matrix6x dv1_dq, da1_dq, da1_dv, da1_da; + // Matrix6x dv2_dq, da2_dq, da2_dv, da2_da; + // MatrixX dvc_dq, dac_dq, dac_dv, dac_da; + + /// \brief Default constructor + PointConstraintDataBase() + { + } + + /// \brief Copy constructor + PointConstraintDataBase(const PointConstraintDataBase & other) + { + *this = other; + } + + /// \brief Constructor from a given ConstraintModel + /// + /// \param[in] constraint_model input constraint model + /// + explicit PointConstraintDataBase(const ConstraintModel & constraint_model) + : constraint_force(Vector3::Zero()) + , oMc1(SE3::Identity()) + , oMc2(SE3::Identity()) + , c1Mc2(SE3::Identity()) + , constraint_position_error(Vector3::Zero()) + , constraint_velocity_error(Vector3::Zero()) + , constraint_acceleration_error(Vector3::Zero()) + , constraint_acceleration_biais_term(Vector3::Zero()) + // , extended_motion_propagators_joint1(constraint_model.depth_joint1, Matrix6::Zero()) + // , lambdas_joint1(constraint_model.depth_joint1, Matrix6::Zero()) + // , extended_motion_propagators_joint2(constraint_model.depth_joint2, Matrix6::Zero()) + // , dv1_dq(6, constraint_model.nv) + // , da1_dq(6, constraint_model.nv) + // , da1_dv(6, constraint_model.nv) + // , da1_da(6, constraint_model.nv) + // , dv2_dq(6, constraint_model.nv) + // , da2_dq(6, constraint_model.nv) + // , da2_dv(6, constraint_model.nv) + // , da2_da(6, constraint_model.nv) + // , dvc_dq(constraint_model.size(), constraint_model.nv) + // , dac_dq(constraint_model.size(), constraint_model.nv) + // , dac_dv(constraint_model.size(), constraint_model.nv) + // , dac_da(constraint_model.size(), constraint_model.nv) + { + PINOCCHIO_UNUSED_VARIABLE(constraint_model); + } + + /// \brief Assignment operator + PointConstraintDataBase & operator=(const PointConstraintDataBase & other) + { + constraint_force = other.constraint_force; + oMc1 = other.oMc1; + oMc2 = other.oMc2; + c1Mc2 = other.c1Mc2; + constraint_position_error = other.constraint_position_error; + constraint_velocity_error = other.constraint_velocity_error; + constraint_acceleration_error = other.constraint_acceleration_error; + constraint_acceleration_biais_term = other.constraint_acceleration_biais_term; + + return *this; + } + + bool operator==(const PointConstraintDataBase & other) const + { + return constraint_force == other.constraint_force && oMc1 == other.oMc1 && oMc2 == other.oMc2 + && c1Mc2 == other.c1Mc2 && constraint_position_error == other.constraint_position_error + && constraint_velocity_error == other.constraint_velocity_error + && constraint_acceleration_error == other.constraint_acceleration_error + && constraint_acceleration_biais_term == other.constraint_acceleration_biais_term + // && extended_motion_propagators_joint1 == other.extended_motion_propagators_joint1 + // && lambdas_joint1 == other.lambdas_joint1 + // && extended_motion_propagators_joint2 == other.extended_motion_propagators_joint2 + // + // && dv1_dq == other.dv1_dq && da1_dq == other.da1_dq && da1_dv == other.da1_dv + // && da1_da == other.da1_da + // // + // && dv2_dq == other.dv2_dq && da2_dq == other.da2_dq && da2_dv == other.da2_dv + // && da2_da == other.da2_da + // // + // && dvc_dq == other.dvc_dq && dac_dq == other.dac_dq && dac_dv == other.dac_dv + // && dac_da == other.dac_da + ; + } + + bool operator!=(const PointConstraintDataBase & other) const + { + return !(*this == other); + } + + using Base::derived; + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + }; + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_point_constraint_data_hpp__ diff --git a/include/pinocchio/algorithm/constraints/point-constraint-model-base.hpp b/include/pinocchio/algorithm/constraints/point-constraint-model-base.hpp new file mode 100644 index 0000000000..8fe1cee3c9 --- /dev/null +++ b/include/pinocchio/algorithm/constraints/point-constraint-model-base.hpp @@ -0,0 +1,1100 @@ +// +// Copyright (c) 2019-2025 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_point_constraint_model_base_hpp__ +#define __pinocchio_algorithm_constraints_point_constraint_model_base_hpp__ + +#include + +#include "pinocchio/multibody/model.hpp" +#include "pinocchio/spatial/skew.hpp" +#include "pinocchio/algorithm/fwd.hpp" +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/kinematics-constraint-base.hpp" +#include "pinocchio/algorithm/constraints/constraint-data-base.hpp" +#include "pinocchio/algorithm/constraints/constraint-model-common-parameters.hpp" +#include "pinocchio/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp" +#include "pinocchio/algorithm/constraints/baumgarte-corrector-parameters.hpp" + +namespace pinocchio +{ + + template + struct PointConstraintModelBase; + + template + struct traits> + { + static constexpr ConstraintFormulationLevel constraint_formulation_level = + ConstraintFormulationLevel::VELOCITY_LEVEL; + static constexpr bool has_baumgarte_corrector = true; + static constexpr bool has_baumgarte_corrector_vector = true; + + template + struct JacobianMatrixProductReturnType + { + typedef typename InputMatrix::Scalar Scalar; + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(InputMatrix) InputMatrixPlain; + typedef Eigen::Matrix + type; + }; + + template + struct JacobianTransposeMatrixProductReturnType + { + typedef typename InputMatrix::Scalar Scalar; + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(InputMatrix) InputMatrixPlain; + typedef Eigen::Matrix< + Scalar, + Eigen::Dynamic, + InputMatrixPlain::ColsAtCompileTime, + InputMatrixPlain::Options> + type; + }; + }; + + /// + ///  \brief Contact model structure containg all the info describing the rigid contact model + /// + template + struct PointConstraintModelBase + : KinematicsConstraintModelBase + , ConstraintModelCommonParameters + { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef typename traits::Scalar Scalar; + enum + { + Options = traits::Options + }; + + typedef KinematicsConstraintModelBase Base; + typedef ConstraintModelCommonParameters BaseCommonParameters; + typedef ConstraintModelBase RootBase; + + template + friend struct PointConstraintModelBase; + + static const ConstraintFormulationLevel constraint_formulation_level = + traits::constraint_formulation_level; + typedef typename traits::ConstraintData ConstraintData; + typedef typename traits::ComplianceVectorType ComplianceVectorType; + typedef typename traits::ActiveComplianceVectorTypeRef ActiveComplianceVectorTypeRef; + typedef typename traits::ActiveComplianceVectorTypeConstRef + ActiveComplianceVectorTypeConstRef; + typedef typename traits::BaumgarteCorrectorVectorParameters + BaumgarteCorrectorVectorParameters; + typedef BaumgarteCorrectorParametersTpl BaumgarteCorrectorParameters; + + using Base::derived; + using Base::joint1_id; + using Base::joint2_id; + using typename Base::BooleanVector; + using typename Base::EigenIndexVector; + + typedef SE3Tpl SE3; + typedef MotionTpl Motion; + typedef ForceTpl Force; + typedef Eigen::Matrix Matrix36; + typedef Eigen::Matrix Matrix6; + typedef Eigen::Matrix Vector3; + typedef Eigen::Matrix Vector6; + typedef Vector3 VectorConstraintSize; + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + BaseCommonParameters & base_common_parameters() + { + return static_cast(*this); + } + const BaseCommonParameters & base_common_parameters() const + { + return static_cast(*this); + } + + /// \brief Position of attached point with respect to the frame of joint1. + SE3 joint1_placement; + + /// \brief Position of attached point with respect to the frame of joint2. + SE3 joint2_placement; + + /// \brief Desired constraint shift at position level + Vector3 desired_constraint_offset; + + /// \brief Desired constraint velocity at velocity level + Vector3 desired_constraint_velocity; + + /// \brief Desired constraint velocity at acceleration level + Vector3 desired_constraint_acceleration; + + /// \brief Colwise sparsity pattern associated with joint 1. + BooleanVector colwise_joint1_sparsity; + + /// \brief Colwise sparsity pattern associated with joint 2. + BooleanVector colwise_joint2_sparsity; + + /// \brief Jointwise span indexes associated with joint 1. + EigenIndexVector joint1_span_indexes; + + /// \brief Jointwise span indexes associated with joint 2. + EigenIndexVector joint2_span_indexes; + + EigenIndexVector loop_span_indexes; + + /// \brief Sparsity pattern associated to the constraint; + BooleanVector colwise_sparsity; + + /// \brief Indexes of the columns spanned by the constraints. + EigenIndexVector colwise_span_indexes; + + /// \brief Dimensions of the model + int nv; + + ///  \brief Depth of the kinematic tree for joint1 and joint2 + size_t depth_joint1, depth_joint2; + + protected: + using BaseCommonParameters::m_compliance; + // CHOICE: right now we use the scalar Baumgarte + // using BaseCommonParameters::m_baumgarte_vector_parameters; + using BaseCommonParameters::m_baumgarte_parameters; + + public: + /// + ///  \brief Default constructor + /// + PointConstraintModelBase() + : nv(-1) + , depth_joint1(0) + , depth_joint2(0) + { + } + + // public: + /// + ///  \brief Contructor with from a given type, joint indexes and placements. + /// + /// \param[in] type Type of the contact. + /// \param[in] model Model associated to the constraint. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// \param[in] joint2_id Index of the joint 2 in the model tree. + /// \param[in] joint1_placement Placement of the constraint w.r.t the frame of joint1. + /// \param[in] joint2_placement Placement of the constraint w.r.t the frame of joint2. + /// \param[in] reference_frame Reference frame in which the constraints quantities are + /// expressed. + /// + template class JointCollectionTpl> + PointConstraintModelBase( + const ModelTpl & model, + const JointIndex joint1_id, + const SE3 & joint1_placement, + const JointIndex joint2_id, + const SE3 & joint2_placement) + : Base(model, joint1_id, joint2_id) + , joint1_placement(joint1_placement) + , joint2_placement(joint2_placement) + , desired_constraint_offset(Vector3::Zero()) + , desired_constraint_velocity(Vector3::Zero()) + , desired_constraint_acceleration(Vector3::Zero()) + , colwise_joint1_sparsity(model.nv) + , colwise_joint2_sparsity(model.nv) + , loop_span_indexes((size_t)model.nv) + { + init(model); + } + + /// + ///  \brief Contructor with from a given type, joint1_id and placement. + /// + /// \param[in] type Type of the contact. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// \param[in] joint1_placement Placement of the constraint w.r.t the frame of joint1. + /// \param[in] reference_frame Reference frame in which the constraints quantities are + /// expressed. + /// + template class JointCollectionTpl> + PointConstraintModelBase( + const ModelTpl & model, + const JointIndex joint1_id, + const SE3 & joint1_placement) + : Base(model, joint1_id, 0) + , joint1_placement(joint1_placement) + , joint2_placement(SE3::Identity()) + , desired_constraint_offset(Vector3::Zero()) + , desired_constraint_velocity(Vector3::Zero()) + , desired_constraint_acceleration(Vector3::Zero()) + , colwise_joint1_sparsity(model.nv) + , colwise_joint2_sparsity(model.nv) + , loop_span_indexes((size_t)model.nv) + { + init(model); + } + + /// + ///  \brief Contructor with from a given type and the joint ids. + /// + /// \param[in] type Type of the contact. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// \param[in] joint2_id Index of the joint 2 in the model tree. + /// + template class JointCollectionTpl> + PointConstraintModelBase( + const ModelTpl & model, + const JointIndex joint1_id, + const JointIndex joint2_id) + : Base(model, joint1_id, joint2_id) + , joint1_placement(SE3::Identity()) + , joint2_placement(SE3::Identity()) + , desired_constraint_offset(Vector3::Zero()) + , desired_constraint_velocity(Vector3::Zero()) + , desired_constraint_acceleration(Vector3::Zero()) + , colwise_joint1_sparsity(model.nv) + , colwise_joint2_sparsity(model.nv) + , loop_span_indexes((size_t)model.nv) + { + init(model); + } + + /// + ///  \brief Contructor with from a given type and . + /// + /// \param[in] type Type of the contact. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// + /// \remarks The second joint id (joint2_id) is set to be 0 (corresponding to the index of the + /// universe). + /// + template class JointCollectionTpl> + PointConstraintModelBase( + const ModelTpl & model, const JointIndex joint1_id) + : Base(model, joint1_id, 0) + , joint1_placement(SE3::Identity()) + , joint2_placement(SE3::Identity()) + , desired_constraint_offset(Vector3::Zero()) + , desired_constraint_velocity(Vector3::Zero()) + , desired_constraint_acceleration(Vector3::Zero()) + , colwise_joint1_sparsity(model.nv) + , colwise_joint2_sparsity(model.nv) + , loop_span_indexes((size_t)model.nv) + { + init(model); + } + + /// + /// \brief Create data storage associated to the constraint + /// + ConstraintData createData() const + { + return ConstraintData(*this); + } + + /// \brief Returns the colwise sparsity associated with a given row + const BooleanVector & getRowActivableSparsityPattern(const Eigen::DenseIndex row_id) const + { + PINOCCHIO_CHECK_INPUT_ARGUMENT(row_id < size()); + return colwise_sparsity; + } + + /// \brief Returns the sparsity associated with a given row + const BooleanVector & getRowActiveSparsityPattern(const Eigen::DenseIndex row_id) const + { + return getRowActivableSparsityPattern(row_id); + } + + /// \brief Returns the vector of the active indexes associated with a given row + const EigenIndexVector & getRowActivableIndexes(const Eigen::DenseIndex row_id) const + { + PINOCCHIO_CHECK_INPUT_ARGUMENT(row_id < size()); + return colwise_span_indexes; + } + + /// \brief Returns the vector of the active indexes associated with a given row + const EigenIndexVector & getRowActiveIndexes(const Eigen::DenseIndex row_id) const + { + return getRowActivableIndexes(row_id); + } + + /// \brief Returns the compliance internally stored in the constraint model + ActiveComplianceVectorTypeConstRef getActiveCompliance_impl() const + { + return this->compliance(); + } + + /// \brief Returns the compliance internally stored in the constraint model + ActiveComplianceVectorTypeRef getActiveCompliance_impl() + { + return this->compliance(); + } + + /// + ///  \brief Comparison operator + /// + /// \param[in] other Other PointConstraintModelBase to compare with. + /// + /// \returns true if the two *this is equal to other (type, joint1_id and placement attributs + /// must be the same). + /// + bool operator==(const PointConstraintModelBase & other) const + { + if (this == &other) + return true; + return base() == other.base() && base_common_parameters() == other.base_common_parameters() + && joint1_id == other.joint1_id && joint2_id == other.joint2_id + && joint1_placement == other.joint1_placement + && joint2_placement == other.joint2_placement && nv == other.nv + && desired_constraint_offset == other.desired_constraint_offset + && desired_constraint_velocity == other.desired_constraint_velocity + && desired_constraint_acceleration == other.desired_constraint_acceleration + && colwise_joint1_sparsity == other.colwise_joint1_sparsity + && colwise_joint2_sparsity == other.colwise_joint2_sparsity + && joint1_span_indexes == other.joint1_span_indexes + && joint2_span_indexes == other.joint2_span_indexes && nv == other.nv + && depth_joint1 == other.depth_joint1 && depth_joint2 == other.depth_joint2 + && colwise_sparsity == other.colwise_sparsity + && colwise_span_indexes == other.colwise_span_indexes + && loop_span_indexes == other.loop_span_indexes; + } + + /// + ///  \brief Oposite of the comparison operator. + /// + /// \param[in] other Other PointConstraintModelBase to compare with. + /// + /// \returns false if the two *this is not equal to other (at least type, joint1_id or placement + /// attributs is different). + /// + bool operator!=(const PointConstraintModelBase & other) const + { + return !(*this == other); + } + + /// \brief Evaluate the constraint values at the current state given by data and store the + /// results in cdata. + template class JointCollectionTpl> + void calc( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata) const + { + PINOCCHIO_UNUSED_VARIABLE(model); + + if (joint1_id > 0) + cdata.oMc1 = data.oMi[joint1_id] * joint1_placement; + else + cdata.oMc1 = joint1_placement; + + if (joint2_id > 0) + cdata.oMc2 = data.oMi[joint2_id] * joint2_placement; + else + cdata.oMc2 = joint2_placement; + + // Compute relative placement + cdata.c1Mc2 = cdata.oMc1.actInv(cdata.oMc2); + const auto & _1R2_ = cdata.c1Mc2.rotation(); + + // Compute errors + auto & position_error = cdata.constraint_position_error; + position_error.noalias() = cdata.c1Mc2.translation(); + // cdata.constraint_position_error = cdata.oMc1.inverse().translation(); + + const auto vf1 = joint1_placement.actInv(data.v[this->joint1_id]); + const auto vf2 = joint2_placement.actInv(data.v[this->joint2_id]); + + auto & velocity_error = cdata.constraint_velocity_error; + const Vector3 velocity_error_component1 = _1R2_ * vf2.linear() - vf1.linear(); + velocity_error.noalias() = velocity_error_component1 - vf1.angular().cross(position_error); + + const auto af1 = joint1_placement.actInv(data.a[this->joint1_id]); + const auto af2 = joint2_placement.actInv(data.a[this->joint2_id]); + auto & acceleration_error = cdata.constraint_acceleration_error; + acceleration_error.noalias() = _1R2_ * (af2.linear() + vf2.angular().cross(vf2.linear())) + - (af1.linear() + vf1.angular().cross(vf1.linear())); + acceleration_error.noalias() -= af1.angular().cross(position_error); + acceleration_error.noalias() += vf1.angular().cross(vf1.angular().cross(position_error)); + acceleration_error.noalias() -= 2 * vf1.angular().cross(velocity_error_component1); + + cdata.A1_world = this->getA1(cdata, WorldFrameTag()); + cdata.A2_world = this->getA2(cdata, WorldFrameTag()); + cdata.A_world = cdata.A1_world + cdata.A2_world; + + cdata.A1_local = this->getA1(cdata, LocalFrameTag()); + cdata.A2_local = this->getA2(cdata, LocalFrameTag()); + cdata.A_local = cdata.A1_local + cdata.A2_local; + } + + /// \brief Returns the constraint projector associated with joint 1. + /// This matrix transforms a spatial velocity expressed at the origin to the first component of + /// the constraint associated with joint 1. + template + Matrix36 getA1(const ConstraintData & cdata, ReferenceFrameTag) const + { + Matrix36 res; + + if (std::is_same, WorldFrameTag>::value) + { +#define INTERNAL_LOOP(axis_id, v3_in, res) \ + CartesianAxis::cross(v3_in, v_tmp); \ + res.col(axis_id).noalias() = oM1.rotation().transpose() * v_tmp; + + const SE3 & oM1 = cdata.oMc1; + Vector3 v_tmp; + res.template leftCols<3>() = -oM1.rotation().transpose(); + INTERNAL_LOOP(0, -oM1.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(1, -oM1.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(2, -oM1.translation(), res.template rightCols<3>()); + + for (int i = 0; i < 3; ++i) + { + res.template rightCols<3>().col(i) += + cdata.constraint_position_error.cross(oM1.rotation().transpose().col(i)); + } + +#undef INTERNAL_LOOP + } + else if (std::is_same, LocalFrameTag>::value) + { +#define INTERNAL_LOOP(axis_id, v3_in, res) \ + CartesianAxis::cross(v3_in, v_tmp); \ + res.col(axis_id).noalias() = iM1.rotation().transpose() * v_tmp; + + const SE3 & iM1 = this->joint1_placement; + Vector3 v_tmp; + res.template leftCols<3>() = -iM1.rotation().transpose(); + INTERNAL_LOOP(0, -iM1.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(1, -iM1.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(2, -iM1.translation(), res.template rightCols<3>()); + + for (int i = 0; i < 3; ++i) + { + res.template rightCols<3>().col(i) += + cdata.constraint_position_error.cross(iM1.rotation().transpose().col(i)); + } + } + else + { + assert(false && "Should never happened"); + } + +#undef INTERNAL_LOOP + + return res; + } + + /// \brief Returns the constraint projector associated with joint 2. + /// This matrix transforms a spatial velocity expressed at the origin to the first component of + /// the constraint associated with joint 2. + template + Matrix36 getA2(const ConstraintData & cdata, ReferenceFrameTag) const + { + Matrix36 res; + typedef typename SE3::Vector3 Vector3; + + if (std::is_same, WorldFrameTag>::value) + { +#define INTERNAL_LOOP(axis_id, v3_in, res) \ + CartesianAxis::cross(v3_in, v_tmp); \ + res.col(axis_id).noalias() = oM1.rotation().transpose() * v_tmp; + + const SE3 & oM1 = cdata.oMc1; + const SE3 & oM2 = cdata.oMc2; + res.template leftCols<3>() = oM1.rotation().transpose(); + Vector3 v_tmp; + INTERNAL_LOOP(0, oM2.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(1, oM2.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(2, oM2.translation(), res.template rightCols<3>()); + +#undef INTERNAL_LOOP + } + else if (std::is_same, LocalFrameTag>::value) + { + const SE3 & j2Mc2 = this->joint2_placement; + const SE3 & c1Mc2 = cdata.c1Mc2; + const typename SE3::Matrix3 c1Rj2 = c1Mc2.rotation() * j2Mc2.rotation().transpose(); + res.template leftCols<3>() = c1Rj2; + Vector3 v_tmp; +#define INTERNAL_LOOP(axis_id, v3_in, res) \ + CartesianAxis::cross(v3_in, v_tmp); \ + res.col(axis_id).noalias() = c1Rj2 * v_tmp; + + INTERNAL_LOOP(0, j2Mc2.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(1, j2Mc2.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(2, j2Mc2.translation(), res.template rightCols<3>()); + +#undef INTERNAL_LOOP + } + else + { + assert(false && "Should never happened"); + } + + return res; + } + + /// + /// @brief This function computes the spatial inertia associated with the constraint. + /// This function is useful to express the constraint inertia associated with the constraint for + /// AL-based approaches. + /// + template + Matrix6 computeConstraintSpatialInertia( + const SE3Tpl & placement, + const Eigen::MatrixBase & diagonal_constraint_inertia) const + { + EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Vector3Like, Vector3); + Matrix6 res; + + const auto & R = placement.rotation(); + const auto & t = placement.translation(); + + typedef Eigen::Matrix Matrix3; + const Matrix3 R_Sigma = R * diagonal_constraint_inertia.asDiagonal(); + const Matrix3 t_skew = skew(t); + + auto block_LL = res.template block<3, 3>(SE3::LINEAR, SE3::LINEAR); + auto block_LA = res.template block<3, 3>(SE3::LINEAR, SE3::ANGULAR); + auto block_AL = res.template block<3, 3>(SE3::ANGULAR, SE3::LINEAR); + auto block_AA = res.template block<3, 3>(SE3::ANGULAR, SE3::ANGULAR); + + block_LL.noalias() = R_Sigma * R.transpose(); + block_LA.noalias() = -block_LL * t_skew; + block_AL.noalias() = block_LA.transpose(); + block_AA.noalias() = t_skew * block_LA; + + return res; + } + + template< + typename Matrix6LikeOut1, + typename Matrix6LikeOut2, + typename Matrix6LikeOut3, + ReferenceFrame rf> + void computeConstraintInertias( + const ConstraintData & cdata, + const Scalar & constraint_inertia_value, + const Eigen::MatrixBase & I11, + const Eigen::MatrixBase & I12, + const Eigen::MatrixBase & I22, + const ReferenceFrameTag reference_frame) const + { + computeConstraintInertias( + cdata, Vector3::Constant(constraint_inertia_value), I11.const_cast_derived(), + I12.const_cast_derived(), I22.const_cast_derived(), reference_frame); + } + + template< + typename Vector3Like, + typename Matrix6LikeOut1, + typename Matrix6LikeOut2, + typename Matrix6LikeOut3, + ReferenceFrame rf> + void computeConstraintInertias( + const ConstraintData & cdata, + const Eigen::MatrixBase & diagonal_constraint_inertia, + const Eigen::MatrixBase & I11, + const Eigen::MatrixBase & I12, + const Eigen::MatrixBase & I22, + const ReferenceFrameTag reference_frame) const + { + EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Vector3Like, Vector3); + EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Matrix6LikeOut1, Matrix6); + EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Matrix6LikeOut2, Matrix6); + EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Matrix6LikeOut3, Matrix6); + PINOCCHIO_UNUSED_VARIABLE(reference_frame); + // assert((check_expression_if_real(diagonal_constraint_inertia.isZero(Scalar(0))))); + + const auto & A1 = + std::is_same, WorldFrameTag>::value ? cdata.A1_world : cdata.A1_local; + const auto & A2 = + std::is_same, WorldFrameTag>::value ? cdata.A2_world : cdata.A2_local; + + Matrix36 diagonal_constraint_inertia_time_A; + + if (joint1_id > 0) + { + diagonal_constraint_inertia_time_A.noalias() = + diagonal_constraint_inertia.asDiagonal() * A1; + I11.const_cast_derived().noalias() = A1.transpose() * diagonal_constraint_inertia_time_A; + } + else + I11.const_cast_derived().setZero(); + + if (joint2_id > 0) + { + diagonal_constraint_inertia_time_A.noalias() = + diagonal_constraint_inertia.asDiagonal() * A2; + I22.const_cast_derived().noalias() = A2.transpose() * diagonal_constraint_inertia_time_A; + } + else + I22.const_cast_derived().setZero(); + + // Compute the cross coupling term + if (joint1_id > 0 && joint2_id > 0) + { + I12.const_cast_derived().noalias() = A1.transpose() * diagonal_constraint_inertia_time_A; + } + else + I12.const_cast_derived().setZero(); + } + + template< + template class JointCollectionTpl, + typename Vector3Like, + ReferenceFrame rf> + void appendCouplingConstraintInertias( + const ModelTpl & model, + DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & diagonal_constraint_inertia, + const ReferenceFrameTag reference_frame) const + { + PINOCCHIO_UNUSED_VARIABLE(model); + + Matrix6 I11, I12, I22; + computeConstraintInertias(cdata, diagonal_constraint_inertia, I11, I12, I22, reference_frame); + assert( + (std::is_same, WorldFrameTag>::value + || std::is_same, LocalFrameTag>::value) + && "must never happened"); + + Matrix6 & Y1 = std::is_same, WorldFrameTag>::value + ? data.oYaba_augmented[joint1_id] + : data.oYaba_augmented[joint1_id]; + + if (joint1_id > 0) + Y1 += I11; + + Matrix6 & Y2 = std::is_same, WorldFrameTag>::value + ? data.oYaba_augmented[joint2_id] + : data.oYaba_augmented[joint2_id]; + + if (joint2_id > 0) + Y2 += I22; + + if (joint1_id > 0 && joint2_id > 0) + { + if (joint1_id < joint2_id) + { + data.joint_cross_coupling.get({joint1_id, joint2_id}) += I12; + } + else + { + data.joint_cross_coupling.get({joint2_id, joint1_id}) += I12.transpose(); + } + } + } + + template class JointCollectionTpl> + typename traits::template JacobianMatrixProductReturnType::type + jacobianMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat) const + { + typedef typename traits::template JacobianMatrixProductReturnType::type + ReturnType; + ReturnType res(3, mat.cols()); + jacobianMatrixProduct(model, data, cdata, mat.derived(), res); + return res; + } + + template< + typename InputMatrix, + typename OutputMatrix, + template class JointCollectionTpl, + AssignmentOperatorType op = SETTO> + void jacobianMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat, + const Eigen::MatrixBase & _res, + AssignmentOperatorTag aot = SetTo()) const + { + typedef DataTpl Data; + typedef typename Data::Vector3 Vector3; + OutputMatrix & res = _res.const_cast_derived(); + + PINOCCHIO_CHECK_ARGUMENT_SIZE(mat.rows(), model.nv); + PINOCCHIO_CHECK_ARGUMENT_SIZE(mat.cols(), res.cols()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res.rows(), size()); + PINOCCHIO_UNUSED_VARIABLE(aot); + + if (std::is_same, SetTo>::value) + res.setZero(); + + // const Eigen::DenseIndex constraint_dim = size(); + // + // const Eigen::DenseIndex + // complexity_strategy_1 = 6 * res.cols() * 36 + constraint_dim * 36 * res.cols(), + // complexity_strategy_2 = 36 * constraint_dim * 6 + constraint_dim * 36 * res.cols(); + + const auto & A1 = cdata.A1_world; + const auto & A2 = cdata.A2_world; + + const auto & A = cdata.A_world; + for (Eigen::DenseIndex jj = 0; jj < model.nv; ++jj) + { + if (!(colwise_joint1_sparsity[jj] || colwise_joint2_sparsity[jj])) + continue; + Vector3 AxSi; + + typedef typename Data::Matrix6x::ConstColXpr ConstColXpr; + const ConstColXpr Jcol = data.J.col(jj); + + if (colwise_joint1_sparsity[jj] && colwise_joint2_sparsity[jj]) + { + AxSi.noalias() = A * Jcol; + } + else if (colwise_joint1_sparsity[jj]) + AxSi.noalias() = A1 * Jcol; + else + AxSi.noalias() = A2 * Jcol; + + if (std::is_same, RmTo>::value) + res.noalias() -= AxSi * mat.row(jj); + else // AddTo, SetTo + res.noalias() += AxSi * mat.row(jj); + } + } + + template class JointCollectionTpl> + typename traits::template JacobianTransposeMatrixProductReturnType::type + jacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat) const + { + typedef typename traits::template JacobianTransposeMatrixProductReturnType< + InputMatrix>::type ReturnType; + ReturnType res(model.nv, mat.cols()); + jacobianTransposeMatrixProduct(model, data, cdata, mat.derived(), res); + return res; + } + + template< + typename InputMatrix, + typename OutputMatrix, + template class JointCollectionTpl, + AssignmentOperatorType op = SETTO> + void jacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & mat, + const Eigen::MatrixBase & _res, + AssignmentOperatorTag aot = SetTo()) const + { + typedef DataTpl Data; + typedef typename Data::Vector3 Vector3; + OutputMatrix & res = _res.const_cast_derived(); + + PINOCCHIO_CHECK_ARGUMENT_SIZE(mat.rows(), size()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res.cols(), mat.cols()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res.rows(), model.nv); + PINOCCHIO_UNUSED_VARIABLE(aot); + + if (std::is_same, SetTo>::value) + res.setZero(); + + const auto & A1 = cdata.A1_world; + const auto & A2 = cdata.A2_world; + + const auto & A = cdata.A_world; + for (Eigen::DenseIndex jj = 0; jj < model.nv; ++jj) + { + if (!(colwise_joint1_sparsity[jj] || colwise_joint2_sparsity[jj])) + continue; + Vector3 AxSi; + + typedef typename Data::Matrix6x::ConstColXpr ConstColXpr; + const ConstColXpr Jcol = data.J.col(jj); + + if (colwise_joint1_sparsity[jj] && colwise_joint2_sparsity[jj]) + { + AxSi.noalias() = A * Jcol; + } + else if (colwise_joint1_sparsity[jj]) + AxSi.noalias() = A1 * Jcol; + else + AxSi.noalias() = A2 * Jcol; + + if (std::is_same, RmTo>::value) + res.row(jj).noalias() -= AxSi.transpose() * mat; + else + res.row(jj).noalias() += AxSi.transpose() * mat; + } + } + + using RootBase::jacobian; + + ///  \brief Evaluate the Jacobian associated to the constraint at the given state stored in data + /// and cdata.  The results Jacobian is evaluated in the jacobian input/output matrix. + template class JointCollectionTpl, typename JacobianMatrix> + void jacobian( + const ModelTpl & model, + const DataTpl & data, + ConstraintData & cdata, + const Eigen::MatrixBase & _jacobian_matrix) const + { + typedef DataTpl Data; + JacobianMatrix & jacobian_matrix = _jacobian_matrix.const_cast_derived(); + + // const PointConstraintModelBase & cmodel = *this; + + const SE3 & oMc1 = cdata.oMc1; + const SE3 & oMc2 = cdata.oMc2; + const SE3 & c1Mc2 = cdata.c1Mc2; + const auto & position_error = cdata.constraint_position_error; + + for (Eigen::DenseIndex jj = 0; jj < model.nv; ++jj) + { + if (colwise_joint1_sparsity[jj] || colwise_joint2_sparsity[jj]) + { + typedef typename Data::Matrix6x::ConstColXpr ConstColXpr; + const ConstColXpr Jcol = data.J.col(jj); + const MotionRef Jcol_motion(Jcol); + + jacobian_matrix.col(jj).setZero(); + if (colwise_joint1_sparsity[jj]) + { + const Motion Jcol_local(oMc1.actInv(Jcol_motion)); // TODO: simplify computations + jacobian_matrix.col(jj).noalias() -= Jcol_local.linear(); + jacobian_matrix.col(jj).noalias() += -Jcol_local.angular().cross(position_error); + } + + if (colwise_joint2_sparsity[jj]) + { + const Motion Jcol_local(oMc2.actInv(Jcol_motion)); // TODO: simplify computations + jacobian_matrix.col(jj) += c1Mc2.rotation() * Jcol_local.linear(); + } + } + } + } + + /// + /// \copydoc Base::mapConstraintForceToJointForces(const ModelTpl &, const DataTpl &, const + /// ConstraintData &, const Eigen::MatrixBase &, std::vector, ForceAllocator> &, ReferenceFrameTag) + /// + template< + template class JointCollectionTpl, + typename ForceLike, + typename ForceAllocator, + ReferenceFrame rf> + void mapConstraintForceToJointForces( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & constraint_forces, + std::vector, ForceAllocator> & joint_forces, + ReferenceFrameTag reference_frame) const + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(joint_forces.size(), size_t(model.njoints)); + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_forces.rows(), size()); + PINOCCHIO_UNUSED_VARIABLE(data); + PINOCCHIO_UNUSED_VARIABLE(reference_frame); + + // Todo: optimize code + const auto & A1 = + std::is_same, WorldFrameTag>::value ? cdata.A1_world : cdata.A1_local; + const auto & A2 = + std::is_same, WorldFrameTag>::value ? cdata.A2_world : cdata.A2_local; + + if (joint1_id > 0) + joint_forces[this->joint1_id].toVector().noalias() += A1.transpose() * constraint_forces; + if (joint2_id > 0) + joint_forces[this->joint2_id].toVector().noalias() += A2.transpose() * constraint_forces; + } + + /// + /// \copydoc Base::mapJointMotionsToConstraintMotion(const ModelTpl &, const DataTpl &, const + /// ConstraintData &, const std::vector, MotionAllocator> &, const + /// Eigen::MatrixBase &, ReferenceFrameTag) + /// + template< + template class JointCollectionTpl, + typename MotionAllocator, + typename VectorLike, + ReferenceFrame rf> + void mapJointMotionsToConstraintMotion( + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const std::vector, MotionAllocator> & joint_accelerations, + const Eigen::MatrixBase & constraint_motion, + ReferenceFrameTag reference_frame) const + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(joint_accelerations.size(), size_t(model.njoints)); + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_motion.rows(), activeSize()); + PINOCCHIO_UNUSED_VARIABLE(data); + PINOCCHIO_UNUSED_VARIABLE(reference_frame); + + const auto & A1 = + std::is_same, WorldFrameTag>::value ? cdata.A1_world : cdata.A1_local; + const auto & A2 = + std::is_same, WorldFrameTag>::value ? cdata.A2_world : cdata.A2_local; + + if (joint1_id > 0 && joint2_id > 0) + constraint_motion.const_cast_derived().noalias() = + A1 * joint_accelerations[this->joint1_id].toVector() + + A2 * joint_accelerations[this->joint2_id].toVector(); + else if (joint1_id > 0) + constraint_motion.const_cast_derived().noalias() = + A1 * joint_accelerations[this->joint1_id].toVector(); + else if (joint2_id > 0) + constraint_motion.const_cast_derived().noalias() = + A2 * joint_accelerations[this->joint2_id].toVector(); + else + constraint_motion.const_cast_derived().setZero(); + } + + static int size() + { + return 3; + } + + static int activeSize() + { + return size(); + } + + /// \returns An expression of *this with the Scalar type casted to NewScalar. + template + void cast(PointConstraintModelBase & res) const + { + Base::cast(res); + BaseCommonParameters::template cast(res); + + res.joint1_id = joint1_id; + res.joint2_id = joint2_id; + res.joint1_placement = joint1_placement.template cast(); + res.joint2_placement = joint2_placement.template cast(); + res.desired_constraint_offset = desired_constraint_offset.template cast(); + res.desired_constraint_velocity = desired_constraint_velocity.template cast(); + res.desired_constraint_acceleration = + desired_constraint_acceleration.template cast(); + res.colwise_joint1_sparsity = colwise_joint1_sparsity; + res.colwise_joint2_sparsity = colwise_joint2_sparsity; + res.joint1_span_indexes = joint1_span_indexes; + res.joint2_span_indexes = joint2_span_indexes; + res.colwise_sparsity = colwise_sparsity; + res.colwise_span_indexes = colwise_span_indexes; + res.nv = nv; + res.depth_joint1 = depth_joint1; + res.depth_joint2 = depth_joint2; + res.loop_span_indexes = loop_span_indexes; + } + + protected: + template class JointCollectionTpl> + void init(const ModelTpl & model) + { + nv = model.nv; + depth_joint1 = static_cast(model.supports[joint1_id].size()); + depth_joint2 = static_cast(model.supports[joint2_id].size()); + + typedef ModelTpl Model; + typedef typename Model::JointModel JointModel; + static const bool default_sparsity_value = false; + colwise_joint1_sparsity.fill(default_sparsity_value); + colwise_joint2_sparsity.fill(default_sparsity_value); + + joint1_span_indexes.reserve(size_t(model.njoints)); + joint2_span_indexes.reserve(size_t(model.njoints)); + + JointIndex current1_id = 0; + if (joint1_id > 0) + current1_id = joint1_id; + + JointIndex current2_id = 0; + if (joint2_id > 0) + current2_id = joint2_id; + + while (current1_id != current2_id) + { + if (current1_id > current2_id) + { + const JointModel & joint1 = model.joints[current1_id]; + joint1_span_indexes.push_back((Eigen::DenseIndex)current1_id); + Eigen::DenseIndex current1_col_id = joint1.idx_v(); + for (int k = 0; k < joint1.nv(); ++k, ++current1_col_id) + { + colwise_joint1_sparsity[current1_col_id] = true; + } + current1_id = model.parents[current1_id]; + } + else + { + const JointModel & joint2 = model.joints[current2_id]; + joint2_span_indexes.push_back((Eigen::DenseIndex)current2_id); + Eigen::DenseIndex current2_col_id = joint2.idx_v(); + for (int k = 0; k < joint2.nv(); ++k, ++current2_col_id) + { + colwise_joint2_sparsity[current2_col_id] = true; + } + current2_id = model.parents[current2_id]; + } + } + assert(current1_id == current2_id && "current1_id should be equal to current2_id"); + + { + JointIndex current_id = current1_id; + while (current_id > 0) + { + const JointModel & joint = model.joints[current_id]; + joint1_span_indexes.push_back((Eigen::DenseIndex)current_id); + joint2_span_indexes.push_back((Eigen::DenseIndex)current_id); + Eigen::DenseIndex current_row_id = joint.idx_v(); + for (int k = 0; k < joint.nv(); ++k, ++current_row_id) + { + colwise_joint1_sparsity[current_row_id] = true; + colwise_joint2_sparsity[current_row_id] = true; + } + current_id = model.parents[current_id]; + } + } + std::reverse(joint1_span_indexes.begin(), joint1_span_indexes.end()); + std::reverse(joint2_span_indexes.begin(), joint2_span_indexes.end()); + colwise_span_indexes.reserve((size_t)model.nv); + colwise_sparsity.resize(model.nv); + colwise_sparsity.setZero(); + loop_span_indexes.reserve((size_t)model.nv); + for (Eigen::DenseIndex col_id = 0; col_id < model.nv; ++col_id) + { + if (colwise_joint1_sparsity[col_id] || colwise_joint2_sparsity[col_id]) + { + colwise_span_indexes.push_back(col_id); + colwise_sparsity[col_id] = true; + } + + if (colwise_joint1_sparsity[col_id] != colwise_joint2_sparsity[col_id]) + { + loop_span_indexes.push_back(col_id); + } + } + + // Set compliance and baumgarte parameters + m_compliance = ComplianceVectorType::Zero(size()); + // CHOICE: right now we use the scalar Baumgarte + // m_baumgarte_vector_parameters = BaumgarteCorrectorVectorParameters(size()); + m_baumgarte_parameters = BaumgarteCorrectorParameters(); + } + }; // PointConstraintModelBase + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_point_constraint_model_base_hpp__ diff --git a/include/pinocchio/algorithm/constraints/point-frictional-constraint.hpp b/include/pinocchio/algorithm/constraints/point-frictional-constraint.hpp new file mode 100644 index 0000000000..68f171a1c3 --- /dev/null +++ b/include/pinocchio/algorithm/constraints/point-frictional-constraint.hpp @@ -0,0 +1,325 @@ +// +// Copyright (c) 2019-2024 INRIA CNRS +// + +#ifndef __pinocchio_algorithm_constraints_frictional_point_constraint_hpp__ +#define __pinocchio_algorithm_constraints_frictional_point_constraint_hpp__ + +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/coulomb-friction-cone.hpp" +#include "pinocchio/algorithm/constraints/point-constraint-model-base.hpp" +#include "pinocchio/algorithm/constraints/point-constraint-data-base.hpp" + +namespace pinocchio +{ + + template + struct CastType> + { + typedef FrictionalPointConstraintModelTpl type; + }; + + template + struct traits> + : traits>> + { + typedef _Scalar Scalar; + + enum + { + Options = _Options + }; + + typedef FrictionalPointConstraintModelTpl ConstraintModel; + typedef FrictionalPointConstraintDataTpl ConstraintData; + typedef CoulombFrictionConeTpl ConstraintSet; + + typedef ConstraintModel Model; + typedef ConstraintData Data; + + typedef Eigen::Matrix Vector3; + typedef Eigen::Matrix JacobianMatrixType; + typedef Vector3 VectorConstraintSize; + + typedef Vector3 ComplianceVectorType; + typedef ComplianceVectorType & ComplianceVectorTypeRef; + typedef const ComplianceVectorType & ComplianceVectorTypeConstRef; + + typedef ComplianceVectorTypeRef ActiveComplianceVectorTypeRef; + typedef ComplianceVectorTypeConstRef ActiveComplianceVectorTypeConstRef; + + typedef Vector3 BaumgarteVectorType; + typedef BaumgarteCorrectorVectorParametersTpl + BaumgarteCorrectorVectorParameters; + typedef BaumgarteCorrectorVectorParameters & BaumgarteCorrectorVectorParametersRef; + typedef const BaumgarteCorrectorVectorParameters & BaumgarteCorrectorVectorParametersConstRef; + }; + + template + struct traits> + : traits> + { + }; + + /// + ///  \brief Contact model structure containg all the info describing the rigid contact model + /// + template + struct FrictionalPointConstraintModelTpl + : PointConstraintModelBase> + { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + + typedef PointConstraintModelBase Base; + typedef ConstraintModelBase RootBase; + + template + friend struct FrictionalPointConstraintModelTpl; + + typedef FrictionalPointConstraintDataTpl ConstraintData; + typedef CoulombFrictionConeTpl ConstraintSet; + + using typename Base::BooleanVector; + using typename Base::EigenIndexVector; + using typename Base::Force; + using typename Base::Matrix36; + using typename Base::Matrix6; + using typename Base::Motion; + using typename Base::SE3; + using typename Base::Vector3; + using typename Base::Vector6; + using typename Base::VectorConstraintSize; + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + /// + ///  \brief Default constructor + /// + FrictionalPointConstraintModelTpl() + : Base() + { + } + + /// + ///  \brief Contructor with from a given type, joint indexes and placements. + /// + /// \param[in] type Type of the contact. + /// \param[in] model Model associated to the constraint. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// \param[in] joint2_id Index of the joint 2 in the model tree. + /// \param[in] joint1_placement Placement of the constraint w.r.t the frame of joint1. + /// \param[in] joint2_placement Placement of the constraint w.r.t the frame of joint2. + /// expressed. + /// + template class JointCollectionTpl> + FrictionalPointConstraintModelTpl( + const ModelTpl & model, + const JointIndex joint1_id, + const SE3 & joint1_placement, + const JointIndex joint2_id, + const SE3 & joint2_placement) + : Base(model, joint1_id, joint1_placement, joint2_id, joint2_placement) + { + } + + /// + ///  \brief Contructor with from a given type, joint1_id and placement. + /// + /// \param[in] type Type of the contact. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// \param[in] joint1_placement Placement of the constraint w.r.t the frame of joint1. + /// expressed. + /// + template class JointCollectionTpl> + FrictionalPointConstraintModelTpl( + const ModelTpl & model, + const JointIndex joint1_id, + const SE3 & joint1_placement) + : Base(model, joint1_id, joint1_placement) + { + } + + /// + ///  \brief Contructor with from a given type and the joint ids. + /// + /// \param[in] type Type of the contact. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// \param[in] joint2_id Index of the joint 2 in the model tree. + /// + template class JointCollectionTpl> + FrictionalPointConstraintModelTpl( + const ModelTpl & model, + const JointIndex joint1_id, + const JointIndex joint2_id) + : Base(model, joint1_id, joint2_id) + { + } + + /// + ///  \brief Contructor with from a given type and . + /// + /// \param[in] type Type of the contact. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// + /// \remarks The second joint id (joint2_id) is set to be 0 (corresponding to the index of the + /// universe). + /// + template class JointCollectionTpl> + FrictionalPointConstraintModelTpl( + const ModelTpl & model, const JointIndex joint1_id) + : Base(model, joint1_id) + { + } + + /// + /// \brief Create data storage associated to the constraint + /// + ConstraintData createData() const + { + return ConstraintData(*this); + } + + /// \brief Cast operator + template + typename CastType::type cast() const + { + typedef typename CastType::type ReturnType; + ReturnType res; + Base::template cast(res); + res.m_set = m_set.template cast(); + return res; + } + + /// + ///  \brief Comparison operator + /// + /// \param[in] other Other FrictionalPointConstraintModelTpl to compare with. + /// + /// \returns true if the two *this is equal to other (type, joint1_id and placement attributs + /// must be the same). + /// + bool operator==(const FrictionalPointConstraintModelTpl & other) const + { + return base() == other.base() && m_set == other.m_set; + } + + /// + ///  \brief Oposite of the comparison operator. + /// + /// \param[in] other Other FrictionalPointConstraintModelTpl to compare with. + /// + /// \returns false if the two *this is not equal to other (at least type, joint1_id or placement + /// attributs is different). + /// + bool operator!=(const FrictionalPointConstraintModelTpl & other) const + { + return !(*this == other); + } + + const ConstraintSet & set() const + { + return m_set; + } + + ConstraintSet & set() + { + return m_set; + } + + static std::string classname() + { + return std::string("FrictionalPointConstraintModel"); + } + std::string shortname() const + { + return classname(); + } + + protected: + ConstraintSet m_set = ConstraintSet(); + + }; // struct FrictionalPointConstraintModelTpl<_Scalar,_Options> + + /// + ///  \brief Contact model structure containg all the info describing the rigid contact model + /// + template + struct FrictionalPointConstraintDataTpl + : PointConstraintDataBase> + { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + + typedef FrictionalPointConstraintModelTpl ConstraintModel; + typedef FrictionalPointConstraintDataTpl ConstraintData; + typedef PointConstraintDataBase Base; + + using typename Base::Force; + using typename Base::Matrix6; + using typename Base::Matrix6x; + using typename Base::MatrixX; + using typename Base::Motion; + using typename Base::SE3; + using typename Base::Vector3; + using typename Base::VectorOfMatrix6; + + /// \brief Default constructor + FrictionalPointConstraintDataTpl() + { + } + + explicit FrictionalPointConstraintDataTpl(const ConstraintModel & constraint_model) + : Base(constraint_model) + { + } + + bool operator==(const FrictionalPointConstraintDataTpl & other) const + { + return base() == other.base(); + } + + bool operator!=(const FrictionalPointConstraintDataTpl & other) const + { + return !(*this == other); + } + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + static std::string classname() + { + return std::string("FrictionalPointConstraintData"); + } + std::string shortname() const + { + return classname(); + } + }; // struct FrictionalPointConstraintDataTpl<_Scalar,_Options> + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_frictional_point_constraint_hpp__ diff --git a/include/pinocchio/algorithm/constraints/set-base.hpp b/include/pinocchio/algorithm/constraints/set-base.hpp new file mode 100644 index 0000000000..90f301f411 --- /dev/null +++ b/include/pinocchio/algorithm/constraints/set-base.hpp @@ -0,0 +1,83 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_set_base_hpp__ +#define __pinocchio_algorithm_constraints_set_base_hpp__ + +#include "pinocchio/algorithm/constraints/fwd.hpp" + +namespace pinocchio +{ + + template + struct SetBase + { + typedef typename traits::Scalar Scalar; + + Derived & derived() + { + return static_cast(*this); + } + + const Derived & derived() const + { + return static_cast(*this); + } + + Eigen::DenseIndex dim() const + { + return derived().dim(); + } + + template + typename PINOCCHIO_EIGEN_PLAIN_TYPE(VectorLike) + project(const Eigen::MatrixBase & x) const + { + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(VectorLike) ReturnType; + ReturnType res(x.size()); + derived().project(x, res); + return res; + } + + template + void project( + const Eigen::MatrixBase & x, + const Eigen::MatrixBase & x_proj) const + { + return derived().project(x.derived(), x_proj.const_cast_derived()); + } + + template + void scaledProject( + const Eigen::MatrixBase & x, + const Eigen::MatrixBase & scale, + const Eigen::MatrixBase & x_proj) const + { + // project x such that scale * x_proj is in the set. + return derived().scaledProject_impl( + x.derived(), scale.derived(), x_proj.const_cast_derived()); + } + + template + bool isInside(const Eigen::MatrixBase & x, Scalar prec = Scalar(0)) const + { + return derived().isInside(x, prec); + } + + template + bool operator==(const SetBase &) const + { + return true; + } + + template + bool operator!=(const SetBase & other) const + { + return !(*this == other); + } + }; // struct SetBase + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_set_base_hpp__ diff --git a/include/pinocchio/algorithm/constraints/sets.hpp b/include/pinocchio/algorithm/constraints/sets.hpp new file mode 100644 index 0000000000..9730d18add --- /dev/null +++ b/include/pinocchio/algorithm/constraints/sets.hpp @@ -0,0 +1,20 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_sets_hpp__ +#define __pinocchio_algorithm_constraints_sets_hpp__ + +#include "pinocchio/algorithm/constraints/fwd.hpp" + +// Sets +#include "pinocchio/algorithm/constraints/box-set.hpp" +#include "pinocchio/algorithm/constraints/unbounded-set.hpp" +#include "pinocchio/algorithm/constraints/null-set.hpp" + +// Cones +#include "pinocchio/algorithm/constraints/coulomb-friction-cone.hpp" +#include "pinocchio/algorithm/constraints/orthant-cone.hpp" +#include "pinocchio/algorithm/constraints/joint-limit-constraint-cone.hpp" + +#endif // ifndef __pinocchio_algorithm_constraints_sets_hpp__ diff --git a/include/pinocchio/algorithm/constraints/unbounded-set.hpp b/include/pinocchio/algorithm/constraints/unbounded-set.hpp new file mode 100644 index 0000000000..8bcd612ae0 --- /dev/null +++ b/include/pinocchio/algorithm/constraints/unbounded-set.hpp @@ -0,0 +1,150 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_unbounded_set_hpp__ +#define __pinocchio_algorithm_constraints_unbounded_set_hpp__ + +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/cone-base.hpp" + +namespace pinocchio +{ + + template + struct CastType> + { + typedef UnboundedSetTpl type; + }; + + template + struct traits> + { + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + + typedef NullSetTpl DualCone; + }; + + ///  \brief Unbounded set covering the whole space + template + struct UnboundedSetTpl : ConeBase> + { + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + typedef Eigen::Matrix Vector; + typedef ConeBase Base; + typedef typename traits::DualCone DualCone; + + /// \brief Constructor from a given size + /// + explicit UnboundedSetTpl(const Eigen::DenseIndex size) + : m_size(size) + { + } + + /// \brief Copy constructor. + UnboundedSetTpl(const UnboundedSetTpl & other) = default; + + /// \brief Copy operator + UnboundedSetTpl & operator=(const UnboundedSetTpl & other) = default; + + /// \brief Cast operator + template + UnboundedSetTpl cast() const + { + typedef UnboundedSetTpl ReturnType; + return ReturnType(this->size()); + } + + /// \brief Comparison operator + bool operator==(const UnboundedSetTpl & other) const + { + return base() == other.base() && m_size == other.m_size; + } + + /// \brief Difference operator + bool operator!=(const UnboundedSetTpl & other) const + { + return !(*this == other); + } + + /// \brief Check whether a vector x lies within the set. + /// Any vector x always belong the the unbounded set. + /// + /// \param[in] f vector to check (assimilated to a force vector). + /// + template + bool isInside(const Eigen::MatrixBase & x, const Scalar prec = Scalar(0)) const + { + assert(prec >= 0 && "prec should be positive"); + PINOCCHIO_UNUSED_VARIABLE(x); + PINOCCHIO_UNUSED_VARIABLE(prec); + return true; + } + + using Base::project; + + /// \brief Project a vector x into the set. + /// + /// \param[in] x a vector to project. + /// \param[in] res result of the projection. + /// + template + void project( + const Eigen::MatrixBase & x, + const Eigen::MatrixBase & res_) const + { + res_.const_cast_derived() = x; + } + + /// \brief Returns the dimension of the ambiant space. + Eigen::DenseIndex dim() const + { + return m_size; + } + + Eigen::DenseIndex size() const + { + return m_size; + } + + /// \brief Resize by calling the resize method of Eigen. + void resize(Eigen::DenseIndex new_size) + { + m_size = new_size; + } + + /// \brief Resize by calling the conservativeResize method of Eigen. + void conservativeResize(Eigen::DenseIndex new_size) + { + this->resize(new_size); + } + + DualCone dual() const + { + return DualCone(m_size); + } + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + protected: + Eigen::DenseIndex m_size; + }; // UnboundedSetTpl + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_unbounded_set_hpp__ diff --git a/include/pinocchio/algorithm/constraints/utils.hpp b/include/pinocchio/algorithm/constraints/utils.hpp new file mode 100644 index 0000000000..ff737192da --- /dev/null +++ b/include/pinocchio/algorithm/constraints/utils.hpp @@ -0,0 +1,35 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_algorithm_constraints_utils_hpp__ +#define __pinocchio_algorithm_constraints_utils_hpp__ + +#include "pinocchio/utils/std-vector.hpp" + +namespace pinocchio +{ + + template + typename internal::template std_vector_with_same_allocator< + std::vector>:: + template type + createData(const std::vector & constraint_models) + { + typedef typename internal::template std_vector_with_same_allocator< + std::vector>:: + template type + ReturnType; + + ReturnType constraint_datas; + constraint_datas.reserve(constraint_models.size()); + + for (const auto & cm : constraint_models) + constraint_datas.push_back(cm.createData()); + + return constraint_datas; + } + +} // namespace pinocchio + +#endif // __pinocchio_algorithm_constraints_utils_hpp__ diff --git a/include/pinocchio/algorithm/constraints/visitors/constraint-model-visitor.hpp b/include/pinocchio/algorithm/constraints/visitors/constraint-model-visitor.hpp index 5cbecd13ee..b67c9a0802 100644 --- a/include/pinocchio/algorithm/constraints/visitors/constraint-model-visitor.hpp +++ b/include/pinocchio/algorithm/constraints/visitors/constraint-model-visitor.hpp @@ -1,29 +1,163 @@ // -// Copyright (c) 2023 INRIA +// Copyright (c) 2023-2025 INRIA // #ifndef __pinocchio_algorithm_constraints_constraint_model_visitor_hpp__ #define __pinocchio_algorithm_constraints_constraint_model_visitor_hpp__ #include "pinocchio/algorithm/constraints/fwd.hpp" -// #include "pinocchio/algorithm/constraints/constraint-model-generic.hpp" -// #include "pinocchio/algorithm/constraints/constraint-data-generic.hpp" +#include "pinocchio/algorithm/constraints/constraint-model-base.hpp" +#include "pinocchio/algorithm/constraints/constraint-data-base.hpp" #include "pinocchio/multibody/visitor/fusion.hpp" namespace pinocchio { - namespace fusion + namespace visitors { + namespace bf = boost::fusion; + using fusion::NoArg; + + namespace internal + { + template + struct NoRun + { + static T run() + { + assert(false && "Should never happened."); + // Hacky way to not have to return something real. The system should throw before. + const typename std::remove_reference::type * null_ptr = NULL; + return *null_ptr; + } + }; + + // Specialization for reference types + template + struct NoRun + { + static T & run() + { + assert(false && "Should never happen."); + // Hacky way to not have to return something real. The system should throw before. + T * null_ptr = nullptr; + return *null_ptr; + } + }; + + template<> + struct NoRun + { + static void run() + { + return; + } + }; + } // namespace internal + + /** + * @brief ConstraintModelShortnameVisitor visitor + */ + struct ConstraintModelShortnameVisitor : boost::static_visitor + { + template + std::string operator()(const ConstraintModelBase & cmodel) const + { + return cmodel.shortname(); + } + std::string operator()(const boost::blank &) const + { + PINOCCHIO_THROW_PRETTY( + std::invalid_argument, "The constraint model is of type boost::blank."); + return internal::NoRun::run(); + } + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + static std::string + run(const ConstraintModelTpl & cmodel) + { + return boost::apply_visitor(ConstraintModelShortnameVisitor(), cmodel); + } + }; + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + inline std::string + shortname(const ConstraintModelTpl & cmodel) + { + return ConstraintModelShortnameVisitor::run(cmodel); + } + + /** + * @brief ConstraintDataShortnameVisitor visitor + */ + struct ConstraintDataShortnameVisitor : boost::static_visitor + { + template + std::string operator()(const ConstraintDataBase & cdata) const + { + return cdata.shortname(); + } + std::string operator()(const boost::blank &) const + { + PINOCCHIO_THROW_PRETTY( + std::invalid_argument, "The constraint data is of type boost::blank."); + return internal::NoRun::run(); + } + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + static std::string + run(const ConstraintDataTpl & cdata) + { + return boost::apply_visitor(ConstraintDataShortnameVisitor(), cdata); + } + }; + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + inline std::string + shortname(const ConstraintDataTpl & cdata) + { + return ConstraintDataShortnameVisitor::run(cdata); + } + /// /// \brief Base structure for \b Unary visitation of a ConstraintModel. /// This structure provides runners to call the right visitor according to the number of /// arguments. /// + template struct ConstraintUnaryVisitorBase { + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl, + typename ArgsTmp> + static ReturnType run( + ConstraintModelTpl & cmodel, + ConstraintDataTpl & cdata, + ArgsTmp args) + { + typedef ConstraintModelTpl ConstraintModel; + typedef ConstraintDataTpl ConstraintData; + + ModelAndDataVisitor visitor(cdata, args); + + return boost::apply_visitor(visitor, cmodel); + } template< typename Scalar, @@ -36,8 +170,10 @@ namespace pinocchio ArgsTmp args) { typedef ConstraintModelTpl ConstraintModel; - InternalVisitorModelAndData visitor( - cdata, args); + typedef ConstraintDataTpl ConstraintData; + + ModelAndDataVisitor visitor(cdata, args); + return boost::apply_visitor(visitor, cmodel); } @@ -46,12 +182,56 @@ namespace pinocchio int Options, template class ConstraintCollectionTpl, typename ArgsTmp> - static ReturnType - run(const ConstraintDataTpl & cdata, ArgsTmp args) + static ReturnType run( + const ConstraintModelTpl & cmodel, + const ConstraintDataTpl & cdata, + ArgsTmp args) { typedef ConstraintModelTpl ConstraintModel; - InternalVisitorModel visitor(args); - return boost::apply_visitor(visitor, cdata); + typedef ConstraintDataTpl ConstraintData; + + ModelAndDataVisitor visitor(cdata, args); + + return boost::apply_visitor(visitor, cmodel); + } + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl, + typename ArgsTmp> + static ReturnType + run(const ConstraintModelTpl & cmodel, ArgsTmp args) + { + ModelVisitor visitor(args); + return boost::apply_visitor(visitor, cmodel); + } + + template class ConstraintCollectionTpl> + static ReturnType + run(const ConstraintModelTpl & cmodel) + { + ModelVisitor visitor; + return boost::apply_visitor(visitor, cmodel); + } + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl, + typename ArgsTmp> + static ReturnType + run(ConstraintModelTpl & cmodel, ArgsTmp args) + { + ModelVisitor visitor(args); + return boost::apply_visitor(visitor, cmodel); + } + + template class ConstraintCollectionTpl> + static ReturnType run(ConstraintModelTpl & cmodel) + { + ModelVisitor visitor; + return boost::apply_visitor(visitor, cmodel); } private: @@ -60,12 +240,12 @@ namespace pinocchio int Options, template class ConstraintCollectionTpl, typename ArgsTmp> - struct InternalVisitorModel : public boost::static_visitor + struct ModelVisitor : public boost::static_visitor { typedef ConstraintModelTpl ConstraintModel; typedef ConstraintDataTpl ConstraintData; - InternalVisitorModel(ArgsTmp args) + ModelVisitor(ArgsTmp args) : args(args) { } @@ -78,6 +258,14 @@ namespace pinocchio bf::append(boost::ref(cmodel.derived()), args)); } + template + ReturnType operator()(ConstraintModelBase & cmodel) const + { + return bf::invoke( + &ConstraintModelVisitorDerived::template algo, + bf::append(boost::ref(cmodel.derived()), args)); + } + template ReturnType operator()(const ConstraintDataBase & cdata) const { @@ -86,199 +274,1192 @@ namespace pinocchio bf::append(boost::ref(cdata.derived()), args)); } + ReturnType operator()(const boost::blank &) const + { + PINOCCHIO_THROW_PRETTY( + std::invalid_argument, "The constraint model is of type boost::blank."); + return internal::NoRun::run(); + } + + template + ReturnType operator()(const FictiousConstraintModelTpl &) const + { + PINOCCHIO_THROW_PRETTY( + std::invalid_argument, "The constraint model is of type FictiousConstraintModelTpl."); + return internal::NoRun::run(); + } + + template + ReturnType operator()(const FictiousConstraintDataTpl &) const + { + PINOCCHIO_THROW_PRETTY( + std::invalid_argument, "The constraint data is of type FictiousConstraintDataTpl."); + return internal::NoRun::run(); + } + ArgsTmp args; }; - template< - typename Scalar, - int Options, - template class ConstraintCollectionTpl, - typename ArgsTmp> - struct InternalVisitorModelAndData : public boost::static_visitor + template class ConstraintCollectionTpl> + struct ModelVisitor + : public boost::static_visitor { typedef ConstraintModelTpl ConstraintModel; typedef ConstraintDataTpl ConstraintData; - InternalVisitorModelAndData(ConstraintData & cdata, ArgsTmp args) + ModelVisitor() + { + } + + template + ReturnType operator()(const ConstraintModelBase & cmodel) const + { + return ConstraintModelVisitorDerived::template algo( + cmodel.derived()); + } + + template + ReturnType operator()(ConstraintModelBase & cmodel) const + { + return ConstraintModelVisitorDerived::template algo( + cmodel.derived()); + } + + template + ReturnType operator()(const ConstraintDataBase & cdata) const + { + return ConstraintModelVisitorDerived::template algo( + cdata.derived()); + } + + ReturnType operator()(const boost::blank &) const + { + PINOCCHIO_THROW_PRETTY( + std::invalid_argument, "The constraint model is of type boost::blank."); + return internal::NoRun::run(); + } + + template + ReturnType operator()(const FictiousConstraintModelTpl &) const + { + PINOCCHIO_THROW_PRETTY( + std::invalid_argument, "The constraint model is of type FictiousConstraintModelTpl."); + return internal::NoRun::run(); + } + + template + ReturnType operator()(const FictiousConstraintDataTpl &) const + { + PINOCCHIO_THROW_PRETTY( + std::invalid_argument, "The constraint data is of type FictiousConstraintDataTpl."); + return internal::NoRun::run(); + } + }; // struct ModelVisitor + + template + struct ModelAndDataVisitor : public boost::static_visitor + { + + ModelAndDataVisitor(ConstraintData & cdata, ArgsTmp args) : cdata(cdata) , args(args) { } + template + ReturnType operator()(ConstraintModelBase & cmodel) const + { + typedef typename ConstraintModelBase::ConstraintData + ConstraintDataDerived; + using ConstraintDataGet = typename std::conditional< + std::is_const::value, const ConstraintDataDerived, + ConstraintDataDerived>::type; + + return bf::invoke( + &ConstraintModelVisitorDerived::template algo, + bf::append( + boost::ref(cmodel.derived()), boost::ref(boost::get(cdata)), + args)); + } + template ReturnType operator()(const ConstraintModelBase & cmodel) const { + typedef typename ConstraintModelBase::ConstraintData + ConstraintDataDerived; + using ConstraintDataGet = typename std::conditional< + std::is_const::value, const ConstraintDataDerived, + ConstraintDataDerived>::type; + return bf::invoke( &ConstraintModelVisitorDerived::template algo, bf::append( - boost::ref(cmodel.derived()), - boost::ref( - boost::get::ConstraintData>( - cdata)), + boost::ref(cmodel.derived()), boost::ref(boost::get(cdata)), args)); } + template + ReturnType operator()(const FictiousConstraintModelTpl &) const + { + PINOCCHIO_THROW_PRETTY( + std::invalid_argument, "The constraint model is of type FictiousConstraintModelTpl."); + return ReturnType(); + } + + ReturnType operator()(const boost::blank &) const + { + PINOCCHIO_THROW_PRETTY( + std::invalid_argument, "The constraint model is of type boost::blank."); + return internal::NoRun::run(); + } + ConstraintData & cdata; ArgsTmp args; - }; + }; // struct ModelAndDataVisitor }; - } // namespace fusion - - /** - * @brief ConstraintModelCalcVisitor fusion visitor - */ - template class JointCollectionTpl> - struct ConstraintModelCalcVisitor - : fusion::ConstraintUnaryVisitorBase< - ConstraintModelCalcVisitor> - { - typedef ModelTpl Model; - typedef DataTpl Data; - typedef boost::fusion::vector ArgsType; - - template - static void algo( - const pinocchio::ConstraintModelBase & cmodel, - typename ConstraintModel::ConstraintData & cdata, - const Model & model, - const Data & data) - { - cmodel.calc(model, data, cdata.derived()); + + /** + * @brief ConstraintModelCalcVisitor fusion visitor + */ + template class JointCollectionTpl> + struct ConstraintModelCalcVisitor + : visitors::ConstraintUnaryVisitorBase< + ConstraintModelCalcVisitor> + { + typedef ModelTpl Model; + typedef DataTpl Data; + typedef boost::fusion::vector ArgsType; + + template + static void algo( + const pinocchio::ConstraintModelBase & cmodel, + typename ConstraintModel::ConstraintData & cdata, + const Model & model, + const Data & data) + { + cmodel.calc(model, data, cdata.derived()); + } + }; + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + template class ConstraintCollectionTpl> + void calc( + const ConstraintModelTpl & cmodel, + const ModelTpl & model, + const DataTpl & data, + ConstraintDataTpl & cdata) + { + typedef ConstraintModelCalcVisitor Algo; + Algo::run(cmodel, cdata, typename Algo::ArgsType(model, data)); } - }; - - template< - typename Scalar, - int Options, - template class JointCollectionTpl, - template class ConstraintCollectionTpl> - void calc( - const ConstraintModelTpl & cmodel, - ConstraintDataTpl & cdata, - const ModelTpl & model, - const DataTpl & data) - { - typedef ConstraintModelCalcVisitor Algo; - Algo::run(cmodel, cdata, typename Algo::ArgsType(model, data)); - } - - /** - * @brief ConstraintModelJacobianVisitor fusion visitor - */ - template< - typename Scalar, - int Options, - template class JointCollectionTpl, - typename JacobianMatrix> - struct ConstraintModelJacobianVisitor - : fusion::ConstraintUnaryVisitorBase< - ConstraintModelJacobianVisitor> - { - typedef ModelTpl Model; - typedef DataTpl Data; - typedef boost::fusion::vector ArgsType; - - template - static void algo( - const pinocchio::ConstraintModelBase & cmodel, - typename ConstraintModel::ConstraintData & cdata, - const Model & model, - const Data & data, + + /** + * @brief ConstraintModelResizeVisitor fusion visitor + */ + template class JointCollectionTpl> + struct ConstraintModelResizeVisitor + : visitors::ConstraintUnaryVisitorBase< + ConstraintModelResizeVisitor> + { + typedef ModelTpl Model; + typedef DataTpl Data; + typedef boost::fusion::vector ArgsType; + + template + static void algo( + pinocchio::ConstraintModelBase & cmodel, + typename ConstraintModel::ConstraintData & cdata, + const Model & model, + const Data & data) + { + cmodel.resize(model, data, cdata.derived()); + } + }; + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + template class ConstraintCollectionTpl> + void resize( + ConstraintModelTpl & cmodel, + const ModelTpl & model, + const DataTpl & data, + ConstraintDataTpl & cdata) + { + typedef ConstraintModelResizeVisitor Algo; + Algo::run(cmodel, cdata, typename Algo::ArgsType(model, data)); + } + + /** + * @brief ConstraintModelJacobianVisitor fusion visitor + */ + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename JacobianMatrix> + struct ConstraintModelJacobianVisitor + : visitors::ConstraintUnaryVisitorBase< + ConstraintModelJacobianVisitor> + { + typedef ModelTpl Model; + typedef DataTpl Data; + typedef boost::fusion::vector ArgsType; + + template + static void algo( + const pinocchio::ConstraintModelBase & cmodel, + typename ConstraintModel::ConstraintData & cdata, + const Model & model, + const Data & data, + const Eigen::MatrixBase & jacobian_matrix) + { + cmodel.jacobian(model, data, cdata.derived(), jacobian_matrix.const_cast_derived()); + } + }; + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + template class ConstraintCollectionTpl, + typename JacobianMatrix> + void jacobian( + const ConstraintModelTpl & cmodel, + const ModelTpl & model, + const DataTpl & data, + ConstraintDataTpl & cdata, const Eigen::MatrixBase & jacobian_matrix) { - cmodel.jacobian(model, data, cdata.derived(), jacobian_matrix.const_cast_derived()); + typedef ConstraintModelJacobianVisitor + Algo; + Algo::run( + cmodel, cdata, typename Algo::ArgsType(model, data, jacobian_matrix.const_cast_derived())); } - }; - - template< - typename Scalar, - int Options, - template class JointCollectionTpl, - template class ConstraintCollectionTpl, - typename JacobianMatrix> - void jacobian( - const ConstraintModelTpl & cmodel, - ConstraintDataTpl & cdata, - const ModelTpl & model, - const DataTpl & data, - const Eigen::MatrixBase & jacobian_matrix) - { - typedef ConstraintModelJacobianVisitor - Algo; - Algo::run( - cmodel, cdata, typename Algo::ArgsType(model, data, jacobian_matrix.const_cast_derived())); - } - - /** - * @brief ConstraintModelCreateDataVisitor fusion visitor - */ - template class ConstraintCollectionTpl> - struct ConstraintModelCreateDataVisitor - : boost::static_visitor::ConstraintDataVariant> - { - typedef fusion::NoArg ArgsType; - typedef ConstraintCollectionTpl ConstraintCollection; - typedef typename ConstraintCollection::ConstraintModelVariant ConstraintModelVariant; - typedef typename ConstraintCollection::ConstraintDataVariant ConstraintDataVariant; - template - ConstraintDataVariant - operator()(const pinocchio::ConstraintModelBase & cmodel) const + /** + * @brief ConstraintModelCreateDataVisitor fusion visitor + */ + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + struct ConstraintModelCreateDataVisitor + : visitors::ConstraintUnaryVisitorBase< + ConstraintModelCreateDataVisitor, + typename ConstraintCollectionTpl::ConstraintDataVariant> + { + typedef NoArg ArgsType; + typedef ConstraintCollectionTpl ConstraintCollection; + typedef typename ConstraintCollection::ConstraintModelVariant ConstraintModelVariant; + typedef typename ConstraintCollection::ConstraintDataVariant ConstraintDataVariant; + + template + static ConstraintDataVariant + algo(const pinocchio::ConstraintModelBase & cmodel) + { + return cmodel.createData(); + } + }; + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + ConstraintDataTpl + createData(const ConstraintModelTpl & cmodel) + { + typedef ConstraintModelCreateDataVisitor Algo; + return Algo::run(cmodel); + } + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl, + typename ConstraintDataDerived> + struct ConstraintDataComparisonOperatorVisitor + : visitors::ConstraintUnaryVisitorBase< + ConstraintDataComparisonOperatorVisitor< + Scalar, + Options, + ConstraintCollectionTpl, + ConstraintDataDerived>, + bool> + { + typedef boost::fusion::vector ArgsType; + + template + static bool algo( + const ConstraintDataBase & cdata_lhs, + const ConstraintDataDerived & cdata_rhs) + { + return cdata_lhs.derived() == cdata_rhs; + } + }; + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl, + typename ConstraintDataDerived> + bool isEqual( + const ConstraintDataTpl & cdata_generic, + const ConstraintDataBase & cdata) + { + typedef ConstraintDataComparisonOperatorVisitor< + Scalar, Options, ConstraintCollectionTpl, ConstraintDataDerived> + Algo; + return Algo::run(cdata_generic, typename Algo::ArgsType(boost::ref(cdata.derived()))); + } + + /** + * @brief ConstraintModelSizeVisitor visitor + */ + template + struct ConstraintModelSizeVisitor + : visitors::ConstraintUnaryVisitorBase, int> + { + typedef NoArg ArgsType; + + template + static int algo(const pinocchio::ConstraintModelBase & cmodel) + { + return cmodel.size(); + } + }; + + template class ConstraintCollectionTpl> + int size(const ConstraintModelTpl & cmodel) { - return cmodel.createData(); + typedef ConstraintModelSizeVisitor Algo; + return Algo::run(cmodel); } - static ConstraintDataVariant run(const ConstraintModelVariant & cmodel) + /** + * @brief ConstraintModelActiveSizeVisitor visitor + */ + template + struct ConstraintModelActiveSizeVisitor + : visitors::ConstraintUnaryVisitorBase, int> { - return boost::apply_visitor(ConstraintModelCreateDataVisitor(), cmodel); + + typedef NoArg ArgsType; + + template + static int algo(const pinocchio::ConstraintModelBase & cmodel) + { + return cmodel.activeSize(); + } + }; + + template class ConstraintCollectionTpl> + int activeSize(const ConstraintModelTpl & cmodel) + { + typedef ConstraintModelActiveSizeVisitor Algo; + return Algo::run(cmodel); } - }; - template class ConstraintCollectionTpl> - ConstraintDataTpl - createData(const ConstraintModelTpl & cmodel) - { - return ConstraintModelCreateDataVisitor::run(cmodel); - } - - template< - typename Scalar, - int Options, - template class ConstraintCollectionTpl, - typename ConstraintDataDerived> - struct ConstraintDataComparisonOperatorVisitor - : fusion::ConstraintUnaryVisitorBase< - ConstraintDataComparisonOperatorVisitor< + /** + * @brief ConstraintModelGetRowActivableIndexesVisitor visitor + */ + template + struct ConstraintModelGetRowActivableIndexesVisitor + : visitors::ConstraintUnaryVisitorBase< + ConstraintModelGetRowActivableIndexesVisitor, + const std::vector &> + { + typedef const std::vector & ReturnType; + + typedef boost::fusion::vector ArgsType; + + template + static ReturnType algo( + const pinocchio::ConstraintModelBase & cmodel, + const Eigen::DenseIndex row_id) + { + return cmodel.getRowActivableIndexes(row_id); + } + }; + + template class ConstraintCollectionTpl> + const std::vector & getRowActivableIndexes( + const ConstraintModelTpl & cmodel, + const Eigen::DenseIndex row_id) + { + typedef ConstraintModelGetRowActivableIndexesVisitor Algo; + return Algo::run(cmodel, typename Algo::ArgsType(row_id)); + } + + /** + * @brief ConstraintModelGetRowActiveIndexesVisitor visitor + */ + template + struct ConstraintModelGetRowActiveIndexesVisitor + : visitors::ConstraintUnaryVisitorBase< + ConstraintModelGetRowActiveIndexesVisitor, + const std::vector &> + { + typedef const std::vector & ReturnType; + + typedef boost::fusion::vector ArgsType; + + template + static ReturnType algo( + const pinocchio::ConstraintModelBase & cmodel, + const Eigen::DenseIndex row_id) + { + return cmodel.getRowActiveIndexes(row_id); + } + }; + + template class ConstraintCollectionTpl> + const std::vector & getRowActiveIndexes( + const ConstraintModelTpl & cmodel, + const Eigen::DenseIndex row_id) + { + typedef ConstraintModelGetRowActiveIndexesVisitor Algo; + return Algo::run(cmodel, typename Algo::ArgsType(row_id)); + } + + /** + * @brief ConstraintModelGetRowActivableSparsityPatternVisitor visitor + */ + template + struct ConstraintModelGetRowActivableSparsityPatternVisitor + : visitors::ConstraintUnaryVisitorBase< + ConstraintModelGetRowActivableSparsityPatternVisitor, + const Eigen::Matrix &> + { + typedef const Eigen::Matrix & ReturnType; + + typedef boost::fusion::vector ArgsType; + + template + static ReturnType algo( + const pinocchio::ConstraintModelBase & cmodel, + const Eigen::DenseIndex row_id) + { + return cmodel.getRowActivableSparsityPattern(row_id); + } + }; + + template class ConstraintCollectionTpl> + const Eigen::Matrix & getRowActivableSparsityPattern( + const ConstraintModelTpl & cmodel, + const Eigen::DenseIndex row_id) + { + typedef ConstraintModelGetRowActivableSparsityPatternVisitor Algo; + return Algo::run(cmodel, typename Algo::ArgsType(row_id)); + } + + /** + * @brief ConstraintModelGetRowActiveSparsityPatternVisitor visitor + */ + template + struct ConstraintModelGetRowActiveSparsityPatternVisitor + : visitors::ConstraintUnaryVisitorBase< + ConstraintModelGetRowActiveSparsityPatternVisitor, + const Eigen::Matrix &> + { + typedef const Eigen::Matrix & ReturnType; + + typedef boost::fusion::vector ArgsType; + + template + static ReturnType algo( + const pinocchio::ConstraintModelBase & cmodel, + const Eigen::DenseIndex row_id) + { + return cmodel.getRowActiveSparsityPattern(row_id); + } + }; + + template class ConstraintCollectionTpl> + const Eigen::Matrix & getRowActiveSparsityPattern( + const ConstraintModelTpl & cmodel, + const Eigen::DenseIndex row_id) + { + typedef ConstraintModelGetRowActiveSparsityPatternVisitor Algo; + return Algo::run(cmodel, typename Algo::ArgsType(row_id)); + } + + /** + * @brief ConstraintModelJacobianMatrixProductVisitor visitor + */ + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename InputMatrix, + typename OutputMatrix, + AssignmentOperatorType op> + struct ConstraintModelJacobianMatrixProductVisitor + : visitors::ConstraintUnaryVisitorBase, - bool> - { - typedef boost::fusion::vector ArgsType; + JointCollectionTpl, + InputMatrix, + OutputMatrix, + op>> + { + typedef ModelTpl Model; + typedef DataTpl Data; + typedef boost::fusion::vector< + const Model &, + const Data &, + const InputMatrix &, + OutputMatrix &, + AssignmentOperatorTag> + ArgsType; - template - static bool algo( - const ConstraintDataBase & cdata_lhs, const ConstraintDataDerived & cdata_rhs) + template + static void algo( + const pinocchio::ConstraintModelBase & cmodel, + const typename ConstraintModel::ConstraintData & cdata, + const Model & model, + const Data & data, + const Eigen::MatrixBase & input_matrix, + const Eigen::MatrixBase & result_matrix, + AssignmentOperatorTag aot) + { + cmodel.jacobianMatrixProduct( + model, data, cdata.derived(), input_matrix.derived(), result_matrix.const_cast_derived(), + aot); + } + }; + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + template class ConstraintCollectionTpl, + typename InputMatrix, + typename OutputMatrix, + AssignmentOperatorType op = SETTO> + void jacobianMatrixProduct( + const ConstraintModelTpl & cmodel, + const ModelTpl & model, + const DataTpl & data, + const ConstraintDataTpl & cdata, + const Eigen::MatrixBase & input_matrix, + const Eigen::MatrixBase & result_matrix, + AssignmentOperatorTag aot = SetTo()) { - return cdata_lhs.derived() == cdata_rhs; + typedef ConstraintModelJacobianMatrixProductVisitor< + Scalar, Options, JointCollectionTpl, InputMatrix, OutputMatrix, op> + Algo; + + typename Algo::ArgsType args( + model, data, input_matrix.derived(), result_matrix.const_cast_derived(), aot); + Algo::run(cmodel, cdata, args); } - }; - - template< - typename Scalar, - int Options, - template class ConstraintCollectionTpl, - typename ConstraintDataDerived> - bool isEqual( - const ConstraintDataTpl & cdata_generic, - const ConstraintDataBase & cdata) - { - typedef ConstraintDataComparisonOperatorVisitor< - Scalar, Options, ConstraintCollectionTpl, ConstraintDataDerived> - Algo; - return Algo::run(cdata_generic, typename Algo::ArgsType(boost::ref(cdata.derived()))); - } + + /** + * @brief ConstraintModelJacobianTransposeMatrixProductVisitor visitor + */ + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename InputMatrix, + typename OutputMatrix, + AssignmentOperatorType op> + struct ConstraintModelJacobianTransposeMatrixProductVisitor + : visitors::ConstraintUnaryVisitorBase> + { + typedef ModelTpl Model; + typedef DataTpl Data; + typedef boost::fusion::vector< + const Model &, + const Data &, + const InputMatrix &, + OutputMatrix &, + AssignmentOperatorTag> + ArgsType; + + template + static void algo( + const pinocchio::ConstraintModelBase & cmodel, + const typename ConstraintModel::ConstraintData & cdata, + const Model & model, + const Data & data, + const Eigen::MatrixBase & input_matrix, + const Eigen::MatrixBase & result_matrix, + AssignmentOperatorTag aot) + { + cmodel.jacobianTransposeMatrixProduct( + model, data, cdata.derived(), input_matrix.derived(), result_matrix.const_cast_derived(), + aot); + } + }; + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + template class ConstraintCollectionTpl, + typename InputMatrix, + typename OutputMatrix, + AssignmentOperatorType op = SETTO> + void jacobianTransposeMatrixProduct( + const ConstraintModelTpl & cmodel, + const ModelTpl & model, + const DataTpl & data, + const ConstraintDataTpl & cdata, + const Eigen::MatrixBase & input_matrix, + const Eigen::MatrixBase & result_matrix, + AssignmentOperatorTag aot = SetTo()) + { + typedef ConstraintModelJacobianTransposeMatrixProductVisitor< + Scalar, Options, JointCollectionTpl, InputMatrix, OutputMatrix, op> + Algo; + + typename Algo::ArgsType args( + model, data, input_matrix.derived(), result_matrix.const_cast_derived(), aot); + Algo::run(cmodel, cdata, args); + } + + /** + * @brief AppendCouplingConstraintInertiasVisitor visitor + */ + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename VectorNLike, + ReferenceFrame rf> + struct AppendCouplingConstraintInertiasVisitor + : visitors::ConstraintUnaryVisitorBase> + { + typedef ModelTpl Model; + typedef DataTpl Data; + typedef boost::fusion:: + vector> + ArgsType; + + template + static void algo( + const pinocchio::ConstraintModelBase & cmodel, + const typename ConstraintModel::ConstraintData & cdata, + const Model & model, + Data & data, + const Eigen::MatrixBase & diagonal_constraint_inertia, + const ReferenceFrameTag reference_frame) + { + cmodel.appendCouplingConstraintInertias( + model, data, cdata.derived(), diagonal_constraint_inertia.derived(), reference_frame); + } + }; + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + template class ConstraintCollectionTpl, + typename VectorNLike, + ReferenceFrame rf> + void appendCouplingConstraintInertias( + const ConstraintModelTpl & cmodel, + const ModelTpl & model, + DataTpl & data, + const ConstraintDataTpl & cdata, + const Eigen::MatrixBase & diagonal_constraint_inertia, + const ReferenceFrameTag reference_frame) + { + typedef AppendCouplingConstraintInertiasVisitor< + Scalar, Options, JointCollectionTpl, VectorNLike, rf> + Algo; + + typename Algo::ArgsType args( + model, data, diagonal_constraint_inertia.derived(), reference_frame); + Algo::run(cmodel, cdata, args); + } + + /** + * @brief mapConstraintForceToJointSpace visitor + */ + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConstraintForceLike, + class ForceAllocator, + typename JointTorquesLike, + ReferenceFrame rf> + struct MapConstraintForceToJointSpaceVisitor + : visitors::ConstraintUnaryVisitorBase> + { + typedef ModelTpl Model; + typedef DataTpl Data; + typedef std::vector, ForceAllocator> ForceVector; + typedef boost::fusion::vector< + const Model &, + const Data &, + const ConstraintForceLike &, + ForceVector &, + JointTorquesLike &, + const ReferenceFrameTag> + ArgsType; + + template + static void algo( + const pinocchio::ConstraintModelBase & cmodel, + const typename ConstraintModel::ConstraintData & cdata, + const Model & model, + const Data & data, + const Eigen::MatrixBase & constraint_forces, + std::vector, ForceAllocator> & joint_forces, + const Eigen::MatrixBase & joint_torques, + const ReferenceFrameTag reference_frame) + { + cmodel.mapConstraintForceToJointSpace( + model, data, cdata, constraint_forces, joint_forces, joint_torques.const_cast_derived(), + reference_frame); + } + }; + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + template class ConstraintCollectionTpl, + typename ConstraintForceLike, + class ForceAllocator, + typename JointTorquesLike, + ReferenceFrame rf> + void mapConstraintForceToJointSpace( + const ConstraintModelTpl & cmodel, + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const Eigen::MatrixBase & constraint_forces, + std::vector, ForceAllocator> & joint_forces, + const Eigen::MatrixBase & joint_torques, + const ReferenceFrameTag reference_frame) + { + typedef MapConstraintForceToJointSpaceVisitor< + Scalar, Options, JointCollectionTpl, ConstraintForceLike, ForceAllocator, JointTorquesLike, + rf> + Algo; + + typename Algo::ArgsType args( + model, data, constraint_forces.derived(), joint_forces, joint_torques.const_cast_derived(), + reference_frame); + Algo::run(cmodel, cdata, args); + } + + /** + * @brief mapConstraintForceToJointSpace visitor + */ + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class MotionAllocator, + typename GeneralizedVelocityLike, + typename ConstraintMotionLike, + ReferenceFrame rf> + struct MapJointSpaceToConstraintMotionVisitor + : visitors::ConstraintUnaryVisitorBase> + { + typedef ModelTpl Model; + typedef DataTpl Data; + typedef std::vector, MotionAllocator> MotionVector; + typedef boost::fusion::vector< + const Model &, + const Data &, + const MotionVector &, + const GeneralizedVelocityLike &, + ConstraintMotionLike &, + const ReferenceFrameTag> + ArgsType; + + template + static void algo( + const pinocchio::ConstraintModelBase & cmodel, + const typename ConstraintModel::ConstraintData & cdata, + const Model & model, + const Data & data, + const std::vector, MotionAllocator> & joint_motions, + const Eigen::MatrixBase & generalized_velocity, + const Eigen::MatrixBase & constraint_motions, + const ReferenceFrameTag reference_frame) + { + cmodel.mapJointSpaceToConstraintMotion( + model, data, cdata, joint_motions, generalized_velocity.derived(), + constraint_motions.const_cast_derived(), reference_frame); + } + }; + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + template class ConstraintCollectionTpl, + class MotionAllocator, + typename GeneralizedVelocityLike, + typename ConstraintMotionLike, + ReferenceFrame rf> + void mapJointSpaceToConstraintMotion( + const ConstraintModelTpl & cmodel, + const ModelTpl & model, + const DataTpl & data, + const ConstraintData & cdata, + const std::vector, MotionAllocator> & joint_motions, + const Eigen::MatrixBase & generalized_velocity, + const Eigen::MatrixBase & constraint_motions, + const ReferenceFrameTag reference_frame) + { + typedef MapJointSpaceToConstraintMotionVisitor< + Scalar, Options, JointCollectionTpl, MotionAllocator, GeneralizedVelocityLike, + ConstraintMotionLike, rf> + Algo; + + typename Algo::ArgsType args( + model, data, joint_motions, generalized_velocity.derived(), + constraint_motions.const_cast_derived(), reference_frame); + Algo::run(cmodel, cdata, args); + } + + /** + * @brief ConstraintModelComplianceVisitor visitor + */ + template + struct ConstraintModelComplianceVisitor + : ConstraintUnaryVisitorBase, ReturnType> + { + typedef NoArg ArgsType; + + template + static ReturnType algo(const ConstraintModelBase & cmodel) + { + return cmodel.compliance(); + } + template + static ReturnType algo(ConstraintModelBase & cmodel) + { + return cmodel.compliance(); + } + }; + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + typename traits< + ConstraintModelTpl>::ComplianceVectorTypeConstRef + compliance(const ConstraintModelTpl & cmodel) + { + typedef typename traits>:: + ComplianceVectorTypeConstRef ReturnType; + typedef ConstraintModelComplianceVisitor Algo; + return Algo::run(cmodel); + } + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + typename traits< + ConstraintModelTpl>::ComplianceVectorTypeRef + compliance(ConstraintModelTpl & cmodel) + { + typedef typename traits>:: + ComplianceVectorTypeRef ReturnType; + typedef ConstraintModelComplianceVisitor Algo; + return Algo::run(cmodel); + } + + /** + * @brief ConstraintModelActiveComplianceVisitor visitor + */ + template + struct ConstraintModelActiveComplianceVisitor + : ConstraintUnaryVisitorBase, ReturnType> + { + typedef NoArg ArgsType; + + template + static ReturnType algo(const ConstraintModelBase & cmodel) + { + return cmodel.getActiveCompliance(); + } + template + static ReturnType algo(ConstraintModelBase & cmodel) + { + return cmodel.getActiveCompliance(); + } + }; + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + typename traits< + ConstraintModelTpl>::ComplianceVectorTypeConstRef + getActiveCompliance(const ConstraintModelTpl & cmodel) + { + typedef typename traits>:: + ComplianceVectorTypeConstRef ReturnType; + typedef ConstraintModelActiveComplianceVisitor Algo; + return Algo::run(cmodel); + } + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + typename traits< + ConstraintModelTpl>::ComplianceVectorTypeRef + getActiveCompliance(ConstraintModelTpl & cmodel) + { + typedef typename traits>:: + ComplianceVectorTypeRef ReturnType; + typedef ConstraintModelActiveComplianceVisitor Algo; + return Algo::run(cmodel); + } + + /// \brief BaumgarteCorrectorVectorParametersGetter - default behavior for false for + /// HasBaumgarteCorrectorVector + template< + bool HasBaumgarteCorrectorVector, + typename BaumgarteVector, + typename BaumgarteVectorReturnType> + struct BaumgarteCorrectorVectorParametersGetter + { + template + static BaumgarteVectorReturnType + run(const ConstraintModelBase & cmodel) + { + std::stringstream ss; + ss << cmodel.shortname() << " does not have baumgarte vector corrector parameters.\n"; + PINOCCHIO_THROW(std::invalid_argument, ss.str()); + return internal::NoRun::run(); + } + template + static BaumgarteVectorReturnType run(ConstraintModelBase & cmodel) + { + std::stringstream ss; + ss << cmodel.shortname() << " does not have baumgarte vector corrector parameters.\n"; + PINOCCHIO_THROW(std::invalid_argument, ss.str()); + return internal::NoRun::run(); + } + }; + + /// \brief BaumgarteCorrectorVectorParametersGetter - partial specialization for true for + /// HasBaumgarteCorrectorVector + template + struct BaumgarteCorrectorVectorParametersGetter< + true, + BaumgarteVector, + BaumgarteVectorReturnType> + { + template + static BaumgarteVectorReturnType + run(const ConstraintModelBase & cmodel) + { + return cmodel.baumgarte_corrector_vector_parameters().template ref(); + } + template + static BaumgarteVectorReturnType run(ConstraintModelBase & cmodel) + { + return cmodel.baumgarte_corrector_vector_parameters().template ref(); + } + }; + + /** + * @brief BaumgarteCorrectorVectorParametersVisitor visitor + */ + template + struct BaumgarteCorrectorVectorParametersVisitor + : ConstraintUnaryVisitorBase< + BaumgarteCorrectorVectorParametersVisitor, + BaumgarteVectorReturnType> + { + typedef NoArg ArgsType; + + template + static BaumgarteVectorReturnType + algo(const ConstraintModelBase & cmodel) + { + static constexpr bool has_baumgarte_corrector_vector = + traits::has_baumgarte_corrector_vector; + return BaumgarteCorrectorVectorParametersGetter< + has_baumgarte_corrector_vector, BaumgarteVectorType, + BaumgarteVectorReturnType>::run(cmodel); + } + template + static BaumgarteVectorReturnType algo(ConstraintModelBase & cmodel) + { + static constexpr bool has_baumgarte_corrector_vector = + traits::has_baumgarte_corrector_vector; + return BaumgarteCorrectorVectorParametersGetter< + has_baumgarte_corrector_vector, BaumgarteVectorType, + BaumgarteVectorReturnType>::run(cmodel); + } + }; + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + typename traits>:: + BaumgarteCorrectorVectorParametersConstRef + getBaumgarteCorrectorVectorParameters( + const ConstraintModelTpl & cmodel) + { + typedef typename traits>:: + BaumgarteVectorType BaumgarteVectorType; + typedef typename traits>:: + BaumgarteCorrectorVectorParametersConstRef BaumgarteCorrectorVectorParametersConstRef; + return BaumgarteCorrectorVectorParametersVisitor< + BaumgarteVectorType, BaumgarteCorrectorVectorParametersConstRef>::run(cmodel); + } + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + typename traits>:: + BaumgarteCorrectorVectorParametersRef + getBaumgarteCorrectorVectorParameters( + ConstraintModelTpl & cmodel) + { + typedef typename traits>:: + BaumgarteVectorType BaumgarteVectorType; + typedef typename traits>:: + BaumgarteCorrectorVectorParametersRef BaumgarteCorrectorVectorParametersRef; + return BaumgarteCorrectorVectorParametersVisitor< + BaumgarteVectorType, BaumgarteCorrectorVectorParametersRef>::run(cmodel); + } + + /// \brief BaumgarteCorrectorParametersGetter - default behavior for false for + /// HasBaumgarteCorrector + template + struct BaumgarteCorrectorParametersGetter + { + template + static BaumgarteReturnType run(const ConstraintModelBase & cmodel) + { + std::stringstream ss; + ss << cmodel.shortname() << " does not have baumgarte corrector parameters.\n"; + PINOCCHIO_THROW(std::invalid_argument, ss.str()); + return internal::NoRun::run(); + } + template + static BaumgarteReturnType run(ConstraintModelBase & cmodel) + { + std::stringstream ss; + ss << cmodel.shortname() << " does not have baumgarte corrector parameters.\n"; + PINOCCHIO_THROW(std::invalid_argument, ss.str()); + return internal::NoRun::run(); + } + }; + + /// \brief BaumgarteCorrectorParametersGetter - partial specialization for true for + /// HasBaumgarteCorrector + template + struct BaumgarteCorrectorParametersGetter + { + template + static BaumgarteReturnType run(const ConstraintModelBase & cmodel) + { + return cmodel.baumgarte_corrector_parameters(); + } + template + static BaumgarteReturnType run(ConstraintModelBase & cmodel) + { + return cmodel.baumgarte_corrector_parameters(); + } + }; + + /** + * @brief BaumgarteCorrectorParametersVisitor visitor + */ + template + struct BaumgarteCorrectorParametersVisitor + : ConstraintUnaryVisitorBase< + BaumgarteCorrectorParametersVisitor, + BaumgarteReturnType> + { + typedef NoArg ArgsType; + + template + static BaumgarteReturnType algo(const ConstraintModelBase & cmodel) + { + static constexpr bool has_baumgarte_corrector = + traits::has_baumgarte_corrector; + return BaumgarteCorrectorParametersGetter< + has_baumgarte_corrector, BaumgarteReturnType>::run(cmodel); + } + + template + static BaumgarteReturnType algo(ConstraintModelBase & cmodel) + { + static constexpr bool has_baumgarte_corrector = + traits::has_baumgarte_corrector; + return BaumgarteCorrectorParametersGetter< + has_baumgarte_corrector, BaumgarteReturnType>::run(cmodel); + } + }; + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + const BaumgarteCorrectorParametersTpl & getBaumgarteCorrectorParameters( + const ConstraintModelTpl & cmodel) + { + typedef BaumgarteCorrectorParametersTpl BaumgarteCorrectorParameters; + typedef const BaumgarteCorrectorParameters & ReturnType; + typedef BaumgarteCorrectorParametersVisitor Algo; + return Algo::run(cmodel); + } + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + BaumgarteCorrectorParametersTpl & getBaumgarteCorrectorParameters( + ConstraintModelTpl & cmodel) + { + typedef BaumgarteCorrectorParametersTpl BaumgarteCorrectorParameters; + typedef BaumgarteCorrectorParameters & ReturnType; + typedef BaumgarteCorrectorParametersVisitor Algo; + return Algo::run(cmodel); + } + + } // namespace visitors } // namespace pinocchio diff --git a/include/pinocchio/algorithm/constraints/weld-constraint.hpp b/include/pinocchio/algorithm/constraints/weld-constraint.hpp new file mode 100644 index 0000000000..38fd81cc75 --- /dev/null +++ b/include/pinocchio/algorithm/constraints/weld-constraint.hpp @@ -0,0 +1,322 @@ +// +// Copyright (c) 2019-2024 INRIA CNRS +// + +#ifndef __pinocchio_algorithm_constraints_weld_constraint_hpp__ +#define __pinocchio_algorithm_constraints_weld_constraint_hpp__ + +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/unbounded-set.hpp" +#include "pinocchio/algorithm/constraints/frame-constraint-model-base.hpp" +#include "pinocchio/algorithm/constraints/frame-constraint-data-base.hpp" + +namespace pinocchio +{ + + template + struct CastType> + { + typedef WeldConstraintModelTpl type; + }; + + template + struct traits> + : traits>> + { + typedef _Scalar Scalar; + + enum + { + Options = _Options + }; + + typedef WeldConstraintModelTpl ConstraintModel; + typedef WeldConstraintDataTpl ConstraintData; + typedef UnboundedSetTpl ConstraintSet; + + typedef ConstraintModel Model; + typedef ConstraintData Data; + + typedef Eigen::Matrix Vector6; + typedef Eigen::Matrix JacobianMatrixType; + typedef Vector6 VectorConstraintSize; + + typedef Vector6 ComplianceVectorType; + typedef ComplianceVectorType & ComplianceVectorTypeRef; + typedef const ComplianceVectorType & ComplianceVectorTypeConstRef; + + typedef ComplianceVectorTypeRef ActiveComplianceVectorTypeRef; + typedef ComplianceVectorTypeConstRef ActiveComplianceVectorTypeConstRef; + + typedef Vector6 BaumgarteVectorType; + typedef BaumgarteCorrectorVectorParametersTpl + BaumgarteCorrectorVectorParameters; + typedef BaumgarteCorrectorVectorParameters & BaumgarteCorrectorVectorParametersRef; + typedef const BaumgarteCorrectorVectorParameters & BaumgarteCorrectorVectorParametersConstRef; + }; + + template + struct traits> + : traits> + { + }; + + /// + ///  \brief Contact model structure containg all the info describing the rigid contact model + /// + template + struct WeldConstraintModelTpl + : FrameConstraintModelBase> + { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + + typedef FrameConstraintModelBase Base; + typedef ConstraintModelBase RootBase; + + template + friend struct WeldConstraintModelTpl; + + typedef WeldConstraintDataTpl ConstraintData; + typedef UnboundedSetTpl ConstraintSet; + + using typename Base::BooleanVector; + using typename Base::EigenIndexVector; + using typename Base::Force; + using typename Base::Matrix6; + using typename Base::Motion; + using typename Base::SE3; + using typename Base::Vector6; + using typename Base::VectorConstraintSize; + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + /// + ///  \brief Default constructor + /// + WeldConstraintModelTpl() + : Base() + { + } + + /// + ///  \brief Contructor with from a given type, joint indexes and placements. + /// + /// \param[in] model Model associated to the constraint. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// \param[in] joint2_id Index of the joint 2 in the model tree. + /// \param[in] joint1_placement Placement of the constraint w.r.t the frame of joint1. + /// \param[in] joint2_placement Placement of the constraint w.r.t the frame of joint2. + /// expressed. + /// + template class JointCollectionTpl> + WeldConstraintModelTpl( + const ModelTpl & model, + const JointIndex joint1_id, + const SE3 & joint1_placement, + const JointIndex joint2_id, + const SE3 & joint2_placement) + : Base(model, joint1_id, joint1_placement, joint2_id, joint2_placement) + { + } + + /// + ///  \brief Contructor with from a given type, joint1_id and placement. + /// + /// \param[in] model Model associated to the constraint. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// \param[in] joint1_placement Placement of the constraint w.r.t the frame of joint1. + /// expressed. + /// + template class JointCollectionTpl> + WeldConstraintModelTpl( + const ModelTpl & model, + const JointIndex joint1_id, + const SE3 & joint1_placement) + : Base(model, joint1_id, joint1_placement) + { + } + + /// + ///  \brief Contructor with from a given type and the joint ids. + /// + /// \param[in] model Model associated to the constraint. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// \param[in] joint2_id Index of the joint 2 in the model tree. + /// + template class JointCollectionTpl> + WeldConstraintModelTpl( + const ModelTpl & model, + const JointIndex joint1_id, + const JointIndex joint2_id) + : Base(model, joint1_id, joint2_id) + { + } + + /// + ///  \brief Contructor with from a given type and . + /// + /// \param[in] model Model associated to the constraint. + /// \param[in] joint1_id Index of the joint 1 in the model tree. + /// + /// \remarks The second joint id (joint2_id) is set to be 0 (corresponding to the index of the + /// universe). + /// + template class JointCollectionTpl> + WeldConstraintModelTpl( + const ModelTpl & model, const JointIndex joint1_id) + : Base(model, joint1_id) + { + } + + /// + /// \brief Create data storage associated to the constraint + /// + ConstraintData createData() const + { + return ConstraintData(*this); + } + + /// \brief Cast operator + template + typename CastType::type cast() const + { + typedef typename CastType::type ReturnType; + ReturnType res; + Base::template cast(res); + res.m_set = m_set.template cast(); + return res; + } + + /// + ///  \brief Comparison operator + /// + /// \param[in] other Other WeldConstraintModelTpl to compare with. + /// + /// \returns true if the two *this is equal to other (type, joint1_id and placement attributs + /// must be the same). + /// + bool operator==(const WeldConstraintModelTpl & other) const + { + return base() == other.base() && m_set == other.m_set; + } + + /// + ///  \brief Oposite of the comparison operator. + /// + /// \param[in] other Other WeldConstraintModelTpl to compare with. + /// + /// \returns false if the two *this is not equal to other (at least type, joint1_id or placement + /// attributs is different). + /// + bool operator!=(const WeldConstraintModelTpl & other) const + { + return !(*this == other); + } + + const ConstraintSet & set() const + { + return m_set; + } + + ConstraintSet & set() + { + return m_set; + } + + static std::string classname() + { + return std::string("WeldConstraintModel"); + } + std::string shortname() const + { + return classname(); + } + + protected: + ConstraintSet m_set = ConstraintSet(6); + + }; // struct WeldConstraintModelTpl<_Scalar,_Options> + + /// + ///  \brief Contact model structure containg all the info describing the rigid contact model + /// + template + struct WeldConstraintDataTpl : FrameConstraintDataBase> + { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + + typedef WeldConstraintModelTpl ConstraintModel; + typedef WeldConstraintDataTpl ConstraintData; + typedef FrameConstraintDataBase Base; + + using typename Base::Force; + using typename Base::Matrix6; + using typename Base::Matrix6x; + using typename Base::MatrixX; + using typename Base::Motion; + using typename Base::SE3; + using typename Base::Vector3; + using typename Base::Vector6; + using typename Base::VectorOfMatrix6; + + /// \brief Default constructor + WeldConstraintDataTpl() + { + } + + explicit WeldConstraintDataTpl(const ConstraintModel & constraint_model) + : Base(constraint_model) + { + } + + bool operator==(const WeldConstraintDataTpl & other) const + { + return base() == other.base(); + } + + bool operator!=(const WeldConstraintDataTpl & other) const + { + return !(*this == other); + } + + Base & base() + { + return static_cast(*this); + } + const Base & base() const + { + return static_cast(*this); + } + + static std::string classname() + { + return std::string("WeldConstraintData"); + } + std::string shortname() const + { + return classname(); + } + }; // struct WeldConstraintDataTpl<_Scalar,_Options> + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_constraints_weld_constraint_hpp__ diff --git a/include/pinocchio/algorithm/contact-cholesky.hpp b/include/pinocchio/algorithm/contact-cholesky.hpp index c549417012..e0e712ca74 100644 --- a/include/pinocchio/algorithm/contact-cholesky.hpp +++ b/include/pinocchio/algorithm/contact-cholesky.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2019-2024 INRIA +// Copyright (c) 2019-2025 INRIA // #ifndef __pinocchio_algorithm_contact_cholesky_hpp__ @@ -8,9 +8,10 @@ #include "pinocchio/multibody/model.hpp" #include "pinocchio/math/matrix-block.hpp" #include "pinocchio/math/triangular-matrix.hpp" +#include "pinocchio/container/storage.hpp" -#include "pinocchio/algorithm/contact-info.hpp" -#include "pinocchio/algorithm/delassus-operator-base.hpp" +#include "pinocchio/algorithm/constraints/constraints.hpp" +#include namespace pinocchio { @@ -69,14 +70,20 @@ namespace pinocchio typedef Eigen::Matrix Vector; typedef Eigen::Matrix Matrix; typedef typename PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Matrix) RowMatrix; + + typedef EigenStorageTpl EigenStorageVector; + typedef EigenStorageTpl EigenStorageMatrix; + typedef EigenStorageTpl EigenStorageRowMatrix; + // TODO Remove when API is stabilized PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS typedef RigidConstraintModelTpl RigidConstraintModel; typedef RigidConstraintDataTpl RigidConstraintData; PINOCCHIO_COMPILER_DIAGNOSTIC_POP - typedef Eigen::Matrix IndexVector; - typedef typename PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(IndexVector) VectorOfIndexVector; + typedef Eigen::Matrix EigenIndexVector; + typedef + typename PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(EigenIndexVector) VectorOfEigenIndexVector; typedef Eigen::Matrix BooleanVector; ///@{ @@ -104,7 +111,15 @@ namespace pinocchio /// /// \brief Default constructor /// - ContactCholeskyDecompositionTpl() = default; + ContactCholeskyDecompositionTpl() + : D(D_storage.map()) + , Dinv(Dinv_storage.map()) + , U(U_storage.map()) + , DUt(DUt_storage.map()) + , compliance(compliance_storage.map()) + , damping(damping_storage.map()) + { + } /// /// \brief Constructor from a model. @@ -113,77 +128,204 @@ namespace pinocchio /// template class JointCollectionTpl> explicit ContactCholeskyDecompositionTpl(const ModelTpl & model) + : D(D_storage.map()) + , Dinv(Dinv_storage.map()) + , U(U_storage.map()) + , DUt(DUt_storage.map()) + , compliance(compliance_storage.map()) + , damping(damping_storage.map()) { // TODO Remove when API is stabilized PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) empty_contact_models; + std::vector empty_contact_models; PINOCCHIO_COMPILER_DIAGNOSTIC_POP - allocate(model, empty_contact_models); + resize(model, empty_contact_models); } /// /// \brief Constructor from a model and a collection of RigidConstraintModel objects. /// /// \param[in] model Model of the kinematic tree - /// \param[in] contact_models Vector of RigidConstraintModel objects containing the contact + /// \param[in] constraint_models Vector of ConstraintModels /// information /// - // TODO Remove when API is stabilized - PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH - PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS - template class JointCollectionTpl, class Allocator> + template< + typename S1, + int O1, + template class JointCollectionTpl, + class ConstraintModel, + class ConstraintAllocator> ContactCholeskyDecompositionTpl( const ModelTpl & model, - const std::vector, Allocator> & contact_models) - { - allocate(model, contact_models); + const std::vector & constraint_models) + : D(D_storage.map()) + , Dinv(Dinv_storage.map()) + , U(U_storage.map()) + , DUt(DUt_storage.map()) + , compliance(compliance_storage.map()) + , damping(damping_storage.map()) + { + typedef std::reference_wrapper WrappedType; + typedef std::vector WrappedTypeVector; + + WrappedTypeVector wrapped_constraint_models( + constraint_models.cbegin(), constraint_models.cend()); + resize(model, wrapped_constraint_models); + } + + /// + /// \brief Constructor from a model and a collection of RigidConstraintModel objects. + /// + /// \param[in] model Model of the kinematic tree + /// \param[in] contact_models Vector of RigidConstraintModel references containing the contact + /// information + /// + template< + typename S1, + int O1, + template class JointCollectionTpl, + template class Holder, + class ConstraintAllocator> + ContactCholeskyDecompositionTpl( + const ModelTpl & model, + const std::vector, ConstraintAllocator> & + wrapped_constraint_models) + : D(D_storage.map()) + , Dinv(Dinv_storage.map()) + , U(U_storage.map()) + , DUt(DUt_storage.map()) + , compliance(compliance_storage.map()) + , damping(damping_storage.map()) + { + resize(model, wrapped_constraint_models); } - PINOCCHIO_COMPILER_DIAGNOSTIC_POP /// /// \brief Copy constructor - ContactCholeskyDecompositionTpl(const ContactCholeskyDecompositionTpl & copy) = default; + /// + /// \param[in] other ContactCholeskyDecompositionTpl to copy + /// + ContactCholeskyDecompositionTpl(const ContactCholeskyDecompositionTpl & other) + : D(D_storage.map()) + , Dinv(Dinv_storage.map()) + , U(U_storage.map()) + , DUt(DUt_storage.map()) + , compliance(compliance_storage.map()) + , damping(damping_storage.map()) + { + *this = other; + } + + ContactCholeskyDecompositionTpl & operator=(const ContactCholeskyDecompositionTpl & other) + { + parents_fromRow = other.parents_fromRow; + nv_subtree_fromRow = other.nv_subtree_fromRow; + nv = other.nv; + + rowise_sparsity_pattern = other.rowise_sparsity_pattern; + + D_storage = other.D_storage; + Dinv_storage = other.Dinv_storage; + U_storage = other.U_storage; + DUt_storage = other.DUt_storage; + compliance_storage = other.compliance_storage; + damping_storage = other.damping_storage; + + return *this; + } /// - ///  \brief Memory allocation of the vectors D, Dinv, and the upper triangular matrix U. + ///  \brief Internal memory allocation. /// /// \param[in] model Model of the kinematic tree - /// \param[in] contact_models Vector of RigidConstraintModel objects containing the contact - /// information + /// \param[in] contact_models Vector of ConstraintModel /// - // TODO Remove when API is stabilized - PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH - PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS - template class JointCollectionTpl, class Allocator> - void allocate( + template< + typename S1, + int O1, + template class JointCollectionTpl, + class ConstraintModel, + class ConstraintAllocator> + void resize( const ModelTpl & model, - const std::vector, Allocator> & contact_models); - PINOCCHIO_COMPILER_DIAGNOSTIC_POP + const std::vector & contact_models) + { + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelTypeVector; + + WrappedConstraintModelTypeVector wrapped_contact_models( + contact_models.cbegin(), contact_models.cend()); + + resize(model, wrapped_contact_models); + } + + /// + ///  \brief Internal memory allocation. + /// + /// \param[in] model Model of the kinematic tree + /// \param[in] contact_models Vector of ConstraintModel + /// \param[in] contact_datas Vector of ConstraintData + /// + template< + typename S1, + int O1, + template class JointCollectionTpl, + class ConstraintModel, + class ConstraintAllocator, + class ConstraintData, + class ConstraintDataAllocator> + PINOCCHIO_DEPRECATED void allocate( + const ModelTpl & model, + const std::vector & contact_models) + { + resize(model, contact_models); + } + + /// + ///  \brief Internal memory allocation. + /// + /// \param[in] model Model of the kinematic tree + /// \param[in] contact_models Vector of ConstraintModel + /// + template< + typename S1, + int O1, + template class JointCollectionTpl, + template class Holder, + class ConstraintModel, + class ConstraintAllocator> + void resize( + const ModelTpl & model, + const std::vector, ConstraintAllocator> & contact_models); /// /// \brief Returns the Inverse of the Operational Space Inertia Matrix resulting from the /// decomposition. /// - Matrix getInverseOperationalSpaceInertiaMatrix() const + Matrix getInverseOperationalSpaceInertiaMatrix(bool enforce_symmetry = false) const { Matrix res(constraintDim(), constraintDim()); - getInverseOperationalSpaceInertiaMatrix(res); + getInverseOperationalSpaceInertiaMatrix(res, enforce_symmetry); return res; } template - void getInverseOperationalSpaceInertiaMatrix(const Eigen::MatrixBase & res) const + void getInverseOperationalSpaceInertiaMatrix( + const Eigen::MatrixBase & res, bool enforce_symmetry = false) const { - typedef typename SizeDepType::template BlockReturn::ConstType - ConstBlockXpr; - // typedef typename RowMatrix::ConstBlockXpr ConstBlockXpr; - const ConstBlockXpr U1 = U.topLeftCorner(constraintDim(), constraintDim()); + const auto U1 = U.topLeftCorner(constraintDim(), constraintDim()); + + const auto dim = constraintDim(); + typedef Eigen::Map MapRowMatrix; + MapRowMatrix OSIMinv = MapRowMatrix(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, dim, dim)); PINOCCHIO_EIGEN_MALLOC_NOT_ALLOWED(); - MatrixType & res_ = PINOCCHIO_EIGEN_CONST_CAST(MatrixType, res); - OSIMinv_tmp.noalias() = D.head(constraintDim()).asDiagonal() * U1.adjoint(); - res_.noalias() = -U1 * OSIMinv_tmp; + MatrixType & res_ = res.const_cast_derived(); + OSIMinv.noalias() = D.head(dim).asDiagonal() * U1.adjoint(); + res_.noalias() = -U1 * OSIMinv; + if (enforce_symmetry) + enforceSymmetry(res_); PINOCCHIO_EIGEN_MALLOC_ALLOWED(); } @@ -208,18 +350,22 @@ namespace pinocchio void getOperationalSpaceInertiaMatrix(const Eigen::MatrixBase & res_) const { MatrixType & res = PINOCCHIO_EIGEN_CONST_CAST(MatrixType, res_); - typedef typename SizeDepType::template BlockReturn::ConstType - ConstBlockXpr; // typedef typename RowMatrix::ConstBlockXpr ConstBlockXpr; - const Eigen::TriangularView U1 = - U.topLeftCorner(constraintDim(), constraintDim()) - .template triangularView(); + const auto U1 = U.topLeftCorner(constraintDim(), constraintDim()) + .template triangularView(); + + const auto dim = constraintDim(); + typedef Eigen::Map MapRowMatrix; + MapRowMatrix OSIMinv = MapRowMatrix(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, dim, dim)); + + typedef Eigen::Map MapMatrix; + MapMatrix U1inv = MapMatrix(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, dim, dim)); PINOCCHIO_EIGEN_MALLOC_NOT_ALLOWED(); U1inv.setIdentity(); U1.solveInPlace(U1inv); // TODO: implement Sparse Inverse - OSIMinv_tmp.noalias() = -U1inv.adjoint() * Dinv.head(constraintDim()).asDiagonal(); - res.noalias() = OSIMinv_tmp * U1inv; + OSIMinv.noalias() = -U1inv.adjoint() * Dinv.head(dim).asDiagonal(); + res.noalias() = OSIMinv * U1inv; PINOCCHIO_EIGEN_MALLOC_ALLOWED(); } @@ -234,30 +380,34 @@ namespace pinocchio void getInverseMassMatrix(const Eigen::MatrixBase & res_) const { MatrixType & res = PINOCCHIO_EIGEN_CONST_CAST(MatrixType, res_); - typedef typename SizeDepType::template BlockReturn::ConstType - ConstBlockXpr; // typedef typename RowMatrix::ConstBlockXpr ConstBlockXpr; - const Eigen::TriangularView U4 = - U.bottomRightCorner(nv, nv).template triangularView(); + const auto U4 = U.bottomRightCorner(nv, nv).template triangularView(); + + typedef Eigen::Map MapRowMatrix; + MapRowMatrix Minv = MapRowMatrix(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, nv, nv)); + + typedef Eigen::Map MapMatrix; + MapMatrix U4inv = MapMatrix(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, nv, nv)); PINOCCHIO_EIGEN_MALLOC_NOT_ALLOWED(); U4inv.setIdentity(); U4.solveInPlace(U4inv); // TODO: implement Sparse Inverse - Minv_tmp.noalias() = U4inv.adjoint() * Dinv.tail(nv).asDiagonal(); - res.noalias() = Minv_tmp * U4inv; + Minv.noalias() = U4inv.adjoint() * Dinv.tail(nv).asDiagonal(); + res.noalias() = Minv * U4inv; PINOCCHIO_EIGEN_MALLOC_ALLOWED(); } template void getJMinv(const Eigen::MatrixBase & res_) const { - MatrixType & res = PINOCCHIO_EIGEN_CONST_CAST(MatrixType, res_); - typedef typename SizeDepType::template BlockReturn::ConstType - ConstBlockXpr; - const Eigen::TriangularView U4 = - U.bottomRightCorner(nv, nv).template triangularView(); - ConstBlockXpr U2 = U.topRightCorner(constraintDim(), nv); PINOCCHIO_EIGEN_MALLOC_NOT_ALLOWED(); + MatrixType & res = PINOCCHIO_EIGEN_CONST_CAST(MatrixType, res_); + const auto U4 = U.bottomRightCorner(nv, nv).template triangularView(); + auto U2 = U.topRightCorner(constraintDim(), nv); + + typedef Eigen::Map MapMatrix; + MapMatrix U4inv = MapMatrix(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, nv, nv)); + U4inv.setIdentity(); U4.solveInPlace(U4inv); // TODO: implement Sparse Inverse res.noalias() = U2 * U4inv; @@ -271,14 +421,18 @@ namespace pinocchio /// /// \param[in] model Model of the dynamical system /// \param[in] data Data related to model containing the computed mass matrix and the Jacobian - /// of the kinematic tree \param[in] contact_models Vector containing the contact models (which - /// frame is in contact and the type of contact: ponctual, 6D rigid, etc.) \param[out] - /// contact_datas Vector containing the contact data related to the contact_models. \param[in] - /// mu Positive regularization factor allowing to enforce the definite property of the KKT - /// matrix. + /// of the kinematic tree + /// \param[in] contact_models Vector containing the contact models (which + /// frame is in contact and the type of contact: ponctual, 6D rigid, etc.) + /// \param[in,out] contact_datas Vector containing the contact data related to the + /// contact_models. + /// \param[in] mu Positive regularization factor allowing to enforce the definite property of + /// the KKT matrix. /// /// \remarks The mass matrix and the Jacobians of the dynamical system should have been computed /// first. This can be achieved by simply calling pinocchio::crba. + /// The `resize` method should have been called before calling this method if the size of the + /// constraints changed. /// // TODO Remove when API is stabilized PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH @@ -287,48 +441,172 @@ namespace pinocchio typename S1, int O1, template class JointCollectionTpl, + class ConstraintModel, class ConstraintModelAllocator, + class ConstraintData, class ConstraintDataAllocator> void compute( const ModelTpl & model, DataTpl & data, - const std::vector, ConstraintModelAllocator> & contact_models, - std::vector, ConstraintDataAllocator> & contact_datas, + const std::vector & contact_models, + std::vector & contact_datas, const S1 mu = S1(0.)) { - compute(model, data, contact_models, contact_datas, Vector::Constant(U1inv.rows(), mu)); + compute(model, data, contact_models, contact_datas, Vector::Constant(constraintDim(), mu)); } /// /// \brief Computes the Cholesky decompostion of the augmented matrix containing the KKT matrix /// related to the system mass matrix and the Jacobians of the contact patches contained - /// in the vector of RigidConstraintModel named contact_models. + /// in the vector of ConstraintModel named contact_models. + /// + /// \param[in] model Model of the dynamical system + /// \param[in] data Data related to model containing the computed mass matrix and the Jacobian + /// of the kinematic tree + /// \param[in] contact_models Vector containing the contact models (which + /// frame is in contact and the type of contact: ponctual, 6D rigid, etc.) + /// \param[in,out] contact_datas Vector containing the contact data related to the + /// contact_models. + /// \param[in] mu Positive regularization factor allowing to enforce the definite property of + /// the KKT matrix. + /// + /// \remarks The mass matrix and the Jacobians of the dynamical system should have been computed + /// first. This can be achieved by simply calling pinocchio::crba. + /// The `resize` method should have been called before calling this method if the size of the + /// constraints changed. + /// + template< + typename S1, + int O1, + template class JointCollectionTpl, + template class Holder, + class ConstraintModelAllocator, + class ConstraintModel, + class ConstraintDataAllocator, + class ConstraintData> + void compute( + const ModelTpl & model, + DataTpl & data, + const std::vector, ConstraintModelAllocator> & contact_models, + std::vector, ConstraintDataAllocator> & contact_datas, + const S1 mu = S1(0.)) + { + compute(model, data, contact_models, contact_datas, Vector::Constant(constraintDim(), mu)); + } + PINOCCHIO_COMPILER_DIAGNOSTIC_POP + + /// + /// \brief Computes the Cholesky decompostion of the augmented matrix containing the KKT matrix + /// related to the system mass matrix and the Jacobians of the contact patches contained + /// in the vector of ConstraintModel named contact_models. + /// + /// \param[in] model Model of the dynamical system + /// \param[in] data Data related to model containing the computed mass matrix and the Jacobian + /// of the kinematic tree + /// \param[in] contact_models Vector containing the contact models (which + /// frame is in contact and the type of contact: ponctual, 6D rigid, etc.) + /// \param[in,out] contact_datas Vector containing the contact data related to the + /// contact_models. + /// \param[in] mu Positive regularization factor allowing to enforce the definite property of + /// the KKT matrix. + /// + /// \remarks The mass matrix and the Jacobians of the dynamical system should have been computed + /// first. This can be achieved by simply calling pinocchio::crba. + /// The `resize` method should have been called before calling this method if the size of the + /// constraints changed. + /// + template< + typename S1, + int O1, + template class JointCollectionTpl, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator, + typename VectorLike> + void compute( + const ModelTpl & model, + DataTpl & data, + const std::vector & contact_models, + std::vector & contact_datas, + const Eigen::MatrixBase & mus) + { + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + contact_models.cbegin(), contact_models.cend()); + + typedef std::reference_wrapper WrappedConstraintDataType; + typedef std::vector WrappedConstraintDataVector; + + WrappedConstraintDataVector wrapped_constraint_datas( + contact_datas.begin(), contact_datas.end()); + + compute(model, data, wrapped_constraint_models, wrapped_constraint_datas, mus); + } + + /// + /// \brief Computes the Cholesky decompostion of the augmented matrix containing the KKT matrix + /// related to the system mass matrix and the Jacobians of the contact patches contained + /// in the vector of onstraintModel named contact_models. /// /// \param[in] model Model of the dynamical system /// \param[in] data Data related to model containing the computed mass matrix and the Jacobian - /// of the kinematic tree \param[in] contact_models Vector containing the contact models (which - /// frame is in contact and the type of contact: ponctual, 6D rigid, etc.) \param[out] - /// contact_datas Vector containing the contact data related to the contact_models. \param[in] - /// mus Vector of positive regularization factor allowing to enforce the definite property of + /// of the kinematic tree + /// \param[in] contact_models Vector containing the contact models (which + /// frame is in contact and the type of contact: ponctual, 6D rigid, etc.) + /// \param[in,out] contact_datas Vector containing the contact data related to the + /// contact_models. + /// \param[in] mu Positive regularization factor allowing to enforce the definite property of /// the KKT matrix. /// /// \remarks The mass matrix and the Jacobians of the dynamical system should have been computed /// first. This can be achieved by simply calling pinocchio::crba. + /// The `resize` method should have been called before calling this method if the size of the + /// constraints changed. /// template< typename S1, int O1, template class JointCollectionTpl, + template class Holder, + class ConstraintModel, class ConstraintModelAllocator, + class ConstraintData, class ConstraintDataAllocator, typename VectorLike> void compute( const ModelTpl & model, DataTpl & data, - const std::vector, ConstraintModelAllocator> & contact_models, - std::vector, ConstraintDataAllocator> & contact_datas, + const std::vector, ConstraintModelAllocator> & contact_models, + std::vector, ConstraintDataAllocator> & contact_datas, const Eigen::MatrixBase & mus); - PINOCCHIO_COMPILER_DIAGNOSTIC_POP + + /// + /// \brief Update the compliance terms on the upper left block part of the KKT matrix. The + /// compliance terms should be all positives. + /// + /// \param[in] compliance Vector of physical compliance for the constraints. + /// + template + void updateCompliance(const Eigen::MatrixBase & compliance); + + /// + /// \brief Update the compliance term on the upper left block part of the KKT matrix. The + /// compliance terms should be all positives. + /// + /// \param[in] compliance The physical compliance for the constraints. + /// + void updateCompliance(const Scalar & compliance); + + /// + /// \brief Returns the current compliance vector. + /// + const typename EigenStorageVector::MapType getCompliance() const + { + return compliance; + } /// /// \brief Update the damping terms on the upper left block part of the KKT matrix. The damping @@ -349,6 +627,14 @@ namespace pinocchio /// void updateDamping(const Scalar & mu); + /// + /// \brief Returns the current damping vector. + /// + const typename EigenStorageVector::MapType getDamping() const + { + return damping; + } + /// \brief Size of the decomposition Eigen::DenseIndex size() const { @@ -362,12 +648,6 @@ namespace pinocchio return size() - nv; } - /// \brief Returns the number of contacts associated to this decomposition. - Eigen::DenseIndex numContacts() const - { - return num_contacts; - } - /// ///  \brief Computes the solution of \f$ A x = b \f$ where *this is the Cholesky decomposition /// of A.   "in-place" version of ContactCholeskyDecompositionTpl::solve(b) where the @@ -433,8 +713,12 @@ namespace pinocchio void inverse(const Eigen::MatrixBase & res) const; // data - Vector D, Dinv; - RowMatrix U; + EigenStorageVector D_storage; + typename EigenStorageVector::RefMapType D; + EigenStorageVector Dinv_storage; + typename EigenStorageVector::RefMapType Dinv; + EigenStorageRowMatrix U_storage; + typename EigenStorageRowMatrix::RefMapType U; ///@{ /// \brief Friend algorithms @@ -468,211 +752,26 @@ namespace pinocchio PINOCCHIO_COMPILER_DIAGNOSTIC_POP protected: - IndexVector parents_fromRow; - IndexVector nv_subtree_fromRow; + EigenIndexVector parents_fromRow; + EigenIndexVector nv_subtree_fromRow; - ///  \brief Last child of the given joint index - IndexVector last_child; - - Vector DUt; // temporary containing the results of D * U^t + EigenStorageVector DUt_storage; + typename EigenStorageVector::RefMapType DUt; // temporary containing the results of D * U^t /// \brief Dimension of the tangent of the configuration space of the model Eigen::DenseIndex nv; - ///  \brief Number of contacts. - Eigen::DenseIndex num_contacts; - VectorOfSliceVector rowise_sparsity_pattern; - /// \brief Inverse of the top left block of U - mutable Matrix U1inv; - /// \brief Inverse of the bottom right block of U - mutable Matrix U4inv; - - mutable RowMatrix OSIMinv_tmp, Minv_tmp; - }; + /// \brief Store the current value of the physical compliance + EigenStorageVector compliance_storage; + typename EigenStorageVector::RefMapType compliance; - template - struct traits> - { - enum - { - RowsAtCompileTime = Eigen::Dynamic - }; - typedef typename ContactCholeskyDecomposition::Scalar Scalar; - typedef typename ContactCholeskyDecomposition::Matrix Matrix; - typedef typename ContactCholeskyDecomposition::Vector Vector; + /// \brief Store the current damping value + EigenStorageVector damping_storage; + typename EigenStorageVector::RefMapType damping; }; - template - struct DelassusCholeskyExpressionTpl - : DelassusOperatorBase> - { - typedef _ContactCholeskyDecomposition ContactCholeskyDecomposition; - typedef typename ContactCholeskyDecomposition::Scalar Scalar; - typedef typename ContactCholeskyDecomposition::Vector Vector; - typedef typename ContactCholeskyDecomposition::Matrix Matrix; - typedef typename ContactCholeskyDecomposition::RowMatrix RowMatrix; - typedef DelassusCholeskyExpressionTpl<_ContactCholeskyDecomposition> Self; - typedef DelassusOperatorBase Base; - - typedef - typename SizeDepType::template BlockReturn::Type RowMatrixBlockXpr; - typedef typename SizeDepType::template BlockReturn::ConstType - RowMatrixConstBlockXpr; - - enum - { - RowsAtCompileTime = traits::RowsAtCompileTime - }; - - explicit DelassusCholeskyExpressionTpl(const ContactCholeskyDecomposition & self) - : Base(self.constraintDim()) - , self(self) - { - } - - template - void applyOnTheRight( - const Eigen::MatrixBase & x, const Eigen::MatrixBase & res) const - { - PINOCCHIO_CHECK_ARGUMENT_SIZE(x.rows(), self.constraintDim()); - PINOCCHIO_CHECK_ARGUMENT_SIZE(res.rows(), self.constraintDim()); - PINOCCHIO_CHECK_ARGUMENT_SIZE(res.cols(), x.cols()); - - PINOCCHIO_EIGEN_MALLOC_NOT_ALLOWED(); - - const RowMatrixConstBlockXpr U1 = - self.U.topLeftCorner(self.constraintDim(), self.constraintDim()); - - if (x.cols() <= self.constraintDim()) - { - RowMatrixBlockXpr tmp_mat = - const_cast(self).OSIMinv_tmp.topLeftCorner( - self.constraintDim(), x.cols()); - // tmp_mat.noalias() = U1.adjoint() * x; - triangularMatrixMatrixProduct(U1.adjoint(), x.derived(), tmp_mat); - tmp_mat.array().colwise() *= -self.D.head(self.constraintDim()).array(); - // res.const_cast_derived().noalias() = U1 * tmp_mat; - triangularMatrixMatrixProduct(U1, tmp_mat, res.const_cast_derived()); - } - else // do memory allocation - { - RowMatrix tmp_mat(x.rows(), x.cols()); - // tmp_mat.noalias() = U1.adjoint() * x; - triangularMatrixMatrixProduct(U1.adjoint(), x.derived(), tmp_mat); - tmp_mat.array().colwise() *= -self.D.head(self.constraintDim()).array(); - // res.const_cast_derived().noalias() = U1 * tmp_mat; - triangularMatrixMatrixProduct(U1, tmp_mat, res.const_cast_derived()); - } - - PINOCCHIO_EIGEN_MALLOC_ALLOWED(); - } - - template - typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixDerived) - operator*(const Eigen::MatrixBase & x) const - { - typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixDerived) ReturnType; - ReturnType res(self.constraintDim(), x.cols()); - applyOnTheRight(x.derived(), res); - return res; - } - - template - void solveInPlace(const Eigen::MatrixBase & x) const - { - PINOCCHIO_CHECK_ARGUMENT_SIZE(x.rows(), self.constraintDim()); - - const Eigen::TriangularView U1 = - self.U.topLeftCorner(self.constraintDim(), self.constraintDim()) - .template triangularView(); - - PINOCCHIO_EIGEN_MALLOC_NOT_ALLOWED(); - U1.solveInPlace(x.const_cast_derived()); - x.const_cast_derived().array().colwise() *= -self.Dinv.head(self.constraintDim()).array(); - U1.adjoint().solveInPlace(x); - PINOCCHIO_EIGEN_MALLOC_ALLOWED(); - } - - template - void solve( - const Eigen::MatrixBase & x, - const Eigen::MatrixBase & res) const - { - res.const_cast_derived() = x; - solveInPlace(res.const_cast_derived()); - } - - template - typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixDerived) - solve(const Eigen::MatrixBase & x) const - { - typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixDerived) ReturnType; - ReturnType res(self.constraintDim(), x.cols()); - solve(x.derived(), res); - return res; - } - - /// \brief Returns the Constraint Cholesky decomposition associated to this - /// DelassusCholeskyExpression. - const ContactCholeskyDecomposition & cholesky() const - { - return self; - } - - Matrix matrix() const - { - return self.getInverseOperationalSpaceInertiaMatrix(); - } - - Matrix inverse() const - { - return self.getOperationalSpaceInertiaMatrix(); - } - - /// - /// \brief Add a damping term to the diagonal of the Delassus matrix. The damping terms should - /// be all positives. - /// - /// \param[in] mus Vector of positive regularization factor allowing to enforce the definite - /// positiveness of the matrix. - /// - template - void updateDamping(const Eigen::MatrixBase & mus) - { - const_cast(self).updateDamping(mus); - } - - /// - /// \brief Add a damping term to the diagonal of the Delassus matrix. The damping term should be - /// positive. - /// - /// \param[in] mu Regularization factor allowing to enforce the definite positiveness of the - /// matrix. - /// - void updateDamping(const Scalar & mu) - { - const_cast(self).updateDamping(mu); - } - - Eigen::DenseIndex size() const - { - return self.constraintDim(); - } - Eigen::DenseIndex rows() const - { - return size(); - } - Eigen::DenseIndex cols() const - { - return size(); - } - - protected: - const ContactCholeskyDecomposition & self; - }; // DelassusCholeskyExpression - } // namespace pinocchio // Because of a GCC bug we should NEVER define a function that use ContactCholeskyDecompositionTpl @@ -687,5 +786,6 @@ namespace pinocchio #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION #include "pinocchio/algorithm/contact-cholesky.hxx" +#include "pinocchio/algorithm/delassus-operator-cholesky-expression.hpp" #endif // ifndef __pinocchio_algorithm_contact_cholesky_hpp__ diff --git a/include/pinocchio/algorithm/contact-cholesky.hxx b/include/pinocchio/algorithm/contact-cholesky.hxx index a5ba846116..0cee594472 100644 --- a/include/pinocchio/algorithm/contact-cholesky.hxx +++ b/include/pinocchio/algorithm/contact-cholesky.hxx @@ -18,35 +18,35 @@ namespace pinocchio PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS template - template class JointCollectionTpl, class Allocator> - void ContactCholeskyDecompositionTpl::allocate( + template< + typename S1, + int O1, + template class JointCollectionTpl, + template class Holder, + class ConstraintModel, + class ConstraintAllocator> + void ContactCholeskyDecompositionTpl::resize( const ModelTpl & model, - const std::vector, Allocator> & contact_models) + const std::vector, ConstraintAllocator> & contact_models) { typedef ModelTpl Model; typedef typename Model::JointModel JointModel; - typedef RigidConstraintModelTpl RigidConstraintModel; - typedef std::vector RigidConstraintModelVector; + + static_assert( + std::is_base_of, ConstraintModel>::value, + "ConstraintModel is not a ConstraintModelBase"); assert(model.check(MimicChecker()) && "Function does not support mimic joints"); nv = model.nv; - num_contacts = (Eigen::DenseIndex)contact_models.size(); Eigen::DenseIndex num_total_constraints = 0; - for (typename RigidConstraintModelVector::const_iterator it = contact_models.begin(); - it != contact_models.end(); ++it) + for (std::size_t i = 0; i < contact_models.size(); i++) { - PINOCCHIO_CHECK_INPUT_ARGUMENT( - it->size() > 0, "The dimension of the constraint must be positive"); - num_total_constraints += it->size(); + const ConstraintModel & cmodel = contact_models[(std::size_t)i]; + num_total_constraints += cmodel.activeSize(); } - U1inv.resize(num_total_constraints, num_total_constraints); - OSIMinv_tmp.resize(num_total_constraints, num_total_constraints); - U4inv.resize(nv, nv); - Minv_tmp.resize(nv, nv); - const Eigen::DenseIndex total_dim = nv + num_total_constraints; // Compute first parents_fromRow for all the joints. @@ -58,24 +58,13 @@ namespace pinocchio nv_subtree_fromRow.resize(total_dim); // nv_subtree_fromRow.fill(0); - last_child.resize(model.njoints); - last_child.fill(-1); - for (long joint_id = model.njoints - 1; joint_id >= 0; --joint_id) - { - const JointIndex & parent = model.parents[(size_t)joint_id]; - if (last_child[joint_id] == -1) - last_child[joint_id] = joint_id; - last_child[(Eigen::DenseIndex)parent] = - std::max(last_child[joint_id], last_child[(Eigen::DenseIndex)parent]); - } - // Fill nv_subtree_fromRow for model for (JointIndex joint_id = 1; joint_id < (JointIndex)(model.njoints); joint_id++) { const JointIndex parent_id = model.parents[joint_id]; - const JointModel & joint = model.joints[joint_id]; - const JointModel & parent_joint = model.joints[parent_id]; + const JointModel joint = model.joints[joint_id]; + const JointModel parent_joint = model.joints[parent_id]; const int nvj = joint.nv(); const int idx_vj = joint.idx_v(); @@ -85,9 +74,10 @@ namespace pinocchio else parents_fromRow[idx_vj + num_total_constraints] = -1; + const JointIndex last_child = + model.subtrees[joint_id].size() > 0 ? model.subtrees[joint_id].back() : JointIndex(0); nv_subtree_fromRow[idx_vj + num_total_constraints] = - model.joints[(size_t)last_child[(Eigen::DenseIndex)joint_id]].idx_v() - + model.joints[(size_t)last_child[(Eigen::DenseIndex)joint_id]].nv() - idx_vj; + model.joints[last_child].idx_v() + model.joints[last_child].nv() - idx_vj; for (int row = 1; row < nvj; ++row) { @@ -99,22 +89,15 @@ namespace pinocchio } Eigen::DenseIndex row_id = 0; - for (typename RigidConstraintModelVector::const_iterator it = contact_models.begin(); - it != contact_models.end(); ++it) + for (std::size_t i = 0; i < contact_models.size(); i++) { - const RigidConstraintModel & cmodel = *it; - const JointIndex joint1_id = cmodel.joint1_id; - const JointModel & joint1 = model.joints[joint1_id]; - const JointIndex joint2_id = cmodel.joint2_id; - const JointModel & joint2 = model.joints[joint2_id]; - - // Fill nv_subtree_fromRow for constraints - const Eigen::DenseIndex nv1 = joint1.idx_v() + joint1.nv(); - const Eigen::DenseIndex nv2 = joint2.idx_v() + joint2.nv(); - const Eigen::DenseIndex nv = std::max(nv1, nv2); - for (Eigen::DenseIndex k = 0; k < cmodel.size(); ++k, row_id++) + const ConstraintModel & cmodel = contact_models[(std::size_t)i]; + for (Eigen::DenseIndex k = 0; k < cmodel.activeSize(); ++k, row_id++) { - nv_subtree_fromRow[row_id] = nv + (num_total_constraints - row_id); + const auto & row_active_indexes = cmodel.getRowActiveIndexes(k); + nv_subtree_fromRow[row_id] = + num_total_constraints - row_id + 1 + + (row_active_indexes.size() > 0 ? row_active_indexes.back() : 0); } } assert(row_id == num_total_constraints); @@ -165,12 +148,17 @@ namespace pinocchio } */ - // Allocate memory - D.resize(total_dim); - Dinv.resize(total_dim); - U.resize(total_dim, total_dim); + // Allocate Eigen memory if needed + compliance_storage.resize(num_total_constraints); + compliance.setZero(); + damping_storage.resize(num_total_constraints); + damping.setZero(); + + D_storage.resize(total_dim); + Dinv_storage.resize(total_dim); + U_storage.resize(total_dim, total_dim); U.setIdentity(); - DUt.resize(total_dim); + DUt_storage.resize(total_dim); } template @@ -178,31 +166,33 @@ namespace pinocchio typename S1, int O1, template class JointCollectionTpl, + template class Holder, + class ConstraintModel, class ConstraintModelAllocator, + class ConstraintData, class ConstraintDataAllocator, typename VectorLike> void ContactCholeskyDecompositionTpl::compute( const ModelTpl & model, DataTpl & data, - const std::vector, ConstraintModelAllocator> & contact_models, - std::vector, ConstraintDataAllocator> & contact_datas, + const std::vector, ConstraintModelAllocator> & contact_models, + std::vector, ConstraintDataAllocator> & contact_datas, const Eigen::MatrixBase & mus) { - typedef RigidConstraintModelTpl RigidConstraintModel; - typedef RigidConstraintDataTpl RigidConstraintData; + static_assert( + std::is_base_of, ConstraintModel>::value, + "ConstraintModel is not a ConstraintModelBase"); + static_assert( + std::is_base_of, ConstraintData>::value, + "ConstraintData is not a ConstraintDataBase"); assert(model.check(data) && "data is not consistent with model."); assert(model.check(MimicChecker()) && "Function does not support mimic joints"); PINOCCHIO_CHECK_INPUT_ARGUMENT( - (Eigen::DenseIndex)contact_models.size() == num_contacts, - "The number of contacts inside contact_models and the one during allocation do not match.\n" - "Please call first ContactCholeskyDecompositionTpl::allocate method."); - PINOCCHIO_CHECK_INPUT_ARGUMENT( - (Eigen::DenseIndex)contact_datas.size() == num_contacts, - "The number of contacts inside contact_datas and the one during allocation do not match.\n" - "Please call first ContactCholeskyDecompositionTpl::allocate method."); - PINOCCHIO_UNUSED_VARIABLE(model); + contact_models.size() == contact_datas.size(), + "The number of constraints between contact_models and contact_datas vectors is different."); + PINOCCHIO_ONLY_USED_FOR_DEBUG(model); const Eigen::DenseIndex total_dim = size(); const Eigen::DenseIndex total_constraints_dim = total_dim - nv; @@ -215,9 +205,9 @@ namespace pinocchio // Update frame placements if needed for (size_t ee_id = 0; ee_id < num_ee; ++ee_id) { - const RigidConstraintModel & cmodel = contact_models[ee_id]; - RigidConstraintData & cdata = contact_datas[ee_id]; - + const ConstraintModel & cmodel = contact_models[ee_id].get(); + ConstraintData & cdata = contact_datas[ee_id].get(); + // TODO: should we call resize on cmodel ? cmodel.calc(model, data, cdata); } @@ -230,12 +220,12 @@ namespace pinocchio U.topRightCorner(total_constraints_dim, model.nv).setZero(); for (size_t ee_id = 0; ee_id < num_ee; ++ee_id) { - const RigidConstraintModel & cmodel = contact_models[ee_id]; - RigidConstraintData & cdata = contact_datas[ee_id]; + const ConstraintModel & cmodel = contact_models[ee_id].get(); + ConstraintData & cdata = contact_datas[ee_id].get(); - const Eigen::DenseIndex constraint_dim = cmodel.size(); + const Eigen::DenseIndex constraint_dim = cmodel.activeSize(); cmodel.jacobian( - model, data, cdata, U.block(current_row, total_constraints_dim, cmodel.size(), model.nv)); + model, data, cdata, U.block(current_row, total_constraints_dim, constraint_dim, model.nv)); current_row += constraint_dim; } @@ -245,7 +235,7 @@ namespace pinocchio // Classic Cholesky decomposition related to the mass matrix const Eigen::DenseIndex jj = total_constraints_dim + j; // shifted index const Eigen::DenseIndex NVT = nv_subtree_fromRow[jj] - 1; - typename Vector::SegmentReturnType DUt_partial = DUt.head(NVT); + auto DUt_partial = DUt.head(NVT); if (NVT) DUt_partial.noalias() = @@ -265,40 +255,67 @@ namespace pinocchio } // Constraint part - // Eigen::DenseIndex current_row = total_constraints_dim - 1; - // for(size_t ee_id = 0; ee_id < num_ee; ++ee_id) - // { - // const RigidConstraintModel & cmodel = contact_models[num_ee - 1 - ee_id]; - // - // const Eigen::DenseIndex constraint_dim = cmodel.size(); - // if(cmodel.colwise_sparsity[j]) - // { - // for(Eigen::DenseIndex k = 0; k < constraint_dim; ++k) - // { - // U(current_row - k,jj) -= U.row(current_row - - // k).segment(jj+1,NVT).dot(DUt_partial); U(current_row - k,jj) *= Dinv[jj]; - // } - // } - // - // current_row -= constraint_dim; - // } - for (Eigen::DenseIndex current_row = total_constraints_dim - 1; current_row >= 0; - --current_row) + Eigen::DenseIndex current_row = total_constraints_dim - 1; + for (size_t ee_id = 0; ee_id < num_ee; ++ee_id) { - U(current_row, jj) -= U.row(current_row).segment(jj + 1, NVT).dot(DUt_partial); - U(current_row, jj) *= Dinv[jj]; + const ConstraintModel & cmodel = contact_models[num_ee - 1 - ee_id]; + const Eigen::DenseIndex constraint_dim = cmodel.activeSize(); + + for (Eigen::DenseIndex constraint_row_id = constraint_dim - 1; constraint_row_id >= 0; + --constraint_row_id, --current_row) + { + const auto & colwise_sparsity = cmodel.getRowActiveSparsityPattern(constraint_row_id); + if (colwise_sparsity[j]) + { + U(current_row, jj) -= U.row(current_row).segment(jj + 1, NVT).dot(DUt_partial); + U(current_row, jj) *= Dinv[jj]; + } + } } } + // Setting physical compliance + int cindex = 0; + for (std::size_t ee_id = 0; ee_id < num_ee; ee_id++) + { + const ConstraintModel & cmodel = contact_models[ee_id]; + // TODO use active compliance + const int cdim = cmodel.activeSize(); + compliance.segment(cindex, cdim) = cmodel.getActiveCompliance(); + cindex += cdim; + } + + // Setting numerical damping updateDamping(mus); } + template + template + void ContactCholeskyDecompositionTpl::updateCompliance( + const Eigen::MatrixBase & vec) + { + EIGEN_STATIC_ASSERT_VECTOR_ONLY(VectorLike) + compliance = vec; + + // The diagonal term of the KKT should be updated with the new compliance + updateDamping(getDamping()); + } + + template + void ContactCholeskyDecompositionTpl::updateCompliance(const Scalar & compliance) + { + const Eigen::DenseIndex total_dim = size(); + const Eigen::DenseIndex total_constraints_dim = total_dim - nv; + updateCompliance(Vector::Constant(total_constraints_dim, compliance)); + } + template template void ContactCholeskyDecompositionTpl::updateDamping( const Eigen::MatrixBase & vec) { EIGEN_STATIC_ASSERT_VECTOR_ONLY(VectorLike) + damping = vec; const Eigen::DenseIndex total_dim = size(); const Eigen::DenseIndex total_constraints_dim = total_dim - nv; @@ -306,11 +323,11 @@ namespace pinocchio for (Eigen::DenseIndex j = total_constraints_dim - 1; j >= 0; --j) { const Eigen::DenseIndex slice_dim = total_dim - j - 1; - typename Vector::SegmentReturnType DUt_partial = DUt.head(slice_dim); + auto DUt_partial = DUt.head(slice_dim); DUt_partial.noalias() = U.row(j).segment(j + 1, slice_dim).transpose().cwiseProduct(D.segment(j + 1, slice_dim)); - D[j] = -vec[j] - U.row(j).segment(j + 1, slice_dim).dot(DUt_partial); + D[j] = -damping[j] - compliance[j] - U.row(j).segment(j + 1, slice_dim).dot(DUt_partial); assert( check_expression_if_real(D[j] != Scalar(0)) && "The diagonal element is equal to zero."); @@ -637,7 +654,7 @@ namespace pinocchio { bool is_same = true; - if (nv != other.nv || num_contacts != other.num_contacts) + if (nv != other.nv) return false; if ( @@ -651,7 +668,6 @@ namespace pinocchio is_same &= (parents_fromRow == other.parents_fromRow); is_same &= (nv_subtree_fromRow == other.nv_subtree_fromRow); - is_same &= (last_child == other.last_child); // is_same &= (rowise_sparsity_pattern == other.rowise_sparsity_pattern); return is_same; @@ -677,13 +693,12 @@ namespace pinocchio EIGEN_STATIC_ASSERT_VECTOR_ONLY(VectorLike); typedef ContactCholeskyDecompositionTpl ContactCholeskyDecomposition; - typedef typename ContactCholeskyDecomposition::RowMatrix RowMatrix; const Eigen::DenseIndex & chol_dim = chol.size(); PINOCCHIO_CHECK_INPUT_ARGUMENT(col < chol_dim && col >= 0); PINOCCHIO_CHECK_INPUT_ARGUMENT(vec.size() == chol_dim); - const typename ContactCholeskyDecomposition::IndexVector & nvt = chol.nv_subtree_fromRow; + const typename ContactCholeskyDecomposition::EigenIndexVector & nvt = chol.nv_subtree_fromRow; VectorLike & vec_ = PINOCCHIO_EIGEN_CONST_CAST(VectorLike, vec); const Eigen::DenseIndex last_col = @@ -695,7 +710,7 @@ namespace pinocchio for (Eigen::DenseIndex k = last_col; k >= 0; --k) { const Eigen::DenseIndex nvt_max = std::min(col - k, nvt[k] - 1); - const typename RowMatrix::ConstRowXpr U_row = chol.U.row(k); + const auto U_row = chol.U.row(k); vec_[k] = -U_row.segment(k + 1, nvt_max).dot(vec_.segment(k + 1, nvt_max)); // if(k >= chol_constraint_dim) // { diff --git a/include/pinocchio/algorithm/contact-cholesky.txx b/include/pinocchio/algorithm/contact-cholesky.txx index 1e00e23ebe..f938a1a424 100644 --- a/include/pinocchio/algorithm/contact-cholesky.txx +++ b/include/pinocchio/algorithm/contact-cholesky.txx @@ -1,5 +1,5 @@ // -// Copyright (c) 2022 INRIA +// Copyright (c) 2022-2025 INRIA // #ifndef __pinocchio_algorithm_contact_cholesky_txx__ @@ -25,17 +25,18 @@ namespace pinocchio ContactCholeskyDecompositionTpl; extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void - ContactCholeskyDecompositionTpl::allocate< + ContactCholeskyDecompositionTpl::resize< context::Scalar, context::Options, JointCollectionDefaultTpl, + context::RigidConstraintModel, typename context::RigidConstraintModelVector::allocator_type>( const context::Model &, const context::RigidConstraintModelVector &); extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void ContactCholeskyDecompositionTpl:: getInverseOperationalSpaceInertiaMatrix( - const Eigen::MatrixBase &) const; + const Eigen::MatrixBase &, bool) const; extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void ContactCholeskyDecompositionTpl:: @@ -51,7 +52,9 @@ namespace pinocchio context::Scalar, context::Options, JointCollectionDefaultTpl, + context::RigidConstraintModel, typename context::RigidConstraintModelVector::allocator_type, + context::RigidConstraintData, typename context::RigidConstraintDataVector::allocator_type>( const context::Model &, context::Data &, diff --git a/include/pinocchio/algorithm/contact-dynamics.hxx b/include/pinocchio/algorithm/contact-dynamics.hxx index 3f5e49c5b4..f704a1e438 100644 --- a/include/pinocchio/algorithm/contact-dynamics.hxx +++ b/include/pinocchio/algorithm/contact-dynamics.hxx @@ -11,8 +11,6 @@ #include "pinocchio/algorithm/check.hpp" #include "pinocchio/math/matrix.hpp" -#include - namespace pinocchio { diff --git a/include/pinocchio/algorithm/contact-info.hpp b/include/pinocchio/algorithm/contact-info.hpp index 2d60a3ff26..d22bf76e29 100644 --- a/include/pinocchio/algorithm/contact-info.hpp +++ b/include/pinocchio/algorithm/contact-info.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2019-2023 INRIA CNRS +// Copyright (c) 2019-2025 INRIA // #ifndef __pinocchio_algorithm_contact_info_hpp__ @@ -8,10 +8,13 @@ #include #include "pinocchio/multibody/model.hpp" +#include "pinocchio/spatial/skew.hpp" #include "pinocchio/algorithm/fwd.hpp" #include "pinocchio/algorithm/constraints/fwd.hpp" -#include "pinocchio/algorithm/constraints/constraint-model-base.hpp" +#include "pinocchio/algorithm/constraints/kinematics-constraint-base.hpp" #include "pinocchio/algorithm/constraints/constraint-data-base.hpp" +#include "pinocchio/algorithm/constraints/baumgarte-corrector-parameters.hpp" +#include "pinocchio/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp" namespace pinocchio { @@ -50,57 +53,6 @@ namespace pinocchio }; }; - template - struct BaumgarteCorrectorParametersTpl; - - template - struct traits> - { - typedef _Scalar Scalar; - }; - - template - struct BaumgarteCorrectorParametersTpl : NumericalBase> - { - typedef _Scalar Scalar; - typedef Eigen::Matrix Vector6Max; - - BaumgarteCorrectorParametersTpl(int size = 6) - : Kp(size) - , Kd(size) - { - Kp.setZero(); - Kd.setZero(); - } - - bool operator==(const BaumgarteCorrectorParametersTpl & other) const - { - return Kp == other.Kp && Kd == other.Kd; - } - - bool operator!=(const BaumgarteCorrectorParametersTpl & other) const - { - return !(*this == other); - } - - // parameters - /// \brief Proportional corrector value. - Vector6Max Kp; - - /// \brief Damping corrector value. - Vector6Max Kd; - - template - BaumgarteCorrectorParametersTpl cast() const - { - typedef BaumgarteCorrectorParametersTpl ReturnType; - ReturnType res; - res.Kp = Kp.template cast(); - res.Kd = Kd.template cast(); - return res; - } - }; - // TODO Remove when API is stabilized PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS @@ -118,18 +70,60 @@ namespace pinocchio { Options = _Options }; + + static constexpr ConstraintFormulationLevel constraint_formulation_level = + ConstraintFormulationLevel::VELOCITY_LEVEL; + static constexpr bool has_baumgarte_corrector = true; + static constexpr bool has_baumgarte_corrector_vector = true; + + typedef RigidConstraintModelTpl ConstraintModel; typedef RigidConstraintDataTpl ConstraintData; + typedef boost::blank ConstraintSet; + + typedef ConstraintModel Model; + typedef ConstraintData Data; + + typedef Eigen::Matrix VectorXs; + typedef Eigen::Matrix + JacobianMatrixType; + typedef VectorXs VectorConstraintSize; + + typedef VectorXs ComplianceVectorType; + typedef ComplianceVectorType & ComplianceVectorTypeRef; + typedef const ComplianceVectorType & ComplianceVectorTypeConstRef; + + typedef ComplianceVectorTypeRef ActiveComplianceVectorTypeRef; + typedef ComplianceVectorTypeConstRef ActiveComplianceVectorTypeConstRef; + + typedef Eigen::Matrix Vector6Max; + typedef Vector6Max BaumgarteVectorType; + typedef BaumgarteCorrectorVectorParametersTpl + BaumgarteCorrectorVectorParameters; + typedef BaumgarteCorrectorVectorParameters & BaumgarteCorrectorVectorParametersRef; + typedef const BaumgarteCorrectorVectorParameters & BaumgarteCorrectorVectorParametersConstRef; + + template + struct JacobianMatrixProductReturnType + { + typedef typename InputMatrix::Scalar Scalar; + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(InputMatrix) InputMatrixPlain; + typedef Eigen::Matrix + type; + }; + + template + struct JacobianTransposeMatrixProductReturnType + { + typedef typename InputMatrix::Scalar Scalar; + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(InputMatrix) InputMatrixPlain; + typedef Eigen::Matrix type; + }; }; template struct traits> + : traits> { - typedef _Scalar Scalar; - enum - { - Options = _Options - }; - typedef RigidConstraintModelTpl ConstraintModel; }; /// @@ -137,7 +131,8 @@ namespace pinocchio /// template struct PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") - RigidConstraintModelTpl : ConstraintModelBase> + RigidConstraintModelTpl + : KinematicsConstraintModelBase> { EIGEN_MAKE_ALIGNED_OPERATOR_NEW @@ -146,36 +141,48 @@ namespace pinocchio { Options = _Options }; - typedef ConstraintModelBase> Base; + + typedef RigidConstraintModelTpl Self; + typedef KinematicsConstraintModelBase Base; template friend struct RigidConstraintModelTpl; using Base::base; - using Base::colwise_span_indexes; - using Base::colwise_sparsity; typedef RigidConstraintModelTpl ContactModel; typedef RigidConstraintDataTpl ContactData; typedef RigidConstraintDataTpl ConstraintData; + typedef typename traits::ComplianceVectorType ComplianceVectorType; + typedef typename traits::ComplianceVectorTypeRef ComplianceVectorTypeRef; + typedef typename traits::ComplianceVectorTypeConstRef ComplianceVectorTypeConstRef; + typedef typename traits::ActiveComplianceVectorTypeRef ActiveComplianceVectorTypeRef; + typedef + typename traits::ActiveComplianceVectorTypeConstRef ActiveComplianceVectorTypeConstRef; + typedef + typename traits::BaumgarteCorrectorVectorParameters BaumgarteCorrectorVectorParameters; + typedef typename traits::BaumgarteCorrectorVectorParametersRef + BaumgarteCorrectorVectorParametersRef; + typedef typename traits::BaumgarteCorrectorVectorParametersConstRef + BaumgarteCorrectorVectorParametersConstRef; + typedef BaumgarteCorrectorParametersTpl BaumgarteCorrectorParameters; + + using typename Base::BooleanVector; + using typename Base::EigenIndexVector; typedef SE3Tpl SE3; typedef MotionTpl Motion; typedef ForceTpl Force; - typedef BaumgarteCorrectorParametersTpl BaumgarteCorrectorParameters; - typedef typename Base::BooleanVector BooleanVector; - typedef typename Base::IndexVector IndexVector; typedef Eigen::Matrix Matrix36; + typedef Eigen::Matrix Matrix6; + typedef Eigen::Matrix Vector3; + typedef Eigen::Matrix Vector6; + typedef Eigen::Matrix VectorXs; + using Base::joint1_id, Base::joint2_id; ///  \brief Type of the contact. ContactType type; - /// \brief Index of the first joint in the model tree - JointIndex joint1_id; - - /// \brief Index of the second joint in the model tree - JointIndex joint2_id; - /// \brief Relative placement with respect to the frame of joint1. SE3 joint1_placement; @@ -194,9 +201,6 @@ namespace pinocchio /// \brief Desired contact spatial acceleration Motion desired_contact_acceleration; - ///  \brief Corrector parameters - BaumgarteCorrectorParameters corrector; - /// \brief Colwise sparsity pattern associated with joint 1. BooleanVector colwise_joint1_sparsity; @@ -204,19 +208,36 @@ namespace pinocchio BooleanVector colwise_joint2_sparsity; /// \brief Jointwise span indexes associated with joint 1. - IndexVector joint1_span_indexes; + EigenIndexVector joint1_span_indexes; /// \brief Jointwise span indexes associated with joint 2. - IndexVector joint2_span_indexes; + EigenIndexVector joint2_span_indexes; - IndexVector loop_span_indexes; + EigenIndexVector loop_span_indexes; - /// \brief Dimensions of the models + /// \brief Sparsity pattern associated to the constraint; + BooleanVector colwise_sparsity; + + /// \brief Indexes of the columns spanned by the constraints. + EigenIndexVector colwise_span_indexes; + + /// \brief Dimensions of the model int nv; ///  \brief Depth of the kinematic tree for joint1 and joint2 size_t depth_joint1, depth_joint2; + /// \brief Compliance associated with the contact model + ComplianceVectorType m_compliance; + + // ///  \brief Corrector parameters + // Reference for retrocompatibility + BaumgarteCorrectorVectorParameters corrector; + // For the new API it is either one of: + // BaumgarteCorrectorParameters m_baumgarte_parameters; + // BaumgarteCorrectorVectorParameters m_baumgarte_vector_parameters; + // Actually it is the scalar one + protected: /// ///  \brief Default constructor @@ -250,22 +271,21 @@ namespace pinocchio const JointIndex joint2_id, const SE3 & joint2_placement, const ReferenceFrame & reference_frame = LOCAL) - : Base(model) + : Base(model, joint1_id, joint2_id) , type(type) - , joint1_id(joint1_id) - , joint2_id(joint2_id) , joint1_placement(joint1_placement) , joint2_placement(joint2_placement) , reference_frame(reference_frame) , desired_contact_placement(SE3::Identity()) , desired_contact_velocity(Motion::Zero()) , desired_contact_acceleration(Motion::Zero()) - , corrector(size()) , colwise_joint1_sparsity(model.nv) , colwise_joint2_sparsity(model.nv) , joint1_span_indexes((size_t)model.njoints) , joint2_span_indexes((size_t)model.njoints) , loop_span_indexes((size_t)model.nv) + , m_compliance(VectorXs::Zero(size())) + , corrector(size()) { init(model); } @@ -286,22 +306,21 @@ namespace pinocchio const JointIndex joint1_id, const SE3 & joint1_placement, const ReferenceFrame & reference_frame = LOCAL) - : Base(model) + : Base(model, joint1_id, 0) , type(type) - , joint1_id(joint1_id) - , joint2_id(0) , joint1_placement(joint1_placement) , joint2_placement(SE3::Identity()) , reference_frame(reference_frame) , desired_contact_placement(SE3::Identity()) , desired_contact_velocity(Motion::Zero()) , desired_contact_acceleration(Motion::Zero()) - , corrector(size()) , colwise_joint1_sparsity(model.nv) , colwise_joint2_sparsity(model.nv) , joint1_span_indexes((size_t)model.njoints) , joint2_span_indexes((size_t)model.njoints) , loop_span_indexes((size_t)model.nv) + , m_compliance(VectorXs::Zero(size())) + , corrector(size()) { init(model); } @@ -320,22 +339,21 @@ namespace pinocchio const JointIndex joint1_id, const JointIndex joint2_id, const ReferenceFrame & reference_frame = LOCAL) - : Base(model) + : Base(model, joint1_id, joint2_id) , type(type) - , joint1_id(joint1_id) - , joint2_id(joint2_id) , joint1_placement(SE3::Identity()) , joint2_placement(SE3::Identity()) , reference_frame(reference_frame) , desired_contact_placement(SE3::Identity()) , desired_contact_velocity(Motion::Zero()) , desired_contact_acceleration(Motion::Zero()) - , corrector(size()) , colwise_joint1_sparsity(model.nv) , colwise_joint2_sparsity(model.nv) , joint1_span_indexes((size_t)model.njoints) , joint2_span_indexes((size_t)model.njoints) , loop_span_indexes((size_t)model.nv) + , m_compliance(VectorXs::Zero(size())) + , corrector(size()) { init(model); } @@ -355,22 +373,21 @@ namespace pinocchio const ModelTpl & model, const JointIndex joint1_id, const ReferenceFrame & reference_frame = LOCAL) - : Base(model) + : Base(model, joint1_id, 0) , type(type) - , joint1_id(joint1_id) - , joint2_id(0) // set to be the Universe , joint1_placement(SE3::Identity()) , joint2_placement(SE3::Identity()) , reference_frame(reference_frame) , desired_contact_placement(SE3::Identity()) , desired_contact_velocity(Motion::Zero()) , desired_contact_acceleration(Motion::Zero()) - , corrector(size()) , colwise_joint1_sparsity(model.nv) , colwise_joint2_sparsity(model.nv) , joint1_span_indexes((size_t)model.njoints) , joint2_span_indexes((size_t)model.njoints) , loop_span_indexes((size_t)model.nv) + , m_compliance(VectorXs::Zero(size())) + , corrector(size()) { init(model); } @@ -383,6 +400,86 @@ namespace pinocchio return ConstraintData(*this); } + /// \brief Returns the colwise sparsity associated with a given row + const BooleanVector & getRowActivableSparsityPattern(const Eigen::DenseIndex row_id) const + { + PINOCCHIO_CHECK_INPUT_ARGUMENT(row_id < size()); + return colwise_sparsity; + } + + /// \brief Returns the sparsity associated with a given row + const BooleanVector & getRowActiveSparsityPattern(const Eigen::DenseIndex row_id) const + { + return getRowActivableSparsityPattern(row_id); + } + + /// \brief Returns the vector of the active indexes associated with a given row + const EigenIndexVector & getRowActiveIndexes(const Eigen::DenseIndex row_id) const + { + PINOCCHIO_CHECK_INPUT_ARGUMENT(row_id < size()); + return colwise_span_indexes; + } + + /// \brief Returns the compliance internally stored in the constraint model + ComplianceVectorTypeConstRef compliance_impl() const + { + return m_compliance; + } + + /// \brief Returns the compliance internally stored in the constraint model + ComplianceVectorTypeRef compliance_impl() + { + return m_compliance; + } + + /// \brief Returns the compliance internally stored in the constraint model + ActiveComplianceVectorTypeConstRef getActiveCompliance_impl() const + { + return this->compliance(); + } + + /// \brief Returns the compliance internally stored in the constraint model + ActiveComplianceVectorTypeRef getActiveCompliance_impl() + { + return this->compliance(); + } + + /// \brief Returns the Baumgarte vector parameters internally stored in the constraint model + BaumgarteCorrectorVectorParametersConstRef baumgarte_corrector_vector_parameters_impl() const + { + return corrector; + } + + /// \brief Returns the Baumgarte vector parameters internally stored in the constraint model + BaumgarteCorrectorVectorParametersRef baumgarte_corrector_vector_parameters_impl() + { + return corrector; + } + + // /// \brief Returns the Baumgarte vector parameters internally stored in the constraint model + // BaumgarteCorrectorVectorParametersConstRef baumgarte_corrector_vector_parameters_impl() const + // { + // return m_baumgarte_vector_parameters; + // } + + // /// \brief Returns the Baumgarte vector parameters internally stored in the constraint model + // BaumgarteCorrectorVectorParametersRef baumgarte_corrector_vector_parameters_impl() + // { + // return m_baumgarte_vector_parameters; + // } + + // /// \brief Returns the Baumgarte parameters internally stored in the constraint model + // const BaumgarteCorrectorParameters & baumgarte_corrector_parameters_impl() const + // { + // return m_baumgarte_parameters; + // } + + // /// \brief Returns the Baumgarte parameters internally stored in the constraint model + // BaumgarteCorrectorParameters & baumgarte_corrector_parameters_impl() + // { + // return m_baumgarte_parameters; + // } + /// ///  \brief Comparison operator /// @@ -394,8 +491,8 @@ namespace pinocchio template bool operator==(const RigidConstraintModelTpl & other) const { - return base() == other.base() && type == other.type && joint1_id == other.joint1_id - && joint2_id == other.joint2_id && joint1_placement == other.joint1_placement + return base() == other.base() && type == other.type + && joint1_placement == other.joint1_placement && joint2_placement == other.joint2_placement && reference_frame == other.reference_frame && corrector == other.corrector && colwise_joint1_sparsity == other.colwise_joint1_sparsity @@ -403,7 +500,9 @@ namespace pinocchio && joint1_span_indexes == other.joint1_span_indexes && joint2_span_indexes == other.joint2_span_indexes && nv == other.nv && depth_joint1 == other.depth_joint1 && depth_joint2 == other.depth_joint2 - && loop_span_indexes == other.loop_span_indexes; + && colwise_sparsity == other.colwise_sparsity + && colwise_span_indexes == other.colwise_span_indexes + && loop_span_indexes == other.loop_span_indexes && m_compliance == other.m_compliance; } /// @@ -447,23 +546,43 @@ namespace pinocchio /// \brief Returns the constraint projector associated with joint 1. /// This matrix transforms a spatial velocity expressed at the origin to the first component of /// the constraint associated with joint 1. - Matrix36 getA1(const RigidConstraintDataTpl & cdata) const + template + Matrix36 + getA1(const RigidConstraintDataTpl & cdata, ReferenceFrameTag) const { Matrix36 res; - const SE3 & oMl = cdata.oMc1; typedef typename SE3::Vector3 Vector3; -#define PINOCCHIO_INTERNAL_COMPUTATION(axis_id, v3_in, res) \ + if (std::is_same, WorldFrameTag>::value) + { +#define INTERNAL_LOOP(axis_id, v3_in, res) \ + CartesianAxis::cross(v3_in, v_tmp); \ + res.col(axis_id).noalias() = oM1.rotation().transpose() * v_tmp; + + const SE3 & oM1 = cdata.oMc1; + Vector3 v_tmp; + res.template leftCols<3>() = oM1.rotation().transpose(); + INTERNAL_LOOP(0, oM1.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(1, oM1.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(2, oM1.translation(), res.template rightCols<3>()); + +#undef INTERNAL_LOOP + } + else if (std::is_same, LocalFrameTag>::value) + { +#define INTERNAL_LOOP(axis_id, v3_in, res) \ CartesianAxis::cross(v3_in, v_tmp); \ - res.col(axis_id).noalias() = oMl.rotation().transpose() * v_tmp; + res.col(axis_id).noalias() = M1.rotation().transpose() * v_tmp; - res.template leftCols<3>() = oMl.rotation().transpose(); - Vector3 v_tmp; - PINOCCHIO_INTERNAL_COMPUTATION(0, oMl.translation(), res.template rightCols<3>()); - PINOCCHIO_INTERNAL_COMPUTATION(1, oMl.translation(), res.template rightCols<3>()); - PINOCCHIO_INTERNAL_COMPUTATION(2, oMl.translation(), res.template rightCols<3>()); + const SE3 & M1 = this->joint1_placement; + Vector3 v_tmp; + res.template leftCols<3>() = M1.rotation().transpose(); + INTERNAL_LOOP(0, M1.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(1, M1.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(2, M1.translation(), res.template rightCols<3>()); -#undef PINOCCHIO_INTERNAL_COMPUTATION +#undef INTERNAL_LOOP + } return res; } @@ -471,28 +590,118 @@ namespace pinocchio /// \brief Returns the constraint projector associated with joint 2. /// This matrix transforms a spatial velocity expressed at the origin to the first component of /// the constraint associated with joint 2. - Matrix36 getA2(const RigidConstraintDataTpl & cdata) const + template + Matrix36 + getA2(const RigidConstraintDataTpl & cdata, ReferenceFrameTag) const { Matrix36 res; - const SE3 & oM1 = cdata.oMc1; - const SE3 & oM2 = cdata.oMc2; typedef typename SE3::Vector3 Vector3; -#define PINOCCHIO_INTERNAL_COMPUTATION(axis_id, v3_in, res) \ + if (std::is_same, WorldFrameTag>::value) + { +#define INTERNAL_LOOP(axis_id, v3_in, res) \ CartesianAxis::cross(v3_in, v_tmp); \ res.col(axis_id).noalias() = oM1.rotation().transpose() * v_tmp; - res.template leftCols<3>() = -oM1.rotation().transpose(); - Vector3 v_tmp; - PINOCCHIO_INTERNAL_COMPUTATION(0, -oM2.translation(), res.template rightCols<3>()); - PINOCCHIO_INTERNAL_COMPUTATION(1, -oM2.translation(), res.template rightCols<3>()); - PINOCCHIO_INTERNAL_COMPUTATION(2, -oM2.translation(), res.template rightCols<3>()); + const SE3 & oM1 = cdata.oMc1; + const SE3 & oM2 = cdata.oMc2; + res.template leftCols<3>() = -oM1.rotation().transpose(); + Vector3 v_tmp; + INTERNAL_LOOP(0, -oM2.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(1, -oM2.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(2, -oM2.translation(), res.template rightCols<3>()); -#undef PINOCCHIO_INTERNAL_COMPUTATION +#undef INTERNAL_LOOP + } + else if (std::is_same, LocalFrameTag>::value) + { + const SE3 & j2Mc2 = this->joint2_placement; + const SE3 & c1Mc2 = cdata.c1Mc2; + const typename SE3::Matrix3 c1Rj2 = c1Mc2.rotation() * j2Mc2.rotation().transpose(); + res.template leftCols<3>() = -c1Rj2; + Vector3 v_tmp; +#define INTERNAL_LOOP(axis_id, v3_in, res) \ + CartesianAxis::cross(v3_in, v_tmp); \ + res.col(axis_id).noalias() = -c1Rj2 * v_tmp; + + INTERNAL_LOOP(0, j2Mc2.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(1, j2Mc2.translation(), res.template rightCols<3>()); + INTERNAL_LOOP(2, j2Mc2.translation(), res.template rightCols<3>()); + +#undef INTERNAL_LOOP + } + + return res; + } + + /// + /// @brief This function computes the spatial inertia associated with the constraint. + /// This function is useful to express the constraint inertia associated with the constraint for + /// AL settings. + /// + template + Matrix6 computeConstraintSpatialInertia( + const SE3Tpl & placement, + const Eigen::MatrixBase & diagonal_constraint_inertia) const + { + EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Vector3Like, Vector3); + Matrix6 res; + + const auto & R = placement.rotation(); + const auto & t = placement.translation(); + + typedef Eigen::Matrix Matrix3; + const Matrix3 R_Sigma = R * diagonal_constraint_inertia.asDiagonal(); + const Matrix3 t_skew = skew(t); + + auto block_LL = res.template block<3, 3>(SE3::LINEAR, SE3::LINEAR); + auto block_LA = res.template block<3, 3>(SE3::LINEAR, SE3::ANGULAR); + auto block_AL = res.template block<3, 3>(SE3::ANGULAR, SE3::LINEAR); + auto block_AA = res.template block<3, 3>(SE3::ANGULAR, SE3::ANGULAR); + + block_LL.noalias() = R_Sigma * R.transpose(); + block_LA.noalias() = -block_LL * t_skew; + block_AL.noalias() = block_LA.transpose(); + block_AA.noalias() = t_skew * block_LA; return res; } + template< + template class JointCollectionTpl, + typename Vector3Like, + typename Matrix6Like, + typename Matrix6LikeAllocator> + void appendCouplingConstraintInertias( + const ModelTpl & model, + const DataTpl & data, + const RigidConstraintDataTpl & cdata, + const Eigen::MatrixBase & diagonal_constraint_inertia, + std::vector & inertias) const + { + EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Vector3Like, Vector3); + PINOCCHIO_UNUSED_VARIABLE(data); + PINOCCHIO_UNUSED_VARIABLE(cdata); + PINOCCHIO_CHECK_ARGUMENT_SIZE(inertias.size(), size_t(model.njoints)); + assert( + ((joint1_id > 0 && joint2_id == 0) || (joint1_id == 0 && joint2_id > 0)) + && "The behavior is only defined for this context"); + + if (this->joint1_id != 0) + { + const SE3 & placement = this->joint1_placement; + inertias[this->joint1_id] += + computeConstraintSpatialInertia(placement, diagonal_constraint_inertia); + } + + if (this->joint2_id != 0) + { + const SE3 & placement = this->joint2_placement; + inertias[this->joint2_id] += + computeConstraintSpatialInertia(placement, diagonal_constraint_inertia); + } + } + template< typename InputMatrix, typename OutputMatrix, @@ -519,8 +728,8 @@ namespace pinocchio // complexity_strategy_1 = 6 * res.cols() * 36 + constraint_dim * 36 * res.cols(), // complexity_strategy_2 = 36 * constraint_dim * 6 + constraint_dim * 36 * res.cols(); - const Matrix36 A1 = getA1(cdata); - const Matrix36 A2 = getA2(cdata); + const Matrix36 A1 = getA1(cdata, WorldFrameTag()); + const Matrix36 A2 = getA2(cdata, WorldFrameTag()); for (Eigen::DenseIndex jj = 0; jj < model.nv; ++jj) { if (!(colwise_joint1_sparsity[jj] || colwise_joint2_sparsity[jj])) @@ -547,7 +756,7 @@ namespace pinocchio ///  \brief Evaluate the Jacobian associated to the constraint at the given state stored in data /// and cdata.  The results Jacobian is evaluated in the jacobian input/output matrix. - template class JointCollectionTpl> + template class JointCollectionTpl, typename JacobianMatrix> void jacobian( const ModelTpl & model, const DataTpl & data, @@ -636,8 +845,6 @@ namespace pinocchio } case CONTACT_6D: { - assert( - check_expression_if_real(sign != 0) && "sign should be equal to +1 or -1."); switch (cmodel.reference_frame) { case LOCAL: { @@ -668,6 +875,74 @@ namespace pinocchio } } + /// \brief Map the constraint forces (aka constraint Lagrange multipliers) to the forces + /// supported by the joints. + template< + template class JointCollectionTpl, + typename ForceLike, + typename ForceAllocator> + void mapConstraintForceToJointForces( + const ModelTpl & model, + const DataTpl & data, + const RigidConstraintDataTpl & cdata, + const Eigen::MatrixBase & constraint_forces, + std::vector, ForceAllocator> & joint_forces) const + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(joint_forces.size(), size_t(model.njoints)); + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_forces.rows(), size()); + PINOCCHIO_UNUSED_VARIABLE(data); + + assert(this->type == CONTACT_3D); + + // Todo: optimize code + const Matrix36 A1 = getA1(cdata, LocalFrameTag()), A2 = getA2(cdata, LocalFrameTag()); + joint_forces[this->joint1_id].toVector().noalias() += A1.transpose() * constraint_forces; + joint_forces[this->joint2_id].toVector().noalias() += A2.transpose() * constraint_forces; + } + + /// \brief Map the joint accelerations to constraint value + template< + template class JointCollectionTpl, + typename MotionAllocator, + typename VectorLike> + void mapJointMotionsToConstraintMotion( + const ModelTpl & model, + const DataTpl & data, + const RigidConstraintDataTpl & cdata, + const std::vector, MotionAllocator> & joint_accelerations, + const Eigen::MatrixBase & constraint_value) const + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(joint_accelerations.size(), size_t(model.njoints)); + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_value.rows(), size()); + PINOCCHIO_UNUSED_VARIABLE(data); + + assert(this->type == CONTACT_3D); + + // Todo: optimize code + + if (this->joint1_id != 0 && this->joint2_id != 0) + { + const Matrix36 A1 = getA1(cdata, LocalFrameTag()), A2 = getA2(cdata, LocalFrameTag()); + constraint_value.const_cast_derived().noalias() = + A1 * joint_accelerations[this->joint1_id].toVector() + + A2 * joint_accelerations[this->joint2_id].toVector(); + } + else if (this->joint1_id != 0) + { + const Matrix36 A1 = getA1(cdata, LocalFrameTag()); + constraint_value.const_cast_derived().noalias() = + A1 * joint_accelerations[this->joint1_id].toVector(); + } + else if (this->joint2_id != 0) + { + const Matrix36 A2 = getA2(cdata, LocalFrameTag()); + constraint_value.const_cast_derived().noalias() = + A2 * joint_accelerations[this->joint2_id].toVector(); + } + else + constraint_value.const_cast_derived().setZero(); + } + int size() const { switch (type) @@ -682,6 +957,11 @@ namespace pinocchio return -1; } + int activeSize() const + { + return size(); + } + /// \returns An expression of *this with the Scalar type casted to NewScalar. template RigidConstraintModelTpl cast() const @@ -698,13 +978,13 @@ namespace pinocchio res.desired_contact_placement = desired_contact_placement.template cast(); res.desired_contact_velocity = desired_contact_velocity.template cast(); res.desired_contact_acceleration = desired_contact_acceleration.template cast(); - res.corrector = corrector.template cast(); res.colwise_joint1_sparsity = colwise_joint1_sparsity; res.colwise_joint2_sparsity = colwise_joint2_sparsity; res.nv = nv; res.depth_joint1 = depth_joint1; res.depth_joint2 = depth_joint2; res.loop_span_indexes = loop_span_indexes; + res.corrector = corrector.template cast(); return res; } @@ -765,7 +1045,6 @@ namespace pinocchio } assert(current1_id == current2_id && "current1_id should be equal to current2_id"); - if (type == CONTACT_3D) { JointIndex current_id = current1_id; while (current_id > 0) @@ -788,7 +1067,8 @@ namespace pinocchio joint1_span_indexes.rbegin(), joint1_span_indexes.rbegin() + 1, joint1_span_indexes.rend()); std::rotate( joint2_span_indexes.rbegin(), joint2_span_indexes.rbegin() + 1, joint2_span_indexes.rend()); - Base::colwise_span_indexes.reserve((size_t)model.nv); + colwise_span_indexes.reserve((size_t)model.nv); + colwise_sparsity.resize(model.nv); loop_span_indexes.reserve((size_t)model.nv); for (Eigen::DenseIndex col_id = 0; col_id < model.nv; ++col_id) { @@ -806,25 +1086,77 @@ namespace pinocchio } }; - template - size_t getTotalConstraintSize( - const std::vector, Allocator> & contact_models) + /// + /// \brief Computes the sum of the active sizes of the constraints contained in the input + /// `contact_models` vector. + template class Holder, class ConstraintModel, class ConstraintModelAllocator> + Eigen::DenseIndex getTotalConstraintActiveSize( + const std::vector, ConstraintModelAllocator> & constraint_models) + { + Eigen::DenseIndex total_size = 0; + for (const auto & wrapper : constraint_models) + { + const ConstraintModel & constraint_model = wrapper; + total_size += constraint_model.activeSize(); + } + + return total_size; + } + + /// + /// \brief Computes the sum of the active sizes of the constraints contained in the input + /// `contact_models` vector. + template + Eigen::DenseIndex getTotalConstraintActiveSize( + const std::vector & contact_models) { - typedef std::vector, Allocator> VectorType; - size_t total_size = 0; - for (typename VectorType::const_iterator it = contact_models.begin(); - it != contact_models.end(); ++it) - total_size += it->size(); + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + contact_models.cbegin(), contact_models.cend()); + + return getTotalConstraintActiveSize(wrapped_constraint_models); + } + + /// + /// \brief Computes the sum of the sizes of the constraints contained in the input + /// `contact_models` vector. + template class Holder, class ConstraintModel, class ConstraintModelAllocator> + Eigen::DenseIndex getTotalConstraintSize( + const std::vector, ConstraintModelAllocator> & constraint_models) + { + Eigen::DenseIndex total_size = 0; + for (const auto & wrapper : constraint_models) + { + const ConstraintModel & constraint_model = wrapper; + total_size += constraint_model.size(); + } return total_size; } + /// + /// \brief Computes the sum of the sizes of the constraints contained in the input + /// `contact_models` vector. + template + Eigen::DenseIndex getTotalConstraintSize( + const std::vector & contact_models) + { + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + contact_models.cbegin(), contact_models.cend()); + + return getTotalConstraintSize(wrapped_constraint_models); + } + /// ///  \brief Contact model structure containg all the info describing the rigid contact model /// template - struct PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") - RigidConstraintDataTpl : ConstraintDataBase> + struct RigidConstraintDataTpl : ConstraintDataBase> { EIGEN_MAKE_ALIGNED_OPERATOR_NEW diff --git a/include/pinocchio/algorithm/contact-inverse-dynamics.hpp b/include/pinocchio/algorithm/contact-inverse-dynamics.hpp index 068e19de7e..f84108dd69 100644 --- a/include/pinocchio/algorithm/contact-inverse-dynamics.hpp +++ b/include/pinocchio/algorithm/contact-inverse-dynamics.hpp @@ -2,148 +2,179 @@ // Copyright (c) 2024 INRIA // -#ifndef __pinocchio_algorithm_contact_inverse_dynamics__hpp__ -#define __pinocchio_algorithm_contact_inverse_dynamics__hpp__ +#ifndef __pinocchio_algorithm_contact_inverse_dynamics_hpp__ +#define __pinocchio_algorithm_contact_inverse_dynamics_hpp__ -#include "pinocchio/multibody/model.hpp" -#include "pinocchio/multibody/data.hpp" -#include "pinocchio/algorithm/constraints/coulomb-friction-cone.hpp" #include "pinocchio/algorithm/rnea.hpp" -#include -#include -#include +#include "pinocchio/algorithm/contact-jacobian.hpp" #include "pinocchio/algorithm/proximal.hpp" -#include - namespace pinocchio { /// - /// \brief Compute the contact impulses given a target velocity of contact points. - /// - /// \tparam JointCollection Collection of Joint types. - /// \tparam ConfigVectorType Type of the joint configuration vector. - /// \tparam TangentVectorType1 Type of the joint velocity vector. - /// \tparam TangentVectorType2 Type of the joint acceleration vector. - /// - /// \param[in] model The model structure of the rigid body system. - /// \param[in] data The data structure of the rigid body system. - /// \param[in] c_ref The contact point velocity - /// \param[in] contact_models The list of contact models. - /// \param[in] contact_datas The list of contact_datas. - /// \param[in] cones list of friction cones. - /// \param[in] R vector representing the diagonal of the compliance matrix. - /// \param[in] constraint_correction vector representing the constraint correction. - /// \param[in] settings The settings for the proximal algorithm. - /// \param[in] impulse_guess initial guess for the contact impulses. + /// \brief Compute the contact forces given a target velocity of contact points. /// - /// \return The desired joint torques stored in data.tau. + /// \param[in] contact_models The vector of constraint models. + /// \param[in] c_ref The desired constraint velocity. + /// \param[in,out] lambda Vector of solution. Should be initialized with zeros or from an initial + /// estimate. + /// \param[in,out] settings The settings for the proximal algorithm + /// \param[in] solve_ncp whether to solve the NCP (true) or CCP (false). /// template< typename Scalar, int Options, - template class JointCollectionTpl, - typename VectorLikeC, + template class Holder, class ConstraintModelAllocator, - class ConstraintDataAllocator, - class CoulombFrictionConelAllocator, - typename VectorLikeR, - typename VectorLikeGamma, - typename VectorLikeImp> - PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") - const typename DataTpl:: - TangentVectorType & computeContactImpulses( - const ModelTpl & model, - DataTpl & data, - const Eigen::MatrixBase & c_ref, - const std::vector, ConstraintModelAllocator> & - contact_models, - std::vector, ConstraintDataAllocator> & contact_datas, - const std::vector, CoulombFrictionConelAllocator> & cones, - const Eigen::MatrixBase & R, - const Eigen::MatrixBase & constraint_correction, - ProximalSettingsTpl & settings, - const boost::optional & impulse_guess = boost::none) + typename VectorLikeC, + typename VectorLikeResult> + bool computeInverseDynamicsConstraintForces( + const std::vector< + Holder>, + ConstraintModelAllocator> & contact_models, + const Eigen::MatrixBase & c_ref, + const Eigen::MatrixBase & _lambda, + ProximalSettingsTpl & settings, + bool solve_ncp = true) { - - typedef Eigen::Matrix MatrixXs; typedef Eigen::Matrix VectorXs; typedef Eigen::Matrix Vector3; + typedef FrictionalPointConstraintModelTpl ConstraintModel; - int problem_size = R.size(); - int n_contacts = (int)problem_size / 3; - PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_correction.size(), problem_size); - PINOCCHIO_CHECK_ARGUMENT_SIZE(contact_models.size(), n_contacts); - PINOCCHIO_CHECK_ARGUMENT_SIZE(contact_datas.size(), n_contacts); - PINOCCHIO_CHECK_INPUT_ARGUMENT( - check_expression_if_real(settings.mu > Scalar(0)), "mu has to be strictly positive"); - MatrixXs J = MatrixXs::Zero(problem_size, model.nv); // TODO: malloc - getConstraintsJacobian(model, data, contact_models, contact_datas, J); - VectorXs c_ref_cor, desaxce_correction, R_prox, impulse_c_prev, dimpulse_c; // TODO: malloc - R_prox = R + VectorXs::Constant(problem_size, settings.mu); - c_ref_cor = c_ref + constraint_correction; - if (impulse_guess) - { - data.impulse_c = impulse_guess.get(); - PINOCCHIO_CHECK_ARGUMENT_SIZE(data.impulse_c.size(), problem_size); - } - else + const Eigen::Index problem_size = getTotalConstraintActiveSize(contact_models); + const std::size_t n_constraints = contact_models.size(); + VectorXs R(problem_size); + Eigen::Index constraint_index = 0; + for (std::size_t i = 0; i < contact_models.size(); i++) { - data.impulse_c.setZero(); + const ConstraintModel & cmodel = contact_models[(std::size_t)i]; + R.segment(constraint_index, cmodel.activeSize()) = cmodel.getActiveCompliance(); + constraint_index += cmodel.activeSize(); } - Scalar impulse_c_prev_norm_inf = data.impulse_c.template lpNorm(); - Scalar complementarity, dual_feasibility; - bool abs_prec_reached = false, rel_prec_reached = false; - const size_t nc = cones.size(); // num constraints + const VectorXs R_prox = R + VectorXs::Constant(problem_size, settings.mu); + + auto & lambda = _lambda.const_cast_derived(); + + // PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_correction.size(), problem_size); + PINOCCHIO_CHECK_ARGUMENT_SIZE(contact_models.size(), n_constraints); + PINOCCHIO_CHECK_ARGUMENT_SIZE(lambda.size(), problem_size); + PINOCCHIO_CHECK_INPUT_ARGUMENT( + check_expression_if_real(settings.mu >= Scalar(0)), "mu has to be strictly positive"); + + assert( + R.size() > 0 && check_expression_if_real(R_prox.minCoeff() >= Scalar(0)) + && "The minimal value of R_prox should strictly positive"); + + Scalar lambda_c_prev_norm_inf = lambda.template lpNorm(); + + bool has_converged = false; settings.iter = 1; for (; settings.iter <= settings.max_iter; ++settings.iter) { - impulse_c_prev = data.impulse_c; - for (size_t cone_id = 0; cone_id < nc; ++cone_id) + bool abs_prec_reached = false, rel_prec_reached = false; + settings.relative_residual = settings.absolute_residual = Scalar(0); + + Eigen::DenseIndex row_id = 0; + for (std::size_t constraint_id = 0; constraint_id < n_constraints; ++constraint_id) { - const Eigen::DenseIndex row_id = 3 * cone_id; - const auto & cone = cones[cone_id]; - auto impulse_segment = data.impulse_c.template segment<3>(row_id); - auto impulse_prev_segment = impulse_c_prev.template segment<3>(row_id); - auto R_prox_segment = R_prox.template segment<3>(row_id); - // Vector3 desaxce_segment; - // auto desaxce_segment = desaxce_correction.template segment<3>(row_id); - auto c_ref_segment = c_ref.template segment<3>(row_id); - Vector3 desaxce_segment = cone.computeNormalCorrection( - c_ref_segment - + (R.template segment<3>(row_id).array() * impulse_segment.array()).matrix()); - impulse_segment = - -((c_ref_segment + desaxce_segment - settings.mu * impulse_prev_segment).array() - / R_prox_segment.array()) - .matrix(); - impulse_segment = cone.weightedProject(impulse_segment, R_prox_segment); + const ConstraintModel & cmodel = contact_models[constraint_id]; + const auto constraint_size = cmodel.size(); + + const auto & cone = cmodel.set(); + auto lambda_segment = lambda.segment(row_id, constraint_size); + const Vector3 lambda_c_previous = lambda_segment; + + const auto R_segment = R.segment(row_id, constraint_size); + const auto R_prox_segment = R_prox.segment(row_id, constraint_size); + const auto c_ref_segment = c_ref.segment(row_id, constraint_size); + + const Vector3 sigma_segment = + c_ref_segment + (R_segment.array() * lambda_segment.array()).matrix(); + Vector3 desaxce_correction = Vector3::Zero(); + if (solve_ncp) + desaxce_correction = cone.computeNormalCorrection(sigma_segment); + const Vector3 c_cor_segment = c_ref_segment + desaxce_correction; + + // Update segment value + const Vector3 lambda_ref = + -(Vector3(c_cor_segment - settings.mu * lambda_c_previous).array() + / R_prox_segment.array()); + lambda_segment = cone.weightedProject(lambda_ref, R_prox_segment); + + // Compute convergence criteria + const Scalar contact_complementarity = cone.computeConicComplementarity( + Vector3(sigma_segment + desaxce_correction), lambda_segment); + const Scalar dual_feasibility = + std::abs(math::min(0., sigma_segment(2))); // proxy of dual feasibility + settings.absolute_residual = math::max( + settings.absolute_residual, math::max(contact_complementarity, dual_feasibility)); + + const Vector3 dlambda_c = lambda_segment - lambda_c_previous; + const Scalar proximal_metric = dlambda_c.template lpNorm(); + settings.relative_residual = math::max(settings.relative_residual, proximal_metric); + + row_id += constraint_size; } - dimpulse_c = data.impulse_c - impulse_c_prev; - settings.relative_residual = dimpulse_c.template lpNorm(); - - // if( check_expression_if_real(complementarity <= this->absolute_precision) - // && check_expression_if_real(dual_feasibility <= this->absolute_precision) - // && check_expression_if_real(primal_feasibility <= - // this->absolute_precision)) - // abs_prec_reached = true; - // else - // abs_prec_reached = false; - - const Scalar impulse_c_norm_inf = data.impulse_c.template lpNorm(); + + const Scalar lambda_c_norm_inf = lambda.template lpNorm(); + + if (check_expression_if_real( + settings.absolute_residual <= settings.absolute_accuracy)) + abs_prec_reached = true; + if (check_expression_if_real( settings.relative_residual - <= settings.relative_accuracy * math::max(impulse_c_norm_inf, impulse_c_prev_norm_inf))) + <= settings.relative_accuracy * math::max(lambda_c_norm_inf, lambda_c_prev_norm_inf))) rel_prec_reached = true; - else - rel_prec_reached = false; if (abs_prec_reached || rel_prec_reached) + { + has_converged = true; break; + } - impulse_c_prev_norm_inf = impulse_c_norm_inf; + lambda_c_prev_norm_inf = lambda_c_norm_inf; } - return data.impulse_c; + + return has_converged; + } + + /// + /// \brief Compute the contact forces given a target velocity of contact points. + /// + /// \param[in] contact_models The vector of constraint models. + /// \param[in] c_ref The desired constraint velocity. + /// \param[in,out] lambda_sol Vector of solution. Should be initialized with zeros or from an + /// initial estimate + /// \param[in,out] settings The settings for the proximal algorithm + /// \param[in] solve_ncp whether to solve the NCP (true) or CCP (false). + /// + template< + typename Scalar, + int Options, + class ConstraintModelAllocator, + typename VectorLikeC, + typename VectorLikeResult> + bool computeInverseDynamicsConstraintForces( + const std::vector< + FrictionalPointConstraintModelTpl, + ConstraintModelAllocator> & contact_models, + const Eigen::MatrixBase & c_ref, + const Eigen::MatrixBase & lambda_sol, + ProximalSettingsTpl & settings, + bool solve_ncp = true) + { + typedef FrictionalPointConstraintModelTpl ConstraintModel; + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + contact_models.cbegin(), contact_models.cend()); + + return computeInverseDynamicsConstraintForces( + wrapped_constraint_models, c_ref.derived(), lambda_sol.const_cast_derived(), settings, + solve_ncp); } /// @@ -164,11 +195,10 @@ namespace pinocchio /// \param[in] dt The time step. /// \param[in] contact_models The list of contact models. /// \param[in] contact_datas The list of contact_datas. - /// \param[in] cones list of friction cones. - /// \param[in] R vector representing the diagonal of the compliance matrix. /// \param[in] constraint_correction vector representing the constraint correction. - /// \param[in] settings The settings for the proximal algorithm. - /// \param[in] lambda_guess initial guess for the contact forces. + /// \param[in] lambda_sol initial guess for the contact forces + /// \param[in] settings The settings for the proximal algorithm + /// \param[in] solve_ncp whether to solve the NCP (true) or CCP (false). /// /// \return The desired joint torques stored in data.tau. /// @@ -179,77 +209,144 @@ namespace pinocchio typename ConfigVectorType, typename TangentVectorType1, typename TangentVectorType2, + template class Holder, class ConstraintModelAllocator, class ConstraintDataAllocator, - class CoulombFrictionConelAllocator, - typename VectorLikeR, typename VectorLikeGamma, typename VectorLikeLam> - PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") - const typename DataTpl:: - TangentVectorType & contactInverseDynamics( - const ModelTpl & model, - DataTpl & data, - const Eigen::MatrixBase & q, - const Eigen::MatrixBase & v, - const Eigen::MatrixBase & a, - Scalar dt, - const std::vector, ConstraintModelAllocator> & - contact_models, - std::vector, ConstraintDataAllocator> & contact_datas, - const std::vector, CoulombFrictionConelAllocator> & cones, - const Eigen::MatrixBase & R, - const Eigen::MatrixBase & constraint_correction, - ProximalSettingsTpl & settings, - const boost::optional & lambda_guess = boost::none) + const typename DataTpl::TangentVectorType & + contactInverseDynamics( + const ModelTpl & model, + DataTpl & data, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & v, + const Eigen::MatrixBase & a, + const Scalar dt, + const std::vector< + Holder>, + ConstraintModelAllocator> & contact_models, + std::vector< + Holder>, + ConstraintDataAllocator> & contact_datas, + const Eigen::MatrixBase & constraint_correction, + const Eigen::MatrixBase & _lambda_sol, + ProximalSettingsTpl & settings, + bool solve_ncp = true) { + typedef ModelTpl Model; + typedef FrictionalPointConstraintModelTpl ConstraintModel; + typedef typename ConstraintModel::ConstraintData ConstraintData; - typedef Eigen::Matrix MatrixXs; - typedef Eigen::Matrix VectorXs; - typedef ForceTpl Force; - typedef RigidConstraintDataTpl RigidConstraintData; + typedef typename Model::MatrixXs MatrixXs; + typedef typename Model::VectorXs VectorXs; + + auto & lambda_sol = _lambda_sol.const_cast_derived(); + + const Eigen::Index problem_size = getTotalConstraintActiveSize(contact_models); + const std::size_t n_constraints = contact_models.size(); - int problem_size = R.size(); - int n_contacts = (int)problem_size / 3; MatrixXs J = MatrixXs::Zero(problem_size, model.nv); // TODO: malloc getConstraintsJacobian(model, data, contact_models, contact_datas, J); VectorXs v_ref, c_ref, tau_c; - v_ref = v + dt * a; + v_ref.noalias() = v + dt * a; c_ref.noalias() = J * v_ref; // TODO should rather use the displacement - boost::optional impulse_guess = boost::none; - if (lambda_guess) - { - data.impulse_c = lambda_guess.get(); - data.impulse_c *= dt; - impulse_guess = boost::make_optional(data.impulse_c); - } - computeContactImpulses( - model, data, c_ref, contact_models, contact_datas, cones, R, constraint_correction, settings, - impulse_guess); - data.lambda_c = data.impulse_c / dt; - container::aligned_vector fext(model.njoints); - for (int i = 0; i < model.njoints; i++) - { - fext[i] = Force::Zero(); - } - for (int i = 0; i < n_contacts; i++) + c_ref += constraint_correction; + c_ref /= dt; // we work with a formulation on forces + computeInverseDynamicsConstraintForces(contact_models, c_ref, lambda_sol, settings, solve_ncp); + { - const auto & cmodel = contact_models[i]; - const Eigen::DenseIndex row_id = 3 * i; - auto lambda_segment = data.lambda_c.template segment<3>(row_id); - typename RigidConstraintData::Matrix6 actInv_transpose1 = - cmodel.joint1_placement.toActionMatrixInverse(); - actInv_transpose1.transposeInPlace(); - fext[cmodel.joint1_id] += Force(actInv_transpose1.template leftCols<3>() * lambda_segment); - typename RigidConstraintData::Matrix6 actInv_transpose2 = - cmodel.joint2_placement.toActionMatrixInverse(); - actInv_transpose2.transposeInPlace(); - fext[cmodel.joint2_id] += Force(actInv_transpose2.template leftCols<3>() * lambda_segment); + rnea(model, data, q, v, a); + auto & tau = data.tau; + Eigen::DenseIndex row_id = 0; + for (std::size_t i = 0; i < n_constraints; i++) + { + const ConstraintModel & cmodel = contact_models[i]; + ConstraintData & cdata = contact_datas[i]; + const auto constraint_size = cmodel.size(); + + const auto lambda_segment = lambda_sol.segment(row_id, constraint_size); + cmodel.jacobianTransposeMatrixProduct(model, data, cdata, lambda_segment, tau, RmTo()); + + row_id += constraint_size; + } } - rnea(model, data, q, v, a, fext); return data.tau; } + /// + /// \brief The Contact Inverse Dynamics algorithm. It computes the inverse dynamics in the + /// presence of contacts, aka the joint torques according to the current state of the system and + /// the desired joint accelerations. + /// + /// \tparam JointCollection Collection of Joint types. + /// \tparam ConfigVectorType Type of the joint configuration vector. + /// \tparam TangentVectorType1 Type of the joint velocity vector. + /// \tparam TangentVectorType2 Type of the joint acceleration vector. + /// + /// \param[in] model The model structure of the rigid body system. + /// \param[in] data The data structure of the rigid body system. + /// \param[in] q The joint configuration vector (dim model.nq). + /// \param[in] v The joint velocity vector (dim model.nv). + /// \param[in] a The joint acceleration vector (dim model.nv). + /// \param[in] dt The time step. + /// \param[in] contact_models The list of contact models. + /// \param[in] contact_datas The list of contact_datas. + /// \param[in] constraint_correction vector representing the constraint correction. + /// \param[in] lambda_sol initial guess for the contact forces + /// \param[in] settings The settings for the proximal algorithm + /// \param[in] solve_ncp whether to solve the NCP (true) or CCP (false). + /// + /// \return The desired joint torques stored in data.tau. + /// + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename TangentVectorType1, + typename TangentVectorType2, + class ConstraintModelAllocator, + class ConstraintDataAllocator, + typename VectorLikeGamma, + typename VectorLikeLam> + const typename DataTpl::TangentVectorType & + contactInverseDynamics( + const ModelTpl & model, + DataTpl & data, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & v, + const Eigen::MatrixBase & a, + const Scalar dt, + const std::vector< + FrictionalPointConstraintModelTpl, + ConstraintModelAllocator> & contact_models, + std::vector, ConstraintDataAllocator> & + contact_datas, + const Eigen::MatrixBase & constraint_correction, + const Eigen::MatrixBase & lambda_sol, + ProximalSettingsTpl & settings, + bool solve_ncp = true) + { + + typedef std::reference_wrapper> + WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + contact_models.cbegin(), contact_models.cend()); + + typedef std::reference_wrapper> + WrappedConstraintDataType; + typedef std::vector WrappedConstraintDataVector; + + WrappedConstraintDataVector wrapped_constraint_datas( + contact_datas.begin(), contact_datas.end()); + + return contactInverseDynamics( + model, data, q, v, a, dt, wrapped_constraint_models, wrapped_constraint_datas, + constraint_correction, lambda_sol.const_cast_derived(), settings, solve_ncp); + } + } // namespace pinocchio // #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION diff --git a/include/pinocchio/algorithm/contact-jacobian.hpp b/include/pinocchio/algorithm/contact-jacobian.hpp index 01dadb5e9e..03f3c0c772 100644 --- a/include/pinocchio/algorithm/contact-jacobian.hpp +++ b/include/pinocchio/algorithm/contact-jacobian.hpp @@ -1,18 +1,111 @@ // -// Copyright (c) 2021 INRIA +// Copyright (c) 2021-2025 INRIA // #ifndef __pinocchio_algorithm_contact_jacobian_hpp__ #define __pinocchio_algorithm_contact_jacobian_hpp__ -#include "pinocchio/algorithm/contact-info.hpp" +#include "pinocchio/algorithm/constraints/constraints.hpp" namespace pinocchio { + /// + /// \brief Evaluates all the constraints by calling cmodel.calc(). + /// + /// \remarks This function assumes that data is up-to-date. + /// + /// \param[in] model The model structure of the rigid body system. + /// \param[in] data The data structure of the rigid body system. + /// \param[in] constraint_models Vector of constraint models. + /// \param[in] constraint_datas Vector of constraint datas. + /// + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator> + void evalConstraints( + const ModelTpl & model, + const DataTpl & data, + const std::vector & constraint_models, + std::vector & constraint_datas); + + /// + /// \brief Maps the constraint forces expressed in the constraint space to joint forces expressed + /// in the local frame. + /// + /// \remarks This function assumes that the constrained data are up-to-date. + /// + /// \param[in] model The model structure of the rigid body system. + /// \param[in] data The data structure of the rigid body system. + /// \param[in] constraint_models Vector of constraint models. + /// \param[in] constraint_datas Vector of constraint datas. + /// \param[in] constraint_forces Matrix or vector containing the constraint forces. + /// \param[out] joint_forces Vector of joint forces (dimension model.njoints). + /// + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator, + typename ForceMatrix, + class ForceAllocator, + ReferenceFrame rf> + void mapConstraintForcesToJointForces( + const ModelTpl & model, + const DataTpl & data, + const std::vector & constraint_models, + const std::vector & constraint_datas, + const Eigen::MatrixBase & constraint_forces, + std::vector, ForceAllocator> & joint_forces, + ReferenceFrameTag reference_frame); + + /// + /// \brief Maps the joint motions expressed in the joint space local frame to the constraint + /// motions. + /// + /// \remarks This function assumes that the constrained data are up-to-date. + /// + /// \param[in] model The model structure of the rigid body system. + /// \param[in] data The data structure of the rigid body system. + /// \param[in] constraint_models Vector of constraint models. + /// \param[in] constraint_datas Vector of constraint datas. + /// \param[in] joint_motions Vector of joint motions (dimension model.njoints). + /// \param[out] constraint_motions Resulting matrix or vector containing the constraint motions. + /// + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator, + class MotionAllocator, + typename MotionMatrix, + ReferenceFrame rf> + void mapJointMotionsToConstraintMotions( + const ModelTpl & model, + const DataTpl & data, + const std::vector & constraint_models, + const std::vector & constraint_datas, + const std::vector, MotionAllocator> & joint_motions, + const Eigen::MatrixBase & constraint_motions, + ReferenceFrameTag reference_frame); + /// /// \brief Computes the kinematic Jacobian associatied to a given constraint model. /// + /// \remarks This function assumes that the a computeJointJacobians has been called first or any + /// algorithms that computes data.J and data.oMi. + /// /// \param[in] model The model structure of the rigid body system. /// \param[in] data The data structure of the rigid body system. /// \param[in] constraint_model Constraint model. @@ -24,18 +117,23 @@ namespace pinocchio typename Scalar, int Options, template class JointCollectionTpl, + typename ConstraintModelDerived, + typename ConstraintDataDerived, typename Matrix6Like> PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") void getConstraintJacobian( const ModelTpl & model, const DataTpl & data, - const RigidConstraintModelTpl & constraint_model, - RigidConstraintDataTpl & constraint_data, + const ConstraintModelBase & constraint_model, + ConstraintDataBase & constraint_data, const Eigen::MatrixBase & J); /// /// \brief Computes the kinematic Jacobian associatied to a given set of constraint models. /// + /// \remarks This function assumes that the a computeJointJacobians has been called first or any + /// algorithms that computes data.J and data.oMi. + /// /// \param[in] model The model structure of the rigid body system. /// \param[in] data The data structure of the rigid body system. /// \param[in] constraint_models Vector of constraint models. @@ -47,18 +145,111 @@ namespace pinocchio typename Scalar, int Options, template class JointCollectionTpl, + template class Holder, typename DynamicMatrixLike, + class ConstraintModel, class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator> + void getConstraintsJacobian( + const ModelTpl & model, + const DataTpl & data, + const std::vector, ConstraintModelAllocator> & constraint_model, + std::vector, ConstraintDataAllocator> & constraint_data, + const Eigen::MatrixBase & J); + + /// + /// \brief Computes the kinematic Jacobian associatied to a given set of constraint models. + /// + /// \remarks This function assumes that the a computeJointJacobians has been called first or any + /// algorithms that computes data.J and data.oMi. + /// + /// \param[in] model The model structure of the rigid body system. + /// \param[in] data The data structure of the rigid body system. + /// \param[in] constraint_models Vector of constraint models. + /// \param[in] constraint_datas Vector of constraint data. + /// \param[out] J A reference on the Jacobian matrix where the results will be stored in (dim nc x + /// model.nv). You must fill J with zero elements, e.g. J.fill(0.). + /// + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename DynamicMatrixLike, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, class ConstraintDataAllocator> - PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") void getConstraintsJacobian( const ModelTpl & model, const DataTpl & data, - const std::vector, ConstraintDataAllocator> & - constraint_model, - std::vector, ConstraintDataAllocator> & constraint_data, + const std::vector & constraint_model, + std::vector & constraint_data, const Eigen::MatrixBase & J); + /// + /// \brief Evaluate the operation res = J.T * rhs + /// + /// \remarks This function assumes that the a computeJointJacobians has been called first or any + /// algorithms that computes data.J and data.oMi. + /// + /// \param[in] model The model structure of the rigid body system. + /// \param[in] data The data structure of the rigid body system. + /// \param[in] constraint_models Vector of constraint models. + /// \param[in] constraint_datas Vector of constraint data. + /// \param[in] rhs Right-hand side term. + /// \param[out] res Results. + /// + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + template class Holder, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator, + typename RhsMatrixType, + typename ResultMatrixType> + void evalConstraintJacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const std::vector, ConstraintModelAllocator> & constraint_models, + const std::vector, ConstraintDataAllocator> & constraint_datas, + const Eigen::MatrixBase & rhs, + const Eigen::MatrixBase & res); + + /// + /// \brief Evaluate the operation res = J.T * rhs + /// + /// \remarks This function assumes that the a computeJointJacobians has been called first or any + /// algorithms that computes data.J and data.oMi. + /// + /// \param[in] model The model structure of the rigid body system. + /// \param[in] data The data structure of the rigid body system. + /// \param[in] constraint_models Vector of constraint models. + /// \param[in] constraint_datas Vector of constraint data. + /// \param[in] rhs Right-hand side term. + /// \param[out] res Results. + /// + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator, + typename RhsMatrixType, + typename ResultMatrixType> + void evalConstraintJacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const std::vector & constraint_models, + const std::vector & constraint_datas, + const Eigen::MatrixBase & rhs, + const Eigen::MatrixBase & res); + } // namespace pinocchio #include "pinocchio/algorithm/contact-jacobian.hxx" diff --git a/include/pinocchio/algorithm/contact-jacobian.hxx b/include/pinocchio/algorithm/contact-jacobian.hxx index 97d5b05b49..dfa9c28195 100644 --- a/include/pinocchio/algorithm/contact-jacobian.hxx +++ b/include/pinocchio/algorithm/contact-jacobian.hxx @@ -1,5 +1,5 @@ // -// Copyright (c) 2021 INRIA +// Copyright (c) 2021-2025 INRIA // #ifndef __pinocchio_algorithm_contact_jacobian_hxx__ @@ -8,6 +8,7 @@ #include "pinocchio/multibody/model.hpp" #include "pinocchio/multibody/data.hpp" #include "pinocchio/algorithm/check.hpp" +#include "pinocchio/utils/reference.hpp" namespace pinocchio { @@ -16,133 +17,120 @@ namespace pinocchio typename Scalar, int Options, template class JointCollectionTpl, - typename Matrix6or3Like> - void getConstraintJacobian( + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator> + void evalConstraints( const ModelTpl & model, const DataTpl & data, - const RigidConstraintModelTpl & constraint_model, - RigidConstraintDataTpl & constraint_data, - const Eigen::MatrixBase & J_) + const std::vector & constraint_models, + std::vector & constraint_datas) { - assert(model.check(data) && "data is not consistent with model."); - assert(model.check(MimicChecker()) && "Function does not support mimic joints"); + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_models.size(), constraint_datas.size()); + const size_t num_ee = constraint_models.size(); - PINOCCHIO_CHECK_ARGUMENT_SIZE(J_.rows(), constraint_model.size()); - PINOCCHIO_CHECK_ARGUMENT_SIZE(J_.cols(), model.nv); + for (size_t ee_id = 0; ee_id < num_ee; ++ee_id) + { + const ConstraintModel & cmodel = constraint_models[ee_id]; + ConstraintData & cdata = constraint_datas[ee_id]; - typedef ModelTpl Model; - typedef typename Model::Motion Motion; - typedef typename Model::SE3 SE3; - typedef DataTpl Data; + cmodel.calc(model, data, cdata); + } + } + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator, + typename ForceMatrix, + class ForceAllocator, + ReferenceFrame rf> + void mapConstraintForcesToJointForces( + const ModelTpl & model, + const DataTpl & data, + const std::vector & constraint_models, + const std::vector & constraint_datas, + const Eigen::MatrixBase & constraint_forces, + std::vector, ForceAllocator> & joint_forces, + ReferenceFrameTag reference_frame) + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_models.size(), constraint_datas.size()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(joint_forces.size(), size_t(model.njoints)); + + const Eigen::DenseIndex constraint_size = getTotalConstraintActiveSize(constraint_models); + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_forces.rows(), constraint_size); + + for (auto & force : joint_forces) + force.setZero(); - Matrix6or3Like & J = J_.const_cast_derived(); + Eigen::Index row_id = 0; + for (size_t ee_id = 0; ee_id < constraint_models.size(); ++ee_id) + { + const ConstraintModel & cmodel = constraint_models[ee_id]; + const auto constraint_size = cmodel.activeSize(); + const ConstraintData & cdata = constraint_datas[ee_id]; - typedef RigidConstraintModelTpl ConstraintModel; - const typename ConstraintModel::BooleanVector & colwise_joint1_sparsity = - constraint_model.colwise_joint1_sparsity; - const typename ConstraintModel::BooleanVector & colwise_joint2_sparsity = - constraint_model.colwise_joint2_sparsity; - const typename ConstraintModel::IndexVector & colwise_span_indexes = - constraint_model.colwise_span_indexes; + const auto constraint_force = constraint_forces.segment(row_id, constraint_size); + cmodel.mapConstraintForceToJointForces( + model, data, cdata, constraint_force, joint_forces, reference_frame); - SE3 & oMc1 = constraint_data.oMc1; - oMc1 = data.oMi[constraint_model.joint1_id] * constraint_model.joint1_placement; - SE3 & oMc2 = constraint_data.oMc2; - oMc2 = data.oMi[constraint_model.joint2_id] * constraint_model.joint2_placement; - SE3 & c1Mc2 = constraint_data.c1Mc2; - c1Mc2 = oMc1.actInv(oMc2); + row_id += constraint_size; + } + } - for (size_t k = 0; k < colwise_span_indexes.size(); ++k) + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator, + typename ForceMatrix, + class ForceAllocator, + typename GeneralizedTorqueVector, + ReferenceFrame rf> + void mapConstraintForcesToJointSpace( + const ModelTpl & model, + const DataTpl & data, + const std::vector & constraint_models, + const std::vector & constraint_datas, + const Eigen::MatrixBase & constraint_forces, + std::vector, ForceAllocator> & joint_forces, + const Eigen::MatrixBase & joint_torques_, + ReferenceFrameTag reference_frame) + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_models.size(), constraint_datas.size()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(joint_forces.size(), size_t(model.njoints)); + PINOCCHIO_CHECK_ARGUMENT_SIZE(joint_torques_.size(), model.nv); + + const Eigen::DenseIndex constraint_size = getTotalConstraintActiveSize(constraint_models); + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_forces.rows(), constraint_size); + + auto & joint_torques = joint_torques_.const_cast_derived(); + + // Reset quantities + joint_torques.setZero(); + for (auto & force : joint_forces) + force.setZero(); + + Eigen::Index row_id = 0; + for (size_t ee_id = 0; ee_id < constraint_models.size(); ++ee_id) { - const Eigen::DenseIndex col_id = colwise_span_indexes[k]; - - const int sign = colwise_joint1_sparsity[col_id] != colwise_joint2_sparsity[col_id] - ? colwise_joint1_sparsity[col_id] ? +1 : -1 - : 0; // specific case for CONTACT_3D - - typedef typename Data::Matrix6x::ConstColXpr ColXprIn; - const ColXprIn Jcol_in = data.J.col(col_id); - const MotionRef Jcol_motion_in(Jcol_in); - - typedef typename Matrix6or3Like::ColXpr ColXprOut; - ColXprOut Jcol_out = J.col(col_id); - - switch (constraint_model.type) - { - case CONTACT_3D: { - switch (constraint_model.reference_frame) - { - case WORLD: { - Jcol_out.noalias() = Jcol_motion_in.linear() * Scalar(sign); - break; - } - case LOCAL: { - if (sign == 0) - { - const Motion Jcol_local1(oMc1.actInv(Jcol_motion_in)); // TODO: simplify computations - const Motion Jcol_local2(oMc2.actInv(Jcol_motion_in)); // TODO: simplify computations - Jcol_out.noalias() = Jcol_local1.linear() - c1Mc2.rotation() * Jcol_local2.linear(); - } - else if (sign == 1) - { - const Motion Jcol_local(oMc1.actInv(Jcol_motion_in)); - Jcol_out.noalias() = Jcol_local.linear(); - } - else // sign == -1 - { - const Motion Jcol_local(oMc2.actInv(Jcol_motion_in)); // TODO: simplify computations - Jcol_out.noalias() = - -c1Mc2.rotation() * Jcol_local.linear(); // TODO: simplify computations - } - break; - } - case LOCAL_WORLD_ALIGNED: { - if (sign == 0) - { - Jcol_out.noalias() = - (oMc2.translation() - oMc1.translation()).cross(Jcol_motion_in.angular()); - } - else - { - if (sign == 1) - Jcol_out.noalias() = - Jcol_motion_in.linear() - oMc1.translation().cross(Jcol_motion_in.angular()); - else - Jcol_out.noalias() = - -Jcol_motion_in.linear() + oMc2.translation().cross(Jcol_motion_in.angular()); - } - break; - } - } - break; - } - case CONTACT_6D: { - MotionRef Jcol_motion_out(Jcol_out); - assert(check_expression_if_real(sign != 0) && "sign should be equal to +1 or -1."); - switch (constraint_model.reference_frame) - { - case WORLD: { - Jcol_motion_out = Jcol_motion_in; - break; - } - case LOCAL: { - Jcol_motion_out = Scalar(sign) * oMc1.actInv(Jcol_motion_in); - break; - } - case LOCAL_WORLD_ALIGNED: { - Motion Jcol_local_world_aligned(Jcol_motion_in); - Jcol_local_world_aligned.linear() -= - oMc1.translation().cross(Jcol_local_world_aligned.angular()); - Jcol_motion_out = Scalar(sign) * Jcol_local_world_aligned; - break; - } - } - break; - } - - default: - break; - } + const auto & cmodel = helper::get_ref(constraint_models[ee_id]); + const auto constraint_size = cmodel.activeSize(); + const auto & cdata = helper::get_ref(constraint_datas[ee_id]); + + const auto constraint_force = constraint_forces.segment(row_id, constraint_size); + cmodel.mapConstraintForceToJointSpace( + model, data, cdata, constraint_force, joint_forces, joint_torques, reference_frame); + + row_id += constraint_size; } } @@ -150,25 +138,144 @@ namespace pinocchio typename Scalar, int Options, template class JointCollectionTpl, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator, + class MotionAllocator, + typename MotionConstraintMatrix, + ReferenceFrame rf> + void mapJointMotionsToConstraintMotions( + const ModelTpl & model, + const DataTpl & data, + const std::vector & constraint_models, + const std::vector & constraint_datas, + const std::vector, MotionAllocator> & joint_motions, + const Eigen::MatrixBase & constraint_motions_, + ReferenceFrameTag reference_frame) + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_models.size(), constraint_datas.size()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(joint_motions.size(), size_t(model.njoints)); + + auto & constraint_motions = constraint_motions_.const_cast_derived(); + const Eigen::DenseIndex constraint_size = getTotalConstraintActiveSize(constraint_models); + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_motions.rows(), constraint_size); + + Eigen::Index row_id = 0; + for (size_t ee_id = 0; ee_id < constraint_models.size(); ++ee_id) + { + const auto & cmodel = helper::get_ref(constraint_models[ee_id]); + const auto & cdata = helper::get_ref(constraint_datas[ee_id]); + const auto constraint_size = cmodel.activeSize(); + + auto constraint_motion = constraint_motions.segment(row_id, constraint_size); + cmodel.mapJointMotionsToConstraintMotion( + model, data, cdata, joint_motions, constraint_motion, reference_frame); + + row_id += constraint_size; + } + } + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator, + class MotionAllocator, + typename GeneralizedVelocityVector, + typename MotionConstraintMatrix, + ReferenceFrame rf> + void mapJointSpaceToConstraintMotions( + const ModelTpl & model, + const DataTpl & data, + const std::vector & constraint_models, + const std::vector & constraint_datas, + const std::vector, MotionAllocator> & joint_motions, + const Eigen::MatrixBase & generalized_velocity, + const Eigen::MatrixBase & constraint_motions_, + ReferenceFrameTag reference_frame) + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_models.size(), constraint_datas.size()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(joint_motions.size(), size_t(model.njoints)); + PINOCCHIO_CHECK_ARGUMENT_SIZE(generalized_velocity.size(), model.nv); + + auto & constraint_motions = constraint_motions_.const_cast_derived(); + const Eigen::DenseIndex constraint_active_size = + getTotalConstraintActiveSize(constraint_models); + PINOCCHIO_CHECK_ARGUMENT_SIZE(constraint_motions.rows(), constraint_active_size); + + Eigen::Index row_id = 0; + for (size_t ee_id = 0; ee_id < constraint_models.size(); ++ee_id) + { + const auto & cmodel = helper::get_ref(constraint_models[ee_id]); + const auto & cdata = helper::get_ref(constraint_datas[ee_id]); + const auto constraint_size = cmodel.activeSize(); + + auto constraint_motion = constraint_motions.segment(row_id, constraint_size); + cmodel.mapJointSpaceToConstraintMotion( + model, data, cdata, joint_motions, generalized_velocity, constraint_motion, + reference_frame); + + row_id += constraint_size; + } + } + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConstraintModel, + typename ConstraintData, + typename JacobianMatrixLike> + void getConstraintJacobian( + const ModelTpl & model, + const DataTpl & data, + const ConstraintModelBase & constraint_model_, + ConstraintDataBase & constraint_data_, + const Eigen::MatrixBase & J_) + { + JacobianMatrixLike & J = J_.const_cast_derived(); + const auto & constraint_model = constraint_model_.derived(); + auto & constraint_data = constraint_data_.derived(); + + assert(model.check(data) && "data is not consistent with model."); + PINOCCHIO_CHECK_ARGUMENT_SIZE(J_.rows(), constraint_model.activeSize()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(J_.cols(), model.nv); + + constraint_model.calc(model, data, constraint_data); + constraint_model.jacobian(model, data, constraint_data, J); + } + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + template class Holder, typename DynamicMatrixLike, + class ConstraintModel, class ConstraintModelAllocator, + class ConstraintData, class ConstraintDataAllocator> void getConstraintsJacobian( const ModelTpl & model, const DataTpl & data, - const std::vector, ConstraintModelAllocator> & - constraint_models, - std::vector, ConstraintDataAllocator> & - constraint_datas, + const std::vector, ConstraintModelAllocator> & constraint_models, + std::vector, ConstraintDataAllocator> & constraint_datas, const Eigen::MatrixBase & J_) { - typedef RigidConstraintModelTpl ContraintModel; - typedef RigidConstraintDataTpl ContraintData; + typedef ConstraintModel ContraintModel; + typedef ConstraintData ContraintData; - const Eigen::DenseIndex constraint_size = getTotalConstraintSize(constraint_models); + const Eigen::DenseIndex constraint_size = getTotalConstraintActiveSize(constraint_models); PINOCCHIO_CHECK_ARGUMENT_SIZE(J_.rows(), constraint_size); PINOCCHIO_CHECK_ARGUMENT_SIZE(J_.cols(), model.nv); + assert(model.check(data) && "data is not consistent with model."); + assert(model.check(MimicChecker()) && "Function does not support mimic joints"); + DynamicMatrixLike & J = J_.const_cast_derived(); Eigen::DenseIndex row_id = 0; for (size_t k = 0; k < constraint_models.size(); ++k) @@ -176,12 +283,177 @@ namespace pinocchio const ContraintModel & cmodel = constraint_models[k]; ContraintData & cdata = constraint_datas[k]; - getConstraintJacobian(model, data, cmodel, cdata, J.middleRows(row_id, cmodel.size())); + getConstraintJacobian(model, data, cmodel, cdata, J.middleRows(row_id, cmodel.activeSize())); row_id += cmodel.size(); } } + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename DynamicMatrixLike, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator> + void getConstraintsJacobian( + const ModelTpl & model, + const DataTpl & data, + const std::vector & constraint_models, + std::vector & constraint_datas, + const Eigen::MatrixBase & J_) + { + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + constraint_models.cbegin(), constraint_models.cend()); + + typedef std::reference_wrapper WrappedConstraintDataType; + typedef std::vector WrappedConstraintDataVector; + + WrappedConstraintDataVector wrapped_constraint_datas( + constraint_datas.begin(), constraint_datas.end()); + + getConstraintsJacobian(model, data, wrapped_constraint_models, wrapped_constraint_datas, J_); + } + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + template class Holder, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator> + typename DataTpl::MatrixXs getConstraintsJacobian( + const ModelTpl & model, + const DataTpl & data, + const std::vector, ConstraintModelAllocator> & constraint_models, + std::vector, ConstraintDataAllocator> & constraint_datas) + { + typedef DataTpl Data; + typedef typename Data::MatrixXs ReturnType; + + Eigen::DenseIndex constraint_size = 0; + for (const ConstraintModel & cm : constraint_models) + constraint_size += cm.size(); + + ReturnType res = ReturnType::Zero(constraint_size, model.nv); + getConstraintsJacobian(model, data, constraint_models, constraint_datas, res); + + return res; + } + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator> + typename DataTpl::MatrixXs getConstraintsJacobian( + const ModelTpl & model, + const DataTpl & data, + const std::vector & constraint_models, + std::vector & constraint_datas) + { + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + constraint_models.cbegin(), constraint_models.cend()); + + typedef std::reference_wrapper WrappedConstraintDataType; + typedef std::vector WrappedConstraintDataVector; + + WrappedConstraintDataVector wrapped_constraint_datas( + constraint_datas.begin(), constraint_datas.end()); + + return getConstraintsJacobian(model, data, wrapped_constraint_models, wrapped_constraint_datas); + } + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + template class Holder, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator, + typename RhsMatrixType, + typename ResultMatrixType> + void evalConstraintJacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const std::vector, ConstraintModelAllocator> & constraint_models, + const std::vector, ConstraintDataAllocator> & constraint_datas, + const Eigen::MatrixBase & rhs, + const Eigen::MatrixBase & res_) + { + + const Eigen::DenseIndex constraint_size = getTotalConstraintActiveSize(constraint_models); + ResultMatrixType & res = res_.const_cast_derived(); + + PINOCCHIO_CHECK_ARGUMENT_SIZE(rhs.rows(), constraint_size); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res_.rows(), model.nv); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res_.cols(), rhs.cols()); + + Eigen::Index row_id = 0; + res.setZero(); + for (size_t constraint_id = 0; constraint_id < constraint_models.size(); ++constraint_id) + { + const ConstraintModel & cmodel = constraint_models[constraint_id]; + const ConstraintData & cdata = constraint_datas[constraint_id]; + const auto constraint_size = cmodel.activeSize(); + + const auto rhs_block = rhs.middleRows(row_id, constraint_size); + cmodel.jacobianTransposeMatrixProduct(model, data, cdata, rhs_block, res, AddTo()); + + row_id += constraint_size; + } + } + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator, + typename RhsMatrixType, + typename ResultMatrixType> + void evalConstraintJacobianTransposeMatrixProduct( + const ModelTpl & model, + const DataTpl & data, + const std::vector & constraint_models, + const std::vector & constraint_datas, + const Eigen::MatrixBase & rhs, + const Eigen::MatrixBase & res_) + { + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + constraint_models.cbegin(), constraint_models.cend()); + + typedef std::reference_wrapper WrappedConstraintDataType; + typedef std::vector WrappedConstraintDataVector; + + WrappedConstraintDataVector wrapped_constraint_datas( + constraint_datas.begin(), constraint_datas.end()); + + evalConstraintJacobianTransposeMatrixProduct( + model, data, wrapped_constraint_models, wrapped_constraint_datas, rhs.derived(), + res_.const_cast_derived()); + } + } // namespace pinocchio #endif // ifndef __pinocchio_algorithm_contact_jacobian_hxx__ diff --git a/include/pinocchio/algorithm/contact-solver-base.hpp b/include/pinocchio/algorithm/contact-solver-base.hpp index d5ac6bc9c1..c34f200b3b 100644 --- a/include/pinocchio/algorithm/contact-solver-base.hpp +++ b/include/pinocchio/algorithm/contact-solver-base.hpp @@ -25,6 +25,55 @@ namespace pinocchio typedef hpp::fcl::Timer Timer; #endif // PINOCCHIO_WITH_HPP_FCL + struct SolverStats + { + SolverStats() + : it(0) + { + } + + explicit SolverStats(const int max_it) + : it(0) + { + reserve(max_it); + } + + void reserve(const int max_it) + { + primal_feasibility.reserve(size_t(max_it)); + dual_feasibility.reserve(size_t(max_it)); + dual_feasibility_ncp.reserve(size_t(max_it)); + complementarity.reserve(size_t(max_it)); + } + + void reset() + { + primal_feasibility.clear(); + dual_feasibility.clear(); + complementarity.clear(); + dual_feasibility_ncp.clear(); + it = 0; + } + + size_t size() const + { + return primal_feasibility.size(); + } + + ///  \brief Number of total iterations. + int it; + + /// \brief History of primal feasibility values. + std::vector primal_feasibility; + + /// \brief History of dual feasibility values. + std::vector dual_feasibility; + std::vector dual_feasibility_ncp; + + /// \brief History of complementarity values. + std::vector complementarity; + }; + explicit ContactSolverBaseTpl(const int problem_size) : problem_size(problem_size) , max_it(1000) diff --git a/include/pinocchio/algorithm/contact-solver-utils.hpp b/include/pinocchio/algorithm/contact-solver-utils.hpp index df0ffe5e57..8bfb0ed0a8 100644 --- a/include/pinocchio/algorithm/contact-solver-utils.hpp +++ b/include/pinocchio/algorithm/contact-solver-utils.hpp @@ -7,8 +7,9 @@ #include "pinocchio/math/fwd.hpp" #include "pinocchio/math/comparison-operators.hpp" -#include "pinocchio/algorithm/constraints/coulomb-friction-cone.hpp" +#include "pinocchio/algorithm/constraints/constraints.hpp" #include "pinocchio/algorithm/delassus-operator-base.hpp" +#include "pinocchio/algorithm/constraints/visitors/constraint-model-visitor.hpp" namespace pinocchio { @@ -16,138 +17,668 @@ namespace pinocchio namespace internal { + template + struct ProjectionVisitor + : visitors::ConstraintUnaryVisitorBase> + { + + typedef boost::fusion::vector ArgsType; + + typedef visitors::ConstraintUnaryVisitorBase< + ProjectionVisitor> + Base; + + template + static void algo( + const ConstraintModelBase & cmodel, + const ForceVectorLike & force, + ResultVectorLike & result) + { + cmodel.set().project(force, result); + // result = cmodel.set().project(force); + // assert(set.dual().isInside(result, Scalar(1e-12))); + } + + using Base::run; + + template + static void run( + const pinocchio::ConstraintModelBase & cmodel, + const ForceVectorLike & force, + ResultVectorLike & result) + { + algo(cmodel.derived(), force, result); + } + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + static void run( + const pinocchio::ConstraintModelTpl & cmodel, + const ForceVectorLike & force, + ResultVectorLike & result) + { + // typedef boost::fusion::vector ArgsType1; + // ArgsType args(force.derived(), result.const_cast_derived()); + ArgsType args(force, result); //, result.const_cast_derived()); + run(cmodel, args); + } + }; + /// \brief Project a vector x on the vector of cones. template< - typename Scalar, - typename ConstraintAllocator, + template class Holder, + typename ConstraintModel, + typename ConstraintModelAllocator, typename VectorLikeIn, typename VectorLikeOut> void computeConeProjection( - const std::vector, ConstraintAllocator> & cones, + const std::vector, ConstraintModelAllocator> & + constraint_models, const Eigen::DenseBase & x, const Eigen::DenseBase & x_proj_) { assert(x.size() == x_proj_.size()); Eigen::DenseIndex index = 0; VectorLikeOut & x_proj = x_proj_.const_cast_derived(); - for (const auto & cone : cones) + + typedef typename VectorLikeIn::ConstSegmentReturnType SegmentType1; + typedef typename VectorLikeOut::SegmentReturnType SegmentType2; + + for (const ConstraintModel & cmodel : constraint_models) { - x_proj.template segment<3>(index) = cone.project(x.template segment<3>(index)); - assert(cone.isInside(x_proj.template segment<3>(index), Scalar(1e-12))); - index += 3; + const auto size = cmodel.activeSize(); + SegmentType1 force_segment = x.derived().segment(index, size); + SegmentType2 res = x_proj.segment(index, size); + + typedef ProjectionVisitor Algo; + Algo::run(cmodel, force_segment, res); + + index += size; } } + /// \brief Project a vector x on the vector of cones. + template< + typename ConstraintModel, + typename ConstraintModelAllocator, + typename VectorLikeIn, + typename VectorLikeOut> + void computeConeProjection( + const std::vector & constraint_models, + const Eigen::DenseBase & x, + const Eigen::DenseBase & x_proj) + { + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + constraint_models.cbegin(), constraint_models.cend()); + + computeConeProjection(wrapped_constraint_models, x.derived(), x_proj.const_cast_derived()); + } + + template + struct ScaledProjectionVisitor + : visitors::ConstraintUnaryVisitorBase< + ScaledProjectionVisitor> + { + + typedef boost::fusion:: + vector + ArgsType; + + typedef visitors::ConstraintUnaryVisitorBase< + ScaledProjectionVisitor> + Base; + + template + static void algo( + const ConstraintModelBase & cmodel, + const ForceVectorLike & force, + const ScaleVectorLike & scale, + ResultVectorLike & result) + { + cmodel.set().scaledProject(force, scale, result); + // assert(set.dual().isInside(result, Scalar(1e-12))); + } + + using Base::run; + + template + static void run( + const pinocchio::ConstraintModelBase & cmodel, + const ForceVectorLike & force, + const ScaleVectorLike & scale, + ResultVectorLike & result) + { + algo(cmodel.derived(), force, scale, result); + } + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + static void run( + const pinocchio::ConstraintModelTpl & cmodel, + const ForceVectorLike & force, + const ScaleVectorLike & scale, + ResultVectorLike & result) + { + // typedef boost::fusion::vector ArgsType1; + // ArgsType args(force.derived(), result.const_cast_derived()); + ArgsType args(force, scale, result); //, result.const_cast_derived()); + run(cmodel, args); + } + }; + + /// \brief Project a vector x on the vector of cones. + template< + template class Holder, + typename ConstraintModel, + typename ConstraintModelAllocator, + typename VectorLikeIn, + typename VectorLikeIn2, + typename VectorLikeOut> + void computeScaledConeProjection( + const std::vector, ConstraintModelAllocator> & + constraint_models, + const Eigen::DenseBase & x, + const Eigen::DenseBase & scale, + const Eigen::DenseBase & x_proj_) + { + assert(x.size() == x_proj_.size()); + Eigen::DenseIndex index = 0; + VectorLikeOut & x_proj = x_proj_.const_cast_derived(); + + typedef typename VectorLikeIn::ConstSegmentReturnType SegmentType1; + typedef typename VectorLikeIn2::ConstSegmentReturnType SegmentType2; + typedef typename VectorLikeOut::SegmentReturnType SegmentType3; + + for (const ConstraintModel & cmodel : constraint_models) + { + const auto size = cmodel.activeSize(); + SegmentType1 force_segment = x.derived().segment(index, size); + SegmentType2 scale_segment = scale.derived().segment(index, size); + SegmentType3 res = x_proj.segment(index, size); + + typedef ScaledProjectionVisitor Algo; + Algo::run(cmodel, force_segment, scale_segment, res); + + index += size; + } + } + + /// \brief Project a vector x on the vector of cones. + template< + typename ConstraintModel, + typename ConstraintModelAllocator, + typename VectorLikeIn, + typename VectorLikeIn2, + typename VectorLikeOut> + void computeScaledConeProjection( + const std::vector & constraint_models, + const Eigen::DenseBase & x, + const Eigen::DenseBase & scale, + const Eigen::DenseBase & x_proj) + { + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + constraint_models.cbegin(), constraint_models.cend()); + + computeScaledConeProjection( + wrapped_constraint_models, x.derived(), scale.derived(), x_proj.const_cast_derived()); + } + + template + struct DualProjectionVisitor + : visitors::ConstraintUnaryVisitorBase< + DualProjectionVisitor> + { + typedef typename VelocityVectorLike::Scalar Scalar; + typedef boost::fusion::vector ArgsType; + + typedef visitors::ConstraintUnaryVisitorBase< + DualProjectionVisitor> + Base; + + template + static void algo( + const ConstraintModelBase & cmodel, + const VelocityVectorLike & velocity, + ResultVectorLike & result) + { + algo_step(cmodel.set(), velocity, result); + } + + template + static void algo_step( + const CoulombFrictionConeTpl & cone, + const Eigen::MatrixBase & velocity, + const Eigen::MatrixBase & result) + { + result.const_cast_derived() = cone.dual().project(velocity); + // assert(set.dual().isInside(result, Scalar(1e-12))); + } + + template + static void algo_step( + const JointLimitConstraintConeTpl & cone, + const Eigen::MatrixBase & velocity, + const Eigen::MatrixBase & result) + { + result.const_cast_derived() = cone.dual().project(velocity); + // assert(set.dual().isInside(result, Scalar(1e-12))); + } + + template + static void algo_step( + const UnboundedSetTpl & set, + const Eigen::MatrixBase & velocity, + const Eigen::MatrixBase & result) + { + PINOCCHIO_UNUSED_VARIABLE(set); + PINOCCHIO_UNUSED_VARIABLE(velocity); + result.const_cast_derived().setZero(); + } + + template + static void algo_step( + const ConstraintSet & set, + const Eigen::MatrixBase & velocity, + const Eigen::MatrixBase & result) + { + PINOCCHIO_UNUSED_VARIABLE(set); + result.const_cast_derived() = velocity; + } + + using Base::run; + + template + static void run( + const pinocchio::ConstraintModelBase & cmodel, + const VelocityVectorLike & velocity, + ResultVectorLike & result) + { + algo(cmodel.derived(), velocity, result); + } + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + static void run( + const pinocchio::ConstraintModelTpl & cmodel, + const VelocityVectorLike & velocity, + ResultVectorLike & result) + { + ArgsType args(velocity, result); + run(cmodel.derived(), args); + } + }; // struct DualProjectionVisitor + /// \brief Project a vector x on the dual of the cones contained in the vector of cones. template< - typename Scalar, - typename ConstraintAllocator, + template class Holder, + typename ConstraintModel, + typename ConstraintModelAllocator, typename VectorLikeIn, typename VectorLikeOut> void computeDualConeProjection( - const std::vector, ConstraintAllocator> & cones, + const std::vector, ConstraintModelAllocator> & + constraint_models, const Eigen::DenseBase & x, const Eigen::DenseBase & x_proj_) { assert(x.size() == x_proj_.size()); - Eigen::DenseIndex index = 0; VectorLikeOut & x_proj = x_proj_.const_cast_derived(); - for (const auto & cone : cones) + Eigen::DenseIndex index = 0; + + typedef typename VectorLikeIn::ConstSegmentReturnType SegmentType1; + typedef typename VectorLikeOut::SegmentReturnType SegmentType2; + + for (const ConstraintModel & cmodel : constraint_models) { - x_proj.template segment<3>(index) = cone.dual().project(x.template segment<3>(index)); - assert(cone.dual().isInside(x_proj.template segment<3>(index), Scalar(1e-12))); - index += 3; + const auto size = cmodel.activeSize(); + + SegmentType1 velocity_segment = x.segment(index, size); + SegmentType2 res_segment = x_proj.segment(index, size); + + typedef DualProjectionVisitor Algo; + Algo::run(cmodel, velocity_segment, res_segment); + index += size; } } template< - typename Scalar, - typename ConstraintAllocator, + typename ConstraintModel, + typename ConstraintModelAllocator, + typename VectorLikeIn, + typename VectorLikeOut> + void computeDualConeProjection( + const std::vector & constraint_models, + const Eigen::DenseBase & x, + const Eigen::DenseBase & x_proj) + { + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + constraint_models.cbegin(), constraint_models.cend()); + + computeDualConeProjection( + wrapped_constraint_models, x.derived(), x_proj.const_cast_derived()); + } + + template + struct ComplementarityVisitor + : visitors::ConstraintUnaryVisitorBase< + ComplementarityVisitor, + Scalar> + { + typedef boost::fusion::vector ArgsType; + + typedef visitors::ConstraintUnaryVisitorBase< + ComplementarityVisitor, + Scalar> + Base; + using Base::run; + + template + static Scalar algo( + const ConstraintModelBase & cmodel, + const VelocityVectorLike & velocity, + const ForceVectorLike & force) + { + return algo_step(cmodel.set(), velocity, force); + } + + template + static Scalar algo_step( + const CoulombFrictionConeTpl & set, + const Eigen::MatrixBase & velocity, + const Eigen::MatrixBase & force) + { + return set.computeConicComplementarity(velocity, force); + } + + template + static Scalar algo_step( + const UnboundedSetTpl & set, + const Eigen::MatrixBase & velocity, + const Eigen::MatrixBase & force) + { + PINOCCHIO_UNUSED_VARIABLE(set); + PINOCCHIO_UNUSED_VARIABLE(velocity); + PINOCCHIO_UNUSED_VARIABLE(force); + return Scalar(0); + } + + template + static Scalar algo_step( + const BoxSetTpl & set, + const Eigen::MatrixBase & velocity, + const Eigen::MatrixBase & force) + { + Scalar complementarity = Scalar(0); + + const auto & lb = set.lb(); + const auto & ub = set.ub(); + for (Eigen::DenseIndex row_id = 0; row_id < set.size(); ++row_id) + { + const Scalar velocity_positive_part = math::max(Scalar(0), velocity[row_id]); + const Scalar velocity_negative_part = velocity_positive_part - velocity[row_id]; + + Scalar row_complementarity = velocity_positive_part * (force[row_id] - lb[row_id]); + row_complementarity = + math::max(row_complementarity, velocity_negative_part * (ub[row_id] - force[row_id])); + complementarity = math::max(complementarity, row_complementarity); + } + + return complementarity; + } + + template + static Scalar algo_step( + const JointLimitConstraintConeTpl & cone, + const Eigen::MatrixBase & velocity, + const Eigen::MatrixBase & force) + { + Scalar complementarity = Scalar(0); + + for (Eigen::DenseIndex row_id = 0; row_id < cone.size(); ++row_id) + { + const Scalar row_complementarity = math::fabs(Scalar(velocity[row_id] * force[row_id])); + complementarity = math::max(complementarity, row_complementarity); + } + + return complementarity; + } + + template + static Scalar run( + const pinocchio::ConstraintModelBase & cmodel, + const VelocityVectorLike & velocity, + const ForceVectorLike & force) + { + return algo(cmodel.derived(), velocity, force); + } + + template class ConstraintCollectionTpl> + static Scalar run( + const pinocchio::ConstraintModelTpl & cmodel, + const VelocityVectorLike & velocity, + const ForceVectorLike & force) + { + ArgsType args(velocity, force); + return run(cmodel.derived(), args); + } + }; // struct ComplementarityVisitor + + template< + template class Holder, + typename ConstraintModel, + typename ConstraintModelAllocator, typename VectorLikeVelocity, typename VectorLikeForce> - Scalar computeConicComplementarity( - const std::vector, ConstraintAllocator> & cones, + typename ConstraintModel::Scalar computeConicComplementarity( + const std::vector, ConstraintModelAllocator> & + constraint_models, const Eigen::DenseBase & velocities, const Eigen::DenseBase & forces) { + typedef typename ConstraintModel::Scalar Scalar; assert(velocities.size() == forces.size()); Eigen::DenseIndex index = 0; - Scalar complementarity = 0; - for (const auto & cone : cones) + Scalar complementarity = Scalar(0); + + typedef typename VectorLikeVelocity::ConstSegmentReturnType SegmentType1; + typedef typename VectorLikeForce::ConstSegmentReturnType SegmentType2; + + for (const ConstraintModel & cmodel : constraint_models) { - const Scalar cone_complementarity = cone.computeConicComplementarity( - velocities.template segment<3>(index), forces.template segment<3>(index)); - complementarity = math::max(complementarity, cone_complementarity); - index += 3; + const auto size = cmodel.activeSize(); + + SegmentType1 velocity_segment = velocities.segment(index, size); + SegmentType2 force_segment = forces.segment(index, size); + + typedef ComplementarityVisitor Algo; + const Scalar constraint_complementarity = + Algo::run(cmodel, velocity_segment, force_segment); + + complementarity = math::max(complementarity, constraint_complementarity); + index += size; } return complementarity; } + template + struct DeSaxeCorrectionVisitor + : visitors::ConstraintUnaryVisitorBase< + DeSaxeCorrectionVisitor> + { + + typedef boost::fusion::vector ArgsType; + + typedef visitors::ConstraintUnaryVisitorBase< + DeSaxeCorrectionVisitor> + Base; + using Base::run; + + template + static void algo( + const ConstraintModelBase & cmodel, + const VelocityVectorLike & velocity, + ResultVectorLike & result) + { + return algo_step(cmodel.set(), velocity, result); + } + + template + static void algo_step( + const CoulombFrictionConeTpl & set, + const Eigen::MatrixBase & velocity, + const Eigen::MatrixBase & result) + { + result.const_cast_derived() = set.computeNormalCorrection(velocity); + } + + template + static void algo_step( + const ConstraintSet & set, + const Eigen::MatrixBase & velocity, + const Eigen::MatrixBase & result) + { + PINOCCHIO_UNUSED_VARIABLE(set); + PINOCCHIO_UNUSED_VARIABLE(velocity); + result.const_cast_derived().setZero(); + } + + template + static void run( + const pinocchio::ConstraintModelBase & cmodel, + const VelocityVectorLike & velocity, + ResultVectorLike & result) + { + algo(cmodel.derived(), velocity, result); + } + + template< + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + static void run( + const pinocchio::ConstraintModelTpl & cmodel, + const VelocityVectorLike & velocity, + ResultVectorLike & result) + { + ArgsType args(velocity, result); + run(cmodel.derived(), args); + } + }; // struct DeSaxeCorrectionVisitor + template< - typename Scalar, - typename ConstraintAllocator, + template class Holder, + typename ConstraintModel, + typename ConstraintModelAllocator, typename VectorLikeIn, typename VectorLikeOut> - void computeComplementarityShift( - const std::vector, ConstraintAllocator> & cones, + void computeDeSaxeCorrection( + const std::vector, ConstraintModelAllocator> & + constraint_models, const Eigen::DenseBase & velocities, - const Eigen::DenseBase & shift_) + const Eigen::DenseBase & correction_) { - assert(velocities.size() == shift_.size()); + assert(velocities.size() == correction_.size()); + VectorLikeOut & correction = correction_.const_cast_derived(); + + typedef typename VectorLikeIn::ConstSegmentReturnType SegmentType1; + typedef typename VectorLikeOut::SegmentReturnType SegmentType2; + Eigen::DenseIndex index = 0; - VectorLikeOut & shift = shift_.const_cast_derived(); - for (const auto & cone : cones) + for (const ConstraintModel & cmodel : constraint_models) { - shift.template segment<3>(index) = - cone.computeNormalCorrection(velocities.template segment<3>(index)); - index += 3; + const auto size = cmodel.activeSize(); + + SegmentType1 velocity_segment = velocities.segment(index, size); + SegmentType2 result_segment = correction.segment(index, size); + typedef DeSaxeCorrectionVisitor Step; + + Step::run(cmodel, velocity_segment, result_segment); + + index += size; } } - template - Scalar computePrimalFeasibility( - const std::vector, ConstraintAllocator> & cones, + template< + typename ConstraintModel, + typename ConstraintModelAllocator, + typename VectorLikeIn, + typename VectorLikeOut> + void computeDeSaxeCorrection( + const std::vector & constraint_models, + const Eigen::DenseBase & velocities, + const Eigen::DenseBase & correction) + { + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + constraint_models.cbegin(), constraint_models.cend()); + + computeDeSaxeCorrection( + wrapped_constraint_models, velocities.derived(), correction.const_cast_derived()); + } + + template + typename ConstraintSet::Scalar computePrimalFeasibility( + const std::vector & sets, const Eigen::DenseBase & forces) { - typedef CoulombFrictionConeTpl Cone; - typedef typename Cone::Vector3 Vector3; + typedef typename ConstraintSet::Vector3 Vector3; + typedef typename ConstraintSet::Scalar Scalar; Eigen::DenseIndex index = 0; Scalar norm(0); - for (const auto & cone : cones) + for (const auto & set : sets) { - const Vector3 df_projected = - cone.project(forces.template segment<3>(index)) - forces.template segment<3>(index); + const auto size = set.size(); + Vector3 df_projected = + set.project(forces.segment(index, size)) - forces.segment(index, size); norm = math::max(norm, df_projected.norm()); - index += 3; + index += size; } return norm; } template< - typename Scalar, + typename ConstraintSet, typename ConstraintAllocator, typename ForceVector, typename VelocityVector> - Scalar computeReprojectionError( - const std::vector, ConstraintAllocator> & cones, + typename ConstraintSet::Scalar computeReprojectionError( + const std::vector & sets, const Eigen::DenseBase & forces, const Eigen::DenseBase & velocities) { - typedef CoulombFrictionConeTpl Cone; - typedef typename Cone::Vector3 Vector3; + typedef typename ConstraintSet::Vector3 Vector3; + typedef typename ConstraintSet::Scalar Scalar; Eigen::DenseIndex index = 0; Scalar norm(0); - for (const auto & cone : cones) + for (const auto & set : sets) { + const auto size = set.size(); const Vector3 df_projected = - forces.template segment<3>(index) - - cone.project(forces.template segment<3>(index) - velocities.template segment<3>(index)); + forces.segment(index, size) + - set.project(forces.segment(index, size) - velocities.segment(index, size)); norm = math::max(norm, df_projected.norm()); - index += 3; + index += size; } return norm; @@ -175,6 +706,144 @@ namespace pinocchio // return norm; // } + template + struct GetTimeScalingFromConstraint + : visitors::ConstraintUnaryVisitorBase> + { + using ArgsType = boost::fusion::vector; + using Base = visitors::ConstraintUnaryVisitorBase< + GetTimeScalingFromConstraint>; + + template + static void + algo(const ConstraintModelBase &, Scalar dt, ResultVectorLike & res) + { + switch (ConstraintModel::constraint_formulation_level) + { + case ::pinocchio::ConstraintFormulationLevel::POSITION_LEVEL: + assert( + dt * dt > Eigen::NumTraits::dummy_precision() + && "Numerical loss due to a small dt."); + res.setConstant(Scalar(dt * dt)); + break; + case ::pinocchio::ConstraintFormulationLevel::VELOCITY_LEVEL: + res.setConstant(Scalar(dt)); + break; + case ::pinocchio::ConstraintFormulationLevel::ACCELERATION_LEVEL: + res.setOnes(); + break; + } + } + + /// ::run for individual constraints + template + static void run( + const pinocchio::ConstraintModelBase & cmodel, + Scalar dt, + ResultVectorLike & res) + { + algo(cmodel.derived(), dt, res); + } + + /// ::run for constraints variant + template class ConstraintCollectionTpl> + static void run( + const pinocchio::ConstraintModelTpl & cmodel, + Scalar dt, + ResultVectorLike & res) + { + ArgsType args(dt, res); + // Note: Base::run will call `algo` of this visitor + Base::run(cmodel.derived(), args); + } + }; // struct GetTimeScalingFromConstraint + + /// + /// \brief Retrieve a vector of time scaling factors from a vector of constraints. + /// Depending on the constraint formulation level, the time scaling factor is: + /// - position level -> dt * dt + /// - velocity level -> dt + /// - acceleration level -> 1 + /// Consequently, if z is a vector of constraint residuals, where each component of z is + /// expressed at each constraint formulation level, then the vector z / time_scaling is an + /// acceleration level vector. + /// Conversly, if z is an acceleration vector, then z * time_scaling brings the vector back to + /// the constraints formulation levels. + /// + /// \param[in] constraint_models Vector of constraints + /// \param[in] dt the time step used to linearize the constraints + /// \param[out] time_scaling the vector of time scaling factors + /// + template< + template class Holder, + typename ConstraintModel, + typename ConstraintModelAllocator, + typename VectorLikeOut> + void getTimeScalingFromAccelerationToConstraints( + const std::vector, ConstraintModelAllocator> & + constraint_models, + const typename ConstraintModel::Scalar dt, + const Eigen::DenseBase & time_scaling_) + { + using Scalar = typename ConstraintModel::Scalar; + using SegmentType = typename VectorLikeOut::SegmentReturnType; + VectorLikeOut & time_scaling = time_scaling_.const_cast_derived(); + + Eigen::DenseIndex cindex = 0; + for (const ConstraintModel & cmodel : constraint_models) + { + const auto csize = cmodel.activeSize(); + + SegmentType time_scaling_segment = time_scaling.segment(cindex, csize); + typedef GetTimeScalingFromConstraint Algo; + + Algo::run(cmodel, dt, time_scaling_segment); + + cindex += csize; + } + } + + /// + /// \brief see \ref getTimeScalingFromConstraints + /// + template + void getTimeScalingFromAccelerationToConstraints( + const std::vector & constraint_models, + const typename ConstraintModel::Scalar dt, + const Eigen::DenseBase & time_scaling) + { + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + constraint_models.cbegin(), constraint_models.cend()); + getTimeScalingFromAccelerationToConstraints(wrapped_constraint_models, dt, time_scaling); + } + + /// + /// \brief + /// + /// \param[in] time_scaling_acc_to_constraints Vector of time scaling that scale accelerations + /// to the units of constraints + /// \param[in] dt the time step used to linearize the constraints + /// \param[out] time_scaling_constraints_to_pos the vector of time scaling that scales + /// constraints units to position. + /// + template + void getTimeScalingFromConstraintsToPosition( + const Eigen::MatrixBase & time_scaling_acc_to_constraints, + const Scalar dt, + const Eigen::DenseBase & time_scaling_constraints_to_pos_) + { + assert( + dt * dt > Eigen::NumTraits::dummy_precision() + && "Numerical loss due to a small dt."); + VectorLikeOut & time_scaling_constraints_to_pos = + time_scaling_constraints_to_pos_.const_cast_derived(); + time_scaling_constraints_to_pos = time_scaling_acc_to_constraints.array().inverse(); + time_scaling_constraints_to_pos *= dt * dt; + } + } // namespace internal } // namespace pinocchio diff --git a/include/pinocchio/algorithm/delassus-operator-base.hpp b/include/pinocchio/algorithm/delassus-operator-base.hpp index e7ba58a3c2..06d0098775 100644 --- a/include/pinocchio/algorithm/delassus-operator-base.hpp +++ b/include/pinocchio/algorithm/delassus-operator-base.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2024 INRIA +// Copyright (c) 2024-2025 INRIA // #ifndef __pinocchio_algorithm_delassus_operator_base_hpp__ @@ -7,15 +7,129 @@ #include "pinocchio/algorithm/fwd.hpp" #include "pinocchio/math/eigenvalues.hpp" +#include "pinocchio/math/arithmetic-operators.hpp" namespace pinocchio { + template + struct DelassusOperatorBase; + + template + struct DelassusOperatorApplyOnTheRightReturnType; + + template + struct traits> + { + typedef typename traits::Scalar Scalar; + typedef typename traits::Matrix Matrix; + }; + + template + struct MultiplicationOperatorReturnType< + DelassusOperatorBase, + Eigen::MatrixBase> + { + typedef DelassusOperatorApplyOnTheRightReturnType type; + }; + +} // namespace pinocchio + +namespace Eigen +{ + namespace internal + { + + template + struct traits< + pinocchio::DelassusOperatorApplyOnTheRightReturnType> + { + typedef typename ::pinocchio::traits::Matrix ReturnType; + enum + { + Flags = 0 + }; + }; + + template< + typename DstXprType, + typename DelassusOperatorDerived, + typename MatrixDerived, + typename Functor> + struct Assignment< + DstXprType, + Eigen::ReturnByValue>, + Functor, + Dense2Dense, + void> + { + typedef Eigen::ReturnByValue> + SrcXprType; + + EIGEN_DEVICE_FUNC + static EIGEN_STRONG_INLINE void + run(DstXprType & dst, const SrcXprType & src, const Functor & /*func*/) + { + Index dstRows = src.rows(); + Index dstCols = src.cols(); + if ((dst.rows() != dstRows) || (dst.cols() != dstCols)) + dst.resize(dstRows, dstCols); + + eigen_assert(dst.rows() == src.rows() && dst.cols() == src.cols()); + src.evalTo(dst); + } + }; + + } // namespace internal +} // namespace Eigen + +namespace pinocchio +{ + + template + struct DelassusOperatorApplyOnTheRightReturnType + : public Eigen::ReturnByValue< + DelassusOperatorApplyOnTheRightReturnType> + { + typedef DelassusOperatorApplyOnTheRightReturnType Self; + + DelassusOperatorApplyOnTheRightReturnType( + const DelassusOperatorDerived & lhs, const MatrixDerived & rhs) + : m_lhs(lhs) + , m_rhs(rhs) + { + } + + template + inline void evalTo(ResultType & result) const + { + m_lhs.applyOnTheRight(m_rhs.derived(), result); + } + + EIGEN_CONSTEXPR Eigen::Index rows() const PINOCCHIO_NOEXCEPT + { + return m_lhs.rows(); + } + EIGEN_CONSTEXPR Eigen::Index cols() const PINOCCHIO_NOEXCEPT + { + return m_rhs.cols(); + } + + protected: + const DelassusOperatorDerived & m_lhs; + const MatrixDerived & m_rhs; + }; + template struct DelassusOperatorBase { typedef typename traits::Scalar Scalar; typedef typename traits::Vector Vector; + typedef typename traits::getDampingReturnType getDampingReturnType; typedef PowerIterationAlgoTpl PowerIterationAlgo; DelassusOperatorDerived & derived() @@ -27,81 +141,19 @@ namespace pinocchio return static_cast(*this); } - explicit DelassusOperatorBase(const Eigen::DenseIndex size) - : power_iteration_algo(size) - { - } - - Scalar computeLargestEigenValue( - const bool reset = true, const int max_it = 10, const Scalar rel_tol = Scalar(1e-8)) const + explicit DelassusOperatorBase() { - power_iteration_algo.max_it = max_it; - power_iteration_algo.rel_tol = rel_tol; - if (reset) - power_iteration_algo.reset(); - - power_iteration_algo.run(derived()); - - return power_iteration_algo.largest_eigen_value; } template - Scalar computeLargestEigenValue( - const Eigen::PlainObjectBase & largest_eigenvector_est, - const bool reset = true, - const int max_it = 10, - const Scalar rel_tol = Scalar(1e-8)) const + void updateCompliance(const Eigen::MatrixBase & compliance) { - PINOCCHIO_CHECK_ARGUMENT_SIZE(largest_eigenvector_est.size(), size()); - power_iteration_algo.max_it = max_it; - power_iteration_algo.rel_tol = rel_tol; - if (reset) - power_iteration_algo.reset(); - power_iteration_algo.principal_eigen_vector = largest_eigenvector_est; - - power_iteration_algo.run(derived()); - - return power_iteration_algo.largest_eigen_value; + derived().updateCompliance(compliance.derived()); } - Scalar computeLowestEigenValue( - const bool reset = true, - const bool compute_largest = true, - const int max_it = 10, - const Scalar rel_tol = Scalar(1e-8)) const + void updateCompliance(const Scalar compliance) { - power_iteration_algo.max_it = max_it; - power_iteration_algo.rel_tol = rel_tol; - if (reset) - power_iteration_algo.reset(); - - power_iteration_algo.lowest(derived(), compute_largest); - - return power_iteration_algo.lowest_eigen_value; - } - - template - Scalar computeLowestEigenValue( - const Eigen::PlainObjectBase & largest_eigenvector_est, - const Eigen::PlainObjectBase & lowest_eigenvector_est, - const bool reset = true, - const bool compute_largest = true, - const int max_it = 10, - const Scalar rel_tol = Scalar(1e-8)) const - { - PINOCCHIO_CHECK_ARGUMENT_SIZE(largest_eigenvector_est.size(), size()); - PINOCCHIO_CHECK_ARGUMENT_SIZE(lowest_eigenvector_est.size(), size()); - - power_iteration_algo.max_it = max_it; - power_iteration_algo.rel_tol = rel_tol; - if (reset) - power_iteration_algo.reset(); - power_iteration_algo.principal_eigen_vector = largest_eigenvector_est; - power_iteration_algo.lowest_eigen_vector = lowest_eigenvector_est; - - power_iteration_algo.lowest(derived(), compute_largest); - - return power_iteration_algo.lowest_eigen_value; + derived().updateCompliance(Vector::Constant(size(), compliance)); } template @@ -144,10 +196,19 @@ namespace pinocchio } template - typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixDerived) + typename MultiplicationOperatorReturnType< + DelassusOperatorBase, + Eigen::MatrixBase>::type operator*(const Eigen::MatrixBase & x) const { - return derived() * x.derived(); + typedef typename MultiplicationOperatorReturnType< + DelassusOperatorBase, Eigen::MatrixBase>::type ReturnType; + return ReturnType(derived(), x.derived()); + } + + getDampingReturnType getDamping() const + { + return derived().getDamping(); } Eigen::DenseIndex size() const @@ -163,19 +224,6 @@ namespace pinocchio return derived().cols(); } - PowerIterationAlgo & getPowerIterationAlgo() - { - return power_iteration_algo; - } - - const PowerIterationAlgo & getPowerIterationAlgo() const - { - return power_iteration_algo; - } - - protected: - mutable PowerIterationAlgo power_iteration_algo; - }; // struct DelassusOperatorBase } // namespace pinocchio diff --git a/include/pinocchio/algorithm/delassus-operator-cholesky-expression.hpp b/include/pinocchio/algorithm/delassus-operator-cholesky-expression.hpp new file mode 100644 index 0000000000..5c15887f56 --- /dev/null +++ b/include/pinocchio/algorithm/delassus-operator-cholesky-expression.hpp @@ -0,0 +1,250 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#ifndef __pinocchio_algorithm_delassus_operator_cholesky_expression_hpp__ +#define __pinocchio_algorithm_delassus_operator_cholesky_expression_hpp__ + +#include "pinocchio/algorithm/fwd.hpp" +#include "pinocchio/algorithm/delassus-operator-base.hpp" +#include "pinocchio/algorithm/delassus-operator-dense.hpp" +#include "pinocchio/algorithm/contact-cholesky.hpp" + +namespace pinocchio +{ + template + struct traits> + { + enum + { + RowsAtCompileTime = Eigen::Dynamic + }; + typedef typename ContactCholeskyDecomposition::Scalar Scalar; + typedef typename ContactCholeskyDecomposition::Matrix Matrix; + typedef typename ContactCholeskyDecomposition::Vector Vector; + + typedef typename ContactCholeskyDecomposition::EigenStorageVector EigenStorageVector; + typedef const typename EigenStorageVector::MapType getDampingReturnType; + }; + + // TODO(jcarpent): change const_cast usage. + template + struct DelassusCholeskyExpressionTpl + : DelassusOperatorBase> + { + typedef _ContactCholeskyDecomposition ContactCholeskyDecomposition; + typedef typename ContactCholeskyDecomposition::Scalar Scalar; + typedef typename ContactCholeskyDecomposition::Vector Vector; + typedef typename ContactCholeskyDecomposition::Matrix Matrix; + typedef typename ContactCholeskyDecomposition::RowMatrix RowMatrix; + typedef DelassusCholeskyExpressionTpl<_ContactCholeskyDecomposition> Self; + typedef DelassusOperatorBase Base; + typedef typename ContactCholeskyDecomposition::EigenStorageVector EigenStorageVector; + enum + { + Options = ContactCholeskyDecomposition::Options, + }; + typedef DelassusOperatorDenseTpl DelassusOperatorDense; + + typedef + typename SizeDepType::template BlockReturn::Type RowMatrixBlockXpr; + typedef typename SizeDepType::template BlockReturn::ConstType + RowMatrixConstBlockXpr; + + enum + { + RowsAtCompileTime = traits::RowsAtCompileTime + }; + + explicit DelassusCholeskyExpressionTpl(const ContactCholeskyDecomposition & self) + : Base() + , self(self) + { + } + + template + void applyOnTheRight( + const Eigen::MatrixBase & x, const Eigen::MatrixBase & res) const + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(x.rows(), self.constraintDim()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res.rows(), self.constraintDim()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(res.cols(), x.cols()); + + const auto U1 = self.U.topLeftCorner(self.constraintDim(), self.constraintDim()); + { + PINOCCHIO_EIGEN_MALLOC_NOT_ALLOWED(); + typedef Eigen::Map MapType; + MapType tmp_mat = MapType(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, x.rows(), x.cols())); + // tmp_mat.noalias() = U1.adjoint() * x; + triangularMatrixMatrixProduct(U1.adjoint(), x.derived(), tmp_mat); + + // The following commented lines produced some memory allocation. + // Should be replaced by a manual loop + // tmp_mat.array().colwise() *= -self.D.head(self.constraintDim()).array(); + for (Eigen::DenseIndex i = 0; i < x.cols(); ++i) + tmp_mat.col(i).array() *= -self.D.head(self.constraintDim()).array(); + + // res.const_cast_derived().noalias() = U1 * tmp_mat; + triangularMatrixMatrixProduct(U1, tmp_mat, res.const_cast_derived()); + PINOCCHIO_EIGEN_MALLOC_ALLOWED(); + } + } + + template + void solveInPlace(const Eigen::MatrixBase & x) const + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(x.rows(), self.constraintDim()); + + const auto U1 = self.U.topLeftCorner(self.constraintDim(), self.constraintDim()) + .template triangularView(); + + PINOCCHIO_EIGEN_MALLOC_NOT_ALLOWED(); + U1.solveInPlace(x.const_cast_derived()); + + // The following commented lines produced some memory allocation. + // Should be replaced by a manual loop + // x.const_cast_derived().array().colwise() *= + // -self.Dinv.head(self.constraintDim()).array(); + for (Eigen::DenseIndex i = 0; i < x.cols(); ++i) + x.const_cast_derived().col(i).array() *= -self.Dinv.head(self.constraintDim()).array(); + + U1.adjoint().solveInPlace(x); + PINOCCHIO_EIGEN_MALLOC_ALLOWED(); + } + + template + void solve( + const Eigen::MatrixBase & x, + const Eigen::MatrixBase & res) const + { + res.const_cast_derived() = x; + solveInPlace(res.const_cast_derived()); + } + + template + typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixDerived) + solve(const Eigen::MatrixBase & x) const + { + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixDerived) ReturnType; + ReturnType res(self.constraintDim(), x.cols()); + solve(x.derived(), res); + return res; + } + + /// \brief Returns the Constraint Cholesky decomposition associated to this + /// DelassusCholeskyExpression. + const ContactCholeskyDecomposition & cholesky() const + { + return self; + } + + Matrix matrix(bool enforce_symmetry = false) const + { + return self.getInverseOperationalSpaceInertiaMatrix(enforce_symmetry); + } + + /// \brief Fill the input matrix with the matrix resulting from the decomposition + template + void matrix(const Eigen::MatrixBase & mat, bool enforce_symmetry = false) const + { + return self.getInverseOperationalSpaceInertiaMatrix( + mat.const_cast_derived(), enforce_symmetry); + } + + /// + /// \brief Returns the current compliance vector. + /// + const typename EigenStorageVector::MapType getCompliance() const + { + return self.getCompliance(); + } + + /// + /// \brief Returns the current damping vector. + /// + const typename EigenStorageVector::MapType getDamping() const + { + return self.getDamping(); + } + + Matrix inverse() const + { + return self.getOperationalSpaceInertiaMatrix(); + } + + /// + /// \brief Returns the corresponding dense delassus operator. + /// + DelassusOperatorDense dense(bool enforce_symmetry = false) const + { + return DelassusOperatorDense(*this, enforce_symmetry); + } + + /// + /// \brief Add a compliance term to the diagonal of the Delassus matrix. The compliance terms + /// should be all positives. + /// + /// \param[in] compliances Vector of compliances related to the constraints. + /// + template + void updateCompliance(const Eigen::MatrixBase & compliances) + { + const_cast(self).updateCompliance(compliances); + } + + /// + /// \brief Add a compliance term to the diagonal of the Delassus matrix. The compliance term + /// should be positive. + /// + /// \param[in] compliance Compliance of the constraints. + /// + void updateCompliance(const Scalar & compliance) + { + const_cast(self).updateCompliance(compliance); + } + + /// + /// \brief Add a damping term to the diagonal of the Delassus matrix. The damping terms should + /// be all positives. + /// + /// \param[in] mus Vector of positive regularization factor allowing to enforce the definite + /// positiveness of the matrix. + /// + template + void updateDamping(const Eigen::MatrixBase & mus) + { + const_cast(self).updateDamping(mus); + } + + /// + /// \brief Add a damping term to the diagonal of the Delassus matrix. The damping term should be + /// positive. + /// + /// \param[in] mu Regularization factor allowing to enforce the definite positiveness of the + /// matrix. + /// + void updateDamping(const Scalar & mu) + { + const_cast(self).updateDamping(mu); + } + + Eigen::DenseIndex size() const + { + return self.constraintDim(); + } + Eigen::DenseIndex rows() const + { + return size(); + } + Eigen::DenseIndex cols() const + { + return size(); + } + + protected: + const ContactCholeskyDecomposition & self; + }; // DelassusCholeskyExpression + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_delassus_operator_cholesky_expression_hpp__ diff --git a/include/pinocchio/algorithm/delassus-operator-dense.hpp b/include/pinocchio/algorithm/delassus-operator-dense.hpp index 7afb1d4d88..28fd6da18f 100644 --- a/include/pinocchio/algorithm/delassus-operator-dense.hpp +++ b/include/pinocchio/algorithm/delassus-operator-dense.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2024 INRIA +// Copyright (c) 2024-2025 INRIA // #ifndef __pinocchio_algorithm_delassus_operator_dense_hpp__ @@ -7,6 +7,7 @@ #include "pinocchio/algorithm/fwd.hpp" #include "pinocchio/algorithm/delassus-operator-base.hpp" +#include "pinocchio/algorithm/contact-cholesky.hpp" namespace pinocchio { @@ -23,12 +24,16 @@ namespace pinocchio typedef Eigen::Matrix Matrix; typedef Eigen::Matrix Vector; + + typedef const Vector & getDampingReturnType; }; template struct DelassusOperatorDenseTpl : DelassusOperatorBase> { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + typedef _Scalar Scalar; typedef DelassusOperatorDenseTpl Self; enum @@ -44,22 +49,50 @@ namespace pinocchio template explicit DelassusOperatorDenseTpl(const Eigen::MatrixBase & mat) - : Base(mat.rows()) + : Base() , delassus_matrix(mat) , mat_tmp(mat.rows(), mat.cols()) , llt(mat) + , m_llt_dirty(false) , damping(Vector::Zero(mat.rows())) + , compliance(Vector::Zero(mat.rows())) { PINOCCHIO_CHECK_ARGUMENT_SIZE(mat.rows(), mat.cols()); } + template + explicit DelassusOperatorDenseTpl( + const DelassusCholeskyExpressionTpl & delassus_expression, + const bool enforce_symmetry = false) + : Base() + , delassus_matrix(delassus_expression.matrix(enforce_symmetry)) + , mat_tmp(delassus_expression.rows(), delassus_expression.cols()) + , llt(delassus_matrix) + , m_llt_dirty(false) + , damping(delassus_expression.getDamping()) + , compliance(delassus_expression.getCompliance()) + { + delassus_matrix -= damping.asDiagonal(); + delassus_matrix -= compliance.asDiagonal(); + } + + template + void updateCompliance(const Eigen::MatrixBase & vec) + { + compliance = vec; + m_llt_dirty = true; + } + + void updateCompliance(const Scalar & compliance) + { + updateCompliance(Vector::Constant(size(), compliance)); + } + template void updateDamping(const Eigen::MatrixBase & vec) { damping = vec; - mat_tmp = delassus_matrix; - mat_tmp += vec.asDiagonal(); - llt.compute(mat_tmp); + m_llt_dirty = true; } void updateDamping(const Scalar & mu) @@ -70,6 +103,7 @@ namespace pinocchio template void solveInPlace(const Eigen::MatrixBase & mat) const { + runCholeskyDecomposition(); // only if needed llt.solveInPlace(mat.const_cast_derived()); } @@ -95,21 +129,11 @@ namespace pinocchio void applyOnTheRight( const Eigen::MatrixBase & x, const Eigen::MatrixBase & res_) const { + PINOCCHIO_CHECK_ARGUMENT_SIZE(x.rows(), size()); MatrixOut & res = res_.const_cast_derived(); res.noalias() = delassus_matrix * x; res.array() += damping.array() * x.array(); - } - - template - typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixDerived) - operator*(const Eigen::MatrixBase & x) const - { - typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixDerived) ReturnType; - - PINOCCHIO_CHECK_ARGUMENT_SIZE(x.rows(), size()); - ReturnType res(x.rows(), x.cols()); - applyOnTheRight(x, res); - return res; + res.array() += compliance.array() * x.array(); } Eigen::DenseIndex size() const @@ -125,25 +149,78 @@ namespace pinocchio return delassus_matrix.cols(); } - Matrix matrix() const + Matrix matrix(bool enforce_symmetry = false) const { mat_tmp = delassus_matrix; mat_tmp += damping.asDiagonal(); + mat_tmp += compliance.asDiagonal(); + if (enforce_symmetry) + { + enforceSymmetry(mat_tmp); + } return mat_tmp; } + Matrix undampedMatrix(bool enforce_symmetry = false) const + { + mat_tmp = delassus_matrix; + mat_tmp += compliance.asDiagonal(); + if (enforce_symmetry) + { + enforceSymmetry(mat_tmp); + } + return mat_tmp; + } + + const Vector & getCompliance() const + { + return compliance; + } + + const Vector & getDamping() const + { + return damping; + } + Matrix inverse() const { Matrix res = Matrix::Identity(size(), size()); - llt.solveInPlace(res); + solveInPlace(res); return res; } + bool operator==(const Self & other) const + { + if (&other == this) + return true; + return delassus_matrix == other.delassus_matrix && damping == other.damping + && compliance == other.compliance; + } + + bool operator!=(const Self & other) const + { + return !(*this == other); + } + protected: + void runCholeskyDecomposition() const + { + if (m_llt_dirty) + { + mat_tmp = delassus_matrix; + mat_tmp += damping.asDiagonal(); + mat_tmp += compliance.asDiagonal(); + llt.compute(mat_tmp); + m_llt_dirty = false; + } + } + Matrix delassus_matrix; mutable Matrix mat_tmp; - CholeskyDecomposition llt; + mutable CholeskyDecomposition llt; + mutable bool m_llt_dirty; Vector damping; + Vector compliance; }; // struct DelassusOperatorDenseTpl diff --git a/include/pinocchio/algorithm/delassus-operator-preconditioned.hpp b/include/pinocchio/algorithm/delassus-operator-preconditioned.hpp new file mode 100644 index 0000000000..4f3e7c2a1f --- /dev/null +++ b/include/pinocchio/algorithm/delassus-operator-preconditioned.hpp @@ -0,0 +1,141 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_algorithm_delassus_operator_preconditioned_hpp__ +#define __pinocchio_algorithm_delassus_operator_preconditioned_hpp__ + +#include "pinocchio/algorithm/fwd.hpp" +#include "pinocchio/math/arithmetic-operators.hpp" +#include "pinocchio/algorithm/delassus-operator-base.hpp" +#include "pinocchio/algorithm/preconditioner-base.hpp" + +namespace pinocchio +{ + + template + struct DelassusOperatorPreconditionedTpl; + + template + struct traits> + : traits + { + }; + + template + struct DelassusOperatorPreconditionedTpl + : DelassusOperatorBase> + { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef DelassusOperatorPreconditionedTpl Self; + typedef DelassusOperatorBase Base; + + typedef typename traits::Matrix Matrix; + typedef typename traits::Vector Vector; + typedef typename traits::Scalar Scalar; + + DelassusOperatorPreconditionedTpl( + DelassusOperatorBase & delassus, const PreconditionerType & preconditioner) + : m_delassus(delassus.derived()) + , m_preconditioner(preconditioner) + , m_tmp_vec(preconditioner.cols()) + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(m_delassus.rows(), m_preconditioner.cols()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(m_delassus.cols(), m_preconditioner.rows()); + } + + DelassusOperator & ref() + { + return m_delassus; + } + const DelassusOperator & ref() const + { + return m_delassus; + } + + template + void updateDamping(const Eigen::MatrixBase & vec) + { + // G_bar + mu * Id = P * (G + mu * P^{-2}) * P + m_preconditioner.scaleSquare(vec, m_tmp_vec); + ref().updateDamping(m_tmp_vec); + } + + void updateDamping(const Scalar mu) + { + this->updateDamping(Vector::Constant(ref().size(), mu)); + } + + template + void solveInPlace(const Eigen::MatrixBase & mat) const + { + auto & mat_ = mat.const_cast_derived(); + m_preconditioner.scaleInPlace(mat_); + ref().solveInPlace(mat_); + m_preconditioner.scaleInPlace(mat_); + } + + template + typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixLike) + solve(const Eigen::MatrixBase & mat) const + { + typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixLike) res(mat); + solveInPlace(res); + return res; + } + + template + void solve( + const Eigen::MatrixBase & x, + const Eigen::MatrixBase & res) const + { + res.const_cast_derived() = x; + solveInPlace(res.const_cast_derived()); + } + + template + void applyOnTheRight( + const Eigen::MatrixBase & x, const Eigen::MatrixBase & res) const + { + auto & res_ = res.const_cast_derived(); + m_preconditioner.unscale(x, res_); + ref().applyOnTheRight(res_, m_tmp_vec); + m_preconditioner.unscale(m_tmp_vec, res_); + } + + Eigen::DenseIndex size() const + { + return ref().size(); + } + Eigen::DenseIndex rows() const + { + return ref().rows(); + } + Eigen::DenseIndex cols() const + { + return ref().cols(); + } + + Matrix matrix(bool enforce_symmetry = false) const + { + return m_preconditioner.getDiagonal().asDiagonal() * m_delassus.matrix(enforce_symmetry) + * m_preconditioner.getDiagonal().asDiagonal(); + } + + const Vector & getDamping() const + { + m_preconditioner.unscaleSquare(ref().getDamping(), m_tmp_vec); + return m_tmp_vec; + } + + protected: + DelassusOperator & m_delassus; + const PreconditionerType & m_preconditioner; + Vector m_tmp_vec; + + }; // struct DelassusOperatorPreconditioned + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_delassus_operator_preconditioned_hpp__ diff --git a/include/pinocchio/algorithm/delassus-operator-ref.hpp b/include/pinocchio/algorithm/delassus-operator-ref.hpp new file mode 100644 index 0000000000..e69de29bb2 diff --git a/include/pinocchio/algorithm/delassus-operator-rigid-body-visitors.hxx b/include/pinocchio/algorithm/delassus-operator-rigid-body-visitors.hxx new file mode 100644 index 0000000000..fc94d990c6 --- /dev/null +++ b/include/pinocchio/algorithm/delassus-operator-rigid-body-visitors.hxx @@ -0,0 +1,412 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#ifndef __pinocchio_algorithm_delassus_operator_linear_complexity_visitors_hxx__ +#define __pinocchio_algorithm_delassus_operator_linear_complexity_visitors_hxx__ + +namespace pinocchio +{ + + template + struct DelassusOperatorRigidBodySystemsComputeForwardPass + : public fusion::JointUnaryVisitorBase< + DelassusOperatorRigidBodySystemsComputeForwardPass> + { + typedef typename DelassusOperator::Model Model; + typedef typename DelassusOperator::Data Data; + + typedef boost::fusion::vector ArgsType; + + template + static void algo( + const pinocchio::JointModelBase & jmodel, + pinocchio::JointDataBase & jdata, + const Model & model, + Data & data, + const Eigen::MatrixBase & q) + { + typedef typename Model::JointIndex JointIndex; + + const JointIndex i = jmodel.id(); + jmodel.calc(jdata.derived(), q.derived()); + + const JointIndex parent = model.parents[i]; + data.liMi[i] = model.jointPlacements[i] * jdata.M(); + auto & oMi = data.oMi[i]; + if (parent > 0) + oMi = data.oMi[parent] * data.liMi[i]; + else + oMi = data.liMi[i]; + + // ABA in WORLD frame requires these quantities + jmodel.jointCols(data.J) = oMi.act(jdata.S()); + } + }; + + template + struct DelassusOperatorRigidBodySystemsComputeBackwardPass + : public fusion::JointUnaryVisitorBase> + { + typedef typename DelassusOperator::Model Model; + typedef typename DelassusOperator::Data Data; + typedef typename Model::Scalar Scalar; + + typedef boost::fusion::vector ArgsType; + + template + static void algo( + const pinocchio::JointModelBase & jmodel, + pinocchio::JointDataBase & jdata, + const Model & model, + Data & data) + { + typedef typename Model::JointIndex JointIndex; + typedef typename Data::Matrix6 Matrix6; + typedef typename JointModel::JointDataDerived JointData; + typedef std::pair JointPair; + + const JointIndex i = jmodel.id(); + const JointIndex parent = model.parents[i]; + + // ApplyOnTheRight + if (apply_on_the_right) + { + auto & Ia = data.Yaba[i]; + jmodel.calc_aba( + jdata.derived(), jmodel.jointVelocitySelector(model.armature), Ia, parent > 0); + if (parent > 0) + { + data.Yaba[parent] += impl::internal::SE3actOn::run(data.liMi[i], Ia); + } + } + + // SolveInPlace + if (solve_in_place) + { + JointData & _jdata_augmented = boost::get(data.joints_augmented[i]); + JointDataBase & jdata_augmented = + static_cast &>(_jdata_augmented); + + auto Jcols = jmodel.jointCols(data.J); + auto & Ia_augmented = data.oYaba_augmented[i]; + + jdata_augmented.U().noalias() = Ia_augmented * Jcols; + jdata_augmented.StU().noalias() = Jcols.transpose() * jdata_augmented.U(); + + // Account for the rotor inertia contribution + jdata_augmented.StU().diagonal() += + jmodel.jointVelocitySelector(data.joint_apparent_inertia); + + ::pinocchio::matrix_inversion(jdata_augmented.StU(), jdata_augmented.Dinv()); + + jdata_augmented.UDinv().noalias() = jdata_augmented.U() * jdata_augmented.Dinv(); + + if (parent > 0) + { + Ia_augmented.noalias() -= jdata_augmented.UDinv() * jdata_augmented.U().transpose(); + data.oYaba_augmented[parent] += Ia_augmented; + } + + // End of the classic ABA backward pass - beginning of cross-coupling handling + const auto & neighbours = data.neighbour_links; + auto & joint_cross_coupling = data.joint_cross_coupling; + const auto & joint_neighbours = neighbours[i]; + + if (joint_neighbours.size() == 0) + return; // We can return from this point as this joint has no neighbours + + using Matrix6xNV = typename std::remove_reference::type; + typedef Eigen::Map MapMatrix6xNV; + MapMatrix6xNV mat1_tmp = MapMatrix6xNV(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, 6, jmodel.nv())); + MapMatrix6xNV mat2_tmp = MapMatrix6xNV(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, 6, jmodel.nv())); + + auto & JDinv = mat1_tmp; + JDinv.noalias() = Jcols * jdata_augmented.Dinv(); + + // oL == data.oL[i] + Matrix6 oL = -JDinv * jdata_augmented.U().transpose(); + oL += Matrix6::Identity(); + + for (size_t j = 0; j < joint_neighbours.size(); j++) + { + const JointIndex vertex_j = joint_neighbours[j]; + const Matrix6 & crosscoupling_ij = + (i > vertex_j) + ? joint_cross_coupling.get(JointPair(vertex_j, i)) + : joint_cross_coupling.get(JointPair(i, vertex_j)).transpose(); // avoid memalloc + + auto & crosscoupling_ix_Jcols = mat1_tmp; + crosscoupling_ix_Jcols.noalias() = + crosscoupling_ij * Jcols; // Warning: UDinv() is actually edge_ij * J + + auto & crosscoupling_ij_Jcols_Dinv = mat2_tmp; + crosscoupling_ij_Jcols_Dinv.noalias() = crosscoupling_ix_Jcols * jdata_augmented.Dinv(); + + data.oYaba_augmented[vertex_j].noalias() -= + crosscoupling_ij_Jcols_Dinv + * crosscoupling_ix_Jcols.transpose(); // Warning: UDinv() is actually edge_ij * J, U() + // is actually edge_ij * J_cols * Dinv + // data.of[vertex_j].toVector().noalias() + // += crosscoupling_ij * a_tmp; + + const Matrix6 crosscoupling_ij_oL = crosscoupling_ij * oL; + if (vertex_j == parent) + { + data.oYaba_augmented[parent].noalias() += + crosscoupling_ij_oL + crosscoupling_ij_oL.transpose(); + } + else + { + if (vertex_j < parent) + { + joint_cross_coupling.get({vertex_j, parent}).noalias() += crosscoupling_ij_oL; + } + else + { + joint_cross_coupling.get({parent, vertex_j}).noalias() += + crosscoupling_ij_oL.transpose(); + } + } + + for (size_t k = j + 1; k < joint_neighbours.size(); ++k) + { + const JointIndex vertex_k = joint_neighbours[k]; + + const Matrix6 & edge_ik = + (i > vertex_k) ? joint_cross_coupling.get(JointPair(vertex_k, i)) + : joint_cross_coupling.get(JointPair(i, vertex_k)).transpose(); + + crosscoupling_ix_Jcols.noalias() = edge_ik * Jcols; + + assert(vertex_j != vertex_k && "Must never happen!"); + if (vertex_j < vertex_k) + { + joint_cross_coupling.get({vertex_j, vertex_k}).noalias() -= + crosscoupling_ij_Jcols_Dinv + * crosscoupling_ix_Jcols.transpose(); // Warning: UDinv() is actually edge_ik * + // J_col, U() is edge_ij * J_col * Dinv + } + else // if (vertex_k < vertex_j) + { + joint_cross_coupling.get({vertex_k, vertex_j}).transpose().noalias() -= + crosscoupling_ij_Jcols_Dinv + * crosscoupling_ix_Jcols.transpose(); // Warning: UDinv() is actually edge_ik * + // J_col, U() is edge_ij * J_col * Dinv + } + } + } + } + } + }; + + template + struct DelassusOperatorRigidBodySystemsTplApplyOnTheRightBackwardPass + : public fusion::JointUnaryVisitorBase< + DelassusOperatorRigidBodySystemsTplApplyOnTheRightBackwardPass> + { + typedef typename DelassusOperator::Model Model; + typedef typename DelassusOperator::Data Data; + typedef typename DelassusOperator::CustomData CustomData; + + typedef boost::fusion::vector ArgsType; + + template + static void algo( + const pinocchio::JointModelBase & jmodel, + const pinocchio::JointDataBase & jdata, + const Model & model, + const Data & data, + CustomData & custom_data) + { + const JointIndex i = jmodel.id(); + const JointIndex parent = model.parents[i]; + + // Compare to ABA, the sign of f[i] is reversed + jmodel.jointVelocitySelector(custom_data.u) += jdata.S().transpose() * custom_data.f[i]; + + if (parent > 0) + { + auto & pa = custom_data.f[i]; + // Compare to ABA, the sign of f[i] is reversed + pa.toVector().noalias() -= jdata.UDinv() * jmodel.jointVelocitySelector(custom_data.u); + custom_data.f[parent] += data.liMi[i].act(pa); + } + } + }; + + template + struct DelassusOperatorRigidBodySystemsTplApplyOnTheRightForwardPass + : public fusion::JointUnaryVisitorBase< + DelassusOperatorRigidBodySystemsTplApplyOnTheRightForwardPass> + { + typedef typename DelassusOperator::Model Model; + typedef typename DelassusOperator::Data Data; + typedef typename DelassusOperator::CustomData CustomData; + + typedef boost::fusion::vector ArgsType; + + template + static void algo( + const pinocchio::JointModelBase & jmodel, + const pinocchio::JointDataBase & jdata, + const Model & model, + const Data & data, + CustomData & custom_data) + { + typedef typename Model::JointIndex JointIndex; + + const JointIndex i = jmodel.id(); + const JointIndex parent = model.parents[i]; + + // typename JointData::TangentVector_t ddq_joint; + auto ddq_joint = jmodel.jointVelocitySelector(custom_data.ddq); + if (parent > 0) + { + custom_data.a[i] += data.liMi[i].actInv(custom_data.a[parent]); + ddq_joint = jdata.Dinv() * jmodel.jointVelocitySelector(custom_data.u) + - jdata.UDinv().transpose() * custom_data.a[i].toVector(); + custom_data.a[i] += jdata.S() * ddq_joint; + } + else + { + ddq_joint.noalias() = jdata.Dinv() * jmodel.jointVelocitySelector(custom_data.u); + custom_data.a[i] = jdata.S() * ddq_joint; + } + } + + }; // struct DelassusOperatorRigidBodySystemsTplApplyOnTheRightForwardPass + + template + struct AugmentedMassMatrixOperatorSolveInPlaceBackwardPass + : public fusion::JointUnaryVisitorBase< + AugmentedMassMatrixOperatorSolveInPlaceBackwardPass> + { + typedef typename DelassusOperator::Model Model; + typedef typename DelassusOperator::Data Data; + typedef typename DelassusOperator::CustomData CustomData; + + typedef boost::fusion::vector ArgsType; + + template + static void algo( + const pinocchio::JointModelBase & jmodel, + const pinocchio::JointDataBase & jdata, + const Model & model, + const Data & data, + CustomData & custom_data) + { + typedef typename Model::Scalar Scalar; + typedef typename Data::Force Force; + typedef typename Data::Motion Motion; + typedef typename Motion::Vector6 Vector6; + typedef typename Data::Matrix6 Matrix6; + typedef std::pair JointPair; + + const auto & neighbours = data.neighbour_links; + auto & joint_cross_coupling = data.joint_cross_coupling; + + const JointIndex i = jmodel.id(); + const JointIndex parent = model.parents[i]; + const auto & joint_neighbours = neighbours[i]; + + const auto Jcols = jmodel.jointCols(data.J); + + Force & ofi = custom_data.of_augmented[i]; + + // Compare to ABA, the sign of ofi is reversed + jmodel.jointVelocitySelector(custom_data.u).noalias() += Jcols.transpose() * ofi.toVector(); + + if (joint_neighbours.size()) + { + using VectorNV = typename std::remove_reference::type; + typedef Eigen::Map MapVectorNV; + MapVectorNV res = MapVectorNV(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, jmodel.nv(), 1)); + res.noalias() = (jdata.Dinv() * jmodel.jointVelocitySelector(custom_data.u)); + + const Vector6 a_tmp = Jcols * res; + + for (JointIndex vertex_j : neighbours[i]) + { + const Matrix6 & crosscoupling_ij = + (i > vertex_j) ? joint_cross_coupling.get(JointPair(vertex_j, i)) + : joint_cross_coupling.get(JointPair(i, vertex_j)).transpose(); + + Force & ofj = custom_data.of_augmented[vertex_j]; + // Compare to ABA, the sign of ofj is reversed + ofj.toVector().noalias() -= crosscoupling_ij * a_tmp; + } + } + + if (parent > 0) + { + // Compare to ABA, the sign of ofi is reversed + ofi.toVector().noalias() -= jdata.UDinv() * jmodel.jointVelocitySelector(custom_data.u); + custom_data.of_augmented[parent] += ofi; + } + } + }; + + template + struct AugmentedMassMatrixOperatorSolveInPlaceForwardPass + : public fusion::JointUnaryVisitorBase< + AugmentedMassMatrixOperatorSolveInPlaceForwardPass> + { + typedef typename DelassusOperator::Model Model; + typedef typename DelassusOperator::Data Data; + typedef typename DelassusOperator::CustomData CustomData; + typedef std::pair JointPair; + + typedef boost::fusion::vector ArgsType; + + template + static void algo( + const pinocchio::JointModelBase & jmodel, + const pinocchio::JointDataBase & jdata, + const Model & model, + const Data & data, + CustomData & custom_data) + { + typedef typename Model::JointIndex JointIndex; + typedef typename Data::Matrix6 Matrix6; + + const auto J_cols = jmodel.jointCols(data.J); + + const JointIndex i = jmodel.id(); + const JointIndex parent = model.parents[i]; + const auto & joint_neighbours = data.neighbour_links[i]; + + auto & oai = custom_data.oa_augmented[i]; + oai = custom_data.oa_augmented[parent]; + + if (joint_neighbours.size()) + { + Force coupling_forces = Force::Zero(); + for (const JointIndex vertex_j : joint_neighbours) + { + const Matrix6 & crosscoupling_ij = + (i > vertex_j) ? data.joint_cross_coupling.get(JointPair(vertex_j, i)).transpose() + : data.joint_cross_coupling.get(JointPair(i, vertex_j)); + + coupling_forces.toVector().noalias() += + crosscoupling_ij * custom_data.oa_augmented[vertex_j].toVector(); + } + + jmodel.jointVelocitySelector(custom_data.u).noalias() -= + J_cols.transpose() * coupling_forces.toVector(); + } + + // Abuse of notation using custom_data.ddq for storing delta ddq + jmodel.jointVelocitySelector(custom_data.ddq).noalias() = + jdata.Dinv() * jmodel.jointVelocitySelector(custom_data.u) + - jdata.UDinv().transpose() * oai.toVector(); + oai.toVector().noalias() += J_cols * jmodel.jointVelocitySelector(custom_data.ddq); + } + }; + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_delassus_operator_linear_complexity_visitors_hxx__ diff --git a/include/pinocchio/algorithm/delassus-operator-rigid-body.hpp b/include/pinocchio/algorithm/delassus-operator-rigid-body.hpp index e69de29bb2..ce969152e1 100644 --- a/include/pinocchio/algorithm/delassus-operator-rigid-body.hpp +++ b/include/pinocchio/algorithm/delassus-operator-rigid-body.hpp @@ -0,0 +1,425 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#ifndef __pinocchio_algorithm_delassus_operator_linear_complexity_hpp__ +#define __pinocchio_algorithm_delassus_operator_linear_complexity_hpp__ + +#include "pinocchio/algorithm/fwd.hpp" +#include "pinocchio/algorithm/delassus-operator-base.hpp" +#include "pinocchio/utils/reference.hpp" + +#include "pinocchio/algorithm/constraints/constraint-collection-default.hpp" +#include "pinocchio/algorithm/constraints/constraint-model-generic.hpp" +#include "pinocchio/algorithm/constraints/constraint-data-generic.hpp" +#include "pinocchio/utils/template-template-parameter.hpp" + +namespace pinocchio +{ + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + template class Holder = std::reference_wrapper> + struct DelassusOperatorRigidBodySystemsTpl; + + template< + typename _Scalar, + int _Options, + template class JointCollectionTpl, + class _ConstraintModel, + template class Holder> + struct traits> + { + typedef _Scalar Scalar; + + enum + { + Options = _Options, + RowsAtCompileTime = Eigen::Dynamic + }; + + typedef Eigen::Matrix Vector; + typedef Eigen::Matrix DenseMatrix; + typedef DenseMatrix Matrix; + + typedef ModelTpl Model; + typedef typename Model::Data Data; + + typedef _ConstraintModel ConstraintModel; + typedef typename helper::remove_ref::type InnerConstraintModel; + + typedef typename helper::remove_ref::type::ConstraintData InnerConstraintData; + typedef typename std::conditional< + helper::is_type_holder::value, + typename internal::extract_template_template_parameter::template type< + InnerConstraintData>, + InnerConstraintData>::type ConstraintData; + + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConstraintModel) ConstraintModelVector; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConstraintData) ConstraintDataVector; + + typedef const Vector & getDampingReturnType; + }; + + template< + typename _Scalar, + int _Options, + template class _JointCollectionTpl, + class _ConstraintModel, + template class Holder> + struct DelassusOperatorRigidBodySystemsTpl + : DelassusOperatorBase> + { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + + typedef DelassusOperatorRigidBodySystemsTpl Self; + typedef DelassusOperatorBase Base; + + typedef typename traits::Scalar Scalar; + enum + { + Options = traits::Options + }; + + typedef typename traits::Vector Vector; + typedef typename traits::DenseMatrix DenseMatrix; + + typedef typename traits::Model Model; + typedef Holder ModelHolder; + typedef typename traits::Data Data; + typedef Holder DataHolder; + + typedef typename Data::Force Force; + typedef typename Data::VectorXs VectorXs; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(Force) ForceVector; + + typedef typename traits::ConstraintModel ConstraintModel; + typedef typename traits::InnerConstraintModel InnerConstraintModel; + typedef typename traits::ConstraintModelVector ConstraintModelVector; + typedef Holder ConstraintModelVectorHolder; + + typedef typename traits::ConstraintData ConstraintData; + typedef typename traits::InnerConstraintData InnerConstraintData; + typedef typename traits::ConstraintDataVector ConstraintDataVector; + typedef Holder ConstraintDataVectorHolder; + + DelassusOperatorRigidBodySystemsTpl( + const ModelHolder & model_ref, + const DataHolder & data_ref, + const ConstraintModelVectorHolder & constraint_models_ref, + const ConstraintDataVectorHolder & constraint_datas_ref, + const Scalar min_damping_value = Scalar(1e-8)) + : Base() + , m_size(evalConstraintSize(helper::get_ref(constraint_models_ref))) + , m_model_ref(model_ref) + , m_data_ref(data_ref) + , m_constraint_models_ref(constraint_models_ref) + , m_constraint_datas_ref(constraint_datas_ref) + , m_custom_data(helper::get_ref(model_ref)) + , m_dirty(true) + , m_damping(Vector::Zero(m_size)) + , m_compliance(Vector::Zero(m_size)) + , m_sum_compliance_damping(Vector::Zero(m_size)) + , m_sum_compliance_damping_inverse(Vector::Zero(m_size)) + { + assert(model().check(data()) && "data is not consistent with model."); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + constraint_models().size(), constraint_datas().size(), + "The sizes of contact vector models and contact vector datas are not the same."); + PINOCCHIO_CHECK_INPUT_ARGUMENT( + min_damping_value >= Scalar(0) && "The damping value should be positive."); + + updateDamping(min_damping_value); + update(constraint_models_ref, constraint_datas_ref); + } + + /// \brief Update the constraint model and data vectors. + /// + /// \param[in] constraint_models_ref Vector of constraint models + /// \param[in] constraint_datas_ref Vector of constraint datas + /// + void update( + const ConstraintModelVectorHolder & constraint_models_ref, + const ConstraintDataVectorHolder & constraint_datas_ref); + + /// + /// \brief Update the intermediate computations according to a new configuration vector entry + /// + /// \param[in] q Configuration vector + /// + template + void compute( + const Eigen::MatrixBase & q, + bool apply_on_the_right = true, + bool solve_in_place = true); + + DenseMatrix matrix(bool enforce_symmetry = false) const + { + DenseMatrix res(this->size(), this->size()); + + typedef Eigen::Map MapVectorXs; + MapVectorXs x = MapVectorXs(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, this->size(), 1)); + + for (Eigen::DenseIndex i = 0; i < this->size(); ++i) + { + x = VectorXs::Unit(this->size(), i); + this->applyOnTheRight(x, res.col(i)); + } + if (enforce_symmetry) + { + res = 0.5 * (res + res.transpose()); + } + return res; + } + + protected: + void compute_or_update_decomposition(bool apply_on_the_right, bool solve_in_place); + + /// + /// \brief Update the internal factorization because the damping or compliance vectors have been + /// modified + /// + void updateDecomposition() + { + compute_or_update_decomposition(false, true); + } + + public: + /// + /// \brief Update the intermediate computations before calling solveInPlace or operator* + /// + /// \param[in] apply_on_the_right If true, this will update the quantities related to the + /// applyOnTheRight method + /// \param[in] solve_in_place If true, this will update the quantities related to the + /// solveInPlace method + /// + /// \remarks By activating or deactivating apply_on_the_right and solve_in_place, this enables + /// to lower the quantities updated to the minimum, helping to save time overall. + void compute(bool apply_on_the_right = true, bool solve_in_place = true) + { + const ConstraintModelVector & constraint_models_ref = constraint_models(); + ConstraintDataVector & constraint_datas_ref = constraint_datas(); + + for (size_t ee_id = 0; ee_id < constraint_models_ref.size(); ++ee_id) + { + const auto & cmodel = helper::get_ref(constraint_models_ref[ee_id]); + auto & cdata = helper::get_ref(constraint_datas_ref[ee_id]); + cmodel.calc(model(), data(), cdata); + } + + compute_or_update_decomposition(apply_on_the_right, solve_in_place); + } + + public: + const Model & model() const + { + return helper::get_ref(m_model_ref); + } + + Data & data() + { + return helper::get_ref(m_data_ref); + } + const Data & data() const + { + return helper::get_ref(m_data_ref); + } + + const ConstraintModelVector & constraint_models() const + { + return helper::get_ref(m_constraint_models_ref); + } + + const ConstraintDataVector & constraint_datas() const + { + return helper::get_ref(m_constraint_datas_ref); + } + ConstraintDataVector & constraint_datas() + { + return helper::get_ref(m_constraint_datas_ref); + } + + Eigen::DenseIndex size() const + { + return m_size; + } + Eigen::DenseIndex rows() const + { + return m_size; + } + Eigen::DenseIndex cols() const + { + return m_size; + } + + bool isDirty() const + { + return m_dirty; + } + + template + void applyOnTheRight( + const Eigen::MatrixBase & x, const Eigen::MatrixBase & res) const; + + template + void updateDamping(const Eigen::MatrixBase & vec) + { + m_damping = vec; + updateSumComplianceDamping(); + } + + void updateDamping(const Scalar & mu) + { + updateDamping(Vector::Constant(size(), mu)); + } + + const Vector & getDamping() const + { + return m_damping; + } + + template + void updateCompliance(const Eigen::MatrixBase & compliance_vector) + { + m_compliance = compliance_vector; + updateSumComplianceDamping(); + } + + void updateCompliance(const Scalar & compliance_value) + { + updateCompliance(Vector::Constant(size(), compliance_value)); + } + + const Vector & getCompliance() const + { + return m_compliance; + } + + /// \brief solveInPlace operation returning the results of the inverse of the Delassus operator + /// times the input matrix mat + /// + /// \param[in,out] mat Input/output argument containing the right hand side and the result of + /// the operation + /// + /// \warning The parameter is only marked 'const' to make the C++ compiler accept a temporary + /// expression here. This function will const_cast it, so constness isn't honored here. + /// + /// \remarks Even if the method is marked 'const', it will update the internal decomposition if + /// the Delassus operator is dirty after an update of the damping or compliance values. + template + void solveInPlace(const Eigen::MatrixBase & mat) const; + + struct CustomData + { + typedef typename Data::Motion Motion; + typedef typename Data::Force Force; + + typedef typename PINOCCHIO_ALIGNED_STD_VECTOR(Motion) MotionVector; + typedef typename PINOCCHIO_ALIGNED_STD_VECTOR(Force) ForceVector; + + CustomData(const Model & model) + : a(size_t(model.njoints), Motion::Zero()) + , oa_augmented(size_t(model.njoints), Motion::Zero()) + , u(model.nv) + , ddq(model.nv) + , f(size_t(model.njoints)) + , of_augmented(size_t(model.njoints)) + { + } + + MotionVector a, oa_augmented; + VectorXs u, ddq; + ForceVector f, of_augmented; + }; + + const CustomData & getCustomData() const + { + return m_custom_data; + } + + CustomData & getCustomData() + { + return m_custom_data; + } + + struct AugmentedMassMatrixOperator + { + AugmentedMassMatrixOperator(const DelassusOperatorRigidBodySystemsTpl & delassus_operator) + : m_self(delassus_operator) + { + } + + template + void solveInPlace( + const Eigen::MatrixBase & mat, bool reset_joint_force_vector = true) const; + + protected: + const DelassusOperatorRigidBodySystemsTpl & m_self; + }; + + AugmentedMassMatrixOperator getAugmentedMassMatrixOperator() const + { + return AugmentedMassMatrixOperator(*this); + } + + protected: + static Eigen::DenseIndex evalConstraintSize(const ConstraintModelVector & constraint_models) + { + Eigen::DenseIndex size = 0; + for (const ConstraintModel & cm : constraint_models) + { + const auto & cmodel = helper::get_ref(cm); + size += cmodel.size(); + } + + return size; + } + + inline void compute_conclude() + { + m_dirty = false; + } + + void updateSumComplianceDamping() + { + m_sum_compliance_damping = m_damping + m_compliance; + m_sum_compliance_damping_inverse = m_sum_compliance_damping.cwiseInverse(); + m_dirty = true; + } + + DelassusOperatorRigidBodySystemsTpl & self_const_cast() const + { + return const_cast(*this); + } + + // Holders + Eigen::DenseIndex m_size; + ModelHolder m_model_ref; + DataHolder m_data_ref; + ConstraintModelVectorHolder m_constraint_models_ref; + ConstraintDataVectorHolder m_constraint_datas_ref; + + mutable CustomData m_custom_data; + bool m_dirty; + Vector m_damping, m_compliance; + Vector m_sum_compliance_damping, m_sum_compliance_damping_inverse; + }; + +} // namespace pinocchio + +#include "pinocchio/algorithm/delassus-operator-rigid-body.hxx" + +#endif // ifndef __pinocchio_algorithm_delassus_operator_linear_complexity_hpp__ diff --git a/include/pinocchio/algorithm/delassus-operator-rigid-body.hxx b/include/pinocchio/algorithm/delassus-operator-rigid-body.hxx new file mode 100644 index 0000000000..379bbf0106 --- /dev/null +++ b/include/pinocchio/algorithm/delassus-operator-rigid-body.hxx @@ -0,0 +1,441 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#ifndef __pinocchio_algorithm_delassus_operator_linear_complexity_hxx__ +#define __pinocchio_algorithm_delassus_operator_linear_complexity_hxx__ + +#include "pinocchio/algorithm/check.hpp" +#include "pinocchio/algorithm/constraints/constraints.hpp" + +#include "pinocchio/algorithm/loop-constrained-aba.hpp" +#include "pinocchio/algorithm/aba.hpp" +#include "pinocchio/algorithm/contact-jacobian.hpp" + +#include "pinocchio/algorithm/delassus-operator-rigid-body-visitors.hxx" + +namespace pinocchio +{ + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + template class Holder> + void DelassusOperatorRigidBodySystemsTpl< + Scalar, + Options, + JointCollectionTpl, + ConstraintModel, + Holder>:: + update( + const ConstraintModelVectorHolder & constraint_models_ref, + const ConstraintDataVectorHolder & constraint_datas_ref) + { + m_constraint_models_ref = constraint_models_ref; + m_constraint_datas_ref = constraint_datas_ref; + + computeJointMinimalOrdering(model(), data(), helper::get_ref(constraint_models_ref)); + m_dirty = true; + } + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + template class Holder> + template + void DelassusOperatorRigidBodySystemsTpl< + Scalar, + Options, + JointCollectionTpl, + ConstraintModel, + Holder>:: + compute( + const Eigen::MatrixBase & q, bool apply_on_the_right, bool solve_in_place) + { + PINOCCHIO_CHECK_ARGUMENT_SIZE( + q.size(), model().nq, "The joint configuration vector is not of right size"); + + const Model & model_ref = model(); + Data & data_ref = data(); + + // Zero-th order forward kinematics + typedef DelassusOperatorRigidBodySystemsComputeForwardPass< + DelassusOperatorRigidBodySystemsTpl, ConfigVectorType> + Pass1; + for (JointIndex i = 1; i < (JointIndex)model_ref.njoints; ++i) + { + typename Pass1::ArgsType args(model_ref, data_ref, q.derived()); + Pass1::run(model_ref.joints[i], data_ref.joints[i], args); + } + + compute(apply_on_the_right, solve_in_place); + } + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + template class Holder> + void DelassusOperatorRigidBodySystemsTpl< + Scalar, + Options, + JointCollectionTpl, + ConstraintModel, + Holder>::compute_or_update_decomposition(bool apply_on_the_right, bool solve_in_place) + { + typedef typename Data::Inertia Inertia; + using Matrix6 = typename Inertia::Matrix6; + + const Model & model_ref = model(); + Data & data_ref = data(); + const ConstraintModelVector & constraint_models_ref = constraint_models(); + ConstraintDataVector & constraint_datas_ref = constraint_datas(); + + // computeJointMinimalOrdering(model_ref, data_ref, constraint_models_ref); + + for (JointIndex i = 1; i < JointIndex(model_ref.njoints); ++i) + { + const auto & joint_inertia = model_ref.inertias[i]; + if (apply_on_the_right) + data_ref.Yaba[i] = joint_inertia.matrix(); + if (solve_in_place) + { + const Inertia oinertia = data_ref.oMi[i].act(joint_inertia); + data_ref.oYaba_augmented[i] = oinertia.matrix(); + } + } + + if (solve_in_place) + { + data_ref.joint_apparent_inertia = model_ref.armature; + data_ref.joint_cross_coupling.apply([](Matrix6 & v) { v.setZero(); }); + + // Append constraint inertia to oYaba_augmented + Eigen::Index row_id = 0; + for (size_t ee_id = 0; ee_id < constraint_models_ref.size(); ++ee_id) + { + const auto & cmodel = helper::get_ref(constraint_models_ref[ee_id]); + auto & cdata = helper::get_ref(constraint_datas_ref[ee_id]); + + const auto constraint_size = cmodel.size(); + + const auto constraint_diagonal_inertia = + this->m_sum_compliance_damping_inverse.segment(row_id, constraint_size); + + cmodel.appendCouplingConstraintInertias( + model_ref, data_ref, cdata, constraint_diagonal_inertia, WorldFrameTag()); + + row_id += constraint_size; + } + } + +#define DO_PASS(apply_on_the_right_v, solve_in_place_v) \ + { \ + typedef DelassusOperatorRigidBodySystemsComputeBackwardPass< \ + DelassusOperatorRigidBodySystemsTpl, apply_on_the_right_v, solve_in_place_v> \ + Pass2; \ + for (const JointIndex i : data_ref.elimination_order) \ + { \ + typename Pass2::ArgsType args(model_ref, data_ref); \ + Pass2::run(model_ref.joints[i], data_ref.joints[i], args); \ + } \ + } + + if (apply_on_the_right) + { + if (solve_in_place) + { + DO_PASS(true, true); + } + else + { + DO_PASS(true, false); + } + } + else + { + if (solve_in_place) + { + DO_PASS(false, true); + } + else + { + DO_PASS(false, false); + } + } +#undef DO_PASS + + compute_conclude(); + } + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + template class Holder> + template + void DelassusOperatorRigidBodySystemsTpl< + Scalar, + Options, + JointCollectionTpl, + ConstraintModel, + Holder>:: + applyOnTheRight( + const Eigen::MatrixBase & rhs, const Eigen::MatrixBase & res_) const + { + MatrixOut & res = res_.const_cast_derived(); + PINOCCHIO_CHECK_SAME_MATRIX_SIZE(rhs, res); + + const Model & model_ref = model(); + const Data & data_ref = data(); + const ConstraintModelVector & constraint_models_ref = constraint_models(); + const ConstraintDataVector & constraint_datas_ref = constraint_datas(); + auto & custom_data = this->m_custom_data; + auto & u = custom_data.u; + + // Make a pass over the whole set of constraints to add the contributions of constraint forces + // u and custom_data.f are reset by mapConstraintForcesToJointSpace + mapConstraintForcesToJointSpace( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, rhs, m_custom_data.f, u, + LocalFrameTag()); + // TODO(jcarpent): extend the code to operator on matrices + + // typedef Eigen::Map MapVectorXs; + // MapVectorXs u = MapVectorXs(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, model_ref.nv, 1)); + // { + // auto & u = custom_data.u; + // u.setZero(); + // Eigen::Index row_id = 0; + // for (size_t ee_id = 0; ee_id < constraint_models_ref.size(); ++ee_id) + // { + // const auto & cmodel = + // helper::get_ref(constraint_models_ref[ee_id]); + // const auto & cdata = + // helper::get_ref(constraint_datas_ref[ee_id]); + // const auto csize = cmodel.size(); + // const auto rhs_rows = rhs.middleRows(row_id, csize); + // + // cmodel.jacobianTransposeMatrixProduct(model_ref, data_ref, cdata, rhs_rows, u, + // AddTo()); + // + // row_id += csize; + // } + // } + + // Backward sweep: propagate joint force contributions + { + // for (auto & f : m_custom_data.f) + // f.setZero(); + // auto & u = custom_data.u; + // u.setZero(); + + typedef DelassusOperatorRigidBodySystemsTplApplyOnTheRightBackwardPass< + DelassusOperatorRigidBodySystemsTpl> + Pass1; + typename Pass1::ArgsType args1(model_ref, data_ref, custom_data); + for (JointIndex i = JointIndex(model_ref.njoints - 1); i > 0; --i) + { + Pass1::run(model_ref.joints[i], data_ref.joints[i], args1); + } + } + + // Forward sweep: compute joint accelerations + { + typedef DelassusOperatorRigidBodySystemsTplApplyOnTheRightForwardPass< + DelassusOperatorRigidBodySystemsTpl> + Pass2; + for (auto & motion : custom_data.a) + motion.setZero(); + typename Pass2::ArgsType args2(model_ref, data_ref, custom_data); + for (JointIndex i = 1; i < JointIndex(model_ref.njoints); ++i) + { + Pass2::run(model_ref.joints[i], data_ref.joints[i], args2); + } + } + + // Make a pass over the whole set of constraints to project back the accelerations onto the + // joint + mapJointSpaceToConstraintMotions( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, custom_data.a, + custom_data.ddq, res, LocalFrameTag()); + + // TODO(jcarpent): extend the code to operator on matrices + // { + // const auto & ddq = custom_data.ddq; + // Eigen::Index row_id = 0; + // for (size_t ee_id = 0; ee_id < constraint_models_ref.size(); ++ee_id) + // { + // const auto & cmodel = + // helper::get_ref(constraint_models_ref[ee_id]); + // const auto & cdata = + // helper::get_ref(constraint_datas_ref[ee_id]); + // const auto csize = cmodel.size(); + // + // cmodel.jacobianMatrixProduct( + // model_ref, data_ref, cdata, ddq, res.middleRows(row_id, csize)); + // + // row_id += csize; + // } + // } + + // Add damping contribution + res.array() += m_sum_compliance_damping.array() * rhs.array(); + } + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + template class Holder> + template + void DelassusOperatorRigidBodySystemsTpl< + Scalar, + Options, + JointCollectionTpl, + ConstraintModel, + Holder>::solveInPlace(const Eigen::MatrixBase & mat_) const + { + MatrixLike & mat = mat_.const_cast_derived(); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + mat.rows(), size(), "The input matrix does not match the size of the Delassus."); + + // PINOCCHIO_THROW_IF( + // m_dirty, std::logic_error, + // "The DelassusOperator has dirty quantities. Please call compute() method first."); + if (isDirty()) + self_const_cast().updateDecomposition(); + + const Model & model_ref = model(); + const Data & data_ref = data(); + const ConstraintModelVector & constraint_models_ref = constraint_models(); + const ConstraintDataVector & constraint_datas_ref = constraint_datas(); + auto & custom_data = this->m_custom_data; + + mat.array() *= m_sum_compliance_damping_inverse.array(); + + // Make a pass over the whole set of constraints to add the contributions of constraint + + typedef Eigen::Map MapVectorXs; + MapVectorXs u = MapVectorXs(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, model_ref.nv, 1)); + // u and custom_data.of_augmented are reset by mapConstraintForcesToJointSpace + mapConstraintForcesToJointSpace( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, mat, + custom_data.of_augmented, u, WorldFrameTag()); + + // { + // u.setZero(); + // Eigen::Index row_id = 0; + // for (size_t ee_id = 0; ee_id < constraint_models_ref.size(); ++ee_id) + // { + // const auto & cmodel = + // helper::get_ref(constraint_models_ref[ee_id]); + // const auto & cdata = + // helper::get_ref(constraint_datas_ref[ee_id]); + // const auto csize = cmodel.size(); + // const auto mat_rows = mat.middleRows(row_id, csize); + // + // cmodel.jacobianTransposeMatrixProduct(model_ref, data_ref, cdata, mat_rows, u, + // AddTo()); + // + // row_id += csize; + // } + // } + + const auto & augmented_mass_matrix_operator = this->getAugmentedMassMatrixOperator(); + augmented_mass_matrix_operator.solveInPlace(u, false); + + typedef Eigen::Map MapVectorXs; + MapVectorXs tmp_vec = MapVectorXs(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, size(), 1)); + // { + // Eigen::Index row_id = 0; + // for (size_t ee_id = 0; ee_id < constraint_models_ref.size(); ++ee_id) + // { + // const auto & cmodel = + // helper::get_ref(constraint_models_ref[ee_id]); + // const auto & cdata = + // helper::get_ref(constraint_datas_ref[ee_id]); + // const auto csize = cmodel.size(); + // + // cmodel.jacobianMatrixProduct( + // model_ref, data_ref, cdata, u, tmp_vec.middleRows(row_id, csize)); + // + // row_id += csize; + // } + // } + + // Make a pass over the whole set of constraints to project back the joint accelerations onto + // the constraints + mapJointSpaceToConstraintMotions( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, custom_data.oa_augmented, u, + tmp_vec, WorldFrameTag()); + + mat.noalias() -= m_sum_compliance_damping_inverse.asDiagonal() * tmp_vec; + } + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + class ConstraintModel, + template class Holder> + template + void DelassusOperatorRigidBodySystemsTpl< + Scalar, + Options, + JointCollectionTpl, + ConstraintModel, + Holder>::AugmentedMassMatrixOperator:: + solveInPlace(const Eigen::MatrixBase & mat_, bool reset_joint_force_vector) const + { + MatrixLike & mat = mat_.const_cast_derived(); + const auto & model_ref = m_self.model(); + const auto & data_ref = m_self.data(); + auto & custom_data = const_cast(m_self).getCustomData(); + const auto & elimination_order = data_ref.elimination_order; + + if (reset_joint_force_vector) + { + for (auto & of_augmented : custom_data.of_augmented) + of_augmented.setZero(); + } + + // Backward sweep: propagate joint force contributions + { + custom_data.u = mat; + typedef AugmentedMassMatrixOperatorSolveInPlaceBackwardPass< + DelassusOperatorRigidBodySystemsTpl> + Pass1; + typename Pass1::ArgsType args1(model_ref, data_ref, custom_data); + for (const JointIndex i : elimination_order) + { + Pass1::run(model_ref.joints[i], data_ref.joints_augmented[i], args1); + } + } + + // Forward sweep: compute joint accelerations + { + typedef AugmentedMassMatrixOperatorSolveInPlaceForwardPass< + DelassusOperatorRigidBodySystemsTpl> + Pass2; + custom_data.oa_augmented[0].setZero(); + typename Pass2::ArgsType args2(model_ref, data_ref, custom_data); + for (int it = int(elimination_order.size()) - 1; it >= 0; it--) + { + const JointIndex i = elimination_order[size_t(it)]; + Pass2::run(model_ref.joints[i], data_ref.joints_augmented[i], args2); + } + } + + mat = custom_data.ddq; + } + +} // namespace pinocchio + +#endif // ifndef __pinocchio_algorithm_delassus_operator_linear_complexity_hxx__ diff --git a/include/pinocchio/algorithm/delassus-operator-sparse.hpp b/include/pinocchio/algorithm/delassus-operator-sparse.hpp index f626181a55..58a5986def 100644 --- a/include/pinocchio/algorithm/delassus-operator-sparse.hpp +++ b/include/pinocchio/algorithm/delassus-operator-sparse.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2024 INRIA +// Copyright (c) 2024-2025 INRIA // #ifndef __pinocchio_algorithm_delassus_operator_sparse_hpp__ @@ -120,13 +120,17 @@ namespace pinocchio }; typedef Eigen::Matrix Vector; - typedef Eigen::Matrix DenseMatrix; + typedef Eigen::Matrix Matrix; + + typedef const Vector & getDampingReturnType; }; template struct DelassusOperatorSparseTpl : DelassusOperatorBase> { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW + typedef DelassusOperatorSparseTpl Self; typedef typename traits::Scalar Scalar; enum @@ -137,22 +141,42 @@ namespace pinocchio typedef typename traits::SparseMatrix SparseMatrix; typedef typename traits::Vector Vector; - typedef typename traits::DenseMatrix DenseMatrix; + typedef typename traits::Matrix Matrix; typedef SparseCholeskyDecomposition CholeskyDecomposition; typedef DelassusOperatorBase Base; template explicit DelassusOperatorSparseTpl(const Eigen::SparseMatrixBase & mat) - : Base(mat.rows()) + : Base() , delassus_matrix(mat) , delassus_matrix_plus_damping(mat) , llt(mat) , damping(Vector::Zero(mat.rows())) + , compliance(Vector::Zero(mat.rows())) , tmp(mat.rows()) { PINOCCHIO_CHECK_ARGUMENT_SIZE(mat.rows(), mat.cols()); } + template + void updateCompliance(const Eigen::MatrixBase & vec) + { + for (Eigen::DenseIndex k = 0; k < size(); ++k) + { + delassus_matrix_plus_damping.coeffRef(k, k) += -compliance[k] + vec[k]; + } + compliance = vec; + PINOCCHIO_EIGEN_MALLOC_SAVE_STATUS(); + PINOCCHIO_EIGEN_MALLOC_ALLOWED(); + llt.factorize(delassus_matrix_plus_damping); + PINOCCHIO_EIGEN_MALLOC_RESTORE_STATUS(); + } + + void updateCompliance(const Scalar & compliance) + { + updateCompliance(Vector::Constant(size(), compliance)); + } + template void updateDamping(const Eigen::MatrixBase & vec) { @@ -201,23 +225,13 @@ namespace pinocchio void applyOnTheRight( const Eigen::MatrixBase & x, const Eigen::MatrixBase & res_) const { + PINOCCHIO_CHECK_ARGUMENT_SIZE(x.rows(), size()); MatrixOut & res = res_.const_cast_derived(); res.noalias() = delassus_matrix * x; + res.array() += compliance.array() * x.array(); res.array() += damping.array() * x.array(); } - template - typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixDerived) - operator*(const Eigen::MatrixBase & x) const - { - typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixDerived) ReturnType; - - PINOCCHIO_CHECK_ARGUMENT_SIZE(x.rows(), size()); - ReturnType res(x.rows(), x.cols()); - applyOnTheRight(x, res); - return res; - } - Eigen::DenseIndex size() const { return delassus_matrix.rows(); @@ -231,13 +245,30 @@ namespace pinocchio return delassus_matrix.cols(); } - SparseMatrix matrix() const + SparseMatrix matrix(bool enforce_symmetry = false) const { delassus_matrix_plus_damping = delassus_matrix; + delassus_matrix_plus_damping += compliance.asDiagonal(); delassus_matrix_plus_damping += damping.asDiagonal(); + if (enforce_symmetry) + { + // TODO: enforce symmetry for sparse matrices + PINOCCHIO_THROW( + std::invalid_argument, "enforceSymmetry not implemented for sparse matrices"); + } return delassus_matrix_plus_damping; } + const Vector & getCompliance() const + { + return compliance; + } + + const Vector & getDamping() const + { + return damping; + } + SparseMatrix inverse() const { SparseMatrix identity_matrix(size(), size()); @@ -251,6 +282,7 @@ namespace pinocchio mutable SparseMatrix delassus_matrix_plus_damping; CholeskyDecomposition llt; Vector damping; + Vector compliance; mutable Vector tmp; }; // struct DelassusOperatorSparseTpl diff --git a/include/pinocchio/algorithm/delassus-operator.hpp b/include/pinocchio/algorithm/delassus-operator.hpp new file mode 100644 index 0000000000..9c070e4cff --- /dev/null +++ b/include/pinocchio/algorithm/delassus-operator.hpp @@ -0,0 +1,12 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_algorithm_delassus_operator_hpp__ +#define __pinocchio_algorithm_delassus_operator_hpp__ + +#include "pinocchio/algorithm/delassus-operator-dense.hpp" +#include "pinocchio/algorithm/delassus-operator-sparse.hpp" +#include "pinocchio/algorithm/delassus-operator-rigid-body.hpp" + +#endif // ifndef __pinocchio_algorithm_delassus_operator_hpp__ diff --git a/include/pinocchio/algorithm/delassus.hxx b/include/pinocchio/algorithm/delassus.hxx index a42354b698..1aab9586a6 100644 --- a/include/pinocchio/algorithm/delassus.hxx +++ b/include/pinocchio/algorithm/delassus.hxx @@ -89,7 +89,7 @@ namespace pinocchio // Account for the rotor inertia contribution jdata.StU().diagonal() += jmodel.jointVelocitySelector(model.armature); - internal::PerformStYSInversion::run(jdata.StU(), jdata.Dinv()); + matrix_inversion(jdata.StU(), jdata.Dinv()); jdata.UDinv().noalias() = Jcols @@ -135,9 +135,9 @@ namespace pinocchio contact_models.size(), contact_data.size(), "contact models and data size are not the same"); MatrixType & delassus = delassus_.const_cast_derived(); - const size_t constraint_total_size = getTotalConstraintSize(contact_models); - PINOCCHIO_CHECK_ARGUMENT_SIZE(delassus_.rows(), (Eigen::DenseIndex)constraint_total_size); - PINOCCHIO_CHECK_ARGUMENT_SIZE(delassus_.cols(), (Eigen::DenseIndex)constraint_total_size); + const Eigen::DenseIndex constraint_total_size = getTotalConstraintSize(contact_models); + PINOCCHIO_CHECK_ARGUMENT_SIZE(delassus_.rows(), constraint_total_size); + PINOCCHIO_CHECK_ARGUMENT_SIZE(delassus_.cols(), constraint_total_size); typedef ModelTpl Model; typedef DataTpl Data; @@ -449,7 +449,7 @@ namespace pinocchio // Account for the rotor inertia contribution jdata.StU().diagonal() += jmodel.jointVelocitySelector(model.armature); - internal::PerformStYSInversion::run(jdata.StU(), jdata.Dinv()); + matrix_inversion(jdata.StU(), jdata.Dinv()); jdata.UDinv().noalias() = Jcols * jdata.Dinv().transpose(); data.oL[i].setIdentity(); @@ -490,9 +490,9 @@ namespace pinocchio contact_models.size(), contact_data.size(), "contact models and data size are not the same"); MatrixType & delassus = delassus_.const_cast_derived(); - const size_t constraint_total_size = getTotalConstraintSize(contact_models); - PINOCCHIO_CHECK_ARGUMENT_SIZE(delassus_.rows(), (Eigen::DenseIndex)constraint_total_size); - PINOCCHIO_CHECK_ARGUMENT_SIZE(delassus_.cols(), (Eigen::DenseIndex)constraint_total_size); + const Eigen::DenseIndex constraint_total_size = getTotalConstraintSize(contact_models); + PINOCCHIO_CHECK_ARGUMENT_SIZE(delassus_.rows(), constraint_total_size); + PINOCCHIO_CHECK_ARGUMENT_SIZE(delassus_.cols(), constraint_total_size); typedef DataTpl Data; diff --git a/include/pinocchio/algorithm/diagonal-preconditioner.hpp b/include/pinocchio/algorithm/diagonal-preconditioner.hpp new file mode 100644 index 0000000000..17ad3a1c3f --- /dev/null +++ b/include/pinocchio/algorithm/diagonal-preconditioner.hpp @@ -0,0 +1,170 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_algorithm_diagonal_preconditioner_hpp__ +#define __pinocchio_algorithm_diagonal_preconditioner_hpp__ + +#include "pinocchio/algorithm/preconditioner-base.hpp" + +namespace pinocchio +{ + + /// + /// \brief Pre-Conditioning a constraint problem is done purely for numerical reasons. + /// We have a problem that looks like $$ min_{x \in K} x^T G x + g^T x $$. + /// The pre-conditioner is a diagonal matrix P. + /// We write x = P * x_bar (hence x_bar = P^{-1} * x), g_bar = Pg and G_bar = P*G*P, such that + /// the problem now becomes: + /// $$ min_{x_bar \in K} x_bar^T G_bar x + g_bar^T x $$. + // + /// \note We call the original problem working on (x, g, G) the **unscaled** problem. + /// We call the new problem working on (x_bar, g_bar, G_bar) the **scaled** problem. + /// + template + struct DiagonalPreconditionerTpl : PreconditionerBase> + { + + /// \brief Default constructor takes a vector. + /// @param diagonal Vector composing the diagonal of the preconditioner + template + explicit DiagonalPreconditionerTpl(const Eigen::MatrixBase & diagonal) + : m_diagonal(diagonal) + , m_squared_diagonal(diagonal) + { + typedef typename VectorLike::Scalar Scalar; + PINOCCHIO_CHECK_INPUT_ARGUMENT((diagonal.array() >= Scalar(0)).all()); + m_squared_diagonal.array() *= diagonal.array(); + } + + /// @brief Default constructor from a given size. + /// @param size Size of the preconditioner + explicit DiagonalPreconditionerTpl(const Eigen::Index size) + : m_diagonal(VectorLike::Ones(size)) + , m_squared_diagonal(VectorLike::Ones(size)) + { + } + + /// \brief Construct an identity preconditioner + /// @param size Size of the preconditioner + static DiagonalPreconditionerTpl Identity(const Eigen::Index size) + { + return DiagonalPreconditionerTpl(size); + } + + /// \brief Move constructor + DiagonalPreconditionerTpl(DiagonalPreconditionerTpl && other) + : m_diagonal(std::move(other.m_diagonal)) + , m_squared_diagonal(std::move(other.m_squared_diagonal)) + { + } + + /// \brief Copy constructor + DiagonalPreconditionerTpl(const DiagonalPreconditionerTpl & other) + : m_diagonal(other.m_diagonal) + , m_squared_diagonal(other.m_squared_diagonal) + { + } + + /// \brief Copy operator + DiagonalPreconditionerTpl & operator=(const DiagonalPreconditionerTpl & other) + { + m_diagonal = other.m_diagonal; + m_squared_diagonal = other.m_squared_diagonal; + return *this; + } + + bool operator==(const DiagonalPreconditionerTpl & other) const + { + return m_diagonal == other.m_diagonal && m_squared_diagonal == other.m_squared_diagonal; + } + + bool operator!=(const DiagonalPreconditionerTpl & other) const + { + return !(*this == other); + } + + /// \brief Performs the scale operation to go from x to x_bar: x_bar = P^{-1} * x. + template + void + scale(const Eigen::MatrixBase & x, const Eigen::MatrixBase & x_bar) const + { + auto & x_bar_ = x_bar.const_cast_derived(); + x_bar_ = x; + scaleInPlace(x_bar_); + } + + /// \brief see \ref scale + template + void scaleInPlace(const Eigen::MatrixBase & x) const + { + auto & x_ = x.const_cast_derived(); + x_.array() = x.array() / m_diagonal.array(); + } + + /// \brief Performs the unscale operation to go from x_bar to x: x = P * x_bar. + template + void + unscale(const Eigen::MatrixBase & x_bar, const Eigen::MatrixBase & x) const + { + auto & x_ = x.const_cast_derived(); + x_ = x_bar; + unscaleInPlace(x_); + } + + /// \brief see \ref \unscale + template + void unscaleInPlace(const Eigen::MatrixBase & x) const + { + auto & x_ = x.const_cast_derived(); + x_.array() *= m_diagonal.array(); + } + + /// \brief Performs the scale operation twice: x_bar = P^{-2} * x. + template + void scaleSquare( + const Eigen::MatrixBase & x, const Eigen::MatrixBase & x_bar) const + { + auto & x_bar_ = x_bar.const_cast_derived(); + x_bar_.array() = x.array() / m_squared_diagonal.array(); + } + + /// \brief Performs the unscale operation twice: x = P * x_bar. + template + void unscaleSquare( + const Eigen::MatrixBase & x_bar, const Eigen::MatrixBase & x) const + { + auto & x_ = x.const_cast_derived(); + x_.array() = x_bar.array() * m_squared_diagonal.array(); + } + + Eigen::DenseIndex rows() const + { + return m_diagonal.size(); + } + Eigen::DenseIndex cols() const + { + return m_diagonal.size(); + } + + template + void setDiagonal(const Eigen::MatrixBase & x) + { + m_diagonal = x; + m_squared_diagonal.array() = x.array().square(); + } + + const VectorLike & getDiagonal() const + { + return m_diagonal; + } + + protected: + VectorLike m_diagonal; + VectorLike m_squared_diagonal; + + }; // struct DiagonalPreconditionerTpl + +} // namespace pinocchio + +#endif // #ifndef __pinocchio_algorithm_diagonal_preconditioner_hpp__ diff --git a/include/pinocchio/algorithm/joint-configuration.hpp b/include/pinocchio/algorithm/joint-configuration.hpp index 6124295c59..b240c40834 100644 --- a/include/pinocchio/algorithm/joint-configuration.hpp +++ b/include/pinocchio/algorithm/joint-configuration.hpp @@ -498,6 +498,247 @@ namespace pinocchio model, q.derived(), v.derived(), PINOCCHIO_EIGEN_CONST_CAST(JacobianMatrixType, J), arg, op); } + /** + * + * @brief Computes the tangentMap that map a small variation of the configuration express in the + * Lie algebra (a vector of size nv) to a small variation of the configuration in the parametric + * space (a vector of size nq). + * + * @details This map can be interpreted as a vector space Jacobian of the integrate function + * regarding the variable v in 0. Chained with a Lie group Jacobian in q it allows to recover a + * vector space Jacobian in the parametric space. + * + * @param[in] model Model of the kinematic tree on which the integration operation is + * performed. + * @param[in] q Initial configuration (size model.nq) + * @param[out] TM Tangent map in q mapping the Lie algebra with the parametric tangent + * space. + * + */ + template< + typename LieGroup_t, + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename TangentMapMatrixType> + void tangentMap( + const ModelTpl & model, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & TM, + const AssignmentOperatorType op = SETTO); + + /** + * + * @brief Computes the tangentMap that map a small variation of the configuration express in the + * Lie algebra (a vector of size nv) to a small variation of the configuration in the parametric + * space (a vector of size nq). + * + * @details This map can be interpreted as a vector space Jacobian of the integrate function + * regarding the variable v in 0. Chained with a Lie group Jacobian in q it allows to recover a + * vector space Jacobian in the parametric space. + * + * @param[in] model Model of the kinematic tree on which the integration operation is + * performed. + * @param[in] q Initial configuration (size model.nq) + * @param[out] TM Tangent map in q mapping the Lie algebra with the parametric tangent + * space. + * + */ + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename TangentMapMatrixType> + void tangentMap( + const ModelTpl & model, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & TM, + const AssignmentOperatorType op = SETTO) + { + tangentMap< + LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorType, TangentMapMatrixType>( + model, q.derived(), PINOCCHIO_EIGEN_CONST_CAST(TangentMapMatrixType, TM), op); + } + + /** + * + * @brief Set the tangentMap in a compact manner in matric of size nq x MAX_JOINT_NV. + * + * @param[in] model Model of the kinematic tree on which the integration operation is + * performed. + * @param[in] joint_selection Joint to condider to compute the tangentMap + * @param[in] q Initial configuration (size model.nq) + * @param[out] TMc Compact storage of the tangent map + * space. + * + */ + template< + typename LieGroup_t, + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename TangentMapMatrixType> + void compactTangentMap( + const ModelTpl & model, + const std::vector::JointIndex> & + joint_selection, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & TMc); + + /** + * + * @brief Set the tangentMap in a compact manner in matric of size nq x MAX_JOINT_NV. + * + * @param[in] model Model of the kinematic tree on which the integration operation is + * performed. + * @param[in] q Initial configuration (size model.nq) + * @param[out] TMc Compact storage of the tangent map + * space. + * + */ + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename TangentMapMatrixType> + void compactTangentMap( + const ModelTpl & model, + const std::vector::JointIndex> & + joint_selection, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & TMc) + { + compactTangentMap< + LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorType, TangentMapMatrixType>( + model, joint_selection, q.derived(), PINOCCHIO_EIGEN_CONST_CAST(TangentMapMatrixType, TMc)); + } + + /** + * + * @brief Compose the tangentMap with a matrix, e.g., a Lie group Jacobian in order to recover a + * vector space Jacobian or chain Lie Group derivatives with vector space derivative in a forward + * manner. + * + * @param[in] model Model of the kinematic tree on which the integration operation is + * performed. + * @param[in] q Initial configuration (size model.nq) + * @param[in] mat_in A matrix with range in the Lie algebra (size model.nv, n_cols) + * @param[out] mat_out A matrix with range in the parametric space (size model.nq, n_cols) + * + */ + template< + typename LieGroup_t, + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename MatrixInType, + typename MatrixOutType> + void tangentMapProduct( + const ModelTpl & model, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & mat_in, + const Eigen::MatrixBase & mat_out, + const AssignmentOperatorType op = SETTO); + + /** + * + * @brief Compose the tangentMap with a matrix, e.g., a Lie group Jacobian in order to recover a + * vector space Jacobian or chain Lie Group derivatives with vector space derivative in a forward + * manner. + * + * @param[in] model Model of the kinematic tree on which the integration operation is + * performed. + * @param[in] q Initial configuration (size model.nq) + * @param[in] mat_in A matrix with range in the Lie algebra (size model.nv, n_cols) + * @param[out] mat_out A matrix with range in the parametric space (size model.nq, n_cols) + * + */ + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename MatrixInType, + typename MatrixOutType> + void tangentMapProduct( + const ModelTpl & model, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & mat_in, + const Eigen::MatrixBase & mat_out, + const AssignmentOperatorType op = SETTO) + { + tangentMapProduct< + LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorType, MatrixInType, + MatrixOutType>( + model, q.derived(), mat_in.derived(), PINOCCHIO_EIGEN_CONST_CAST(MatrixOutType, mat_out), op); + } + + /** + * + * @brief Compose the tangentMap with a matrix, e.g., a Lie group Jacobian in order to recover a + * vector space Jacobian or chain Lie Group derivatives with vector space derivative in reverse + * mode. + * + * @param[in] model Model of the kinematic tree on which the integration operation is + * performed. + * @param[in] q Initial configuration (size model.nq) + * @param[in] mat_in A matrix with range in the parametric space (size model.nq, n_cols) + * @param[out] mat_out A matrix with range in the Lie algebra (size model.nv, n_cols) + * + */ + template< + typename LieGroup_t, + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename MatrixInType, + typename MatrixOutType> + void tangentMapTransposeProduct( + const ModelTpl & model, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & mat_in, + const Eigen::MatrixBase & mat_out, + const AssignmentOperatorType op = SETTO); + + /** + * + * @brief Compose the tangentMap with a matrix, e.g., a Lie group Jacobian in order to recover a + * vector space Jacobian or chain Lie Group derivatives with vector space derivative in reverse + * mode. + * + * @param[in] model Model of the kinematic tree on which the integration operation is + * performed. + * @param[in] q Initial configuration (size model.nq) + * @param[in] mat_in A matrix with range in the parametric space (size model.nq, n_cols) + * @param[out] mat_out A matrix with range in the Lie algebra (size model.nv, n_cols) + * + */ + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename MatrixInType, + typename MatrixOutType> + void tangentMapTransposeProduct( + const ModelTpl & model, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & mat_in, + const Eigen::MatrixBase & mat_out, + const AssignmentOperatorType op = SETTO) + { + tangentMapTransposeProduct< + LieGroupMap, Scalar, Options, JointCollectionTpl, ConfigVectorType, MatrixInType, + MatrixOutType>( + model, q.derived(), mat_in.derived(), PINOCCHIO_EIGEN_CONST_CAST(MatrixOutType, mat_out), op); + } + /** * * @brief Transport a matrix from the terminal to the initial tangent space of the integrate @@ -1053,6 +1294,63 @@ namespace pinocchio model, q.derived(), PINOCCHIO_EIGEN_CONST_CAST(JacobianMatrix, jacobian)); } + /** + * + * @brief Returns the Lie group associated to the model. It is the cartesian product of + * the lie groups of all its joints. + * + * @param[in] model Model of the kinematic tree. + * @param[out] lgo The cartesian Lie group object. + * + */ + template< + typename LieGroup_t, + typename Scalar, + int Options, + template class JointCollectionTpl> + void lieGroup( + const ModelTpl & model, + typename LieGroup_t::template operationProduct::type & lgo); + + /** + * + * @brief Returns the Lie group associated to the model. It is the cartesian product of + * the lie groups of all its joints. + * + * @param[in] model Model of the kinematic tree. + * @param[out] lgo The cartesian Lie group object. + * + */ + template class JointCollectionTpl> + void lieGroup( + const ModelTpl & model, + typename LieGroupMap::template operationProduct::type & lgo) + { + lieGroup(model, lgo); + } + + /** + * + * @brief Return two vector of size nq where for each, the idx_v and v associated to the + * same atomic joint is given. + * + * @param[in] model Model of the kinematic tree. + * @param[in] joint_selection Joint to condider to compute the tangentMap + * @param[out] nvs For each id give the nv of the associated joint + * @param[out] idx_vs For each id give the idx_v of the associated joint + * + * @details This function is often required for the numerical solvers that are working on + * the tangent of the configuration space, instead of the configuration space itself. + * + */ + template class JointCollectionTpl> + void indexvInfo( + const ModelTpl & model, + const std::vector::JointIndex> & + joint_selection, + std::vector & nvs, + std::vector & idx_vs); + /// \} /// \name API that allocates memory @@ -1428,6 +1726,39 @@ namespace pinocchio return neutral(model); } + /** + * + * @brief Returns the Lie group associated to the model. It is the cartesian product of + * the lie groups of all its joints. + * + * @param[in] model Model of the kinematic tree. + * @param[out] lgo The cartesian Lie group object. + * + */ + template< + typename LieGroup_t, + typename Scalar, + int Options, + template class JointCollectionTpl> + typename LieGroup_t::template operationProduct::type + lieGroup(const ModelTpl & model); + + /** + * + * @brief Returns the Lie group associated to the model. It is the cartesian product of + * the lie groups of all its joints. + * + * @param[in] model Model of the kinematic tree. + * @param[out] lgo The cartesian Lie group object. + * + */ + template class JointCollectionTpl> + typename LieGroupMap::template operationProduct::type + lieGroup(const ModelTpl & model) + { + return lieGroup(model); + } + /// \} } // namespace pinocchio diff --git a/include/pinocchio/algorithm/joint-configuration.hxx b/include/pinocchio/algorithm/joint-configuration.hxx index d55ca1e6fd..c836ed0261 100644 --- a/include/pinocchio/algorithm/joint-configuration.hxx +++ b/include/pinocchio/algorithm/joint-configuration.hxx @@ -7,6 +7,7 @@ #include "pinocchio/multibody/visitor.hpp" #include "pinocchio/multibody/liegroup/liegroup-algo.hpp" +#include "pinocchio/multibody/liegroup/liegroup-joint.hpp" /* --- Details -------------------------------------------------------------------- */ namespace pinocchio @@ -243,6 +244,143 @@ namespace pinocchio } } + template< + typename LieGroup_t, + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename TangentMapMatrixType> + void tangentMap( + const ModelTpl & model, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & TM, + const AssignmentOperatorType op) + { + PINOCCHIO_CHECK_ARGUMENT_SIZE( + q.size(), model.nq, "The configuration vector is not of the right size"); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + TM.rows(), model.nq, "The output argument is not of the right size"); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + TM.cols(), model.nv, "The output argument is not of the right size"); + + typedef ModelTpl Model; + typedef typename Model::JointIndex JointIndex; + + typedef TangentMapStep Algo; + typename Algo::ArgsType args( + q.derived(), PINOCCHIO_EIGEN_CONST_CAST(TangentMapMatrixType, TM), op); + for (JointIndex i = 1; i < (JointIndex)model.njoints; ++i) + { + Algo::run(model.joints[i], args); + } + } + + template< + typename LieGroup_t, + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename TangentMapMatrixType> + void compactTangentMap( + const ModelTpl & model, + const std::vector::JointIndex> & + joint_selection, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & TMc) + { + PINOCCHIO_CHECK_ARGUMENT_SIZE( + q.size(), model.nq, "The configuration vector is not of the right size"); + // Assume TMc.rows() == SUM_(j in joint_selection) j.nq() --> assert at the end + // Assume TMc.cols() >= max_nv --> assert in the Visitor + + typedef CompactSetTangentMapStep Algo; + + int idx = 0; + typename Algo::ArgsType args( + q.derived(), PINOCCHIO_EIGEN_CONST_CAST(TangentMapMatrixType, TMc), idx); + for (size_t i = 0; i < joint_selection.size(); ++i) + { + Algo::run(model.joints[joint_selection[i]], args); + } + assert(idx == TMc.rows()); + } + + template< + typename LieGroup_t, + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename MatrixInType, + typename MatrixOutType> + void tangentMapProduct( + const ModelTpl & model, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & mat_in, + const Eigen::MatrixBase & mat_out, + const AssignmentOperatorType op) + { + PINOCCHIO_CHECK_ARGUMENT_SIZE( + q.size(), model.nq, "The configuration vector is not of the right size"); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + mat_in.rows(), model.nv, "The input matrix is not of the right size"); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + mat_out.rows(), model.nq, "The output matrix is not of the right size"); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + mat_in.cols(), mat_out.cols(), "The input/output matrix sized do not match"); + + typedef ModelTpl Model; + typedef typename Model::JointIndex JointIndex; + + typedef TangentMapProductStep Algo; + typename Algo::ArgsType args( + q.derived(), mat_in.derived(), PINOCCHIO_EIGEN_CONST_CAST(MatrixOutType, mat_out), op); + for (JointIndex i = 1; i < (JointIndex)model.njoints; ++i) + { + Algo::run(model.joints[i], args); + } + } + + template< + typename LieGroup_t, + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename MatrixInType, + typename MatrixOutType> + void tangentMapTransposeProduct( + const ModelTpl & model, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & mat_in, + const Eigen::MatrixBase & mat_out, + const AssignmentOperatorType op) + { + PINOCCHIO_CHECK_ARGUMENT_SIZE( + q.size(), model.nq, "The configuration vector is not of the right size"); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + mat_in.rows(), model.nq, "The input matrix is not of the right size"); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + mat_out.rows(), model.nv, "The output matrix is not of the right size"); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + mat_in.cols(), mat_out.cols(), "The input/output matrix sized do not match"); + + typedef ModelTpl Model; + typedef typename Model::JointIndex JointIndex; + + typedef TangentMapTransposeProductStep< + LieGroup_t, ConfigVectorType, MatrixInType, MatrixOutType> + Algo; + typename Algo::ArgsType args( + q.derived(), mat_in.derived(), PINOCCHIO_EIGEN_CONST_CAST(MatrixOutType, mat_out), op); + for (JointIndex i = 1; i < (JointIndex)model.njoints; ++i) + { + Algo::run(model.joints[i], args); + } + } + template< typename LieGroup_t, typename Scalar, @@ -525,6 +663,46 @@ namespace pinocchio } } + template< + typename LieGroup_t, + typename Scalar, + int Options, + template class JointCollectionTpl> + void lieGroup( + const ModelTpl & model, + typename LieGroup_t::template operationProduct::type & lgo) + { + + typedef ModelTpl Model; + typedef LieGroupInstanceStep Algo; + typedef typename Model::JointIndex JointIndex; + + typename Algo::ArgsType args(lgo); + for (JointIndex i = 1; i < (JointIndex)model.njoints; ++i) + { + Algo::run(model.joints[i], args); + } + } + + template class JointCollectionTpl> + void indexvInfo( + const ModelTpl & model, + const std::vector::JointIndex> & + joint_selection, + std::vector & nvs, + std::vector & idx_vs) + { + PINOCCHIO_CHECK_ARGUMENT_SIZE(nvs.size(), 0, "The nvs vector must be empty"); + PINOCCHIO_CHECK_ARGUMENT_SIZE(idx_vs.size(), 0, "The idx_vs vector must empty"); + + typename IndexvInfoStep::ArgsType args(nvs, idx_vs); + + for (size_t i = 0; i < joint_selection.size(); ++i) + { + IndexvInfoStep::run(model.joints[joint_selection[i]], args); + } + } + // ----------------- API that allocates memory ---------------------------- // template< @@ -661,6 +839,20 @@ namespace pinocchio return q; } + template< + typename LieGroup_t, + typename Scalar, + int Options, + template class JointCollectionTpl> + typename LieGroup_t::template operationProduct::type + lieGroup(const ModelTpl & model) + { + typedef typename LieGroup_t::template operationProduct::type LGO; + LGO lgo; + lieGroup(model, lgo); + return lgo; + } + } // namespace pinocchio #endif // ifndef __pinocchio_algorithm_joint_configuration_hxx__ diff --git a/include/pinocchio/algorithm/joint-configuration.txx b/include/pinocchio/algorithm/joint-configuration.txx index e43b6d7e08..e6ce19957a 100644 --- a/include/pinocchio/algorithm/joint-configuration.txx +++ b/include/pinocchio/algorithm/joint-configuration.txx @@ -188,6 +188,87 @@ namespace pinocchio const ArgumentPosition, const AssignmentOperatorType); + extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void tangentMap< + LieGroupMap, + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + context::VectorXs, + context::MatrixXs>( + const context::Model &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const AssignmentOperatorType); + + extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void tangentMap< + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + context::VectorXs, + context::MatrixXs>( + const context::Model &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const AssignmentOperatorType); + + // compactTangentMap is not explicitelly instantiated as it is only use in JointLimit + + extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void tangentMapProduct< + LieGroupMap, + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + context::VectorXs, + context::MatrixXs, + context::MatrixXs>( + const context::Model &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const AssignmentOperatorType); + + extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void tangentMapProduct< + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + context::VectorXs, + context::MatrixXs, + context::MatrixXs>( + const context::Model &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const AssignmentOperatorType); + + extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void + tangentMapTransposeProduct< + LieGroupMap, + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + context::VectorXs, + context::MatrixXs, + context::MatrixXs>( + const context::Model &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const AssignmentOperatorType); + + extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void + tangentMapTransposeProduct< + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + context::VectorXs, + context::MatrixXs, + context::MatrixXs>( + const context::Model &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const AssignmentOperatorType); + extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void dIntegrateTransport< LieGroupMap, context::Scalar, @@ -315,6 +396,18 @@ namespace pinocchio normalize( const context::Model &, const Eigen::MatrixBase &); + extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void + lieGroup( + const context::Model &, + typename LieGroupMap::template operationProduct::type &); + + extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void + lieGroup( + const context::Model &, + typename LieGroupMap::template operationProduct::type &); + + // indexvInfo is not explicitelly instantiated as it is only use in JointLimit + #ifndef PINOCCHIO_SKIP_CASADI_UNSUPPORTED extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI bool isNormalized< @@ -502,5 +595,15 @@ namespace pinocchio extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI context::VectorXs neutral(const context::Model &); + + extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI + typename LieGroupMap::template operationProduct::type + lieGroup( + const context::Model &); + + extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI + typename LieGroupMap::template operationProduct::type + lieGroup(const context::Model &); + } // namespace pinocchio #endif // ifndef __pinocchio_algorithm_joint_configuration_txx__ diff --git a/include/pinocchio/algorithm/kinematics-derivatives.hpp b/include/pinocchio/algorithm/kinematics-derivatives.hpp index 76f86f15aa..a5d09021ab 100644 --- a/include/pinocchio/algorithm/kinematics-derivatives.hpp +++ b/include/pinocchio/algorithm/kinematics-derivatives.hpp @@ -1,5 +1,6 @@ // -// Copyright (c) 2017-2020 CNRS INRIA +// Copyright (c) 2017-2020 CNRS +// Copyright (c) 2018-2024 INRIA // #ifndef __pinocchio_algorithm_kinematics_derivatives_hpp__ @@ -13,6 +14,37 @@ namespace pinocchio { + /// + /// \brief Computes all the terms required to compute the derivatives of the placement, spatial + /// velocity + /// for any joint of the model. + /// + /// \tparam JointCollection Collection of Joint types. + /// \tparam ConfigVectorType Type of the joint configuration vector. + /// \tparam TangentVectorType Type of the joint velocity vector. + /// + /// \param[in] model The model structure of the rigid body system. + /// \param[in] data The data structure of the rigid body system. + /// \param[in] q The joint configuration (vector dim model.nq). + /// \param[in] v The joint velocity (vector dim model.nv). + /// + /// \remarks This function is similar to do a forwardKinematics(model,data,q,v) followed by a + /// computeJointJacobians(model,data,q). + /// In addition, it computes the spatial velocity of the joint expressed in the world + /// frame (see data.ov). + /// + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename TangentVectorType> + void computeForwardKinematicsDerivatives( + const ModelTpl & model, + DataTpl & data, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & v); + /// /// \brief Computes all the terms required to compute the derivatives of the placement, spatial /// velocity and acceleration @@ -27,6 +59,7 @@ namespace pinocchio /// \param[in] data The data structure of the rigid body system. /// \param[in] q The joint configuration (vector dim model.nq). /// \param[in] v The joint velocity (vector dim model.nv). + /// \param[in] a The joint acceleration (vector dim model.nv). /// /// \remarks This function is similar to do a forwardKinematics(model,data,q,v) followed by a /// computeJointJacobians(model,data,q). diff --git a/include/pinocchio/algorithm/kinematics-derivatives.hxx b/include/pinocchio/algorithm/kinematics-derivatives.hxx index 98d7604ab4..15c6eeec7c 100644 --- a/include/pinocchio/algorithm/kinematics-derivatives.hxx +++ b/include/pinocchio/algorithm/kinematics-derivatives.hxx @@ -1,5 +1,6 @@ // -// Copyright (c) 2017-2020 CNRS INRIA +// Copyright (c) 2017-2020 CNRS +// Copyright (c) 2018-2024 INRIA // #ifndef __pinocchio_algorithm_kinematics_derivatives_hxx__ @@ -14,6 +15,104 @@ namespace pinocchio { namespace impl { + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename TangentVectorType> + struct ForwardKinematicsDerivativesForwardStepOrder1 + : public fusion::JointUnaryVisitorBase> + { + typedef ModelTpl Model; + typedef DataTpl Data; + + typedef boost::fusion:: + vector + ArgsType; + + template + static void algo( + const JointModelBase & jmodel, + JointDataBase & jdata, + const Model & model, + Data & data, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & v) + { + typedef typename Model::JointIndex JointIndex; + typedef typename Data::SE3 SE3; + typedef typename Data::Motion Motion; + + const JointIndex i = jmodel.id(); + const JointIndex parent = model.parents[i]; + SE3 & oMi = data.oMi[i]; + Motion & vi = data.v[i]; + Motion & ov = data.ov[i]; + + jmodel.calc(jdata.derived(), q.derived(), v.derived()); + + data.liMi[i] = model.jointPlacements[i] * jdata.M(); + + if (parent > 0) + oMi = data.oMi[parent] * data.liMi[i]; + else + oMi = data.liMi[i]; + + vi = jdata.v(); + if (parent > 0) + vi += data.liMi[i].actInv(data.v[parent]); + + typedef + typename SizeDepType::template ColsReturn::Type + ColsBlock; + ColsBlock dJcols = jmodel.jointCols(data.dJ); + ColsBlock Jcols = jmodel.jointCols(data.J); + + Jcols = oMi.act(jdata.S()); + ov = oMi.act(vi); // Spatial velocity of joint i expressed in the global frame o + motionSet::motionAction(ov, Jcols, dJcols); + } + }; + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename TangentVectorType> + void computeForwardKinematicsDerivatives( + const ModelTpl & model, + DataTpl & data, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & v) + { + PINOCCHIO_CHECK_ARGUMENT_SIZE( + q.size(), model.nq, "The configuration vector is not of right size"); + PINOCCHIO_CHECK_ARGUMENT_SIZE(v.size(), model.nv, "The velocity vector is not of right size"); + assert(model.check(data) && "data is not consistent with model."); + + typedef ModelTpl Model; + typedef typename Model::JointIndex JointIndex; + + data.v[0].setZero(); + + typedef ForwardKinematicsDerivativesForwardStepOrder1< + Scalar, Options, JointCollectionTpl, ConfigVectorType, TangentVectorType> + Pass; + typename Pass::ArgsType args(model, data, q.derived(), v.derived()); + for (JointIndex i = 1; i < (JointIndex)model.njoints; ++i) + { + Pass::run(model.joints[i], data.joints[i], args); + } + } + template< typename Scalar, int Options, @@ -629,10 +728,8 @@ namespace pinocchio if (rf == LOCAL_WORLD_ALIGNED) { FOR_NV() - v_partial_dq_cols.col(j) = oMlast.rotation() - * (v_partial_dq_cols.col(j) - + GET_ANGULAR(v_spatial_partial_dv_cols.col(j)) - .cross(spatial_point_velocity.linear())); + v_partial_dq_cols.col(j) = oMlast.rotation() * (v_partial_dq_cols.col(j) + + GET_ANGULAR(v_spatial_partial_dv_cols.col(j)).cross(spatial_point_velocity.linear())); FOR_NV() v_partial_dv_cols.col(j) = oMlast.rotation() * v_partial_dv_cols.col(j); } @@ -849,10 +946,8 @@ namespace pinocchio { FOR_NV() - v_partial_dq_cols.col(j) = oMlast.rotation() - * (v_partial_dq_cols.col(j) - + GET_ANGULAR(a_spatial_partial_da_cols.col(j)) - .cross(spatial_point_velocity.linear())); + v_partial_dq_cols.col(j) = oMlast.rotation() * (v_partial_dq_cols.col(j) + + GET_ANGULAR(a_spatial_partial_da_cols.col(j)).cross(spatial_point_velocity.linear())); FOR_NV() a_partial_dq_cols.col(j) = oMlast.rotation() @@ -1278,6 +1373,22 @@ namespace pinocchio } } + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename TangentVectorType> + void computeForwardKinematicsDerivatives( + const ModelTpl & model, + DataTpl & data, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & v) + { + impl::computeForwardKinematicsDerivatives( + model, data, make_const_ref(q.derived()), make_const_ref(v.derived())); + } + template< typename Scalar, int Options, diff --git a/include/pinocchio/algorithm/kinematics-derivatives.txx b/include/pinocchio/algorithm/kinematics-derivatives.txx index c72147dbae..62cf543946 100644 --- a/include/pinocchio/algorithm/kinematics-derivatives.txx +++ b/include/pinocchio/algorithm/kinematics-derivatives.txx @@ -1,5 +1,5 @@ // -// Copyright (c) 2022 INRIA +// Copyright (c) 2022-2024 INRIA // #ifndef __pinocchio_algorithm_kinematics_derivatives_txx__ @@ -10,6 +10,18 @@ namespace pinocchio namespace impl { + extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void + computeForwardKinematicsDerivatives< + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + Eigen::Ref, + Eigen::Ref>( + const context::Model &, + context::Data &, + const Eigen::MatrixBase> &, + const Eigen::MatrixBase> &); + extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void computeForwardKinematicsDerivatives< context::Scalar, diff --git a/include/pinocchio/algorithm/loop-constrained-aba.hpp b/include/pinocchio/algorithm/loop-constrained-aba.hpp new file mode 100644 index 0000000000..37b19e9339 --- /dev/null +++ b/include/pinocchio/algorithm/loop-constrained-aba.hpp @@ -0,0 +1,72 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#ifndef __pinocchio_algorithm_loop_constrained_aba_hpp__ +#define __pinocchio_algorithm_loop_constrained_aba_hpp__ + +#include "pinocchio/multibody/model.hpp" +#include "pinocchio/multibody/data.hpp" + +#include "pinocchio/algorithm/check.hpp" +#include "pinocchio/algorithm/constraints/constraints.hpp" +#include "pinocchio/algorithm/constraints/constraint-ordering.hpp" + +namespace pinocchio +{ + + /// + /// \brief The closed-loop constrained Articulated Body Algorithm (CLconstrainedABA). It computes + /// constrained forward dynamics, aka the joint accelerations and constraint forces given the + /// current state, actuation and the constraints on the system for mechanisms potentially with + /// internal closed kinematic loops. + /// + /// \tparam JointCollection Collection of Joint types. + /// \tparam ConfigVectorType Type of the joint configuration vector. + /// \tparam TangentVectorType1 Type of the joint velocity vector. + /// \tparam TangentVectorType2 Type of the joint torque vector. + /// \tparam ConstraintModelAllocator Allocator class for the std::vector. + /// \tparam ConstraintDataAllocator Allocator class for the std::vector. + /// + /// \param[in] model The model structure of the rigid body system. + /// \param[in] data The data structure of the rigid body system. + /// \param[in] q The joint configuration vector (dim model.nq). + /// \param[in] v The joint velocity vector (dim model.nv). + /// \param[in] tau The joint torque vector (dim model.nv). + /// \param[in] constraint_models Vector of contact models. + /// \param[in] constraint_datas Vector of contact data. + /// \param[in] settings Proximal settings (mu, accuracy and maximal number of iterations). + /// + /// \note A hint: a typical value of mu in proximal settings is 1e-6, and should always be + /// positive. This also overwrites data.f, possibly leaving it in an inconsistent state. + /// + /// \return A reference to the joint acceleration stored in data.ddq. data.lambdaA[0] stores the + /// constraint forces. + /// + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename TangentVectorType1, + typename TangentVectorType2, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator> + inline const typename DataTpl::TangentVectorType & lcaba( + const ModelTpl & model, + DataTpl & data, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & v, + const Eigen::MatrixBase & tau, + const std::vector & constraint_models, + std::vector & constraint_datas, + ProximalSettingsTpl & settings); + +} // namespace pinocchio + +/* --- Details -------------------------------------------------------------------- */ +#include "pinocchio/algorithm/loop-constrained-aba.hxx" + +#endif // ifndef __pinocchio_algorithm_loop_constrained_aba_hpp__ diff --git a/include/pinocchio/algorithm/loop-constrained-aba.hxx b/include/pinocchio/algorithm/loop-constrained-aba.hxx new file mode 100644 index 0000000000..cea2c90e65 --- /dev/null +++ b/include/pinocchio/algorithm/loop-constrained-aba.hxx @@ -0,0 +1,762 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#ifndef __pinocchio_algorithm_loop_constrained_aba_hxx__ +#define __pinocchio_algorithm_loop_constrained_aba_hxx__ + +/// @cond DEV + +namespace pinocchio +{ + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename TangentVectorType> + struct LCABAForwardStep1 + : public fusion::JointUnaryVisitorBase< + LCABAForwardStep1> + { + typedef ModelTpl Model; + typedef DataTpl Data; + + typedef boost::fusion:: + vector + ArgsType; + + template + static void algo( + const pinocchio::JointModelBase & jmodel, + pinocchio::JointDataBase & jdata, + const Model & model, + Data & data, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & v) + { + typedef typename Model::JointIndex JointIndex; + typedef typename Data::Motion Motion; + + const JointIndex i = jmodel.id(); + Motion & ov = data.ov[i]; + jmodel.calc(jdata.derived(), q.derived(), v.derived()); + + const JointIndex parent = model.parents[i]; + data.liMi[i] = model.jointPlacements[i] * jdata.M(); + if (parent > 0) + data.oMi[i] = data.oMi[parent] * data.liMi[i]; + else + data.oMi[i] = data.liMi[i]; + + jmodel.jointCols(data.J) = data.oMi[i].act(jdata.S()); + + ov = data.oMi[i].act(jdata.v()); + if (parent > 0) + ov += data.ov[parent]; + + data.oa_gf[i] = data.oMi[i].act(jdata.c()); + if (parent > 0) + data.oa_gf[i] += (data.ov[parent] ^ ov); + + data.oinertias[i] = data.oYcrb[i] = data.oMi[i].act(model.inertias[i]); + data.oYaba_augmented[i] = data.oYcrb[i].matrix(); + + data.oh[i] = data.oYcrb[i] * ov; // necessary for ABA derivatives + data.of[i] = ov.cross(data.oh[i]); + } + }; + + template class JointCollectionTpl> + struct LCABABackwardStep + : public fusion::JointUnaryVisitorBase> + { + typedef ModelTpl Model; + typedef DataTpl Data; + + typedef boost::fusion::vector ArgsType; + + template + static void algo( + const JointModelBase & jmodel, + JointDataBase & jdata, + const Model & model, + Data & data) + { + typedef typename JointModel::JointDataDerived JointData; + typedef typename Model::JointIndex JointIndex; + typedef typename Data::Force Force; + typedef typename Data::Vector6 Vector6; + typedef typename Data::Matrix6 Matrix6; + + typedef std::pair JointPair; + + const JointIndex i = jmodel.id(); + const JointIndex parent = model.parents[i]; + auto & Ia = data.oYaba_augmented[i]; + + const auto Jcols = jmodel.jointCols(data.J); + + Force & fi = data.of[i]; + + jmodel.jointVelocitySelector(data.u).noalias() -= Jcols.transpose() * fi.toVector(); + + jdata.U().noalias() = Ia * Jcols; + jdata.StU().noalias() = Jcols.transpose() * jdata.U(); + + // Account for the rotor inertia contribution + jdata.StU().diagonal() += jmodel.jointVelocitySelector(model.armature); + + ::pinocchio::matrix_inversion(jdata.StU(), jdata.Dinv()); + + jdata.UDinv().noalias() = + jdata.U() * jdata.Dinv(); // TODO:check where its used when parent == 0 + if (parent > 0) + { + Ia.noalias() -= jdata.UDinv() * jdata.U().transpose(); + data.oYaba_augmented[parent] += Ia; + + fi.toVector().noalias() += + Ia * data.oa_gf[i].toVector() + jdata.UDinv() * jmodel.jointVelocitySelector(data.u); + data.of[parent] += fi; + } + + // End of the classic ABA backward pass - beginning of cross-coupling handling + const auto & neighbours = data.neighbour_links; + auto & joint_cross_coupling = data.joint_cross_coupling; + const auto & joint_neighbours = neighbours[i]; + + if (joint_neighbours.size() == 0) + return; // We can return from this point as this joint has no neighbours + + using Matrix6xNV = typename std::remove_reference::type; + typedef Eigen::Map MapMatrix6xNV; + MapMatrix6xNV mat1_tmp = MapMatrix6xNV(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, 6, jmodel.nv())); + MapMatrix6xNV mat2_tmp = MapMatrix6xNV(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, 6, jmodel.nv())); + + auto & JDinv = mat1_tmp; + JDinv.noalias() = Jcols * jdata.Dinv(); + + // oL == data.oL[i] + Matrix6 oL = -JDinv * jdata.U().transpose(); + oL += Matrix6::Identity(); + + // a_tmp is a Spatial Acceleration + Vector6 a_tmp = oL * data.oa_gf[i].toVector(); + a_tmp.noalias() += JDinv * jmodel.jointVelocitySelector(data.u); + + for (size_t j = 0; j < joint_neighbours.size(); j++) + { + const JointIndex vertex_j = joint_neighbours[j]; + const Matrix6 & crosscoupling_ij = + (i > vertex_j) + ? joint_cross_coupling.get(JointPair(vertex_j, i)) + : joint_cross_coupling.get(JointPair(i, vertex_j)).transpose(); // avoid memalloc + + auto & crosscoupling_ix_Jcols = mat1_tmp; + crosscoupling_ix_Jcols.noalias() = + crosscoupling_ij * Jcols; // Warning: UDinv() is actually edge_ij * J + + auto & crosscoupling_ij_Jcols_Dinv = mat2_tmp; + crosscoupling_ij_Jcols_Dinv.noalias() = crosscoupling_ix_Jcols * jdata.Dinv(); + + data.oYaba_augmented[vertex_j].noalias() -= + crosscoupling_ij_Jcols_Dinv + * crosscoupling_ix_Jcols.transpose(); // Warning: UDinv() is actually edge_ij * J, U() is + // actually edge_ij * J_cols * Dinv + data.of[vertex_j].toVector().noalias() += crosscoupling_ij * a_tmp; + + const Matrix6 crosscoupling_ij_oL = crosscoupling_ij * oL; + if (vertex_j == parent) + { + data.oYaba_augmented[parent].noalias() += + crosscoupling_ij_oL + crosscoupling_ij_oL.transpose(); + } + else + { + if (vertex_j < parent) + { + joint_cross_coupling.get({vertex_j, parent}).noalias() += crosscoupling_ij_oL; + } + else + { + joint_cross_coupling.get({parent, vertex_j}).noalias() += + crosscoupling_ij_oL.transpose(); + } + } + + for (size_t k = j + 1; k < joint_neighbours.size(); ++k) + { + const JointIndex vertex_k = joint_neighbours[k]; + + const Matrix6 & edge_ik = + (i > vertex_k) ? joint_cross_coupling.get(JointPair(vertex_k, i)) + : joint_cross_coupling.get(JointPair(i, vertex_k)).transpose(); + + crosscoupling_ix_Jcols.noalias() = edge_ik * Jcols; + + assert(vertex_j != vertex_k && "Must never happen!"); + if (vertex_j < vertex_k) + { + joint_cross_coupling.get({vertex_j, vertex_k}).noalias() -= + crosscoupling_ij_Jcols_Dinv + * crosscoupling_ix_Jcols.transpose(); // Warning: UDinv() is actually edge_ik * J_col, + // U() is edge_ij * J_col * Dinv + } + else // if (vertex_k < vertex_j) + { + joint_cross_coupling.get({vertex_k, vertex_j}).transpose().noalias() -= + crosscoupling_ij_Jcols_Dinv + * crosscoupling_ix_Jcols.transpose(); // Warning: UDinv() is actually edge_ik * + // J_col, U() is edge_ij * J_col * Dinv + } + } + } + } + }; + + // A reduced backward sweep that only propagates the affine terms + template class JointCollectionTpl> + struct LCABAReducedBackwardStep + : public fusion::JointUnaryVisitorBase< + LCABAReducedBackwardStep> + { + typedef ModelTpl Model; + typedef DataTpl Data; + + typedef boost::fusion::vector ArgsType; + + template + static void algo( + const JointModelBase & jmodel, + JointDataBase & jdata, + const Model & model, + Data & data) + { + + typedef typename Model::JointIndex JointIndex; + typedef typename Data::Force Force; + typedef typename Data::Motion Motion; + typedef typename Motion::Vector6 Vector6; + typedef typename Data::Matrix6 Matrix6; + typedef std::pair JointPair; + + const auto & neighbours = data.neighbour_links; + auto & joint_cross_coupling = data.joint_cross_coupling; + + const JointIndex i = jmodel.id(); + const JointIndex parent = model.parents[i]; + + const auto Jcols = jmodel.jointCols(data.J); + + Force & fi = data.of[i]; + + jmodel.jointVelocitySelector(data.u).noalias() = -Jcols.transpose() * fi.toVector(); + + jmodel.jointVelocitySelector(data.g).noalias() = + jdata.Dinv() + * jmodel.jointVelocitySelector( + data.u); // Abuse of notation to reuse existing unused data variable + + const Vector6 a_tmp = Jcols * jmodel.jointVelocitySelector(data.g); + + for (JointIndex vertex_j : neighbours[i]) + { + const Matrix6 & edge_ij = (i > vertex_j) + ? joint_cross_coupling.get(JointPair(vertex_j, i)) + : joint_cross_coupling.get(JointPair(i, vertex_j)).transpose(); + data.of[vertex_j].toVector().noalias() += edge_ij * a_tmp; + } + + if (parent > 0) + { + data.of[parent].toVector().noalias() += + fi.toVector() + jdata.U() * jmodel.jointVelocitySelector(data.g); + } + } + }; + + template class JointCollectionTpl> + struct LCABAForwardStep2 + : public fusion::JointUnaryVisitorBase> + { + typedef ModelTpl Model; + typedef DataTpl Data; + + typedef std::pair JointPair; + typedef typename Data::Matrix6 Matrix6; + + typedef boost::fusion::vector ArgsType; + + template + static void algo( + const pinocchio::JointModelBase & jmodel, + pinocchio::JointDataBase & jdata, + const Model & model, + Data & data) + { + typedef typename Model::JointIndex JointIndex; + typedef typename Data::Matrix6x Matrix6x; + + typedef typename SizeDepType::template ColsReturn::Type ColBlock; + ColBlock J_cols = jmodel.jointCols(data.J); + + const JointIndex i = jmodel.id(); + const JointIndex parent = model.parents[i]; + const std::vector & neighbours = data.neighbour_links[i]; + + data.oa_gf[i] += data.oa_gf[parent]; // does take into account the gravity field + + Force coupling_forces = Force::Zero(); + for (JointIndex vertex_j : neighbours) + { + const Matrix6 & edge_ij = + (i > vertex_j) ? data.joint_cross_coupling.get(JointPair(vertex_j, i)).transpose() + : data.joint_cross_coupling.get(JointPair(i, vertex_j)); + coupling_forces.toVector().noalias() += edge_ij * data.oa_gf[vertex_j].toVector(); + } + + jmodel.jointVelocitySelector(data.u).noalias() -= + J_cols.transpose() * coupling_forces.toVector(); + + jmodel.jointVelocitySelector(data.ddq).noalias() = + jdata.Dinv() * jmodel.jointVelocitySelector(data.u) + - jdata.UDinv().transpose() * data.oa_gf[i].toVector(); + data.oa_gf[i].toVector().noalias() += J_cols * jmodel.jointVelocitySelector(data.ddq); + + // Handle consistent output + data.oa[i] = data.oa_gf[i]; // + model.gravity; + // data.of[i] = data.oinertias[i] * data.oa_gf[i] + data.ov[i].cross(data.oh[i]); + } + }; + + template class JointCollectionTpl> + struct LCABAReducedForwardStep + : public fusion::JointUnaryVisitorBase< + LCABAReducedForwardStep> + { + typedef ModelTpl Model; + typedef DataTpl Data; + + typedef std::pair JointPair; + typedef typename Data::Matrix6 Matrix6; + + typedef boost::fusion::vector ArgsType; + + template + static void algo( + const pinocchio::JointModelBase & jmodel, + pinocchio::JointDataBase & jdata, + const Model & model, + Data & data) + { + typedef typename Model::JointIndex JointIndex; + typedef typename Data::Matrix6x Matrix6x; + typedef typename Data::Matrix6 Matrix6; + + typedef typename SizeDepType::template ColsReturn::Type ColBlock; + ColBlock J_cols = jmodel.jointCols(data.J); + + const JointIndex i = jmodel.id(); + const JointIndex parent = model.parents[i]; + const auto & neighbours = data.neighbour_links[i]; + + data.oa_gf[i] = data.oa_gf[parent]; // does take into account the gravity field + + Force & fi = data.of[i]; + for (JointIndex vertex_j : neighbours) + { + + const Matrix6 & edge_ij = + (i > vertex_j) ? data.joint_cross_coupling.get(JointPair(vertex_j, i)).transpose() + : data.joint_cross_coupling.get(JointPair(i, vertex_j)); + fi.toVector().noalias() += edge_ij * data.oa_gf[vertex_j].toVector(); + } + + jmodel.jointVelocitySelector(data.u).noalias() = -J_cols.transpose() * fi.toVector(); + + // Abuse of notation using data.g for storing delta ddq + jmodel.jointVelocitySelector(data.g).noalias() = + jdata.Dinv() + * (jmodel.jointVelocitySelector(data.u) - jdata.U().transpose() * data.oa_gf[i].toVector()); + data.oa_gf[i].toVector().noalias() += J_cols * jmodel.jointVelocitySelector(data.g); + + data.oa[i] += data.oa_gf[i]; + } + }; + + namespace internal + { + template + struct LCABAConstraintCalcStep + { + typedef typename ConstraintModel::ConstraintData ConstraintData; + typedef typename ConstraintModel::Scalar Scalar; + + template + static void run( + const Model & model, + Data & data, + const ConstraintModel & cmodel, + ConstraintData & cdata, + const Scalar mu); + }; + + template + struct LCABAConstraintCalcStep> + { + typedef RigidConstraintModelTpl ConstraintModel; + typedef typename ConstraintModel::ConstraintData ConstraintData; + + template + static void run( + const Model & model, + Data & data, + const ConstraintModel & cmodel, + ConstraintData & cdata, + const Scalar mu) + { + typedef typename Data::SE3 SE3; + typedef typename Model::JointIndex JointIndex; + typedef std::pair JointPair; + typedef typename Data::Matrix6 Matrix6; + typedef typename ConstraintModel::Matrix36 Matrix36; + + cdata.contact_force.setZero(); + + cmodel.calc(model, data, cdata); + + SE3 & oMc1 = cdata.oMc1; + SE3 & oMc2 = cdata.oMc2; + SE3 & c1Mc2 = cdata.c1Mc2; + typename ConstraintData::Motion & vc1 = cdata.contact1_velocity; + typename ConstraintData::Motion & vc2 = cdata.contact2_velocity; + const JointIndex joint1_id = cmodel.joint1_id; + const JointIndex joint2_id = cmodel.joint2_id; + + const auto & corrector = cmodel.corrector; + auto & contact_velocity_error = cdata.contact_velocity_error; + + if (joint1_id > 0) + vc1 = oMc1.actInv(data.ov[joint1_id]); + else + vc1.setZero(); + if (joint2_id > 0) + vc2 = oMc2.actInv(data.ov[joint2_id]); + else + vc2.setZero(); + const Motion vc2_in_frame1 = c1Mc2.act(vc2); + + if (cmodel.type == CONTACT_6D) + { + cdata.contact_placement_error = -log6(c1Mc2); + contact_velocity_error = vc1 - vc2_in_frame1; + const Matrix6 A1 = oMc1.toActionMatrixInverse(); + const Matrix6 A1tA1 = A1.transpose() * A1; + data.oYaba_augmented[joint1_id].noalias() += mu * A1tA1; + + // Baumgarte + if (check_expression_if_real( + isZero(corrector.Kp, static_cast(0.)) + && isZero(corrector.Kd, static_cast(0.)))) + { + cdata.contact_acceleration_desired.setZero(); + } + else + { + cdata.contact_acceleration_desired.toVector().noalias() = + -(corrector.Kd.asDiagonal() * contact_velocity_error.toVector()) + - (corrector.Kp.asDiagonal() * cdata.contact_placement_error.toVector()); + } + + cdata.contact_acceleration_desired -= oMc1.actInv(data.oa[joint1_id]); + cdata.contact_acceleration_desired -= cdata.contact_velocity_error.cross(vc2_in_frame1); + + if (joint2_id > 0) + { + cdata.contact_acceleration_desired += oMc1.actInv(data.oa[joint2_id]); + + const Matrix6 A2 = + -A1; // only for 6D case. also used below for computing A2tA2 and A1tA2 + data.oYaba_augmented[joint2_id].noalias() += mu * A1tA1; + data.of[joint2_id].toVector().noalias() += + A2.transpose() + * (/*cdata.contact_force.toVector()*/ -mu * cdata.contact_acceleration_desired.toVector()); + + const JointPair jp = joint1_id < joint2_id ? JointPair{joint1_id, joint2_id} + : JointPair{joint2_id, joint1_id}; + assert(data.joint_cross_coupling.exist(jp) && "Must never happen"); + data.joint_cross_coupling.get(jp) -= mu * A1tA1; + } + else + { + cdata.contact_acceleration_desired.toVector().noalias() -= + A1 * model.gravity.toVector(); + } + + data.of[joint1_id].toVector().noalias() += + A1.transpose() + * (/*cdata.contact_force.toVector()*/ -mu * cdata.contact_acceleration_desired.toVector()); + } + else if (cmodel.type == CONTACT_3D) + { + const Matrix36 & A1 = oMc1.toActionMatrixInverse().template topRows<3>(); + data.oYaba_augmented[joint1_id].noalias() += mu * A1.transpose() * A1; + + if (check_expression_if_real( + isZero(corrector.Kp, static_cast(0.)) + && isZero(corrector.Kd, static_cast(0.)))) + { + cdata.contact_acceleration_desired.setZero(); + } + else + { + cdata.contact_acceleration_desired.linear().noalias() = + -(corrector.Kd.asDiagonal() * contact_velocity_error.linear()) + - (corrector.Kp.asDiagonal() * cdata.contact_placement_error.linear()); + cdata.contact_acceleration_desired.angular().setZero(); + } + + cdata.contact_acceleration_desired.linear().noalias() -= + vc1.angular().cross(vc1.linear()); + if (joint2_id > 0) + { + const Matrix36 A2 = + -c1Mc2.rotation() + * (oMc2.toActionMatrixInverse().template topRows<3>()); // TODO:remove memalloc + + cdata.contact_acceleration_desired.linear().noalias() += + c1Mc2.rotation() * vc2.angular().cross(vc2.linear()); + data.oYaba_augmented[joint2_id].noalias() += mu * A2.transpose() * A2; + data.of[joint2_id].toVector().noalias() += + A2.transpose() + * (/*cdata.contact_force.toVector()*/ -mu * cdata.contact_acceleration_desired.linear()); + + if (joint1_id < joint2_id) + { + data.joint_cross_coupling.get({joint1_id, joint2_id}).noalias() += + mu * A1.transpose() * A2; + } + else + { + data.joint_cross_coupling.get({joint2_id, joint1_id}).noalias() += + mu * A2.transpose() * A1; + } + } + else + { + cdata.contact_acceleration_desired.linear().noalias() -= A1 * model.gravity.toVector(); + } + + data.of[joint1_id].toVector().noalias() += + A1.transpose() + * (/*cdata.contact_force.toVector()*/ -mu * cdata.contact_acceleration_desired.linear()); + } + else + { + assert(false && "Must never happen"); + } + } + }; + } // namespace internal + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ConfigVectorType, + typename TangentVectorType1, + typename TangentVectorType2, + class ConstraintModel, + class ConstraintModelAllocator, + class ConstraintData, + class ConstraintDataAllocator> + inline const typename DataTpl::TangentVectorType & lcaba( + const ModelTpl & model, + DataTpl & data, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & v, + const Eigen::MatrixBase & tau, + const std::vector & constraint_models, + std::vector & constraint_datas, + ProximalSettingsTpl & settings) + { + + assert(model.check(data) && "data is not consistent with model."); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + q.size(), model.nq, "The joint configuration vector is not of right size"); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + v.size(), model.nv, "The joint velocity vector is not of right size"); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + tau.size(), model.nv, "The joint torque vector is not of right size"); + + typedef ModelTpl Model; + typedef typename Model::JointIndex JointIndex; + typedef typename ConstraintModel::Matrix36 Matrix36; + + data.u = tau; + data.oa_gf[0] = -model.gravity; + data.oa[0] = data.oa_gf[0]; + data.of[0].setZero(); + + const Scalar mu = Scalar(1) / settings.mu; + + for (auto & coupling : data.joint_cross_coupling) + coupling.setZero(); + + typedef LCABAForwardStep1< + Scalar, Options, JointCollectionTpl, ConfigVectorType, TangentVectorType1> + Pass1; + for (JointIndex i = 1; i < (JointIndex)model.njoints; ++i) + { + Pass1::run( + model.joints[i], data.joints[i], + typename Pass1::ArgsType(model, data, q.derived(), v.derived())); + } + + for (std::size_t i = 0; i < constraint_models.size(); ++i) + { + ConstraintData & cdata = constraint_datas[i]; + const ConstraintModel & cmodel = constraint_models[i]; + + typedef internal::LCABAConstraintCalcStep CalcStep; + CalcStep::run(model, data, cmodel, cdata, mu); + } + + typedef LCABABackwardStep Pass2; + + const auto & elimination_order = data.elimination_order; + + for (JointIndex i : elimination_order) + { + Pass2::run(model.joints[i], data.joints[i], typename Pass2::ArgsType(model, data)); + } + + assert(settings.mu > 0 && "constrainedABA requires mu > 0."); + + typedef LCABAForwardStep2 Pass3; + + for (int it = int(elimination_order.size()) - 1; it >= 0; --it) + { + const JointIndex i = elimination_order[size_t(it)]; + if (data.constraints_supported_dim[i] > 0) + Pass3::run(model.joints[i], data.joints[i], typename Pass3::ArgsType(model, data)); + } + + typedef LCABAReducedBackwardStep ReducedPass2; + typedef LCABAReducedForwardStep ReducedPass3; + data.g.setZero(); + int iter = 1; + for (; iter < settings.max_iter; iter++) + { + settings.absolute_residual = Scalar(0); + for (JointIndex j = 1; j < (JointIndex)model.njoints; ++j) + { + if (data.constraints_supported_dim[j] > 0) + data.of[j].setZero(); + } + for (std::size_t j = 0; j < constraint_models.size(); ++j) + { + const ConstraintModel & cmodel = constraint_models[j]; + ConstraintData & cdata = constraint_datas[j]; + const JointIndex joint1_id = cmodel.joint1_id; + const JointIndex joint2_id = cmodel.joint2_id; + typename ConstraintData::Motion & contact_acc_err = cdata.contact_acceleration_error; + + if (cmodel.type == CONTACT_6D) + { + if (joint2_id > 0) + contact_acc_err = cdata.oMc1.actInv((data.oa[joint1_id] - data.oa[joint2_id])) + - cdata.contact_acceleration_desired; + else + contact_acc_err = + cdata.oMc1.actInv((data.oa[joint1_id])) - cdata.contact_acceleration_desired; + + const auto mu_lambda = Force(mu * contact_acc_err.toVector()); + cdata.contact_force += mu_lambda; + + if (joint1_id > 0) + data.of[joint1_id] += cdata.oMc1.act(mu_lambda); + + if (joint2_id > 0) + data.of[joint2_id] -= cdata.oMc1.act(mu_lambda); + } + else if (cmodel.type == CONTACT_3D) + { + contact_acc_err.linear() = -cdata.contact_acceleration_desired.linear(); + if (joint1_id > 0) + contact_acc_err.linear() += cdata.oMc1.actInv(data.oa[joint1_id]).linear(); + if (joint2_id > 0) + contact_acc_err.linear() -= + cdata.c1Mc2.rotation() * cdata.oMc2.actInv(data.oa[joint2_id]).linear(); + + const auto mu_lambda = Force(mu * contact_acc_err.toVector()); + cdata.contact_force.linear() += mu_lambda.linear(); + + if (joint1_id > 0) + data.of[joint1_id] += cdata.oMc1.act(mu_lambda); + + if (joint2_id > 0) + { + const Matrix36 A2 = + -cdata.c1Mc2.rotation() * (cdata.oMc2.toActionMatrixInverse().template topRows<3>()); + + data.of[joint2_id].toVector().noalias() += A2.transpose() * mu_lambda.linear(); + } + } + + const Scalar constraint_residual_norm = + contact_acc_err.toVector().template lpNorm(); + if (settings.absolute_residual < constraint_residual_norm) + settings.absolute_residual = constraint_residual_norm; + } + + if (settings.absolute_residual < settings.absolute_accuracy) + break; + + // reduced backward sweep + for (JointIndex j : elimination_order) + { + if (data.constraints_supported_dim[j] > 0) + ReducedPass2::run( + model.joints[j], data.joints[j], typename ReducedPass2::ArgsType(model, data)); + } + + // reduced forward sweep + data.oa_gf[0].setZero(); + for (int it = int(elimination_order.size()) - 1; it >= 0; it--) + { + const JointIndex j = elimination_order[size_t(it)]; + if (data.constraints_supported_dim[j] > 0) + { + ReducedPass3::run( + model.joints[j], data.joints[j], typename ReducedPass3::ArgsType(model, data)); + } + } + data.ddq += data.g; + // related to least-squares residual + if (data.g.template lpNorm() < settings.absolute_accuracy) + break; + } + settings.iter = iter; + + // outward sweep after convergence/timeout for joints not supporting a constraint + data.oa_gf[0] = -model.gravity; + for (int it = int(elimination_order.size()) - 1; it >= 0; --it) + { + const JointIndex j = elimination_order[size_t(it)]; + if (data.constraints_supported_dim[j] == 0) + Pass3::run(model.joints[j], data.joints[j], typename Pass3::ArgsType(model, data)); + else + data.oa_gf[j] = data.oa[j]; + } + + return data.ddq; + } + +} // namespace pinocchio + +/// @endcond + +#endif // ifndef __pinocchio_algorithm_loop_constrained_aba_hxx__ diff --git a/include/pinocchio/algorithm/model.hpp b/include/pinocchio/algorithm/model.hpp index 1ada28efe7..97ea597220 100644 --- a/include/pinocchio/algorithm/model.hpp +++ b/include/pinocchio/algorithm/model.hpp @@ -265,6 +265,26 @@ namespace pinocchio size_t & index_ancestor_in_support1, size_t & index_ancestor_in_support2); + /** + * + * \brief Computes the common ancestor between two joints belonging to the same kinematic tree. + * + * \param[in] model the input model. + * \param[in] joint1_id index of the first joint. + * \param[in] joint2_id index of the second joint. + * + */ + template class JointCollectionTpl> + JointIndex findCommonAncestor( + const ModelTpl & model, + JointIndex joint1_id, + JointIndex joint2_id) + { + size_t index_ancestor_in_support1, index_ancestor_in_support2; + return findCommonAncestor( + model, joint1_id, joint2_id, index_ancestor_in_support1, index_ancestor_in_support2); + } + } // namespace pinocchio #include "pinocchio/algorithm/model.hxx" diff --git a/include/pinocchio/algorithm/model.hxx b/include/pinocchio/algorithm/model.hxx index cce70c3599..1bcd83fd43 100644 --- a/include/pinocchio/algorithm/model.hxx +++ b/include/pinocchio/algorithm/model.hxx @@ -65,8 +65,8 @@ namespace pinocchio typedef ModelTpl Model; typedef typename Model::Frame Frame; - PINOCCHIO_THROW( - parentFrame < model.frames.size(), std::invalid_argument, + PINOCCHIO_THROW_IF( + parentFrame >= model.frames.size(), std::invalid_argument, "parentFrame is greater than the size of the frames vector."); const Frame & pframe = model.frames[parentFrame]; @@ -210,13 +210,15 @@ namespace pinocchio parent_id, jmodel_inter, // Use the intermediate joint (jmodel_inter) with updates id, idx, ... pMi * modelAB.jointPlacements[joint_id_in], modelAB.names[joint_id_in], - jmodel_in.jointVelocitySelector( - modelAB - .effortLimit), // Need to select the vector base on the origin idxs, so use jmodel_in. - jmodel_in.jointVelocitySelector(modelAB.velocityLimit), + jmodel_in.jointVelocitySelector(modelAB.lowerEffortLimit), + jmodel_in.jointVelocitySelector(modelAB.upperEffortLimit), + jmodel_in.jointVelocitySelector(modelAB.lowerVelocityLimit), + jmodel_in.jointVelocitySelector(modelAB.upperVelocityLimit), jmodel_in.jointConfigSelector(modelAB.lowerPositionLimit), jmodel_in.jointConfigSelector(modelAB.upperPositionLimit), - jmodel_in.jointVelocitySelector(modelAB.friction), + jmodel_in.jointConfigSelector(modelAB.positionLimitMargin), + jmodel_in.jointVelocitySelector(modelAB.lowerDryFrictionLimit), + jmodel_in.jointVelocitySelector(modelAB.upperDryFrictionLimit), jmodel_in.jointVelocitySelector(modelAB.damping)); assert(joint_id_out < model.joints.size()); @@ -362,15 +364,15 @@ namespace pinocchio std::vector AJointsBeforeB; std::vector AJointsAfterB; // All joints until the parent of frameInModelA come first - for (JointIndex jid = 1; jid <= frame.parent; ++jid) + for (JointIndex jid = 1; jid <= frame.parentJoint; ++jid) { AJointsBeforeB.push_back(jid); } // descendants of the parent of frameInModelA come also before model B // TODO(jcarpent): enhancement by taking into account the compactness of the joint ordering. - for (JointIndex jid = frame.parent + 1; jid < modelA.joints.size(); ++jid) + for (JointIndex jid = frame.parentJoint + 1; jid < modelA.joints.size(); ++jid) { - if (hasAncestor(modelA, jid, frame.parent)) + if (hasAncestor(modelA, jid, frame.parentJoint)) { AJointsBeforeB.push_back(jid); } @@ -558,7 +560,6 @@ namespace pinocchio for (JointIndex joint_id = 1; joint_id < (JointIndex)input_model.njoints; ++joint_id) { - const JointIndex joint_id_to_lock = (current_index_to_lock < list_of_joints_to_lock.size()) ? list_of_joints_to_lock[current_index_to_lock] : 0; @@ -662,11 +663,15 @@ namespace pinocchio reduced_joint_id = reduced_model.addJoint( reduced_parent_joint_index, mimic_joint, parent_frame_placement * input_model.jointPlacements[joint_id], joint_name, - mimic_joint.jointVelocitySelector(input_model.effortLimit), - mimic_joint.jointVelocitySelector(input_model.velocityLimit), + mimic_joint.jointVelocitySelector(input_model.lowerEffortLimit), + mimic_joint.jointVelocitySelector(input_model.upperEffortLimit), + mimic_joint.jointVelocitySelector(input_model.lowerVelocityLimit), + mimic_joint.jointVelocitySelector(input_model.upperVelocityLimit), mimic_joint.jointConfigSelector(input_model.lowerPositionLimit), mimic_joint.jointConfigSelector(input_model.upperPositionLimit), - mimic_joint.jointVelocitySelector(input_model.friction), + mimic_joint.jointVelocitySelector(input_model.positionLimitMargin), + mimic_joint.jointVelocitySelector(input_model.lowerDryFrictionLimit), + mimic_joint.jointVelocitySelector(input_model.upperDryFrictionLimit), mimic_joint.jointVelocitySelector(input_model.damping)); } else @@ -675,11 +680,15 @@ namespace pinocchio reduced_joint_id = reduced_model.addJoint( reduced_parent_joint_index, joint_input_model, parent_frame_placement * input_model.jointPlacements[joint_id], joint_name, - joint_input_model.jointVelocitySelector(input_model.effortLimit), - joint_input_model.jointVelocitySelector(input_model.velocityLimit), + joint_input_model.jointVelocitySelector(input_model.lowerEffortLimit), + joint_input_model.jointVelocitySelector(input_model.upperEffortLimit), + joint_input_model.jointVelocitySelector(input_model.lowerVelocityLimit), + joint_input_model.jointVelocitySelector(input_model.upperVelocityLimit), joint_input_model.jointConfigSelector(input_model.lowerPositionLimit), joint_input_model.jointConfigSelector(input_model.upperPositionLimit), - joint_input_model.jointVelocitySelector(input_model.friction), + joint_input_model.jointConfigSelector(input_model.positionLimitMargin), + joint_input_model.jointVelocitySelector(input_model.lowerDryFrictionLimit), + joint_input_model.jointVelocitySelector(input_model.upperDryFrictionLimit), joint_input_model.jointVelocitySelector(input_model.damping)); } // Append inertia @@ -891,14 +900,18 @@ namespace pinocchio int nv = output_model.nv; // Resize limits - output_model.effortLimit.resize(nv); - output_model.velocityLimit.resize(nv); + output_model.lowerEffortLimit.resize(nv); + output_model.upperEffortLimit.resize(nv); + output_model.lowerVelocityLimit.resize(nv); + output_model.upperVelocityLimit.resize(nv); output_model.lowerPositionLimit.resize(nq); output_model.upperPositionLimit.resize(nq); + output_model.positionLimitMargin.resize(nq); output_model.armature.resize(nv); output_model.rotorInertia.resize(nv); output_model.rotorGearRatio.resize(nv); - output_model.friction.resize(nv); + output_model.lowerDryFrictionLimit.resize(nv); + output_model.upperDryFrictionLimit.resize(nv); output_model.damping.resize(nv); // Move indexes and limits @@ -906,15 +919,22 @@ namespace pinocchio { const JointModel & jmodel_input = input_model.joints[joint_id]; const JointModel & jmodel_output = output_model.joints[joint_id]; - jmodel_output.jointVelocitySelector(output_model.effortLimit) = - jmodel_input.jointVelocitySelector(input_model.effortLimit); - jmodel_output.jointVelocitySelector(output_model.velocityLimit) = - jmodel_input.jointVelocitySelector(input_model.velocityLimit); + + jmodel_output.jointVelocitySelector(output_model.lowerEffortLimit) = + jmodel_input.jointVelocitySelector(input_model.lowerEffortLimit); + jmodel_output.jointVelocitySelector(output_model.upperEffortLimit) = + jmodel_input.jointVelocitySelector(input_model.upperEffortLimit); + jmodel_output.jointVelocitySelector(output_model.lowerVelocityLimit) = + jmodel_input.jointVelocitySelector(input_model.lowerVelocityLimit); + jmodel_output.jointVelocitySelector(output_model.upperVelocityLimit) = + jmodel_input.jointVelocitySelector(input_model.upperVelocityLimit); jmodel_output.jointConfigSelector(output_model.lowerPositionLimit) = jmodel_input.jointConfigSelector(input_model.lowerPositionLimit); jmodel_output.jointConfigSelector(output_model.upperPositionLimit) = jmodel_input.jointConfigSelector(input_model.upperPositionLimit); + jmodel_output.jointConfigSelector(output_model.positionLimitMargin) = + jmodel_input.jointConfigSelector(input_model.positionLimitMargin); jmodel_output.jointVelocitySelector(output_model.armature) = jmodel_input.jointVelocitySelector(input_model.armature); @@ -922,8 +942,10 @@ namespace pinocchio jmodel_input.jointVelocitySelector(input_model.rotorInertia); jmodel_output.jointVelocitySelector(output_model.rotorGearRatio) = jmodel_input.jointVelocitySelector(input_model.rotorGearRatio); - jmodel_output.jointVelocitySelector(output_model.friction) = - jmodel_input.jointVelocitySelector(input_model.friction); + jmodel_output.jointVelocitySelector(output_model.lowerDryFrictionLimit) = + jmodel_input.jointVelocitySelector(input_model.lowerDryFrictionLimit); + jmodel_output.jointVelocitySelector(output_model.upperDryFrictionLimit) = + jmodel_input.jointVelocitySelector(input_model.upperDryFrictionLimit); jmodel_output.jointVelocitySelector(output_model.damping) = jmodel_input.jointVelocitySelector(input_model.damping); } @@ -957,15 +979,21 @@ namespace pinocchio idx_v += jmodel_output.nv(); if (joint_id != index_mimicking) { - jmodel_output.jointVelocitySelector(output_model.effortLimit) = - jmodel_input.jointVelocitySelector(input_model.effortLimit); - jmodel_output.jointVelocitySelector(output_model.velocityLimit) = - jmodel_input.jointVelocitySelector(input_model.velocityLimit); + jmodel_output.jointVelocitySelector(output_model.lowerEffortLimit) = + jmodel_input.jointVelocitySelector(input_model.lowerEffortLimit); + jmodel_output.jointVelocitySelector(output_model.upperEffortLimit) = + jmodel_input.jointVelocitySelector(input_model.upperEffortLimit); + jmodel_output.jointVelocitySelector(output_model.lowerVelocityLimit) = + jmodel_input.jointVelocitySelector(input_model.lowerVelocityLimit); + jmodel_output.jointVelocitySelector(output_model.upperVelocityLimit) = + jmodel_input.jointVelocitySelector(input_model.upperVelocityLimit); jmodel_output.jointConfigSelector(output_model.lowerPositionLimit) = jmodel_input.jointConfigSelector(input_model.lowerPositionLimit); jmodel_output.jointConfigSelector(output_model.upperPositionLimit) = jmodel_input.jointConfigSelector(input_model.upperPositionLimit); + jmodel_output.jointConfigSelector(output_model.positionLimitMargin) = + jmodel_input.jointConfigSelector(input_model.positionLimitMargin); jmodel_output.jointVelocitySelector(output_model.armature) = jmodel_input.jointVelocitySelector(input_model.armature); @@ -973,8 +1001,10 @@ namespace pinocchio jmodel_input.jointVelocitySelector(input_model.rotorInertia); jmodel_output.jointVelocitySelector(output_model.rotorGearRatio) = jmodel_input.jointVelocitySelector(input_model.rotorGearRatio); - jmodel_output.jointVelocitySelector(output_model.friction) = - jmodel_input.jointVelocitySelector(input_model.friction); + jmodel_output.jointVelocitySelector(output_model.lowerDryFrictionLimit) = + jmodel_input.jointVelocitySelector(input_model.lowerDryFrictionLimit); + jmodel_output.jointVelocitySelector(output_model.upperDryFrictionLimit) = + jmodel_input.jointVelocitySelector(input_model.upperDryFrictionLimit); jmodel_output.jointVelocitySelector(output_model.damping) = jmodel_input.jointVelocitySelector(input_model.damping); } diff --git a/include/pinocchio/algorithm/parallel/aba.hpp b/include/pinocchio/algorithm/parallel/aba.hpp index 9af6077f1b..7da4ecf6bd 100644 --- a/include/pinocchio/algorithm/parallel/aba.hpp +++ b/include/pinocchio/algorithm/parallel/aba.hpp @@ -7,7 +7,7 @@ #include "pinocchio/multibody/pool/model.hpp" #include "pinocchio/algorithm/aba.hpp" -#include "pinocchio/algorithm/parallel/omp.hpp" +#include "pinocchio/utils/openmp.hpp" namespace pinocchio { @@ -68,7 +68,7 @@ namespace pinocchio PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), a.cols()); PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), res.cols()); - set_default_omp_options(num_threads); + setDefaultOpenMPSettings(num_threads); const Eigen::DenseIndex batch_size = res.cols(); Eigen::DenseIndex i = 0; diff --git a/include/pinocchio/algorithm/parallel/geometry.hpp b/include/pinocchio/algorithm/parallel/geometry.hpp index 66ca88b6bf..43fbfdf9f4 100644 --- a/include/pinocchio/algorithm/parallel/geometry.hpp +++ b/include/pinocchio/algorithm/parallel/geometry.hpp @@ -8,7 +8,7 @@ #include "pinocchio/macros.hpp" // clang-format off -PINOCCHIO_PRAGMA_DEPRECATED_HEADER(pinocchio/algorithm/parallel/geometry.hpp, pinocchio/collision/parallel/geometry.hpp) +PINOCCHIO_DEPRECATED_HEADER(pinocchio/algorithm/parallel/geometry.hpp, pinocchio/collision/parallel/geometry.hpp) // clang-format on #include "pinocchio/collision/parallel/geometry.hpp" diff --git a/include/pinocchio/algorithm/parallel/omp.hpp b/include/pinocchio/algorithm/parallel/omp.hpp index bce2c93204..050e504b4a 100644 --- a/include/pinocchio/algorithm/parallel/omp.hpp +++ b/include/pinocchio/algorithm/parallel/omp.hpp @@ -1,19 +1,13 @@ // -// Copyright (c) 2022 INRIA +// Copyright (c) 2022-2024 INRIA // #ifndef __pinocchio_algorithm_parallel_omp_hpp__ #define __pinocchio_algorithm_parallel_omp_hpp__ -#include - -namespace pinocchio -{ - inline void set_default_omp_options(const size_t num_threads = (size_t)omp_get_max_threads()) - { - omp_set_num_threads((int)num_threads); - omp_set_dynamic(0); - } -} // namespace pinocchio +#include "pinocchio/macros.hpp" +PINOCCHIO_DEPRECATED_MOVED_HEADER( + pinocchio / algorithm / parallel / omp.hpp, pinocchio / utils / openmp.hpp) +#include "pinocchio/utils/openmp.hpp" #endif // ifndef __pinocchio_algorithm_parallel_omp_hpp__ diff --git a/include/pinocchio/algorithm/parallel/rnea.hpp b/include/pinocchio/algorithm/parallel/rnea.hpp index 2434fcaef6..1e8607adf1 100644 --- a/include/pinocchio/algorithm/parallel/rnea.hpp +++ b/include/pinocchio/algorithm/parallel/rnea.hpp @@ -7,7 +7,7 @@ #include "pinocchio/multibody/pool/model.hpp" #include "pinocchio/algorithm/rnea.hpp" -#include "pinocchio/algorithm/parallel/omp.hpp" +#include "pinocchio/utils/openmp.hpp" namespace pinocchio { @@ -67,7 +67,7 @@ namespace pinocchio PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), a.cols()); PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), res.cols()); - set_default_omp_options(num_threads); + setDefaultOpenMPSettings(num_threads); const Eigen::DenseIndex batch_size = res.cols(); Eigen::DenseIndex i = 0; diff --git a/include/pinocchio/algorithm/pgs-solver.hpp b/include/pinocchio/algorithm/pgs-solver.hpp index f6dc87537e..16c782e0b3 100644 --- a/include/pinocchio/algorithm/pgs-solver.hpp +++ b/include/pinocchio/algorithm/pgs-solver.hpp @@ -7,55 +7,124 @@ #include "pinocchio/algorithm/constraints/fwd.hpp" #include "pinocchio/algorithm/contact-solver-base.hpp" +#include "pinocchio/algorithm/delassus-operator-dense.hpp" +#include namespace pinocchio { + template + struct PGSContactSolverTpl; + typedef PGSContactSolverTpl PGSContactSolver; + /// \brief Projected Gauss Siedel solver template struct PGSContactSolverTpl : ContactSolverBaseTpl<_Scalar> { typedef _Scalar Scalar; typedef ContactSolverBaseTpl Base; + typedef Eigen::Matrix MatrixXs; typedef Eigen::Matrix VectorXs; + typedef Eigen::Ref RefConstVectorXs; + + typedef typename Base::SolverStats SolverStats; explicit PGSContactSolverTpl(const int problem_size) : Base(problem_size) , x(problem_size) , x_previous(problem_size) + , y(problem_size) + , y_to_pos(problem_size) + , time_scaling_acc_to_constraints(VectorXs::Zero(problem_size)) + , time_scaling_constraints_to_pos(VectorXs::Zero(problem_size)) + , gs(VectorXs::Zero(problem_size)) + , stats() { } /// - /// \brief Solve the constrained conic problem composed of problem data (G,g,cones) and starting - /// from the initial guess. + /// \brief Solve the constrained problem composed of problem data (G,g,constraint_sets) and + /// starting from the initial guess. /// /// \param[in] G Symmetric PSD matrix representing the Delassus of the contact problem. /// \param[in] g Free contact acceleration or velicity associted with the contact problem. - /// \param[in] cones Vector of conic constraints. - /// \param[in,out] x Initial guess and output solution of the problem - /// \param[in] over_relax Over relaxation value + /// \param[in] constraint_models Vector of constraint models. + /// \param[in] x Initial guess solution of the problem. + /// \param[in] over_relax Optional over relaxation value, default to 1. /// /// \returns True if the problem has converged. template< - typename MatrixLike, typename VectorLike, - typename ConstraintAllocator, - typename VectorLikeOut> + template class Holder, + typename ConstraintModel, + typename ConstraintModelAllocator> + bool solve( + const DelassusOperatorDense & delassus, + const Eigen::MatrixBase & g, + const std::vector, ConstraintModelAllocator> & + constraint_models, + const Scalar dt, + const boost::optional x_guess = boost::none, + const Scalar over_relax = Scalar(1), + const bool solve_ncp = true, + const bool stat_record = false); + + /// + /// \brief Solve the constrained problem composed of problem data (G,g,constraint_sets) and + /// starting from the initial guess. + /// + /// \param[in] G Symmetric PSD matrix representing the Delassus of the contact problem. + /// \param[in] g Free contact acceleration or velicity associted with the contact problem. + /// \param[in] constraint_models Vector of constraint models. + /// \param[in] x_guess Initial guess and output solution of the problem + /// \param[in] over_relax Over relaxation value + /// + /// \returns True if the problem has converged. + template bool solve( - const MatrixLike & G, + const DelassusOperatorDense & delassus, const Eigen::MatrixBase & g, - const std::vector, ConstraintAllocator> & cones, - const Eigen::DenseBase & x, - const Scalar over_relax = Scalar(1)); + const std::vector & constraint_models, + const Scalar dt, + const boost::optional x_guess = boost::none, + const Scalar over_relax = Scalar(1), + const bool solve_ncp = true, + const bool stat_record = false); + + /// \returns the primal solution of the problem + const VectorXs & getPrimalSolution() const + { + return x; + } + /// \returns the dual solution of the problem + const VectorXs & getDualSolution() const + { + return y; + } + + SolverStats & getStats() + { + return stats; + } protected: /// \brief Previous temporary value of the optimum. VectorXs x, x_previous; + /// \brief Value of the dual variable + VectorXs y, y_to_pos; + + /// \brief Time scaling vector for constraints + VectorXs time_scaling_acc_to_constraints, time_scaling_constraints_to_pos; + /// \brief Vector g divided by time scaling (g / time_scaling_acc_to_constraints) + VectorXs gs; + #ifdef PINOCCHIO_WITH_HPP_FCL using Base::timer; #endif // PINOCCHIO_WITH_HPP_FCL + /// \brief Stats of the solver + SolverStats stats; + }; // struct PGSContactSolverTpl } // namespace pinocchio diff --git a/include/pinocchio/algorithm/pgs-solver.hxx b/include/pinocchio/algorithm/pgs-solver.hxx index 854e862065..4601df0c44 100644 --- a/include/pinocchio/algorithm/pgs-solver.hxx +++ b/include/pinocchio/algorithm/pgs-solver.hxx @@ -1,104 +1,690 @@ // -// Copyright (c) 2022 INRIA +// Copyright (c) 2022-2024 INRIA // #ifndef __pinocchio_algorithm_pgs_solver_hxx__ #define __pinocchio_algorithm_pgs_solver_hxx__ -#include -#include "pinocchio/algorithm/constraints/coulomb-friction-cone.hpp" +#include "pinocchio/algorithm/constraints/sets.hpp" +#include "pinocchio/algorithm/constraints/visitors/constraint-model-visitor.hpp" +#include "pinocchio/algorithm/contact-solver-utils.hpp" namespace pinocchio { + + template + struct PGSConstraintProjectionStepBase + { + typedef _Scalar Scalar; + + explicit PGSConstraintProjectionStepBase(const Scalar over_relax_value) + : over_relax_value(over_relax_value) + { + } + + const Scalar over_relax_value; + Scalar complementarity; + Scalar dual_feasibility; + Scalar primal_feasibility; + }; // PGSConstraintProjectionBase + + template + struct PGSConstraintProjectionStep + { + }; + + template< + typename Scalar, + typename BlockType, + typename ForceType, + typename VelocityType, + typename DualToPosType, + typename TimeScalingType1, + typename TimeScalingType2> + struct PGSConstraintProjectionStepVisitor + : visitors::ConstraintUnaryVisitorBase> + , PGSConstraintProjectionStepBase + { + typedef boost::fusion::vector< + const Scalar, + const BlockType &, + ForceType &, + VelocityType &, + DualToPosType &, + const TimeScalingType1 &, + const TimeScalingType2 &, + Scalar &, + Scalar &, + Scalar &> + ArgsType; + typedef PGSConstraintProjectionStepBase Base; + typedef visitors::ConstraintUnaryVisitorBase> + VisitorBase; + + explicit PGSConstraintProjectionStepVisitor(const Scalar over_relax_value) + : Base(over_relax_value) + { + } + + template + static void algo( + const pinocchio::ConstraintModelBase & cmodel, + const Scalar over_relax_value, + const Eigen::EigenBase & G_block, + ForceType & force, + VelocityType & velocity, + DualToPosType & dual_to_pos, + const TimeScalingType1 & time_scaling_acc_to_constraints, + const TimeScalingType2 & time_scaling_constraints_to_pos, + Scalar & complementarity, + Scalar & primal_feasibility, + Scalar & dual_feasibility) + { + typedef typename ConstraintModel::ConstraintSet ConstraintSet; + + PGSConstraintProjectionStep step( + over_relax_value, + cmodel.derived().set()); // TODO(jcarpent): change cmodel.derived().set() -> cmodel.set() + step.project(G_block.derived(), force.const_cast_derived(), velocity.const_cast_derived()); + dual_to_pos = velocity.array() * time_scaling_acc_to_constraints.array(); + dual_to_pos.array() *= time_scaling_constraints_to_pos.array(); + step.computeFeasibility(force, dual_to_pos); + + complementarity = step.complementarity; + dual_feasibility = step.dual_feasibility; + primal_feasibility = step.primal_feasibility; + } + + using VisitorBase::run; + template + void run( + const pinocchio::ConstraintModelBase & cmodel, + const Eigen::EigenBase & G_block, + ForceType & force, + VelocityType & velocity, + DualToPosType & dual_to_pos, + const TimeScalingType1 & time_scaling_acc_to_constraints, + const TimeScalingType2 & time_scaling_constraints_to_pos) + { + algo( + cmodel.derived(), this->over_relax_value, G_block.derived(), force, velocity, dual_to_pos, + time_scaling_acc_to_constraints, time_scaling_constraints_to_pos, this->complementarity, + this->primal_feasibility, this->dual_feasibility); + } + + template class ConstraintCollectionTpl> + void run( + const pinocchio::ConstraintModelTpl & cmodel, + const Eigen::EigenBase & G_block, + ForceType & force, + VelocityType & velocity, + DualToPosType & dual_to_pos, + const TimeScalingType1 & time_scaling_acc_to_constraints, + const TimeScalingType2 & time_scaling_constraints_to_pos) + { + ArgsType args( + this->over_relax_value, G_block.derived(), force, velocity, dual_to_pos, + time_scaling_acc_to_constraints, time_scaling_constraints_to_pos, this->complementarity, + this->primal_feasibility, this->dual_feasibility); + this->run(cmodel.derived(), args); + } + }; // struct PGSConstraintProjectionStepVisitor + + template + struct PGSConstraintProjectionStep> + : PGSConstraintProjectionStepBase<_Scalar> + { + typedef _Scalar Scalar; + typedef CoulombFrictionConeTpl ConstraintSet; + typedef Eigen::Matrix Vector3; + typedef PGSConstraintProjectionStepBase Base; + + PGSConstraintProjectionStep(const Scalar over_relax_value, const ConstraintSet & set) + : Base(over_relax_value) + , set(set) + { + } + + /// + /// \brief Perform a projection step associated with the PGS algorithm + /// + /// \param[in] G_block block asscociated with the current + /// \param[in,out] primal_vector_ primal vector which will be update with the new estimate + /// \param[in,out] dual_vector_ dual vector which will be update with the new estimate + /// + template + void project( + const Eigen::EigenBase & G_block_, + const Eigen::MatrixBase & primal_vector_, + const Eigen::MatrixBase & dual_vector_) const + { + typedef Eigen::Matrix Vector2; + + auto & G_block = G_block_.derived(); + auto & primal_vector = primal_vector_.const_cast_derived(); + auto & dual_vector = dual_vector_.const_cast_derived(); + + // Normal update + Scalar & fz = primal_vector.coeffRef(2); + const Scalar fz_previous = fz; + fz -= Scalar( + this->over_relax_value + / math::max(Eigen::NumTraits::dummy_precision(), G_block.coeff(2, 2))) + * dual_vector[2]; + fz = math::max(Scalar(0), fz); + + // Account for the fz updated value + dual_vector += G_block.col(2) * (fz - fz_previous); + + // Tangential update + const Scalar min_D_tangent = math::max( + Eigen::NumTraits::dummy_precision(), + math::min(G_block.coeff(0, 0), G_block.coeff(1, 1))); + auto f_tangent = primal_vector.template head<2>(); + const Vector2 f_tangent_previous = f_tangent; + + f_tangent -= this->over_relax_value / min_D_tangent * dual_vector.template head<2>(); + const Scalar f_tangent_norm = f_tangent.norm(); + + const Scalar mu_fz = this->set.mu * fz; + if (f_tangent_norm > mu_fz) // Project in the circle of radius mu_fz + { + assert(f_tangent_norm > 0 && "f_tangent_norm is zero"); + f_tangent *= mu_fz / f_tangent_norm; + } + + // Account for the f_tangent updated value + dual_vector.noalias() += G_block.template leftCols<2>() * (f_tangent - f_tangent_previous); + } + + /// \brief Compute the feasibility conditions associated with the optimization problem + template + void computeFeasibility( + const Eigen::MatrixBase & primal_vector, + const Eigen::MatrixBase & dual_vector) + { + // The name should be inverted. + this->primal_feasibility = + Scalar(0); // always zero as the primal variable belongs to the friction cone. + + typedef Eigen::Matrix Vector3; + const Vector3 dual_vector_corrected = + dual_vector + this->set.computeNormalCorrection(dual_vector); + this->complementarity = + this->set.computeConicComplementarity(dual_vector_corrected, primal_vector); + assert(this->complementarity >= Scalar(0) && "The complementarity should be positive"); + const Vector3 reprojection_residual = + this->set.dual().project(dual_vector_corrected) - dual_vector_corrected; + this->dual_feasibility = reprojection_residual.norm(); + } + + const ConstraintSet & set; + + }; // PGSConstraintProjectionStep> + + template + struct PGSConstraintProjectionStep> + : PGSConstraintProjectionStepBase<_Scalar> + { + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + typedef UnboundedSetTpl ConstraintSet; + typedef PGSConstraintProjectionStepBase Base; + + PGSConstraintProjectionStep(const Scalar over_relax_value, const ConstraintSet & set) + : Base(over_relax_value) + , set(set) + { + } + + /// + /// \brief Perform a projection step associated with the PGS algorithm + /// + /// \param[in] G_block block asscociated with the current + /// \param[in,out] primal_vector_ primal vector which will be update with the new estimate + /// \param[in,out] dual_vector_ dual vector which will be update with the new estimate + /// + template + void project( + const Eigen::MatrixBase & G_block_, + const Eigen::MatrixBase & primal_vector_, + const Eigen::MatrixBase & dual_vector_) const + { + + const Eigen::DenseIndex size = set.size(); + auto & G_block = G_block_.derived(); + auto & primal_vector = primal_vector_.const_cast_derived(); + auto & dual_vector = dual_vector_.const_cast_derived(); + + for (Eigen::DenseIndex i = 0; i < size; ++i) + { + Scalar d_primal_value = + -this->over_relax_value * dual_vector[i] + / math::max(Eigen::NumTraits::dummy_precision(), G_block.coeff(i, i)); + primal_vector[i] += d_primal_value; + dual_vector.noalias() += G_block.col(i) * d_primal_value; // TODO: this could be optimized + } + } + + /// + /// \brief Perform a projection step associated with the PGS algorithm + /// + /// \param[in] G_block block asscociated with the current + /// \param[in,out] primal_vector_ primal vector which will be update with the new estimate + /// \param[in,out] dual_vector_ dual vector which will be update with the new estimate + /// + template + void project( + const Eigen::EigenBase & G_block_, + const Eigen::MatrixBase & primal_vector_, + const Eigen::MatrixBase & dual_vector_) const + { + + const Eigen::DenseIndex size = set.size(); + auto & G_block = G_block_.derived(); + auto & primal_vector = primal_vector_.const_cast_derived(); + auto & dual_vector = dual_vector_.const_cast_derived(); + + for (Eigen::DenseIndex i = 0; i < size; ++i) + { + Scalar d_primal_value = + -this->over_relax_value * dual_vector[i] + / math::max(Eigen::NumTraits::dummy_precision(), G_block.coeff(i, i)); + primal_vector[i] += d_primal_value; + dual_vector += G_block.col(i) * d_primal_value; // TODO: this could be optimized using aloca + } + } + + /// \brief Compute the feasibility conditions associated with the optimization problem + template + void computeFeasibility( + const Eigen::MatrixBase & primal_vector, + const Eigen::MatrixBase & dual_vector) + { + this->primal_feasibility = Scalar(0); + this->complementarity = primal_vector.dot(dual_vector); + this->dual_feasibility = dual_vector.template lpNorm(); + } + + const ConstraintSet & set; + + }; // PGSConstraintProjectionStep> + + template + struct PGSConstraintProjectionStep> : PGSConstraintProjectionStepBase<_Scalar> + { + typedef _Scalar Scalar; + typedef BoxSetTpl ConstraintSet; + typedef Eigen::Matrix Vector; + typedef PGSConstraintProjectionStepBase Base; + + PGSConstraintProjectionStep(const Scalar over_relax_value, const ConstraintSet & set) + : Base(over_relax_value) + , set(set) + { + } + + /// + /// \brief Perform a projection step associated with the PGS algorithm + /// + /// \param[in] G_block block asscociated with the current + /// \param[in,out] primal_vector_ primal vector which will be update with the new estimate + /// \param[in,out] dual_vector_ dual vector which will be update with the new estimate + /// + template + void project( + const Eigen::MatrixBase & G_block, + const Eigen::MatrixBase & primal_vector, + const Eigen::MatrixBase & dual_vector) const + { + project_impl( + this->set, this->over_relax_value, G_block.derived(), primal_vector.const_cast_derived(), + dual_vector.const_cast_derived()); + } + + template< + typename ConstraintSetType, + typename BlockType, + typename PrimalVectorType, + typename DualVectorType> + static void project_impl( + const ConstraintSetType & set, + const Scalar over_relax_value, + const Eigen::MatrixBase & G_block_, + const Eigen::MatrixBase & primal_vector_, + const Eigen::MatrixBase & dual_vector_) + { + const auto & G_block = G_block_.derived(); + auto & primal_vector = primal_vector_.const_cast_derived(); + auto & dual_vector = dual_vector_.const_cast_derived(); + + assert( + primal_vector.size() == dual_vector.size() + && "The two primal/dual vectors should be of the same size."); + assert( + primal_vector.size() == set.size() + && "The the primal vector should be of the same size than the box set."); + assert( + dual_vector.size() == set.size() + && "The the dual vector should be of the same size than the box set."); + + const Eigen::DenseIndex size = set.size(); + + for (Eigen::DenseIndex row_id = 0; row_id < size; ++row_id) + { + Scalar & value = primal_vector.coeffRef(row_id); + const Scalar value_previous = value; + value -= + Scalar( + over_relax_value + / math::max(Eigen::NumTraits::dummy_precision(), G_block.coeff(row_id, row_id))) + * dual_vector[row_id]; + value = set.rowiseProject(row_id, value); + dual_vector.noalias() += + G_block.col(row_id) + * Scalar(value - value_previous); // TODO optimize: we only need dual_vector[row_id] for + // the update and not the full dual vector + } + } + + /// + /// \brief Perform a projection step associated with the PGS algorithm + /// + /// \param[in] G_block block asscociated with the current + /// \param[in,out] primal_vector_ primal vector which will be update with the new estimate + /// \param[in,out] dual_vector_ dual vector which will be update with the new estimate + /// + template + void project( + const Eigen::EigenBase & G_block, + const Eigen::MatrixBase & primal_vector, + const Eigen::MatrixBase & dual_vector) const + { + project_impl( + this->set, this->over_relax_value, G_block.derived(), primal_vector.const_cast_derived(), + dual_vector.const_cast_derived()); + } + + template< + typename ConstraintSetType, + typename BlockType, + typename PrimalVectorType, + typename DualVectorType> + static void project_impl( + const ConstraintSetType & set, + const Scalar over_relax_value, + const Eigen::EigenBase & G_block_, // for Sparse matrices + const Eigen::MatrixBase & primal_vector_, + const Eigen::MatrixBase & dual_vector_) + { + const auto & G_block = G_block_.derived(); + auto & primal_vector = primal_vector_.const_cast_derived(); + auto & dual_vector = dual_vector_.const_cast_derived(); + + assert( + primal_vector.size() == dual_vector.size() + && "The two primal/dual vectors should be of the same size."); + assert( + primal_vector.size() == set.size() + && "The the primal vector should be of the same size than the box set."); + assert( + dual_vector.size() == set.size() + && "The the dual vector should be of the same size than the box set."); + + const Eigen::DenseIndex size = set.size(); + + for (Eigen::DenseIndex row_id = 0; row_id < size; ++row_id) + { + Scalar & value = primal_vector.coeffRef(row_id); + const Scalar value_previous = value; + value -= + Scalar( + over_relax_value + / math::max(Eigen::NumTraits::dummy_precision(), G_block.coeff(row_id, row_id))) + * dual_vector[row_id]; + value = set.rowiseProject(row_id, value); + dual_vector += G_block.col(row_id) * Scalar(value - value_previous); + } + } + + /// \brief Compute the feasibility conditions associated with the optimization problem + template + void computeFeasibility( + const Eigen::MatrixBase & primal_vector, + const Eigen::MatrixBase & dual_vector) + { + this->primal_feasibility = + Scalar(0); // always zero as the primal variable belongs to the constraint set. + this->dual_feasibility = + Scalar(0); // always zero as the dual variable belongs to the constraint set. + + const Eigen::DenseIndex size = set.size(); + Scalar complementarity = Scalar(0); + + const auto & lb = set.lb(); + const auto & ub = set.ub(); + for (Eigen::DenseIndex row_id = 0; row_id < size; ++row_id) + { + const Scalar dual_positive_part = math::max(Scalar(0), dual_vector[row_id]); + const Scalar dual_negative_part = dual_positive_part - dual_vector[row_id]; + + Scalar row_complementarity = dual_positive_part * (primal_vector[row_id] - lb[row_id]); + row_complementarity = + math::max(row_complementarity, dual_negative_part * (ub[row_id] - primal_vector[row_id])); + complementarity = math::max(complementarity, row_complementarity); + } + this->complementarity = complementarity; + } + + const ConstraintSet & set; + + }; // PGSConstraintProjectionStep> + + template + struct PGSConstraintProjectionStep> + : PGSConstraintProjectionStepBase<_Scalar> + { + typedef _Scalar Scalar; + typedef JointLimitConstraintConeTpl ConstraintSet; + typedef BoxSetTpl BoxSet; + typedef Eigen::Matrix Vector; + typedef PGSConstraintProjectionStepBase Base; + + PGSConstraintProjectionStep(const Scalar over_relax_value, const ConstraintSet & set) + : Base(over_relax_value) + , set(set) + { + } + + /// + /// \brief Perform a projection step associated with the PGS algorithm + /// + /// \param[in] G_block block asscociated with the current + /// \param[in,out] primal_vector_ primal vector which will be update with the new estimate + /// \param[in,out] dual_vector_ dual vector which will be update with the new estimate + /// + template + void project( + const Eigen::MatrixBase & G_block_, + const Eigen::MatrixBase & primal_vector_, + const Eigen::MatrixBase & dual_vector_) const + { + PGSConstraintProjectionStep::project_impl( + this->set, this->over_relax_value, G_block_.derived(), primal_vector_.const_cast_derived(), + dual_vector_.const_cast_derived()); + } + + /// + /// \brief Perform a projection step associated with the PGS algorithm + /// + /// \param[in] G_block block asscociated with the current + /// \param[in,out] primal_vector_ primal vector which will be update with the new estimate + /// \param[in,out] dual_vector_ dual vector which will be update with the new estimate + /// + template + void project( + const Eigen::EigenBase & G_block_, // for Sparse matrices + const Eigen::MatrixBase & primal_vector_, + const Eigen::MatrixBase & dual_vector_) const + { + PGSConstraintProjectionStep::project_impl( + this->set, this->over_relax_value, G_block_.derived(), primal_vector_.const_cast_derived(), + dual_vector_.const_cast_derived()); + } + + /// \brief Compute the feasibility conditions associated with the optimization problem + template + void computeFeasibility( + const Eigen::MatrixBase & primal_vector, + const Eigen::MatrixBase & dual_vector) + { + this->primal_feasibility = + Scalar(0); // always zero as the primal variable belongs to the constraint set. + + const Eigen::DenseIndex size = set.size(); + Scalar complementarity = Scalar(0); + Scalar dual_feasibility = Scalar(0); + + for (Eigen::DenseIndex row_id = 0; row_id < size; ++row_id) + { + const Scalar row_complementarity = + math::fabs(Scalar(primal_vector[row_id] * dual_vector[row_id])); + complementarity = math::max(complementarity, row_complementarity); + + const Scalar row_dual_feasibility = + math::fabs(dual_vector[row_id] - set.dual().rowiseProject(row_id, dual_vector[row_id])); + dual_feasibility = math::max(dual_feasibility, row_dual_feasibility); + } + this->complementarity = complementarity; + this->dual_feasibility = dual_feasibility; + } + + const ConstraintSet & set; + + }; // PGSConstraintProjectionStep> + template template< - typename MatrixLike, typename VectorLike, - typename ConstraintAllocator, - typename VectorLikeOut> + template class Holder, + typename ConstraintModel, + typename ConstraintModelAllocator> bool PGSContactSolverTpl<_Scalar>::solve( - const MatrixLike & G, + const DelassusOperatorDense & delassus, const Eigen::MatrixBase & g, - const std::vector, ConstraintAllocator> & cones, - const Eigen::DenseBase & x_sol, - const Scalar over_relax) + const std::vector, ConstraintModelAllocator> & constraint_models, + const Scalar dt, + const boost::optional x_guess, + const Scalar over_relax, + const bool solve_ncp, + const bool stat_record) { - typedef CoulombFrictionConeTpl CoulombFrictionCone; - typedef Eigen::Matrix Vector2; - typedef Eigen::Matrix Vector3; - // typedef Eigen::Matrix Vector6; - + const MatrixXs & G = delassus.undampedMatrix(); PINOCCHIO_CHECK_INPUT_ARGUMENT( over_relax < Scalar(2) && over_relax > Scalar(0), "over_relax should lie in ]0,2[.") PINOCCHIO_CHECK_ARGUMENT_SIZE(g.size(), this->getProblemSize()); PINOCCHIO_CHECK_ARGUMENT_SIZE(G.rows(), this->getProblemSize()); PINOCCHIO_CHECK_ARGUMENT_SIZE(G.cols(), this->getProblemSize()); - PINOCCHIO_CHECK_ARGUMENT_SIZE(x_sol.size(), this->getProblemSize()); + if (x_guess) + { + x = x_guess.get(); + PINOCCHIO_CHECK_ARGUMENT_SIZE(x.size(), this->getProblemSize()); + } + else + { + x.setZero(); + } - const size_t nc = cones.size(); // num constraints + const size_t nc = constraint_models.size(); // num constraints - int it = 0; + internal::getTimeScalingFromAccelerationToConstraints( + constraint_models, dt, time_scaling_acc_to_constraints); + internal::getTimeScalingFromConstraintsToPosition( + time_scaling_acc_to_constraints, dt, time_scaling_constraints_to_pos); + gs = g.array() / time_scaling_acc_to_constraints.array(); + + int it = 1; PINOCCHIO_EIGEN_MALLOC_NOT_ALLOWED(); #ifdef PINOCCHIO_WITH_HPP_FCL timer.start(); #endif // PINOCCHIO_WITH_HPP_FCL - Scalar complementarity, proximal_metric, dual_feasibility; + Scalar complementarity, proximal_metric, primal_feasibility, dual_feasibility; bool abs_prec_reached = false, rel_prec_reached = false; - x = x_sol; Scalar x_previous_norm_inf = x.template lpNorm(); - for (; it < this->max_it; ++it) + + if (stat_record) + { + stats.reserve(this->max_it); + stats.reset(); + } + + for (; it <= this->max_it; ++it) { x_previous = x; complementarity = Scalar(0); dual_feasibility = Scalar(0); - for (size_t cone_id = 0; cone_id < nc; ++cone_id) + primal_feasibility = Scalar(0); + Eigen::DenseIndex row_id = 0; + for (size_t constraint_id = 0; constraint_id < nc; ++constraint_id) { - Vector3 velocity; // tmp variable - const Eigen::DenseIndex row_id = 3 * cone_id; - const CoulombFrictionCone & cone = cones[cone_id]; - - const auto G_block = G.template block<3, 3>(row_id, row_id, 3, 3); - auto x_segment = x.template segment<3>(row_id); - - velocity.noalias() = G.template middleRows<3>(row_id) * x + g.template segment<3>(row_id); - - // Normal update - Scalar & fz = x_segment.coeffRef(2); - const Scalar fz_previous = fz; - fz -= Scalar(over_relax / G_block.coeff(2, 2)) * velocity[2]; - fz = math::max(Scalar(0), fz); - - // Account for the fz updated value - velocity += G_block.col(2) * (fz - fz_previous); - - // Tangential update - const Scalar min_D_tangent = math::min(G_block.coeff(0, 0), G_block.coeff(1, 1)); - auto f_tangent = x_segment.template head<2>(); - const Vector2 f_tangent_previous = f_tangent; - - assert(min_D_tangent > 0 && "min_D_tangent is zero"); - f_tangent -= over_relax / min_D_tangent * velocity.template head<2>(); - const Scalar f_tangent_norm = f_tangent.norm(); - - const Scalar mu_fz = cone.mu * fz; - if (f_tangent_norm > mu_fz) // Project in the circle of radius mu_fz - f_tangent *= mu_fz / f_tangent_norm; - - // Account for the f_tangent updated value - velocity.noalias() = G_block.template leftCols<2>() * (f_tangent - f_tangent_previous); - - // Compute problem feasibility - Scalar contact_complementarity = cone.computeContactComplementarity(velocity, x_segment); - assert( - contact_complementarity >= Scalar(0) && "contact_complementarity should be positive"); - complementarity = math::max(complementarity, contact_complementarity); - velocity += cone.computeNormalCorrection(velocity); - const Vector3 velocity_proj = cone.dual().project(velocity) - velocity; - Scalar contact_dual_feasibility = velocity_proj.norm(); - dual_feasibility = math::max(dual_feasibility, contact_dual_feasibility); + const ConstraintModel & cmodel = constraint_models[constraint_id]; + const Eigen::DenseIndex constraint_set_size = cmodel.activeSize(); + + auto G_block = G.block(row_id, row_id, constraint_set_size, constraint_set_size); + auto force = x.segment(row_id, constraint_set_size); + + auto velocity = y.segment(row_id, constraint_set_size); + auto dual_to_pos = y_to_pos.segment(row_id, constraint_set_size); + + auto time_scaling_acc_to_constraints_segment = + time_scaling_acc_to_constraints.segment(row_id, constraint_set_size); + auto time_scaling_constraints_to_pos_segment = + time_scaling_constraints_to_pos.segment(row_id, constraint_set_size); + + // Update dual variable + velocity.noalias() = G.middleRows(row_id, constraint_set_size) * x; + velocity += gs.segment(row_id, constraint_set_size); + + typedef PGSConstraintProjectionStepVisitor< + Scalar, decltype(G_block), decltype(force), decltype(velocity), decltype(dual_to_pos), + decltype(time_scaling_acc_to_constraints_segment), + decltype(time_scaling_constraints_to_pos_segment)> + Step; + Step step(over_relax); + step.run( + cmodel, G_block, force, velocity, dual_to_pos, time_scaling_acc_to_constraints_segment, + time_scaling_constraints_to_pos_segment); + // PGSConstraintProjectionStep step(over_relax, set); + // step.project(G_block, velocity, force); + // step.computeFeasibility(velocity, force); + + // Update problem feasibility + complementarity = math::max(complementarity, step.complementarity); + dual_feasibility = math::max(dual_feasibility, step.dual_feasibility); + primal_feasibility = math::max(primal_feasibility, step.primal_feasibility); + + // Update row id for the next constraint + row_id += constraint_set_size; } // Checking stopping residual @@ -118,6 +704,30 @@ namespace pinocchio else rel_prec_reached = false; + if (stat_record) + { + VectorXs tmp = G * x; + tmp += gs; + VectorXs rhs(tmp.size()); + if (solve_ncp) + { + internal::computeDeSaxeCorrection(constraint_models, tmp, rhs); + tmp += rhs; + } + + tmp.array() *= + time_scaling_acc_to_constraints.array(); // back to constraint formulation level + rhs = tmp; + internal::computeDualConeProjection(constraint_models, rhs, rhs); + tmp -= rhs; + Scalar dual_feasibility_ncp = tmp.template lpNorm(); + stats.dual_feasibility_ncp.push_back(dual_feasibility_ncp); + stats.it = it; + stats.primal_feasibility.push_back(primal_feasibility); + stats.dual_feasibility.push_back(dual_feasibility); + stats.complementarity.push_back(complementarity); + } + if (abs_prec_reached || rel_prec_reached) break; @@ -130,16 +740,41 @@ namespace pinocchio PINOCCHIO_EIGEN_MALLOC_ALLOWED(); + // Express the dual variable in the units of constraints + y.array() *= time_scaling_acc_to_constraints.array(); + this->absolute_residual = math::max(complementarity, dual_feasibility); this->relative_residual = proximal_metric; this->it = it; - x_sol.const_cast_derived() = x; if (abs_prec_reached || rel_prec_reached) return true; return false; } + + template + template + bool PGSContactSolverTpl<_Scalar>::solve( + const DelassusOperatorDense & delassus, + const Eigen::MatrixBase & g, + const std::vector & constraint_models, + const Scalar dt, + const boost::optional x_guess, + const Scalar over_relax, + const bool solve_ncp, + const bool stat_record) + + { + typedef std::reference_wrapper WrappedConstraintModelType; + typedef std::vector WrappedConstraintModelVector; + + WrappedConstraintModelVector wrapped_constraint_models( + constraint_models.cbegin(), constraint_models.cend()); + + return solve( + delassus, g, wrapped_constraint_models, dt, x_guess, over_relax, solve_ncp, stat_record); + } } // namespace pinocchio #endif // ifndef __pinocchio_algorithm_pgs_solver_hxx__ diff --git a/include/pinocchio/algorithm/preconditioner-base.hpp b/include/pinocchio/algorithm/preconditioner-base.hpp new file mode 100644 index 0000000000..5555ee907f --- /dev/null +++ b/include/pinocchio/algorithm/preconditioner-base.hpp @@ -0,0 +1,68 @@ +// +// Copyright (c) 2025 INRIA +// +#ifndef __pinocchio_algorithm_preconditioner_base_hpp__ +#define __pinocchio_algorithm_preconditioner_base_hpp__ + +#include "pinocchio/algorithm/fwd.hpp" + +namespace pinocchio +{ + + template + struct PreconditionerBase + { + + Derived & derived() + { + return static_cast(*this); + } + const Derived & derived() const + { + return static_cast(*this); + } + + /// \returns compute the preconditioned variable. + template + void + scale(const Eigen::MatrixBase & x, const Eigen::MatrixBase & res) const + { + derived().scale(x.derived(), res.const_cast_derived()); + } + + /// \returns compute the preconditioned quantity in a inplace fashion. + template + void scaleInPlace(const Eigen::MatrixBase & x) const + { + derived().scaleInPlace(x.derived()); + } + + /// \returns compute the unscaled variable from the preconditioned one. + template + void + unscale(const Eigen::MatrixBase & x, const Eigen::MatrixBase & res) const + { + derived().unscale(x.derived(), res.const_cast_derived()); + } + + /// \returns compute the unscaled variable from the preconditioned one in a inplace fashion. + template + void unscaleInPlace(const Eigen::MatrixBase & x) const + { + derived().unscaleInPlace(x.derived()); + } + + Eigen::DenseIndex rows() const + { + return derived().rows(); + } + Eigen::DenseIndex cols() const + { + return derived().cols(); + } + + }; // struct PreconditionerBase + +} // namespace pinocchio + +#endif // #ifndef __pinocchio_algorithm_preconditioner_base_hpp__ diff --git a/include/pinocchio/algorithm/proximal.hpp b/include/pinocchio/algorithm/proximal.hpp index 97e9cfa107..5fa4f26703 100644 --- a/include/pinocchio/algorithm/proximal.hpp +++ b/include/pinocchio/algorithm/proximal.hpp @@ -1,11 +1,11 @@ // -// Copyright (c) 2019-2022 INRIA +// Copyright (c) 2019-2024 INRIA // #ifndef __pinocchio_algorithm_proximal_hpp__ #define __pinocchio_algorithm_proximal_hpp__ -#include +#include "pinocchio/fwd.hpp" #include "pinocchio/multibody/model.hpp" #include "pinocchio/multibody/data.hpp" diff --git a/include/pinocchio/algorithm/pv.hpp b/include/pinocchio/algorithm/pv.hpp index 566aab97ac..414ad5fee9 100644 --- a/include/pinocchio/algorithm/pv.hpp +++ b/include/pinocchio/algorithm/pv.hpp @@ -119,7 +119,7 @@ namespace pinocchio class ContactModelAllocator, class ContactDataAllocator> PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") - inline const + PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") inline const typename DataTpl::TangentVectorType & constrainedABA( const ModelTpl & model, DataTpl & data, diff --git a/include/pinocchio/algorithm/pv.hxx b/include/pinocchio/algorithm/pv.hxx index 00a492e991..0b6bdb82fa 100644 --- a/include/pinocchio/algorithm/pv.hxx +++ b/include/pinocchio/algorithm/pv.hxx @@ -473,7 +473,7 @@ namespace pinocchio const JointIndex & joint_id = contact_model.joint1_id; int con_dim = contact_model.size(); - const typename RigidConstraintModel::BaumgarteCorrectorParameters & corrector = + const typename RigidConstraintModel::BaumgarteCorrectorVectorParameters & corrector = contact_model.corrector; typename RigidConstraintData::Motion & contact_acc_err = contact_datas[i].contact_acceleration_error; @@ -482,7 +482,7 @@ namespace pinocchio const JointIndex & joint2_id = contact_model.joint2_id; if (joint2_id > 0) - assert(false), "Internal loops are not yet permitted in PV"; + assert(false && "Internal loops are not yet permitted in PV"); else vc2.setZero(); @@ -672,7 +672,7 @@ namespace pinocchio typename RigidConstraintData::Motion & vc2 = contact_datas[i].contact2_velocity; const JointIndex & joint_id = contact_model.joint1_id; int con_dim = contact_model.size(); - const typename RigidConstraintModel::BaumgarteCorrectorParameters & corrector = + const typename RigidConstraintModel::BaumgarteCorrectorVectorParameters & corrector = contact_model.corrector; typename RigidConstraintData::Motion & contact_acc_err = contact_datas[i].contact_acceleration_error; @@ -681,7 +681,7 @@ namespace pinocchio const JointIndex & joint2_id = contact_model.joint2_id; if (joint2_id > 0) - assert(false), "Internal loops are not yet permitted in constrainedABA"; + assert(false && "Internal loops are not yet permitted in constrainedABA"); else vc2.setZero(); diff --git a/include/pinocchio/algorithm/utils/force.hpp b/include/pinocchio/algorithm/utils/force.hpp index a1beaf0648..55f905a0c7 100644 --- a/include/pinocchio/algorithm/utils/force.hpp +++ b/include/pinocchio/algorithm/utils/force.hpp @@ -12,8 +12,14 @@ namespace pinocchio { /// - /// @copydoc changeReferenceFrame(const SE3Tpl &,const ForceDense - /// &,const ReferenceFrame,const ReferenceFrame) \param[out] f_out Resulting force quantity. + /// \copybrief changeReferenceFrame(const SE3Tpl &,const ForceDense + /// &,const ReferenceFrame,const ReferenceFrame) + /// + /// \param[in] placement Placement of the frame having force f_in + /// \param[in] f_in Input force quantity. + /// \param[in] rf_in Reference frame in which m_in is expressed + /// \param[in] rf_out Reference frame in which the result m_out is expressed + /// \param[out] f_out Resulting force quantity. /// template void changeReferenceFrame( @@ -73,10 +79,10 @@ namespace pinocchio } /// - ///  \brief Change the expression of a given Force vector from one reference frame to another + /// \brief Change the expression of a given Force vector from one reference frame to another /// reference frame. /// - ///  \example If ones has an initial f_in Force expressed locally (rf_in=LOCAL) in a Frame + /// \details If ones has an initial f_in Force expressed locally (rf_in=LOCAL) in a Frame /// localized at a given placement value,   ones may want to retrieve its value inside /// another reference frame e.g. the world (rf_out=WORLD). /// @@ -84,7 +90,7 @@ namespace pinocchio /// \param[in] f_in Input force quantity. /// \param[in] rf_in Reference frame in which m_in is expressed /// \param[in] rf_out Reference frame in which the result m_out is expressed - /// \param[out] f_out Resulting force quantity. + /// \return Resulting force quantity. /// template typename ForceIn::ForcePlain changeReferenceFrame( diff --git a/include/pinocchio/algorithm/utils/motion.hpp b/include/pinocchio/algorithm/utils/motion.hpp index 660f9c4801..7883f44d35 100644 --- a/include/pinocchio/algorithm/utils/motion.hpp +++ b/include/pinocchio/algorithm/utils/motion.hpp @@ -13,8 +13,14 @@ namespace pinocchio { /// - /// @copydoc changeReferenceFrame(const SE3Tpl &,const MotionDense - /// &,const ReferenceFrame,const ReferenceFrame) \param[out] m_out Resulting motion quantity. + /// \copybrief changeReferenceFrame(const SE3Tpl &,const MotionDense + /// &,const ReferenceFrame,const ReferenceFrame) + /// + /// \param[in] placement Placement of the frame having velocity m_in + /// \param[in] m_in Input motion quantity. + /// \param[in] rf_in Reference frame in which m_in is expressed + /// \param[in] rf_out Reference frame in which the result m_out is expressed + /// \param[out] m_out Resulting motion quantity. /// template void changeReferenceFrame( @@ -74,10 +80,10 @@ namespace pinocchio } /// - ///  \brief Change the expression of a given Motion vector from one reference frame to another + /// \brief Change the expression of a given Motion vector from one reference frame to another /// reference frame. /// - ///  \example If ones has an initial m_in Motion expressed locally (rf_in=LOCAL) in a Frame + /// \details If ones has an initial m_in Motion expressed locally (rf_in=LOCAL) in a Frame /// localized at a given placement value,   ones may want to retrieve its value inside /// another reference frame e.g. the world (rf_out=WORLD). /// @@ -85,7 +91,7 @@ namespace pinocchio /// \param[in] m_in Input motion quantity. /// \param[in] rf_in Reference frame in which m_in is expressed /// \param[in] rf_out Reference frame in which the result m_out is expressed - /// \param[out] m_out Resulting motion quantity. + /// \return Resulting motion quantity. /// template typename MotionIn::MotionPlain changeReferenceFrame( diff --git a/include/pinocchio/alloca.hpp b/include/pinocchio/alloca.hpp new file mode 100644 index 0000000000..962f3f14b5 --- /dev/null +++ b/include/pinocchio/alloca.hpp @@ -0,0 +1,24 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#ifndef __pinocchio_alloca_hpp__ +#define __pinocchio_alloca_hpp__ + +#ifdef WIN32 + #include +#else + #include +#endif + +#define PINOCCHIO_ALLOCA EIGEN_ALLOCA +#define PINOCCHIO_ALIGNED_PTR(ptr, align) \ + reinterpret_cast(((intptr_t)ptr + (align - 1)) & ~(align - 1)) +#define PINOCCHIO_EIGEN_MAP_ALLOCA(S, rows, cols) \ + PINOCCHIO_EIGEN_MAP_ALLOCA_ALIGNED(S, rows, cols, EIGEN_DEFAULT_ALIGN_BYTES) +#define PINOCCHIO_EIGEN_MAP_ALLOCA_ALIGNED(S, rows, cols, align) \ + static_cast(PINOCCHIO_ALIGNED_PTR( \ + PINOCCHIO_ALLOCA(size_t(rows * cols) * sizeof(S) + (align > 0 ? (align - 1) : 0)), align)), \ + rows, cols + +#endif // ifndef __pinocchio_alloca_hpp__ diff --git a/include/pinocchio/autodiff/casadi.hpp b/include/pinocchio/autodiff/casadi.hpp index 0340d0121e..218fbdb78f 100644 --- a/include/pinocchio/autodiff/casadi.hpp +++ b/include/pinocchio/autodiff/casadi.hpp @@ -10,8 +10,6 @@ #include "pinocchio/math/fwd.hpp" #include -#include -#include namespace boost { @@ -118,27 +116,27 @@ namespace Eigen MulCost = 2 }; - static ::casadi::Matrix epsilon() + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline ::casadi::Matrix epsilon() { return ::casadi::Matrix(std::numeric_limits::epsilon()); } - static ::casadi::Matrix dummy_precision() + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline ::casadi::Matrix dummy_precision() { return ::casadi::Matrix(NumTraits::dummy_precision()); } - static ::casadi::Matrix highest() + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline ::casadi::Matrix highest() { return ::casadi::Matrix(std::numeric_limits::max()); } - static ::casadi::Matrix lowest() + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline ::casadi::Matrix lowest() { return ::casadi::Matrix(std::numeric_limits::min()); } - static int digits10() + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline int digits10() { return std::numeric_limits::digits10; } diff --git a/include/pinocchio/autodiff/cppad.hpp b/include/pinocchio/autodiff/cppad.hpp index 3004c751f5..a0f9dbe691 100644 --- a/include/pinocchio/autodiff/cppad.hpp +++ b/include/pinocchio/autodiff/cppad.hpp @@ -108,32 +108,32 @@ namespace Eigen // machine epsilon with type of real part of x // (use assumption that Base is not complex) - static CppAD::AD epsilon(void) + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline CppAD::AD epsilon(void) { return CppAD::numeric_limits>::epsilon(); } // relaxed version of machine epsilon for comparison of different // operations that should result in the same value - static CppAD::AD dummy_precision(void) + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline CppAD::AD dummy_precision(void) { return 100. * CppAD::numeric_limits>::epsilon(); } // minimum normalized positive value - static CppAD::AD lowest(void) + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline CppAD::AD lowest(void) { return CppAD::numeric_limits>::min(); } // maximum finite value - static CppAD::AD highest(void) + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline CppAD::AD highest(void) { return CppAD::numeric_limits>::max(); } // number of decimal digits that can be represented without change. - static int digits10(void) + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline int digits10(void) { return CppAD::numeric_limits>::digits10; } diff --git a/include/pinocchio/bindings/python/algorithm/constraints/baumgarte-corrector-parameters.hpp b/include/pinocchio/bindings/python/algorithm/constraints/baumgarte-corrector-parameters.hpp new file mode 100644 index 0000000000..02038633c3 --- /dev/null +++ b/include/pinocchio/bindings/python/algorithm/constraints/baumgarte-corrector-parameters.hpp @@ -0,0 +1,52 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_python_algorithm_constraints_baumgarte_corrector_parameters_hpp__ +#define __pinocchio_python_algorithm_constraints_baumgarte_corrector_parameters_hpp__ + +#include "pinocchio/algorithm/constraints/baumgarte-corrector-parameters.hpp" + +#include "pinocchio/bindings/python/utils/cast.hpp" +#include "pinocchio/bindings/python/utils/copyable.hpp" +#include "pinocchio/bindings/python/utils/comparable.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + template + struct BaumgarteCorrectorParametersPythonVisitor + : public boost::python::def_visitor< + BaumgarteCorrectorParametersPythonVisitor> + { + typedef typename BaumgarteCorrectorParameters::Scalar Scalar; + typedef BaumgarteCorrectorParameters Self; + + public: + template + void visit(PyClass & cl) const + { + cl.def(bp::init(bp::args("self", "Kp", "Kd"), "Default constructor.")) + .def_readwrite("Kp", &Self::Kp, "Proportional corrector value.") + .def_readwrite("Kd", &Self::Kd, "Damping corrector value.") + .def(ComparableVisitor::value>()); + } + + static void expose() + { + if (eigenpy::check_registration()) + return; + bp::class_( + "BaumgarteCorrectorParameters", "Parameters of the Baumgarte Corrector.", bp::no_init) + .def(BaumgarteCorrectorParametersPythonVisitor()); + } + }; + + } // namespace python +} // namespace pinocchio + +#endif // ifndef + // __pinocchio_python_algorithm_constraints_baumgarte_corrector_parameters_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp b/include/pinocchio/bindings/python/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp new file mode 100644 index 0000000000..03cd1da820 --- /dev/null +++ b/include/pinocchio/bindings/python/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp @@ -0,0 +1,61 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_python_algorithm_constraints_baumgarte_corrector_vector_parameters_hpp__ +#define __pinocchio_python_algorithm_constraints_baumgarte_corrector_vector_parameters_hpp__ + +#include "pinocchio/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp" + +#include "pinocchio/bindings/python/utils/cast.hpp" +#include "pinocchio/bindings/python/utils/copyable.hpp" +#include "pinocchio/bindings/python/utils/comparable.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + template + struct BaumgarteCorrectorVectorParametersPythonVisitor + : public boost::python::def_visitor< + BaumgarteCorrectorVectorParametersPythonVisitor> + { + typedef typename BaumgarteCorrectorVectorParameters::Scalar Scalar; + typedef typename BaumgarteCorrectorVectorParameters::VectorType VectorType; + typedef BaumgarteCorrectorVectorParameters Self; + + public: + template + void visit(PyClass & cl) const + { + cl + // .def(bp::init(bp::args("self", "size"), "Default constructor.")) + + .def_readwrite("Kp", &Self::Kp, "Proportional corrector value.") + .def_readwrite("Kd", &Self::Kd, "Damping corrector value.") + + // .def(CastVisitor()) + // .def(ExposeConstructorByCastVisitor< + // Self, + // ::pinocchio::context::RigidConstraintModel::BaumgarteCorrectorVectorParameters>()) + .def(ComparableVisitor::value>()); + } + + static void expose(const std::string & classname) + { + // eigenpy::enableEigenPySpecific(); + if (eigenpy::check_registration()) + return; + bp::class_( + classname.c_str(), "Parameters of the Baumgarte Corrector.", bp::no_init) + .def(BaumgarteCorrectorVectorParametersPythonVisitor()); + } + }; + + } // namespace python +} // namespace pinocchio + +#endif // ifndef + // __pinocchio_python_algorithm_constraints_baumgarte_corrector_vector_parameters_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/constraints/constraint-data-base.hpp b/include/pinocchio/bindings/python/algorithm/constraints/constraint-data-base.hpp new file mode 100644 index 0000000000..cbc572be23 --- /dev/null +++ b/include/pinocchio/bindings/python/algorithm/constraints/constraint-data-base.hpp @@ -0,0 +1,45 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_python_algorithm_constraints_data_base_hpp__ +#define __pinocchio_python_algorithm_constraints_data_base_hpp__ + +#include +#include +#include + +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/constraint-data-base.hpp" +#include "pinocchio/bindings/python/fwd.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + template + struct ConstraintDataBasePythonVisitor + : public bp::def_visitor> + { + typedef ConstraintDataDerived Self; + + public: + template + void visit(PyClass & cl) const + { + cl.def("classname", &Self::classname) + .staticmethod("classname") + .def("shortname", &Self::shortname, "Short name of the class.") +#ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS + .def(bp::self == bp::self) + .def(bp::self != bp::self) +#endif + ; + } + }; + } // namespace python +} // namespace pinocchio + +#endif // ifndef __pinocchio_python_algorithm_constraints_data_base_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/constraints/constraint-data-inheritance.hpp b/include/pinocchio/bindings/python/algorithm/constraints/constraint-data-inheritance.hpp new file mode 100644 index 0000000000..700e64d404 --- /dev/null +++ b/include/pinocchio/bindings/python/algorithm/constraints/constraint-data-inheritance.hpp @@ -0,0 +1,87 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_python_algorithm_constraints_data_inheritance_hpp__ +#define __pinocchio_python_algorithm_constraints_data_inheritance_hpp__ + +#include +#include +#include + +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/frame-constraint-data-base.hpp" +#include "pinocchio/algorithm/constraints/point-constraint-data-base.hpp" +#include "pinocchio/bindings/python/fwd.hpp" +#include "pinocchio/bindings/python/utils/macros.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + // Default inheritance Visitor Template + template + struct ConstraintDataInheritancePythonVisitor + : public bp::def_visitor> + { + public: + template + void visit(PyClass &) const + { + } + }; + + // Specialize + template + struct ConstraintDataInheritancePythonVisitor> + : public bp::def_visitor>> + { + public: + template + void visit(PyClass & cl) const + { + cl.def(bp::init<>(bp::arg("self"), "Default constructor.")) + .def(bp::init( + bp::args("self", "constraint_model"), "From model constructor.")) + .PINOCCHIO_ADD_PROPERTY(T, constraint_force, "Resulting force.") + .PINOCCHIO_ADD_PROPERTY(T, oMc1, "Placement of the constraint frame 1 wrt WORLD.") + .PINOCCHIO_ADD_PROPERTY(T, oMc2, "Placement of the constraint frame 2 wrt WORLD.") + .PINOCCHIO_ADD_PROPERTY(T, c1Mc2, "Placement of the constraint frame 2 wrt frame 1.") + .PINOCCHIO_ADD_PROPERTY(T, constraint_position_error, "Constraint placement (6D) error.") + .PINOCCHIO_ADD_PROPERTY(T, constraint_velocity_error, "Constraint velocity (6D) error.") + .PINOCCHIO_ADD_PROPERTY( + T, constraint_acceleration_error, "Constraint acceleration (6D) error.") + .PINOCCHIO_ADD_PROPERTY( + T, constraint_acceleration_biais_term, "Constraint acceleration (6D) term."); + } + }; + + template + struct ConstraintDataInheritancePythonVisitor> + : public bp::def_visitor>> + { + public: + template + void visit(PyClass & cl) const + { + cl.def(bp::init<>(bp::arg("self"), "Default constructor.")) + .def(bp::init( + bp::args("self", "constraint_model"), "From model constructor.")) + .PINOCCHIO_ADD_PROPERTY(T, constraint_force, "Resulting force.") + .PINOCCHIO_ADD_PROPERTY(T, oMc1, "Placement of the constraint frame 1 wrt WORLD.") + .PINOCCHIO_ADD_PROPERTY(T, oMc2, "Placement of the constraint frame 2 wrt WORLD.") + .PINOCCHIO_ADD_PROPERTY(T, c1Mc2, "Placement of the constraint frame 2 wrt frame 1.") + .PINOCCHIO_ADD_PROPERTY(T, constraint_position_error, "Constraint position (3D) error.") + .PINOCCHIO_ADD_PROPERTY(T, constraint_velocity_error, "Constraint velocity (3D) error.") + .PINOCCHIO_ADD_PROPERTY( + T, constraint_acceleration_error, "Constraint acceleration (3D) error.") + .PINOCCHIO_ADD_PROPERTY( + T, constraint_acceleration_biais_term, "Constraint acceleration (3D) term."); + } + }; + } // namespace python +} // namespace pinocchio + +#endif // ifndef __pinocchio_python_algorithm_constraints_data_inheritance_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/constraints/constraint-data.hpp b/include/pinocchio/bindings/python/algorithm/constraints/constraint-data.hpp new file mode 100644 index 0000000000..2cf3abd91d --- /dev/null +++ b/include/pinocchio/bindings/python/algorithm/constraints/constraint-data.hpp @@ -0,0 +1,68 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_python_algorithm_constraints_data_hpp__ +#define __pinocchio_python_algorithm_constraints_data_hpp__ + +#include "pinocchio/algorithm/constraints/constraint-data-generic.hpp" +#include "pinocchio/serialization/constraints-data.hpp" + +#include "pinocchio/bindings/python/algorithm/constraints/constraint-data-base.hpp" +#include "pinocchio/bindings/python/utils/printable.hpp" +#include "pinocchio/bindings/python/serialization/serializable.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + template + struct ExtractConstraintDataVariantTypeVisitor + { + typedef typename ConstraintData::ConstraintCollection ConstraintCollection; + typedef bp::object result_type; + + template + result_type operator()(const ConstraintDataBase & cdata) const + { + bp::object obj(boost::ref(cdata.derived())); + return obj; + } + + result_type operator()(boost::blank) const + { + bp::object obj; + return obj; + } + + static result_type extract(const ConstraintData & cdata) + { + return boost::apply_visitor(ExtractConstraintDataVariantTypeVisitor(), cdata); + } + }; + + template + struct ConstraintDataPythonVisitor + { + static void expose() + { + bp::class_("ConstraintData", "Generic Constraint Data.", bp::no_init) + .def(bp::init<>(bp::arg("self"), "Default constructor.")) + .def(bp::init( + bp::args("self", "constraint_data"), "Copy constructor.")) + .def(ConstraintDataBasePythonVisitor()) + .def(PrintableVisitor()) + .def(SerializableVisitor()) + .def( + "extract", ExtractConstraintDataVariantTypeVisitor::extract, + bp::arg("self"), + "Returns a reference of the internal constraint managed by the ConstraintData.", + bp::with_custodian_and_ward_postcall<0, 1>()); + } + }; + } // namespace python +} // namespace pinocchio + +#endif // ifndef __pinocchio_python_algorithm_constraints_data_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/constraints/constraint-model-base.hpp b/include/pinocchio/bindings/python/algorithm/constraints/constraint-model-base.hpp new file mode 100644 index 0000000000..cba889fca8 --- /dev/null +++ b/include/pinocchio/bindings/python/algorithm/constraints/constraint-model-base.hpp @@ -0,0 +1,219 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_python_algorithm_constraints_model_base_hpp__ +#define __pinocchio_python_algorithm_constraints_model_base_hpp__ + +#include +#include +#include +#include + +#include "pinocchio/multibody/model.hpp" +#include "pinocchio/multibody/data.hpp" +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/constraint-model-base.hpp" + +#include "pinocchio/bindings/python/fwd.hpp" +#include "pinocchio/bindings/python/utils/macros.hpp" +#include "pinocchio/bindings/python/utils/eigen.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/baumgarte-corrector-parameters.hpp" + +namespace pinocchio +{ + namespace python + { + + namespace bp = boost::python; + + template + struct ConstraintModelBasePythonVisitor + : public bp::def_visitor> + { + typedef ConstraintModelDerived Self; + typedef typename Self::Scalar Scalar; + typedef typename Self::ConstraintSet ConstraintSet; + typedef typename Self::ConstraintData ConstraintData; + typedef context::Model Model; + typedef context::Data Data; + typedef typename traits::ComplianceVectorTypeRef ComplianceVectorTypeRef; + typedef typename traits::ComplianceVectorTypeConstRef ComplianceVectorTypeConstRef; + typedef typename traits::JacobianMatrixType JacobianMatrixType; + + public: + template + void visit(PyClass & cl) const + { + cl.PINOCCHIO_ADD_PROPERTY(Self, name, "Name of the constraint.") + .def("classname", &Self::classname) + .staticmethod("classname") + .def("shortname", &Self::shortname, "Short name of the class.") + .def( + "createData", &Self::createData, "Create a Data object for the given constraint model.") + .add_property( + "set", + bp::make_function( // + +[](const Self & self) -> const ConstraintSet & { return self.set(); }, + bp::return_internal_reference<>()), + bp::make_function( // + +[](Self & self, const ConstraintSet & new_set) { self.set() = new_set; }), + "Constraint set.") + .add_property( + "compliance", + bp::make_function( // + +[](const Self & self) -> context::VectorXs { return self.compliance(); }), + bp::make_function( // + +[](Self & self, const context::VectorXs & new_vector) { + self.compliance() = new_vector; + }), + "Compliance of the constraint.") + .def( + "size", +[](const Self & self) -> int { return self.size(); }, "Constraint size.") + .def( + "activeSize", +[](const Self & self) -> int { return self.activeSize(); }, + "Constraint active size.") + .def( + "calc", &calc, bp::args("self", "model", "data", "constraint_data"), + "Evaluate the constraint values at the current state given by data and store the " + "results.") + .def( + "jacobian", + (JacobianMatrixType(Self::*)(const Model &, const Data &, ConstraintData &) + const)&Self::jacobian, + bp::args("self", "model", "data", "constraint_data"), + "Compute the constraint jacobian.") + .def( + "resize", &resize, bp::args("self", "model", "data", "constraint_data"), + "Resize the constraint before evaluation.") + .def( + "jacobianMatrixProduct", &jacobianMatrixProduct, + bp::args("self", "model", "data", "constraint_data", "matrix"), + "Forward chain rule: return product between the jacobian and a matrix.") + .def( + "jacobianTransposeMatrixProduct", &jacobianTransposeMatrixProduct, + bp::args("self", "model", "data", "constraint_data", "matrix"), + "Backward chain rule: return product between the jacobian transpose and a matrix.") + .def( + "getRowActivableSparsityPattern", &Self::getRowActivableSparsityPattern, + bp::args("self", "row_id"), bp::return_value_policy(), + "Colwise sparsity associated with a given row.") + .def( + "getRowActiveSparsityPattern", &Self::getRowActiveSparsityPattern, + bp::args("self", "row_id"), bp::return_value_policy(), + "Active colwise sparsity associated with a given row.") + .def( + "getRowActivableIndexes", &Self::getRowActivableIndexes, bp::args("self", "row_id"), + bp::return_value_policy(), + "Vector of the activable indexes associated with a given row.") + .def( + "getRowActiveIndexes", &Self::getRowActiveIndexes, bp::args("self", "row_id"), + bp::return_value_policy(), + "Vector of the active indexes associated with a given row.") + .def( + "getActiveCompliance", bp::make_function(+[](const Self & self) -> context::VectorXs { + return self.getActiveCompliance(); + }), + "Vector of the active compliance internally stored in the constraint.") +#ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS + .def(bp::self == bp::self) + .def(bp::self != bp::self) +#endif + ; + // CHOICE: right now we use the scalar Baumgarte + // if (::pinocchio::traits::has_baumgarte_corrector_vector) + // { + // typedef typename traits::BaumgarteCorrectorVectorParameters + // BaumgarteCorrectorVectorParameters; + // typedef typename traits::BaumgarteCorrectorVectorParametersRef + // BaumgarteCorrectorVectorParametersRef; + + // typedef typename std::conditional< + // std::is_reference::value, + // bp::return_internal_reference<>, bp::with_custodian_and_ward_postcall<0, 1>>::type + // ReturnPolicy; + + // cl.add_property( + // "baumgarte_corrector_vector_parameters", + // bp::make_function( // + // +[](Self & self) -> BaumgarteCorrectorVectorParametersRef { + // return self.baumgarte_corrector_vector_parameters(); + // }, + // ReturnPolicy()), + // bp::make_function( // + // +[](Self & self, const BaumgarteCorrectorVectorParameters & copy) { + // self.baumgarte_corrector_vector_parameters() = copy; + // }), + // "Baumgarte vector parameters associated with the constraint."); + + // typedef typename BaumgarteCorrectorVectorParameters::VectorType BaumgarteVectorType; + // const std::string BaumgarteVectorType_name = getEigenTypeName(); + + // const std::string BaumgarteCorrectorVectorParameter_classname = + // "BaumgarteCorrectorVectorParameters_" + BaumgarteVectorType_name; + + // BaumgarteCorrectorVectorParametersPythonVisitor:: + // expose(BaumgarteCorrectorVectorParameter_classname); + // } + if (::pinocchio::traits::has_baumgarte_corrector) + { + typedef BaumgarteCorrectorParametersTpl BaumgarteCorrectorParameters; + BaumgarteCorrectorParametersPythonVisitor::expose(); + + cl.add_property( + "baumgarte_corrector_parameters", + bp::make_function( // + +[](Self & self) -> BaumgarteCorrectorParameters & { + return self.baumgarte_corrector_parameters(); + }, + bp::return_internal_reference<>()), + bp::make_function( // + +[](Self & self, const BaumgarteCorrectorParameters & copy) { + self.baumgarte_corrector_parameters() = copy; + }, + bp::return_internal_reference<>()), + "Baumgarte parameters associated with the constraint."); + } + } + + static void + resize(Self & self, const Model & model, const Data & data, ConstraintData & constraint_data) + { + self.resize(model, data, constraint_data); + } + + static void calc( + const Self & self, const Model & model, const Data & data, ConstraintData & constraint_data) + { + self.calc(model, data, constraint_data); + } + + static context::MatrixXs jacobianMatrixProduct( + const Self & self, + const Model & model, + const Data & data, + const ConstraintData & constraint_data, + const context::MatrixXs & matrix) + { + context::MatrixXs res = context::MatrixXs::Zero(self.activeSize(), matrix.cols()); + self.jacobianMatrixProduct(model, data, constraint_data, matrix, res); + return res; + } + + static context::MatrixXs jacobianTransposeMatrixProduct( + const Self & self, + const Model & model, + const Data & data, + const ConstraintData & constraint_data, + const context::MatrixXs & matrix) + { + context::MatrixXs res = context::MatrixXs::Zero(model.nv, matrix.cols()); + self.jacobianTransposeMatrixProduct(model, data, constraint_data, matrix, res); + return res; + } + }; + } // namespace python +} // namespace pinocchio + +#endif // ifndef __pinocchio_python_algorithm_constraints_model_base_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/constraints/constraint-model-inheritance.hpp b/include/pinocchio/bindings/python/algorithm/constraints/constraint-model-inheritance.hpp new file mode 100644 index 0000000000..40a1baadac --- /dev/null +++ b/include/pinocchio/bindings/python/algorithm/constraints/constraint-model-inheritance.hpp @@ -0,0 +1,271 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_python_algorithm_constraints_model_inheritance_hpp__ +#define __pinocchio_python_algorithm_constraints_model_inheritance_hpp__ + +#include +#include +#include + +#include "pinocchio/multibody/model.hpp" +#include "pinocchio/algorithm/constraints/fwd.hpp" +#include "pinocchio/algorithm/constraints/frame-constraint-model-base.hpp" +#include "pinocchio/algorithm/constraints/point-constraint-model-base.hpp" +#include "pinocchio/bindings/python/fwd.hpp" +#include "pinocchio/bindings/python/utils/macros.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + // Default inheritance Visitor Template + template + struct ConstraintModelInheritancePythonVisitor + : public bp::def_visitor> + { + public: + template + void visit(PyClass &) const + { + } + }; + + // Specialize + template + struct ConstraintModelInheritancePythonVisitor> + : public bp::def_visitor< + ConstraintModelInheritancePythonVisitor>> + { + typedef typename T::Scalar Scalar; + typedef typename T::ConstraintSet ConstraintSet; + typedef typename T::ConstraintData ConstraintData; + typedef context::Model Model; + typedef context::Data Data; + + public: + template + void visit(PyClass & cl) const + { + cl.def(bp::init( + (bp::arg("self"), bp::arg("model"), bp::arg("joint1_id"), + bp::arg("joint1_placement"), bp::arg("joint2_id"), bp::arg("joint2_placement")), + "Contructor from given joint index and placement for the two joints " + "implied in the constraint.")) + .def(bp::init( + (bp::arg("self"), bp::arg("model"), bp::arg("joint1_id"), bp::arg("joint1_placement")), + "Contructor from given joint index and placement of the first joint " + "implied in the constraint.")) + .def(bp::init( + (bp::arg("self"), bp::arg("model"), bp::arg("joint1_id"), bp::arg("joint2_id")), + "Contructor from given joint index for the two joints " + "implied in the constraint.")) + .def(bp::init( + (bp::arg("self"), bp::arg("model"), bp::arg("joint1_id")), + "Contructor from given joint index of the first joint " + "implied in the constraint.")) + .PINOCCHIO_ADD_PROPERTY(T, joint1_id, "Index of the first joint in the model tree.") + .PINOCCHIO_ADD_PROPERTY(T, joint2_id, "Index of the second joint in the model tree.") + .PINOCCHIO_ADD_PROPERTY( + T, joint1_placement, "Position of attached point with respect to the frame of joint1.") + .PINOCCHIO_ADD_PROPERTY( + T, joint2_placement, "Position of attached point with respect to the frame of joint2.") + .PINOCCHIO_ADD_PROPERTY( + T, desired_constraint_offset, "Desired constraint shift at position level.") + .PINOCCHIO_ADD_PROPERTY( + T, desired_constraint_velocity, "Desired constraint velocity at velocity level.") + .PINOCCHIO_ADD_PROPERTY( + T, desired_constraint_acceleration, + "Desired constraint velocity at acceleration level.") + .PINOCCHIO_ADD_PROPERTY( + T, colwise_joint1_sparsity, "Colwise sparsity pattern associated with joint 1.") + .PINOCCHIO_ADD_PROPERTY( + T, colwise_joint2_sparsity, "Colwise sparsity pattern associated with joint 2.") + .PINOCCHIO_ADD_PROPERTY( + T, joint1_span_indexes, "Jointwise span indexes associated with joint 1.") + .PINOCCHIO_ADD_PROPERTY( + T, joint2_span_indexes, "Jointwise span indexes associated with joint 2.") + .PINOCCHIO_ADD_PROPERTY(T, loop_span_indexes, "Loop span indexes.") + .PINOCCHIO_ADD_PROPERTY( + T, colwise_sparsity, "Sparsity pattern associated to the constraint.") + .PINOCCHIO_ADD_PROPERTY( + T, colwise_span_indexes, "Indexes of the columns spanned by the constraints.") + .def( + "getA1", &getA1, bp::args("self", "constraint_data", "reference_frame"), + "Returns the constraint projector associated with joint 1. " + "This matrix transforms a spatial velocity expressed in a reference frame " + "to the first component of the constraint associated with joint 1.") + .def( + "getA2", &getA2, bp::args("self", "constraint_data", "reference_frame"), + "Returns the constraint projector associated with joint 2. " + "This matrix transforms a spatial velocity expressed in a reference frame " + "to the first component of the constraint associated with joint 2."); + } + + static context::Matrix6s + getA1(const T & self, const ConstraintData & constraint_data, ReferenceFrame rf) + { + context::Matrix6s res; + switch (rf) + { + case WORLD: + res = self.getA1(constraint_data, WorldFrameTag()); + case LOCAL: + res = self.getA1(constraint_data, LocalFrameTag()); + case LOCAL_WORLD_ALIGNED: + res = self.getA1(constraint_data, LocalWorldAlignedFrameTag()); + } + return res; + } + + static context::Matrix6s + getA2(const T & self, const ConstraintData & constraint_data, ReferenceFrame rf) + { + context::Matrix6s res; + switch (rf) + { + case WORLD: + res = self.getA2(constraint_data, WorldFrameTag()); + case LOCAL: + res = self.getA2(constraint_data, LocalFrameTag()); + case LOCAL_WORLD_ALIGNED: + res = self.getA2(constraint_data, LocalWorldAlignedFrameTag()); + } + return res; + } + }; + + template + struct ConstraintModelInheritancePythonVisitor> + : public bp::def_visitor< + ConstraintModelInheritancePythonVisitor>> + { + typedef typename T::Scalar Scalar; + typedef typename T::ConstraintSet ConstraintSet; + typedef typename T::ConstraintData ConstraintData; + typedef context::Model Model; + typedef context::Data Data; + + public: + template + void visit(PyClass & cl) const + { + cl.def(bp::init( + (bp::arg("self"), bp::arg("model"), bp::arg("joint1_id"), + bp::arg("joint1_placement"), bp::arg("joint2_id"), bp::arg("joint2_placement")), + "Contructor from given joint index and placement for the two joints " + "implied in the constraint.")) + .def(bp::init( + (bp::arg("self"), bp::arg("model"), bp::arg("joint1_id"), bp::arg("joint1_placement")), + "Contructor from the given joint index and the placement wrt the first joint " + "implied in the constraint.")) + .def(bp::init( + (bp::arg("self"), bp::arg("model"), bp::arg("joint1_id"), bp::arg("joint2_id")), + "Contructor from given joint indexes for the two joints " + "implied in the constraint.")) + .def(bp::init( + (bp::arg("self"), bp::arg("model"), bp::arg("joint1_id")), + "Contructor from given joint index of the first joint " + "implied in the constraint.")) + .PINOCCHIO_ADD_PROPERTY(T, joint1_id, "Index of the first joint in the model tree.") + .PINOCCHIO_ADD_PROPERTY(T, joint2_id, "Index of the second joint in the model tree.") + .PINOCCHIO_ADD_PROPERTY( + T, joint1_placement, "Position of attached point with respect to the frame of joint1.") + .PINOCCHIO_ADD_PROPERTY( + T, joint2_placement, "Position of attached point with respect to the frame of joint2.") + .PINOCCHIO_ADD_PROPERTY( + T, desired_constraint_offset, "Desired constraint shift at position level.") + .PINOCCHIO_ADD_PROPERTY( + T, desired_constraint_velocity, "Desired constraint velocity at velocity level.") + .PINOCCHIO_ADD_PROPERTY( + T, desired_constraint_acceleration, + "Desired constraint velocity at acceleration level.") + .PINOCCHIO_ADD_PROPERTY( + T, colwise_joint1_sparsity, "Colwise sparsity pattern associated with joint 1.") + .PINOCCHIO_ADD_PROPERTY( + T, colwise_joint2_sparsity, "Colwise sparsity pattern associated with joint 2.") + .PINOCCHIO_ADD_PROPERTY( + T, joint1_span_indexes, "Jointwise span indexes associated with joint 1.") + .PINOCCHIO_ADD_PROPERTY( + T, joint2_span_indexes, "Jointwise span indexes associated with joint 2.") + .PINOCCHIO_ADD_PROPERTY(T, loop_span_indexes, "Loop span indexes.") + .PINOCCHIO_ADD_PROPERTY( + T, colwise_sparsity, "Sparsity pattern associated to the constraint.") + .PINOCCHIO_ADD_PROPERTY( + T, colwise_span_indexes, "Indexes of the columns spanned by the constraints.") + .def( + "getA1", &getA1, bp::args("self", "constraint_data", "reference_frame"), + "Returns the constraint projector associated with joint 1. " + "This matrix transforms a spatial velocity expressed in a reference frame " + "to the first component of the constraint associated with joint 1.") + .def( + "getA2", &getA2, bp::args("self", "constraint_data", "reference_frame"), + "Returns the constraint projector associated with joint 2. " + "This matrix transforms a spatial velocity expressed in a reference frame " + "to the first component of the constraint associated with joint 2.") + .def( + "computeConstraintSpatialInertia", &computeConstraintSpatialInertia, + bp::args("self", "placement", "diagonal_constraint_inertia"), + "This function computes the spatial inertia associated with the constraint.") + // The two following methods are not exposed as they rely on allocators. + // .def("appendCouplingConstraintInertias", + // &appendCouplingConstraintInertias, + // bp::args("self", "model", "data", "constraint_data", "diagonal_constraint_inertia", + // "inertias"), "Append the constraint diagonal inertia to the joint inertias." + // ) + // .def("mapConstraintForceToJointForces", + // &mapConstraintForceToJointForces, + // bp::args("self", "model", "data", "constraint_data", "constraint_forces", + // "joint_forces"), "Map the constraint forces (aka constraint Lagrange multipliers) to + // the forces supported by the joints." + // ) + ; + } + + static context::Matrix36s + getA1(const T & self, const ConstraintData & constraint_data, ReferenceFrame rf) + { + context::Matrix36s res; + switch (rf) + { + case WORLD: + res = self.getA1(constraint_data, WorldFrameTag()); + case LOCAL: + res = self.getA1(constraint_data, LocalFrameTag()); + case LOCAL_WORLD_ALIGNED: + res = self.getA1(constraint_data, LocalWorldAlignedFrameTag()); + } + return res; + } + + static context::Matrix36s + getA2(const T & self, const ConstraintData & constraint_data, ReferenceFrame rf) + { + context::Matrix36s res; + switch (rf) + { + case WORLD: + res = self.getA2(constraint_data, WorldFrameTag()); + case LOCAL: + res = self.getA2(constraint_data, LocalFrameTag()); + case LOCAL_WORLD_ALIGNED: + res = self.getA2(constraint_data, LocalWorldAlignedFrameTag()); + } + return res; + } + + static context::Matrix6s computeConstraintSpatialInertia( + const T & self, + const context::SE3 & placement, + const context::Vector3s & diagonal_constraint_inertia) + { + return self.computeConstraintSpatialInertia(placement, diagonal_constraint_inertia); + } + }; + } // namespace python +} // namespace pinocchio + +#endif // ifndef __pinocchio_python_algorithm_constraints_model_inheritance_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/constraints/constraint-model.hpp b/include/pinocchio/bindings/python/algorithm/constraints/constraint-model.hpp new file mode 100644 index 0000000000..30e85b905c --- /dev/null +++ b/include/pinocchio/bindings/python/algorithm/constraints/constraint-model.hpp @@ -0,0 +1,66 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_python_algorithm_constraints_model_hpp__ +#define __pinocchio_python_algorithm_constraints_model_hpp__ + +#include "pinocchio/algorithm/constraints/constraint-model-generic.hpp" +#include "pinocchio/serialization/constraints-model.hpp" + +#include "pinocchio/bindings/python/algorithm/constraints/constraint-model-base.hpp" +#include "pinocchio/bindings/python/utils/printable.hpp" +#include "pinocchio/bindings/python/serialization/serializable.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + template + struct ExtractConstraintModelVariantTypeVisitor + { + typedef typename ConstraintModel::ConstraintCollection ConstraintCollection; + typedef bp::object result_type; + + template + result_type operator()(const ConstraintModelBase & cmodel) const + { + bp::object obj(boost::ref(cmodel.derived())); + return obj; + } + + result_type operator()(boost::blank) const + { + bp::object obj; + return obj; + } + + static result_type extract(const ConstraintModel & cmodel) + { + return boost::apply_visitor(ExtractConstraintModelVariantTypeVisitor(), cmodel); + } + }; + + template + struct ConstraintModelPythonVisitor + { + static void expose() + { + bp::class_("ConstraintModel", "Generic Constraint Model", bp::no_init) + .def(bp::init(bp::args("self", "other"), "Copy constructor")) + .def(ConstraintModelBasePythonVisitor()) + .def(PrintableVisitor()) + .def(SerializableVisitor()) + .def( + "extract", ExtractConstraintModelVariantTypeVisitor::extract, + bp::arg("self"), + "Returns a reference of the internal constraint managed by the ConstraintModel", + bp::with_custodian_and_ward_postcall<0, 1>()); + } + }; + } // namespace python +} // namespace pinocchio + +#endif // ifndef __pinocchio_python_algorithm_constraints_model_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/constraints/constraints-datas.hpp b/include/pinocchio/bindings/python/algorithm/constraints/constraints-datas.hpp new file mode 100644 index 0000000000..300bdf8caa --- /dev/null +++ b/include/pinocchio/bindings/python/algorithm/constraints/constraints-datas.hpp @@ -0,0 +1,83 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_python_algorithm_constraints_datas_hpp__ +#define __pinocchio_python_algorithm_constraints_datas_hpp__ + +#include "pinocchio/algorithm/constraints/constraint-data-generic.hpp" +#include "pinocchio/algorithm/constraints/constraint-collection-default.hpp" +#include "pinocchio/bindings/python/fwd.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/constraint-data-inheritance.hpp" +#include "pinocchio/bindings/python/utils/printable.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + // generic expose_constraint_data : do nothing special + template + inline bp::class_ & expose_constraint_data(bp::class_ & cl) + { + return cl; + } + + // specialization for ConstraintDatas + template<> + bp::class_ & + expose_constraint_data(bp::class_ & cl) + { + return cl; + } + + template<> + bp::class_ & + expose_constraint_data(bp::class_ & cl) + { + return cl; + } + + template<> + bp::class_ & + expose_constraint_data(bp::class_ & cl) + { + return cl; + } + + template<> + bp::class_ & + expose_constraint_data(bp::class_ & cl) + { + return cl.def( + bp::init( + bp::args("self", "constraint_model"), "From model constructor.")); + } + + template<> + bp::class_ & + expose_constraint_data(bp::class_ & cl) + { + typedef context::JointLimitConstraintData Self; + return cl + .def(bp::init( + bp::args("self", "constraint_model"), "From model constructor.")) + .PINOCCHIO_ADD_PROPERTY(Self, compact_tangent_map, "Compact tangent map.") + .PINOCCHIO_ADD_PROPERTY( + Self, activable_constraint_residual, "Activable constraint residual.") + .add_property( + "constraint_residual", + bp::make_function( + +[](const context::JointLimitConstraintData & self) + -> Eigen::Ref { + return Eigen::Ref( + self.constraint_residual); + }, + bp::with_custodian_and_ward_postcall<0, 1>()), + ""); + } + } // namespace python +} // namespace pinocchio + +#endif // ifndef __pinocchio_python_algorithm_constraints_datas_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/constraints/constraints-models.hpp b/include/pinocchio/bindings/python/algorithm/constraints/constraints-models.hpp new file mode 100644 index 0000000000..de1394e116 --- /dev/null +++ b/include/pinocchio/bindings/python/algorithm/constraints/constraints-models.hpp @@ -0,0 +1,134 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_python_algorithm_constraints_models_hpp__ +#define __pinocchio_python_algorithm_constraints_models_hpp__ + +#include "pinocchio/algorithm/constraints/constraint-model-generic.hpp" +#include "pinocchio/algorithm/constraints/constraint-collection-default.hpp" +#include "pinocchio/bindings/python/fwd.hpp" +#include "pinocchio/bindings/python/utils/printable.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + // generic expose_constraint_model : do nothing special + template + bp::class_ & expose_constraint_model(bp::class_ & cl) + { + return cl; + } + + // specialization for ConstraintModels + template<> + bp::class_ & + expose_constraint_model(bp::class_ & cl) + { + return cl; + } + + template<> + bp::class_ & + expose_constraint_model(bp::class_ & cl) + { + return cl; + } + + template<> + bp::class_ & + expose_constraint_model(bp::class_ & cl) + { + return cl; + } + + template<> + bp::class_ & + expose_constraint_model(bp::class_ & cl) + { + typedef typename context::FrictionalJointConstraintModel::JointIndexVector JointIndexVector; + cl.def(bp::init( + (bp::arg("self"), bp::arg("model"), bp::arg("active_joints")), + "Contructor from given joint index vector " + "implied in the constraint.")) + .def( + "getActiveDofs", &context::FrictionalJointConstraintModel::getActiveDofs, + bp::return_value_policy()); + return cl; + } + + template<> + bp::class_ & + expose_constraint_model(bp::class_ & cl) + { + typedef typename context::JointLimitConstraintModel::JointIndexVector JointIndexVector; + typedef typename context::JointLimitConstraintModel::ConstraintData ConstraintData; + typedef typename context::JointLimitConstraintModel Self; + cl.def(bp::init( + (bp::arg("self"), bp::arg("model"), bp::arg("activable_joints")), + "Contructor from given joint index vector " + "implied in the constraint.")) + .def("getNqReduce", &Self::getNqReduce, "Sum of nq of activable joints.") + .def("getNvMaxAtom", &Self::getNvMaxAtom, "Max nv of atomic joints in activable joints.") + .def("lowerSize", &Self::lowerSize, "Part of size() that are lower bound limits.") + .def( + "lowerActiveSize", &Self::lowerActiveSize, + "Part of activeSize() that are lower bound limits.") + .def("upperSize", &Self::upperSize, "Part of size() that are upper bound limits.") + .def( + "upperActiveSize", &Self::upperActiveSize, + "Part of activeSize() that are upper bound limits.") + .def( + "getBoundPositionLimit", &Self::getBoundPositionLimit, + bp::return_value_policy(), + "Position limit of the dof of the constraints.") + .def( + "getBoundPositionMargin", &Self::getBoundPositionMargin, + bp::return_value_policy(), + "Position margin of the dof of the constraints.") + .def( + "getActivableJoints", &Self::getActivableJoints, + bp::return_value_policy(), + "Joints for which there is at least one position limit.") + .def( + "getActivableIdxQs", &Self::getActivableIdxQs, + bp::return_value_policy(), + "Q index in configuration of each limit constraint.") + .def( + "getActivableIdxQsReduce", &Self::getActivableIdxQsReduce, + bp::return_value_policy(), + "Q index in thre reduce configuration (about activable joints) of each activable limit " + "constraint.") + .def( + "getActiveIdxQsReduce", &Self::getActiveIdxQsReduce, + bp::return_value_policy(), + "Q index in thre reduce configuration (about activable joints) of each active limit " + "constraint.") + .def( + "getActivableNvs", &Self::getActivableNvs, + bp::return_value_policy(), + "Nv of the atomic joint for which each activable position limit contribute to.") + .def( + "getActiveNvs", &Self::getActiveNvs, bp::return_value_policy(), + "Nv of the atomic joint for which each active position limit contribute to.") + .def( + "getActivableIdxVs", &Self::getActivableIdxVs, + bp::return_value_policy(), + "V index of the atomic joint for which each activable position limit contribute to.") + .def( + "getActiveIdxVs", &Self::getActiveIdxVs, + bp::return_value_policy(), + "V index of the atomic joint for which each active position limit contribute to.") + .def( + "getActiveSetIndexes", &Self::getActiveSetIndexes, + bp::return_value_policy(), + "Indexes of the active constraints set."); + return cl; + } + } // namespace python +} // namespace pinocchio + +#endif // ifndef __pinocchio_python_algorithm_constraints_models_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/constraints/constraints-variant.hpp b/include/pinocchio/bindings/python/algorithm/constraints/constraints-variant.hpp new file mode 100644 index 0000000000..31eaaa3368 --- /dev/null +++ b/include/pinocchio/bindings/python/algorithm/constraints/constraints-variant.hpp @@ -0,0 +1,101 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_python_algorithm_constraints_variant_hpp__ +#define __pinocchio_python_algorithm_constraints_variant_hpp__ + +#include + +#include "pinocchio/bindings/python/algorithm/constraints/constraint-model.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/constraint-data.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/constraint-model-inheritance.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/constraint-data-inheritance.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/constraints-models.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/constraints-datas.hpp" +#include "pinocchio/bindings/python/utils/std-aligned-vector.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + template + std::string sanitizedClassname() + { + std::string className = boost::replace_all_copy(T::classname(), "<", "_"); + boost::replace_all(className, ">", ""); + return className; + } + + template + struct ConstraintVariantVisitor : boost::static_visitor + { + static result_type convert(VariantType const & jv) + { + return apply_visitor(ConstraintVariantVisitor(), jv); + } + + template + result_type operator()(T const & t) const + { + return bp::incref(bp::object(t).ptr()); + } + }; + + struct ConstraintDataExposer + { + template + void operator()(T) + { + expose_constraint_data( + bp::class_( + sanitizedClassname().c_str(), sanitizedClassname().c_str(), bp::init<>()) + .def(ConstraintDataBasePythonVisitor()) + .def(ConstraintDataInheritancePythonVisitor()) + .def(PrintableVisitor())); + bp::implicitly_convertible(); + } + + void operator()(boost::blank) + { + } + }; + + struct ConstraintModelExposer + { + template + void operator()(T) + { + expose_constraint_model( + bp::class_( + sanitizedClassname().c_str(), sanitizedClassname().c_str(), bp::no_init) + .def(ConstraintModelBasePythonVisitor()) + .def(ConstraintModelInheritancePythonVisitor()) + .def(PrintableVisitor())); + bp::implicitly_convertible(); + } + + void operator()(boost::blank) + { + } + }; + + struct ConstraintStdVectorExposer + { + template + void operator()(T) + { + StdAlignedVectorPythonVisitor::expose( + std::string("StdVec_") + sanitizedClassname().c_str()); + } + + void operator()(boost::blank) + { + } + }; + } // namespace python +} // namespace pinocchio + +#endif // ifndef __pinocchio_python_algorithm_constraints_variant_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/constraints/set-base.hpp b/include/pinocchio/bindings/python/algorithm/constraints/set-base.hpp new file mode 100644 index 0000000000..39b2ded9e8 --- /dev/null +++ b/include/pinocchio/bindings/python/algorithm/constraints/set-base.hpp @@ -0,0 +1,59 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_python_algorithm_constraints_set_base_hpp__ +#define __pinocchio_python_algorithm_constraints_set_base_hpp__ + +#include + +#include "pinocchio/algorithm/constraints/box-set.hpp" + +#include "pinocchio/bindings/python/utils/cast.hpp" +#include "pinocchio/bindings/python/utils/copyable.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + template + struct SetPythonVisitor : public boost::python::def_visitor> + { + typedef typename Set::Scalar Scalar; + template + void visit(PyClass & cl) const + { + cl.def( + "isInside", + +[](const Set & self, const Eigen::MatrixBase & f) -> bool { + return self.template isInside(f, Scalar(0)); + }, + bp::args("self", "f"), "Resize the constraint given active limits.") + .def( + "project", &Set::template project, bp::args("self", "f"), + "Normal projection of a vector f onto the cone.") + .def("dim", &Set::dim, "Returns the dimension of the cone.") + .def("size", &Set::size, "Returns the size of the cone.") +#ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS + .def(bp::self == bp::self) + .def(bp::self != bp::self) +#endif + ; + } + }; + + template + struct ConeSetPythonVisitor : public boost::python::def_visitor> + { + template + void visit(PyClass & cl) const + { + cl.def("dual", &ConeSet::dual, bp::arg("self"), "Returns the dual cone associated to this"); + } + }; + } // namespace python +} // namespace pinocchio + +#endif // ifndef __pinocchio_python_algorithm_constraints_set_base_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/constraints/set-box-set.hpp b/include/pinocchio/bindings/python/algorithm/constraints/set-box-set.hpp new file mode 100644 index 0000000000..6a50d65958 --- /dev/null +++ b/include/pinocchio/bindings/python/algorithm/constraints/set-box-set.hpp @@ -0,0 +1,65 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_python_algorithm_constraints_set_box_set_hpp__ +#define __pinocchio_python_algorithm_constraints_set_box_set_hpp__ + +#include + +#include "pinocchio/algorithm/constraints/box-set.hpp" + +#include "pinocchio/bindings/python/algorithm/constraints/set-base.hpp" +#include "pinocchio/bindings/python/utils/cast.hpp" +#include "pinocchio/bindings/python/utils/copyable.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + template + struct BoxSetPythonVisitor : public boost::python::def_visitor> + { + typedef typename BoxSet::Scalar Scalar; + typedef typename BoxSet::Vector Vector; + typedef BoxSet Self; + + template + void visit(PyClass & cl) const + { + cl.def(bp::init( + bp::args("self", "size"), + "Default constructor. By default, the bounds are set to ±inf.")) + .def(bp::init(bp::args("self", "other"), "Copy constructor.")) + .def(bp::init( + bp::args("self", "lb", "ub"), "Constructor from lower and upper bounds.")) + .def( + "lb", (Vector & (Self::*)()) & Self::lb, + "Returns a reference to the vector of lower bounds", bp::return_internal_reference<>()) + .def( + "ub", (Vector & (Self::*)()) & Self::ub, + "Returns a reference to the vector of upper bounds", bp::return_internal_reference<>()) + .def("resize", &BoxSet::resize, bp::args("self", "size"), "Resize the set.") + .def( + "conservativeResize", &BoxSet::conservativeResize, bp::args("self", "size"), + "Resize the set following Eigen convention."); + } + + static void expose() + { + bp::class_( + "BoxSet", "Box set defined by a lower and an upper bounds [lb;ub].\n", bp::no_init) + .def(SetPythonVisitor()) + .def(BoxSetPythonVisitor()) + // .def(CastVisitor()) + // .def(ExposeConstructorByCastVisitor()) + .def(CopyableVisitor()); + } + }; + + } // namespace python +} // namespace pinocchio + +#endif // ifndef __pinocchio_python_algorithm_constraints_set_box_set_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/constraints/coulomb-friction-cone.hpp b/include/pinocchio/bindings/python/algorithm/constraints/set-coulomb-friction-cone.hpp similarity index 54% rename from include/pinocchio/bindings/python/algorithm/constraints/coulomb-friction-cone.hpp rename to include/pinocchio/bindings/python/algorithm/constraints/set-coulomb-friction-cone.hpp index b32fdeb47e..03a82a4e9c 100644 --- a/include/pinocchio/bindings/python/algorithm/constraints/coulomb-friction-cone.hpp +++ b/include/pinocchio/bindings/python/algorithm/constraints/set-coulomb-friction-cone.hpp @@ -2,11 +2,12 @@ // Copyright (c) 2022 INRIA // -#ifndef __pinocchio_python_algorithm_constraints_coulomb_friction_cone_hpp__ -#define __pinocchio_python_algorithm_constraints_coulomb_friction_cone_hpp__ +#ifndef __pinocchio_python_algorithm_constraints_set_coulomb_friction_cone_hpp__ +#define __pinocchio_python_algorithm_constraints_set_coulomb_friction_cone_hpp__ #include "pinocchio/algorithm/constraints/coulomb-friction-cone.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/set-base.hpp" #include "pinocchio/bindings/python/utils/cast.hpp" #include "pinocchio/bindings/python/utils/copyable.hpp" @@ -26,20 +27,14 @@ namespace pinocchio template void visit(PyClass & cl) const { - cl.def(bp::init(bp::args("self", "mu"), "Default constructor")) + cl.def(bp::init<>(bp::arg("self"), "Default constructor")) + .def(bp::init( + bp::args("self", "mu"), "Constructor from a given friction coefficient")) .def(bp::init(bp::args("self", "other"), "Copy constructor")) - .def_readwrite("mu", &Self::mu, "Friction coefficient.") - - .def( - "isInside", &Self::template isInside, bp::args("self", "f"), - "Check whether a vector x lies within the cone.") - - .def( - "project", &Self::template project, bp::args("self", "f"), - "Normal projection of a vector f onto the cone.") .def( - "weightedProject", &Self::template weightedProject, + "weightedProject", + &Self::template weightedProject, bp::args("self", "f", "R"), "Weighted projection of a vector f onto the cone.") .def( "computeNormalCorrection", &Self::template computeNormalCorrection, @@ -50,26 +45,18 @@ namespace pinocchio "computeRadialProjection", &Self::template computeRadialProjection, bp::args("self", "f"), "Compute the radial projection associted to the Coulomb friction cone.") - - .def("dual", &Self::dual, bp::arg("self"), "Returns the dual cone associated to this") - - .def("dim", Self::dim, "Returns the dimension of the cone.") - .staticmethod("dim") - -#ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS - .def(bp::self == bp::self) - .def(bp::self != bp::self) -#endif - ; + .staticmethod("dim"); } static void expose() { bp::class_( "CoulombFrictionCone", "3d Coulomb friction cone.\n", bp::no_init) + .def(SetPythonVisitor()) + .def(ConeSetPythonVisitor()) .def(CoulombFrictionConePythonVisitor()) - // .def(CastVisitor()) - // .def(ExposeConstructorByCastVisitor()) + // .def(CastVisitor()) + // .def(ExposeConstructorByCastVisitor()) .def(CopyableVisitor()); } }; @@ -85,43 +72,27 @@ namespace pinocchio template void visit(PyClass & cl) const { - cl.def(bp::init(bp::args("self", "mu"), "Default constructor")) + cl.def(bp::init<>(bp::arg("self"), "Default constructor")) + .def(bp::init( + bp::args("self", "mu"), "Constructor from a given friction coefficient")) .def(bp::init(bp::args("self", "other"), "Copy constructor")) - .def_readwrite("mu", &Self::mu, "Friction coefficient.") - - .def( - "isInside", &Self::template isInside, bp::args("self", "v"), - "Check whether a vector x lies within the cone.") - - .def( - "project", &Self::template project, bp::args("self", "v"), - "Project a vector v onto the cone.") - - .def("dual", &Self::dual, bp::arg("self"), "Returns the dual cone associated to this.") - - .def("dim", Self::dim, "Returns the dimension of the cone.") - .staticmethod("dim") - -#ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS - .def(bp::self == bp::self) - .def(bp::self != bp::self) -#endif - ; + .staticmethod("dim"); } static void expose() { bp::class_( "DualCoulombFrictionCone", "Dual cone of the 3d Coulomb friction cone.\n", bp::no_init) + .def(SetPythonVisitor()) + .def(ConeSetPythonVisitor()) .def(DualCoulombFrictionConePythonVisitor()) - // .def(CastVisitor()) - // .def(ExposeConstructorByCastVisitor()) + // .def(CastVisitor()) + // .def(ExposeConstructorByCastVisitor()) .def(CopyableVisitor()); } }; - } // namespace python } // namespace pinocchio -#endif // ifndef __pinocchio_python_algorithm_constraints_coulomb_friction_cone_hpp__ +#endif // ifndef __pinocchio_python_algorithm_constraints_set_coulomb_friction_cone_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/constraints/set-joint-limit-cone.hpp b/include/pinocchio/bindings/python/algorithm/constraints/set-joint-limit-cone.hpp new file mode 100644 index 0000000000..292f81d3a8 --- /dev/null +++ b/include/pinocchio/bindings/python/algorithm/constraints/set-joint-limit-cone.hpp @@ -0,0 +1,57 @@ +// +// Copyright (c) 2022 INRIA +// + +#ifndef __pinocchio_python_algorithm_constraints_set_joint_limit_cone_hpp__ +#define __pinocchio_python_algorithm_constraints_set_joint_limit_cone_hpp__ + +#include "pinocchio/algorithm/constraints/joint-limit-constraint-cone.hpp" + +#include "pinocchio/bindings/python/algorithm/constraints/set-base.hpp" +#include "pinocchio/bindings/python/utils/cast.hpp" +#include "pinocchio/bindings/python/utils/copyable.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + template + struct JointLimitConstraintConePythonVisitor + : public boost::python::def_visitor< + JointLimitConstraintConePythonVisitor> + { + + template + void visit(PyClass & cl) const + { + cl.def(bp::init( + bp::args("self", "negative_orthant_size", "positive_orthant_size"), + "Default constructor given a positive and a negative size.")) + .def( + "resize", &JointLimitConstraintCone::resize, bp::args("self", "size"), + "Resize the set.") + .def( + "conservativeResize", &JointLimitConstraintCone::conservativeResize, + bp::args("self", "size"), "Resize the set following Eigen convention."); + } + + static void expose() + { + bp::class_( + "JointLimitConstraintCone", "Concatenation of positive and negative orthant cone", + bp::no_init) + .def(SetPythonVisitor()) + .def(ConeSetPythonVisitor()) + .def(JointLimitConstraintConePythonVisitor()) + // .def(CastVisitor()) + // .def(ExposeConstructorByCastVisitor()) + .def(CopyableVisitor()); + } + }; + + } // namespace python +} // namespace pinocchio + +#endif // ifndef __pinocchio_python_algorithm_constraints_set_joint_limit_cone_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/constraints/set-trivial-cones.hpp b/include/pinocchio/bindings/python/algorithm/constraints/set-trivial-cones.hpp new file mode 100644 index 0000000000..69338ad618 --- /dev/null +++ b/include/pinocchio/bindings/python/algorithm/constraints/set-trivial-cones.hpp @@ -0,0 +1,53 @@ +// +// Copyright (c) 2022 INRIA +// + +#ifndef __pinocchio_python_algorithm_constraints_set_trivial_cones_hpp__ +#define __pinocchio_python_algorithm_constraints_set_trivial_cones_hpp__ + +#include "pinocchio/algorithm/constraints/null-set.hpp" +#include "pinocchio/algorithm/constraints/unbounded-set.hpp" +#include "pinocchio/algorithm/constraints/orthant-cone.hpp" +#include "pinocchio/algorithm/constraints/joint-limit-constraint-cone.hpp" + +#include "pinocchio/bindings/python/algorithm/constraints/set-base.hpp" +#include "pinocchio/bindings/python/utils/cast.hpp" +#include "pinocchio/bindings/python/utils/copyable.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + template + struct TrivialConePythonVisitor + : public boost::python::def_visitor> + { + + template + void visit(PyClass & cl) const + { + cl.def(bp::init(bp::args("self", "size"), "Default constructor.")) + .def("resize", &TrivialCone::resize, bp::args("self", "size"), "Resize the set.") + .def( + "conservativeResize", &TrivialCone::conservativeResize, bp::args("self", "size"), + "Resize the set following Eigen convention."); + } + + static void expose(const std::string & class_name, const std::string & doc_string = "") + { + bp::class_(class_name.c_str(), doc_string.c_str(), bp::no_init) + .def(SetPythonVisitor()) + .def(ConeSetPythonVisitor()) + .def(TrivialConePythonVisitor()) + // .def(CastVisitor()) + // .def(ExposeConstructorByCastVisitor()) + .def(CopyableVisitor()); + } + }; + + } // namespace python +} // namespace pinocchio + +#endif // ifndef __pinocchio_python_algorithm_constraints_set_trivial_cones_hpp__ diff --git a/include/pinocchio/bindings/python/algorithm/contact-cholesky.hpp b/include/pinocchio/bindings/python/algorithm/contact-cholesky.hpp index ac32b6e3e5..f1ff4e5a63 100644 --- a/include/pinocchio/bindings/python/algorithm/contact-cholesky.hpp +++ b/include/pinocchio/bindings/python/algorithm/contact-cholesky.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2020-2024 INRIA +// Copyright (c) 2020-2025 INRIA // #ifndef __pinocchio_python_algorithm_contact_cholesky_hpp__ @@ -31,16 +31,28 @@ namespace pinocchio ContactCholeskyDecompositionPythonVisitor> { typedef ContactCholeskyDecomposition Self; - typedef typename ContactCholeskyDecomposition::Scalar Scalar; - typedef typename ContactCholeskyDecomposition::RigidConstraintModel RigidConstraintModel; - typedef typename ContactCholeskyDecomposition::RigidConstraintData RigidConstraintData; - typedef typename ContactCholeskyDecomposition::Matrix Matrix; - typedef typename ContactCholeskyDecomposition::Vector Vector; + typedef typename Self::Scalar Scalar; + typedef typename Self::RigidConstraintModel RigidConstraintModel; + typedef typename Self::RigidConstraintData RigidConstraintData; + typedef typename Self::Matrix Matrix; + typedef typename Self::RowMatrix RowMatrix; + typedef typename Self::Vector Vector; + + typedef context::ConstraintModel ConstraintModel; + typedef context::ConstraintData ConstraintData; + + typedef Eigen::Ref RefMatrix; + typedef Eigen::Ref RefRowMatrix; + typedef Eigen::Ref RefVector; + typedef typename PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) RigidConstraintModelVector; typedef typename PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) RigidConstraintDataVector; + typedef context::ConstraintModelVector ConstraintModelVector; + typedef context::ConstraintDataVector ConstraintDataVector; + typedef pinocchio::python::context::Model Model; typedef pinocchio::python::context::Data Data; @@ -55,23 +67,50 @@ namespace pinocchio (bp::arg("self"), bp::arg("model"), bp::arg("contact_models")), "Constructor from a model and a collection of RigidConstraintModels.") [mimic_not_supported_function<>(1)]) + .def(bp::init( + (bp::arg("self"), bp::arg("model"), bp::arg("constraint_models")), + "Constructor from a model and a collection of ConstraintModels.") + [mimic_not_supported_function<>(1)]) - .PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(Self, U, "") - .PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(Self, D, "") - .PINOCCHIO_ADD_PROPERTY_READONLY_BYVALUE(Self, Dinv, "") + .add_property( + "U", + bp::make_function( + +[](const Self & self) -> RefRowMatrix { return RefRowMatrix(self.U); }, + bp::with_custodian_and_ward_postcall<0, 1>()), + "") + .add_property( + "D", + bp::make_function( + +[](const Self & self) -> RefVector { return RefVector(self.D); }, + bp::with_custodian_and_ward_postcall<0, 1>()), + "") + .add_property( + "Dinv", + bp::make_function( + +[](const Self & self) -> RefVector { return RefVector(self.Dinv); }, + bp::with_custodian_and_ward_postcall<0, 1>()), + "") .def("size", &Self::size, bp::arg("self"), "Size of the decomposition.") .def( "constraintDim", &Self::constraintDim, bp::arg("self"), "Returns the total dimension of the constraints contained in the Cholesky " "factorization.") - .def( - "numContacts", &Self::numContacts, bp::arg("self"), - "Returns the number of contacts associated to this decomposition.") .def( "matrix", (Matrix(Self::*)(void) const)&Self::matrix, bp::arg("self"), "Returns the matrix resulting from the decomposition.") + .def( + "resize", + (void (*)(Self & self, const Model &, const RigidConstraintModelVector &))&resize, + (bp::arg("self"), bp::arg("model"), bp::arg("constraint_models")), + "Resizes the Cholesky decompostion according to the input constraint models") + + .def( + "resize", (void (*)(Self & self, const Model &, const ConstraintModelVector &))&resize, + (bp::arg("self"), bp::arg("model"), bp::arg("constraint_models")), + "Resizes the Cholesky decompostion according to the input constraint models") + .def( "compute", (void (*)( @@ -100,21 +139,51 @@ namespace pinocchio "regularized with a factor mu.", mimic_not_supported_function<>(1)) + .def( + "compute", + (void (*)( + Self & self, const Model &, Data &, const ConstraintModelVector &, + ConstraintDataVector &, const Scalar))&compute, + (bp::arg("self"), bp::arg("model"), bp::arg("data"), bp::arg("constraint_models"), + bp::arg("constraint_datas"), bp::arg("mu") = 0), + "Computes the Cholesky decompostion of the augmented matrix containing the KKT matrix\n" + "related to the system mass matrix and the Jacobians of the contact patches contained " + "in\n" + "the vector of ConstraintModel named constraint_models. The decomposition is " + "regularized with a factor mu.") + + .def( + "compute", + (void (*)( + Self & self, const Model &, Data &, const ConstraintModelVector &, + ConstraintDataVector &, const Vector &))&compute, + (bp::arg("self"), bp::arg("model"), bp::arg("data"), bp::arg("constraint_models"), + bp::arg("constraint_datas"), bp::arg("mus")), + "Computes the Cholesky decompostion of the augmented matrix containing the KKT matrix\n" + "related to the system mass matrix and the Jacobians of the contact patches contained " + "in\n" + "the vector of ConstraintModel named constraint_models. The decomposition is " + "regularized with a factor mu.") + .def( "updateDamping", (void(Self::*)(const Scalar &)) & Self::updateDamping, bp::args("self", "mu"), - "Update the damping term on the upper left block part of the KKT matrix. The " - "damping term should be positive.") + "Update the damping term on the upper left block part of the KKT matrix. The damping " + "term should be positive.") .def( "updateDamping", &Self::template updateDamping, bp::args("self", "mus"), - "Update the damping terms on the upper left block part of the KKT matrix. The " - "damping terms should be all positives.") + "Update the damping terms on the upper left block part of the KKT matrix. The damping " + "terms should be all positives.") + + .def( + "getDamping", +[](const Self & self) -> Vector { return Vector(self.getDamping()); }, + bp::arg("self"), "Returns the current damping vector.") .def( "getInverseOperationalSpaceInertiaMatrix", - (Matrix(Self::*)(void) const)&Self::getInverseOperationalSpaceInertiaMatrix, - bp::arg("self"), + (Matrix(Self::*)(bool) const)&Self::getInverseOperationalSpaceInertiaMatrix, + (bp::arg("self"), bp::arg("enforce_symmetry") = false), "Returns the Inverse of the Operational Space Inertia Matrix resulting from the " "decomposition.", bp::return_value_policy()) @@ -151,8 +220,8 @@ namespace pinocchio .def( "getDelassusCholeskyExpression", &Self::getDelassusCholeskyExpression, bp::arg("self"), - "Returns the Cholesky decomposition expression associated to the underlying " - "Delassus matrix.", + "Returns the Cholesky decomposition expression associated to the underlying Delassus " + "matrix.", bp::with_custodian_and_ward_postcall<0, 1>()) .def(ComparableVisitor::value>()); @@ -172,8 +241,8 @@ namespace pinocchio bp::class_( "DelassusCholeskyExpression", - "Delassus Cholesky expression associated to a " - "given ContactCholeskyDecomposition object.", + "Delassus Cholesky expression associated to a given ContactCholeskyDecomposition " + "object.", bp::no_init) .def(bp::init( bp::args("self", "cholesky_decomposition"), @@ -242,23 +311,42 @@ namespace pinocchio return self.solve(mat); } + template + static void resize( + Self & self, + const Model & model, + const std::vector & contact_models) + { + self.resize(model, contact_models); + } + + template< + typename ConstraintModel, + typename ConstraintModelAllocator, + typename ConstraintData, + typename ConstraintDataAllocator> static void compute( Self & self, const Model & model, Data & data, - const RigidConstraintModelVector & contact_models, - RigidConstraintDataVector & contact_datas, + const std::vector & contact_models, + std::vector & contact_datas, const Scalar mu = static_cast(0)) { self.compute(model, data, contact_models, contact_datas, mu); } + template< + typename ConstraintModel, + typename ConstraintModelAllocator, + typename ConstraintData, + typename ConstraintDataAllocator> static void compute( Self & self, const Model & model, Data & data, - const RigidConstraintModelVector & contact_models, - RigidConstraintDataVector & contact_datas, + const std::vector & contact_models, + std::vector & contact_datas, const Vector & mus) { self.compute(model, data, contact_models, contact_datas, mus); diff --git a/include/pinocchio/bindings/python/algorithm/contact-info.hpp b/include/pinocchio/bindings/python/algorithm/contact-info.hpp index cdb01802fc..7e0380dee2 100644 --- a/include/pinocchio/bindings/python/algorithm/contact-info.hpp +++ b/include/pinocchio/bindings/python/algorithm/contact-info.hpp @@ -13,6 +13,9 @@ #include "pinocchio/bindings/python/utils/macros.hpp" #include "pinocchio/bindings/python/utils/comparable.hpp" #include "pinocchio/bindings/python/utils/std-vector.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/baumgarte-corrector-parameters.hpp" +#include "pinocchio/bindings/python/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp" +#include "pinocchio/bindings/python/utils/eigen.hpp" namespace pinocchio { @@ -20,39 +23,6 @@ namespace pinocchio { namespace bp = boost::python; - template - struct BaumgarteCorrectorParametersPythonVisitor - : public boost::python::def_visitor< - BaumgarteCorrectorParametersPythonVisitor> - { - typedef typename BaumgarteCorrectorParameters::Scalar Scalar; - typedef typename BaumgarteCorrectorParameters::Vector6Max Vector6Max; - typedef BaumgarteCorrectorParameters Self; - - public: - template - void visit(PyClass & cl) const - { - cl.def(bp::init(bp::args("self", "size"), "Default constructor.")) - - .def_readwrite("Kp", &Self::Kp, "Proportional corrector value.") - .def_readwrite("Kd", &Self::Kd, "Damping corrector value.") - - .def(CastVisitor()) - .def(ExposeConstructorByCastVisitor< - Self, ::pinocchio::context::RigidConstraintModel::BaumgarteCorrectorParameters>()) - .def(ComparableVisitor::value>()); - } - - static void expose() - { - eigenpy::enableEigenPySpecific(); - bp::class_( - "BaumgarteCorrectorParameters", "Paramaters of the Baumgarte Corrector.", bp::no_init) - .def(BaumgarteCorrectorParametersPythonVisitor()); - } - }; - template struct RigidConstraintModelPythonVisitor : public boost::python::def_visitor> @@ -61,10 +31,9 @@ namespace pinocchio typedef typename RigidConstraintModel::SE3 SE3; typedef RigidConstraintModel Self; typedef typename RigidConstraintModel::ContactData ContactData; - typedef - typename RigidConstraintModel::BaumgarteCorrectorParameters BaumgarteCorrectorParameters; typedef ModelTpl Model; + typedef DataTpl Data; public: template @@ -110,7 +79,6 @@ namespace pinocchio Self, desired_contact_velocity, "Desired contact spatial velocity.") .PINOCCHIO_ADD_PROPERTY( Self, desired_contact_acceleration, "Desired contact spatial acceleration.") - .PINOCCHIO_ADD_PROPERTY(Self, corrector, "Corrector parameters.") .PINOCCHIO_ADD_PROPERTY( Self, colwise_joint1_sparsity, "Sparsity pattern associated to joint 1.") @@ -118,13 +86,48 @@ namespace pinocchio Self, colwise_joint2_sparsity, "Sparsity pattern associated to joint 2.") .PINOCCHIO_ADD_PROPERTY( Self, colwise_span_indexes, "Indexes of the columns spanned by the constraints.") + .PINOCCHIO_ADD_PROPERTY( + Self, colwise_sparsity, "Sparsity pattern associated to the constraint.") .def("size", &RigidConstraintModel::size, "Size of the constraint") .def( "createData", &RigidConstraintModelPythonVisitor::createData, "Create a Data object for the given model.") - .def(ComparableVisitor::value>()); + .def(ComparableVisitor::value>()) + .def( + "calc", (void(Self::*)(const Model &, const Data &, ContactData &) const) & Self::calc, + bp::args("self", "model", "data", "constraint_data")) + .def("jacobian", &jacobian, bp::args("self", "model", "data", "constraint_data")); + + typedef typename traits::BaumgarteCorrectorVectorParameters + BaumgarteCorrectorVectorParameters; + typedef typename traits::BaumgarteCorrectorVectorParametersRef + BaumgarteCorrectorVectorParametersRef; + typedef typename std::conditional< + std::is_reference::value, + bp::return_internal_reference<>, bp::with_custodian_and_ward_postcall<0, 1>>::type + ReturnPolicy; + + cl.add_property( + "corrector", + bp::make_function( // + +[](Self & self) -> BaumgarteCorrectorVectorParametersRef { + return self.baumgarte_corrector_vector_parameters_impl(); + }, + ReturnPolicy()), + bp::make_function( // + +[](Self & self, const BaumgarteCorrectorVectorParameters & copy) { + self.baumgarte_corrector_vector_parameters_impl() = copy; + }), + "Baumgarte vector parameters associated with the constraint."); + + typedef typename BaumgarteCorrectorVectorParameters::VectorType BaumgarteVectorType; + const std::string BaumgarteVectorType_name = getEigenTypeName(); + const std::string BaumgarteCorrectorVectorParameter_classname = + "BaumgarteCorrectorVectorParameters_" + BaumgarteVectorType_name; + BaumgarteCorrectorVectorParametersPythonVisitor::expose( + BaumgarteCorrectorVectorParameter_classname); } static void expose() @@ -136,14 +139,20 @@ namespace pinocchio .def(CastVisitor()) .def(ExposeConstructorByCastVisitor< RigidConstraintModel, ::pinocchio::context::RigidConstraintModel>()); - - BaumgarteCorrectorParametersPythonVisitor::expose(); } static ContactData createData(const Self & self) { return ContactData(self); } + + static context::MatrixXs jacobian( + const Self & self, const Model & model, const Data & data, ContactData & constraint_data) + { + context::MatrixXs res(self.size(), model.nv); + self.jacobian(model, data, constraint_data, res); + return res; + } }; template @@ -189,12 +198,12 @@ namespace pinocchio "Current contact spatial error (due to the integration step).") .PINOCCHIO_ADD_PROPERTY( Self, contact1_acceleration_drift, - "Current contact drift acceleration (acceleration only due to " - "the Coriolis and centrifugal effects) of the contact frame 1.") + "Current contact drift acceleration (acceleration only due to the Coriolis and " + "centrifugal effects) of the contact frame 1.") .PINOCCHIO_ADD_PROPERTY( Self, contact2_acceleration_drift, - "Current contact drift acceleration (acceleration only due to " - "the Coriolis and centrifugal effects) of the contact frame 2.") + "Current contact drift acceleration (acceleration only due to the Coriolis and " + "centrifugal effects) of the contact frame 2.") .PINOCCHIO_ADD_PROPERTY( Self, contact_acceleration_deviation, "Contact deviation from the reference acceleration (a.k.a the error).") diff --git a/include/pinocchio/bindings/python/algorithm/delassus-operator.hpp b/include/pinocchio/bindings/python/algorithm/delassus-operator.hpp index b7bf1eaf78..19bea52105 100644 --- a/include/pinocchio/bindings/python/algorithm/delassus-operator.hpp +++ b/include/pinocchio/bindings/python/algorithm/delassus-operator.hpp @@ -30,7 +30,7 @@ namespace pinocchio .def( "__matmul__", +[](const DelassusOperator & self, const Matrix & other) -> Matrix { - return self * other; + return Matrix(self * other); }, bp::args("self", "other"), "Matrix multiplication between self and another matrix. Returns the result of Delassus " @@ -38,38 +38,52 @@ namespace pinocchio .def( "solve", &DelassusOperator::template solve, bp::args("self", "mat"), - "Returns the solution x of Delassus * x = mat using the current decomposition of " - "the Delassus matrix.") + "Returns the solution x of Delassus * x = mat using the current decomposition of the " + "Delassus matrix.") .def( - "computeLargestEigenValue", - (Scalar(DelassusOperator::*)(const bool, const int, const Scalar) - const)&DelassusOperator::computeLargestEigenValue, - (bp::arg("self"), bp::arg("reset") = true, bp::arg("max_it") = 10, - bp::arg("prec") = Scalar(1e-8)), - "Compute the largest eigenvalue associated to the underlying Delassus matrix.") + "updateCompliance", + (void(DelassusOperator::*)(const Scalar &)) & DelassusOperator::updateCompliance, + bp::args("self", "mu"), + "Add a compliance term to the diagonal of the Delassus matrix. The compliance term " + "should be " + "positive.") .def( - "computeLowestEigenValue", - (Scalar(DelassusOperator::*)(const bool, const bool, const int, const Scalar) - const)&DelassusOperator::computeLowestEigenValue, - (bp::arg("self"), bp::arg("reset") = true, bp::arg("compute_largest") = true, - bp::arg("max_it") = 10, bp::arg("prec") = Scalar(1e-8)), - "Compute the lowest eigenvalue associated to the underlying Delassus matrix.") + "updateCompliance", &DelassusOperator::template updateCompliance, + bp::args("self", "mus"), + "Add a compliance term to the diagonal of the Delassus matrix. The compliance terms " + "should " + "be all positive.") + + .def( + "getCompliance", + +[](const DelassusOperator & self) -> context::VectorXs { + return self.getCompliance(); + }, + bp::arg("self"), + "Returns the value of the compliance terms contained in the Delassus operator") .def( "updateDamping", (void(DelassusOperator::*)(const Scalar &)) & DelassusOperator::updateDamping, bp::args("self", "mu"), - "Add a damping term to the diagonal of the Delassus matrix. The damping term should " - "be positive.") + "Add a damping term to the diagonal of the Delassus matrix. The damping term should be " + "positive.") .def( "updateDamping", &DelassusOperator::template updateDamping, bp::args("self", "mus"), - "Add a damping term to the diagonal of the Delassus matrix. The damping terms " - "should be all positive.") + "Add a damping term to the diagonal of the Delassus matrix. The damping terms should " + "be all positive.") + + .def( + "getDamping", + +[](const DelassusOperator & self) -> context::VectorXs { return self.getDamping(); }, + bp::arg("self"), + "Returns the value of the damping terms contained in the Delassus operator") .def( - "matrix", &DelassusOperator::matrix, bp::arg("self"), + "matrix", (Matrix(DelassusOperator::*)(bool) const)&DelassusOperator::matrix, + (bp::arg("self"), bp::arg("enforce_symmetry") = false), "Returns the Delassus expression as a dense matrix.") .def( "inverse", &DelassusOperator::inverse, bp::arg("self"), diff --git a/include/pinocchio/bindings/python/collision/geometry-functors.hpp b/include/pinocchio/bindings/python/collision/geometry-functors.hpp index dcec7487d8..0d009a1078 100644 --- a/include/pinocchio/bindings/python/collision/geometry-functors.hpp +++ b/include/pinocchio/bindings/python/collision/geometry-functors.hpp @@ -5,8 +5,6 @@ #ifndef __pinocchio_python_collision_geometry_functors_hpp__ #define __pinocchio_python_collision_geometry_functors_hpp__ -#include "pinocchio/bindings/python/utils/registration.hpp" - #include "pinocchio/multibody/geometry.hpp" namespace pinocchio diff --git a/include/pinocchio/bindings/python/context/generic.hpp b/include/pinocchio/bindings/python/context/generic.hpp index cf2020aa8e..574eeed539 100644 --- a/include/pinocchio/bindings/python/context/generic.hpp +++ b/include/pinocchio/bindings/python/context/generic.hpp @@ -20,8 +20,6 @@ #include -#include - namespace pinocchio { namespace python @@ -46,8 +44,12 @@ namespace pinocchio typedef Eigen::SparseMatrix RowSparseMatrix; typedef Eigen::Matrix Matrix1s; typedef Eigen::Matrix Vector7s; + typedef Eigen::Matrix Matrix6s; + typedef Eigen::Matrix Matrix36s; typedef Eigen::Quaternion Quaternion; typedef Eigen::AngleAxis AngleAxis; + typedef Eigen::Ref RefVectorXs; + typedef Eigen::Ref RefMatrixXs; // Spatial typedef SE3Tpl SE3; @@ -62,7 +64,6 @@ namespace pinocchio typedef FrameTpl Frame; typedef ModelTpl Model; typedef DataTpl Data; - typedef JointCollectionDefaultTpl JointCollectionDefault; // Joints @@ -146,22 +147,70 @@ namespace pinocchio typedef ContactCholeskyDecompositionTpl ContactCholeskyDecomposition; typedef RigidConstraintModelTpl RigidConstraintModel; - typedef RigidConstraintDataTpl RigidConstraintData; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) + RigidConstraintModelVector; - typedef CoulombFrictionConeTpl CoulombFrictionCone; - typedef DualCoulombFrictionConeTpl DualCoulombFrictionCone; + typedef RigidConstraintDataTpl RigidConstraintData; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) + RigidConstraintDataVector; - typedef DelassusOperatorDenseTpl DelassusOperatorDense; - typedef DelassusOperatorSparseTpl DelassusOperatorSparse; + typedef BilateralPointConstraintModelTpl BilateralPointConstraintModel; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + BilateralPointConstraintModelVector; + typedef BilateralPointConstraintDataTpl BilateralPointConstraintData; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintData) + BilateralPointConstraintDataVector; + + typedef WeldConstraintModelTpl WeldConstraintModel; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) + WeldConstraintModelVector; + typedef WeldConstraintDataTpl WeldConstraintData; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintData) + WeldConstraintDataVector; + + typedef FrictionalPointConstraintModelTpl FrictionalPointConstraintModel; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(FrictionalPointConstraintModel) + FrictionalPointConstraintModelVector; + typedef FrictionalPointConstraintDataTpl FrictionalPointConstraintData; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(FrictionalPointConstraintData) + FrictionalPointConstraintDataVector; + + typedef FrictionalJointConstraintModelTpl FrictionalJointConstraintModel; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(FrictionalJointConstraintModel) + FrictionalJointConstraintModelVector; + typedef FrictionalJointConstraintDataTpl FrictionalJointConstraintData; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(FrictionalJointConstraintData) + FrictionalJointConstraintDataVector; + + typedef JointLimitConstraintModelTpl JointLimitConstraintModel; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(JointLimitConstraintModel) + JointLimitModelVector; + typedef JointLimitConstraintDataTpl JointLimitConstraintData; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(JointLimitConstraintData) + JointLimitDataVector; + + typedef ConstraintModelTpl ConstraintModel; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConstraintModel) ConstraintModelVector; + typedef ConstraintDataTpl ConstraintData; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConstraintData) ConstraintDataVector; + typedef CoulombFrictionConeTpl CoulombFrictionCone; typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(CoulombFrictionCone) CoulombFrictionConeVector; + typedef DualCoulombFrictionConeTpl DualCoulombFrictionCone; typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(DualCoulombFrictionCone) DualCoulombFrictionConeVector; - typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) - RigidConstraintModelVector; - typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) - RigidConstraintDataVector; + typedef BoxSetTpl BoxSet; + typedef NullSetTpl NullSet; + typedef UnboundedSetTpl UnboundedSet; + typedef NegativeOrthantConeTpl NegativeOrthantCone; + typedef PositiveOrthantConeTpl PositiveOrthantCone; + typedef JointLimitConstraintConeTpl JointLimitConstraintCone; + + typedef ConstraintCollectionDefaultTpl ConstraintCollectionDefault; + + typedef DelassusOperatorDenseTpl DelassusOperatorDense; + typedef DelassusOperatorSparseTpl DelassusOperatorSparse; // Pool #ifdef PINOCCHIO_PYTHON_INTERFACE_WITH_OPENMP diff --git a/include/pinocchio/bindings/python/fwd.hpp b/include/pinocchio/bindings/python/fwd.hpp index df8b29419e..005a7357ce 100644 --- a/include/pinocchio/bindings/python/fwd.hpp +++ b/include/pinocchio/bindings/python/fwd.hpp @@ -16,6 +16,8 @@ namespace pinocchio { namespace python { + using eigenpy::register_symbolic_link_to_registered_type; + // Expose spatial classes void exposeSE3(); void exposeForce(); @@ -33,6 +35,7 @@ namespace pinocchio void exposeLinalg(); void exposeTridiagonalMatrix(); void exposeLanczosDecomposition(); + void exposeGramSchmidtOrthonormalisation(); // Expose multibody classes void exposeJoints(); @@ -50,6 +53,7 @@ namespace pinocchio // Expose algorithms void exposeAlgorithms(); void exposeExtras(); + void exposeConstraints(); #ifdef PINOCCHIO_PYTHON_INTERFACE_WITH_HPP_FCL_PYTHON_BINDINGS void exposeFCL(); diff --git a/include/pinocchio/bindings/python/math/lanczos-decomposition.hpp b/include/pinocchio/bindings/python/math/lanczos-decomposition.hpp index d0dc582fe1..ab84243be5 100644 --- a/include/pinocchio/bindings/python/math/lanczos-decomposition.hpp +++ b/include/pinocchio/bindings/python/math/lanczos-decomposition.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2024 INRIA +// Copyright (c) 2024-2025 INRIA // #ifndef __pinocchio_python_math_lanczos_decomposition_hpp__ @@ -7,6 +7,7 @@ #include "pinocchio/bindings/python/fwd.hpp" #include "pinocchio/math/lanczos-decomposition.hpp" +#include "pinocchio/bindings/python/utils/copyable.hpp" #include #include @@ -21,6 +22,7 @@ namespace pinocchio struct LanczosDecompositionPythonVisitor : public boost::python::def_visitor> { + typedef LanczosDecomposition Self; typedef typename LanczosDecomposition::Scalar Scalar; typedef typename LanczosDecomposition::TridiagonalMatrix TridiagonalMatrix; typedef typename LanczosDecomposition::PlainMatrix PlainMatrix; @@ -32,12 +34,16 @@ namespace pinocchio // static const Scalar dummy_precision = Eigen::NumTraits::dummy_precision(); cl.def(bp::init( - (bp::arg("self"), bp::arg("mat"), bp::arg("decomposition_size")), + (bp::arg("self"), bp::arg("matrix"), bp::arg("decomposition_size")), "Default constructor from a given matrix and a given decomposition size.")) + .def(bp::init( + (bp::arg("self"), bp::arg("size"), bp::arg("decomposition_size")), + "Default constructor for the Lanczos decomposition from a given matrix size.")) + .def( "compute", &LanczosDecomposition::template compute, - bp::args("self", "mat"), + bp::args("self", "matrix"), "Computes the Lanczos decomposition for the given input matrix.") .def( @@ -51,22 +57,27 @@ namespace pinocchio "Returns the orthogonal basis associated with the Lanczos decomposition.", bp::return_internal_reference<>()) - .def( - "rank", &LanczosDecomposition::rank, bp::arg("self"), - "Returns the rank of the decomposition.") - .def( "computeDecompositionResidual", &LanczosDecomposition::template computeDecompositionResidual, - bp::args("self", "mat"), - "Computes the residual associated with the decomposition, namely, the quantity \f$ " - "A Q_s - Q_s T_s \f$") + bp::args("self", "matrix"), + "Computes the residual associated with the decomposition, namely, the quantity \f$ A " + "Q_s - Q_s T_s \f$") + + .def( + "size", &LanczosDecomposition::size, bp::arg("self"), + "Returns the size of the underlying matrix.") + .def( + "decompositionSize", &LanczosDecomposition::decompositionSize, bp::arg("self"), + "Returns the size of the decomposition.") #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS .def(bp::self == bp::self) .def(bp::self != bp::self) #endif + .def(CopyableVisitor()) + ; } diff --git a/include/pinocchio/bindings/python/math/tridiagonal-matrix.hpp b/include/pinocchio/bindings/python/math/tridiagonal-matrix.hpp index 2515a994ef..4715550579 100644 --- a/include/pinocchio/bindings/python/math/tridiagonal-matrix.hpp +++ b/include/pinocchio/bindings/python/math/tridiagonal-matrix.hpp @@ -88,6 +88,18 @@ namespace pinocchio .def("cols", &TridiagonalSymmetricMatrix::cols, bp::arg("self")) .def("matrix", &TridiagonalSymmetricMatrix::matrix, bp::arg("self")) + .def( + "computeEigenvalue", &TridiagonalSymmetricMatrix::computeEigenvalue, + (bp::arg("self"), bp::arg("eigenvalue_index"), bp::arg("eps") = 1e-8), + "Computes the kth eigenvalue associated with the input tridiagonal matrix up to " + "precision eps.") + + .def( + "computeSpectrum", &TridiagonalSymmetricMatrix::computeSpectrum, + (bp::arg("self"), bp::arg("eps") = 1e-8), + "Computes the full spectrum associated with the input tridiagonal matrix up to " + "precision eps.") + .def(bp::self * PlainMatrixType()) .def(PlainMatrixType() * bp::self); } diff --git a/include/pinocchio/bindings/python/multibody/data.hpp b/include/pinocchio/bindings/python/multibody/data.hpp index 7aae84cbad..19d9a5b3c2 100644 --- a/include/pinocchio/bindings/python/multibody/data.hpp +++ b/include/pinocchio/bindings/python/multibody/data.hpp @@ -1,5 +1,6 @@ // -// Copyright (c) 2015-2024 CNRS INRIA +// Copyright (c) 2015-2018 CNRS +// Copyright (c) 2018-2025 INRIA // #ifndef __pinocchio_python_multibody_data_hpp__ @@ -100,13 +101,17 @@ namespace pinocchio .ADD_DATA_PROPERTY( joints, "Vector of JointData associated to each JointModel stored in the related model.") + .ADD_DATA_PROPERTY(q_in, "Input joint configuration vector.") + .ADD_DATA_PROPERTY(v_in, "Input joint velocity vector.") + .ADD_DATA_PROPERTY(a_in, "Input joint acceleration vector.") + .ADD_DATA_PROPERTY(tau_in, "Input joint torque vector.") .ADD_DATA_PROPERTY( a, "Vector of joint accelerations expressed in the local frame of the joint.") .ADD_DATA_PROPERTY( oa, "Joint spatial acceleration expressed at the origin of the world frame.") .ADD_DATA_PROPERTY( - a_gf, "Joint spatial acceleration containing also the contribution of " - "the gravity acceleration") + a_gf, "Joint spatial acceleration containing also the contribution of the gravity " + "acceleration") .ADD_DATA_PROPERTY( oa_gf, "Joint spatial acceleration containing also the contribution of the gravity " "acceleration, but expressed at the origin of the world frame.") @@ -118,8 +123,8 @@ namespace pinocchio .ADD_DATA_PROPERTY(f, "Vector of body forces expressed in the local frame of the joint.") .ADD_DATA_PROPERTY(of, "Vector of body forces expressed at the origin of the world.") .ADD_DATA_PROPERTY( - of_augmented, "Vector of body forces expressed at the origin of the " - "world, in the context of lagrangian formulation") + of_augmented, "Vector of body forces expressed at the origin of the world, in the " + "context of lagrangian formulation") .ADD_DATA_PROPERTY( h, "Vector of spatial momenta expressed in the local frame of the joint.") .ADD_DATA_PROPERTY(oh, "Vector of spatial momenta expressed at the origin of the world.") @@ -131,22 +136,24 @@ namespace pinocchio .ADD_DATA_PROPERTY(ddq, "Joint accelerations (output of ABA)") .ADD_DATA_PROPERTY(Ycrb, "Inertia of the sub-tree composit rigid body") .ADD_DATA_PROPERTY( - oYcrb, "Composite Rigid Body Inertia of the sub-tree expressed in the " - "WORLD coordinate system.") + oYcrb, "Composite Rigid Body Inertia of the sub-tree expressed in the WORLD coordinate " + "system.") .ADD_DATA_PROPERTY(Yaba, "Articulated Body Inertia of the sub-tree") .ADD_DATA_PROPERTY( oYaba, "Articulated Body Inertia of the sub-tree expressed in the WORLD coordinate system.") + .ADD_DATA_PROPERTY( + oYaba_augmented, "Articulated Body Inertia matrix with constraint augmented inertia, " + "expressed in the WORLD coordinate system.") .ADD_DATA_PROPERTY(oL, "Acceleration propagator.") .ADD_DATA_PROPERTY(oK, "Inverse articulated inertia.") .ADD_DATA_PROPERTY(M, "The joint space inertia matrix") .ADD_DATA_PROPERTY(Minv, "The inverse of the joint space inertia matrix") .ADD_DATA_PROPERTY( - C, "The Coriolis C(q,v) matrix such that the Coriolis effects are " - "given by c(q,v) = C(q,v)v") + C, "The Coriolis C(q,v) matrix such that the Coriolis effects are given by c(q,v) = " + "C(q,v)v") .ADD_DATA_PROPERTY(g, "Vector of generalized gravity (dim model.nv).") .ADD_DATA_PROPERTY(Fcrb, "Spatial forces set, used in CRBA") - .ADD_DATA_PROPERTY(lastChild, "Index of the last child (for CRBA)") .ADD_DATA_PROPERTY(nvSubtree, "Dimension of the subtree motion space (for CRBA)") .ADD_DATA_PROPERTY(U, "Joint Inertia square root (upper triangle)") .ADD_DATA_PROPERTY(D, "Diagonal of UDUT inertia decomposition") @@ -184,11 +191,11 @@ namespace pinocchio Ag, "Centroidal matrix which maps from joint velocity to the centroidal momentum.") .ADD_DATA_PROPERTY(dAg, "Time derivative of the centroidal momentum matrix Ag.") .ADD_DATA_PROPERTY( - hg, "Centroidal momentum (expressed in the frame centered at the CoM " - "and aligned with the world frame).") + hg, "Centroidal momentum (expressed in the frame centered at the CoM and aligned with " + "the world frame).") .ADD_DATA_PROPERTY( - dhg, "Centroidal momentum time derivative (expressed in the frame " - "centered at the CoM and aligned with the world frame).") + dhg, "Centroidal momentum time derivative (expressed in the frame centered at the CoM " + "and aligned with the world frame).") .ADD_DATA_PROPERTY(Ig, "Centroidal Composite Rigid Body Inertia.") .ADD_DATA_PROPERTY(com, "CoM position of the subtree starting at joint index i.") @@ -211,39 +218,39 @@ namespace pinocchio dFda, "Variation of the force set with respect to the joint acceleration.") .ADD_DATA_PROPERTY( - dtau_dq, "Partial derivative of the joint torque vector with respect " - "to the joint configuration.") + dtau_dq, "Partial derivative of the joint torque vector with respect to the joint " + "configuration.") .ADD_DATA_PROPERTY( dtau_dv, "Partial derivative of the joint torque vector with respect to the joint velocity.") .ADD_DATA_PROPERTY( - ddq_dq, "Partial derivative of the joint acceleration vector with " - "respect to the joint configuration.") + ddq_dq, "Partial derivative of the joint acceleration vector with respect to the joint " + "configuration.") .ADD_DATA_PROPERTY( - ddq_dv, "Partial derivative of the joint acceleration vector with " - "respect to the joint velocity.") + ddq_dv, "Partial derivative of the joint acceleration vector with respect to the joint " + "velocity.") .ADD_DATA_PROPERTY( ddq_dtau, "Partial derivative of the joint acceleration vector with respect to the joint torque.") .ADD_DATA_PROPERTY( - dvc_dq, "Partial derivative of the constraint velocity vector with " - "respect to the joint configuration.") + dvc_dq, "Partial derivative of the constraint velocity vector with respect to the " + "joint configuration.") .ADD_DATA_PROPERTY( - dac_dq, "Partial derivative of the contact acceleration vector with " - "respect to the joint configuration.") + dac_dq, "Partial derivative of the contact acceleration vector with respect to the " + "joint configuration.") .ADD_DATA_PROPERTY( - dac_dv, "Partial derivative of the contact acceleration vector vector " - "with respect to the joint velocity.") + dac_dv, "Partial derivative of the contact acceleration vector vector with respect to " + "the joint velocity.") .ADD_DATA_PROPERTY( - dac_da, "Partial derivative of the contact acceleration vector vector " - "with respect to the joint acceleration.") + dac_da, "Partial derivative of the contact acceleration vector vector with respect to " + "the joint acceleration.") .ADD_DATA_PROPERTY(osim, "Operational space inertia matrix.") .ADD_DATA_PROPERTY_READONLY_BYVALUE( - dlambda_dq, "Partial derivative of the contact force vector with " - "respect to the joint configuration.") + dlambda_dq, "Partial derivative of the contact force vector with respect to the joint " + "configuration.") .ADD_DATA_PROPERTY_READONLY_BYVALUE( dlambda_dv, "Partial derivative of the contact force vector with respect to the joint velocity.") @@ -265,8 +272,8 @@ namespace pinocchio primal_dual_contact_solution, "Right hand side vector when solving the contact dynamics KKT problem.") .ADD_DATA_PROPERTY( - lambda_c_prox, "Proximal Lagrange Multipliers used in the computation " - "of the Forward Dynamics computations.") + lambda_c_prox, "Proximal Lagrange Multipliers used in the computation of the Forward " + "Dynamics computations.") .ADD_DATA_PROPERTY(primal_rhs_contact, "Primal RHS in contact dynamic equations.") .ADD_DATA_PROPERTY(dq_after, "Generalized velocity after the impact.") diff --git a/include/pinocchio/bindings/python/multibody/frame.hpp b/include/pinocchio/bindings/python/multibody/frame.hpp index cc87fc4c3a..b70494f458 100644 --- a/include/pinocchio/bindings/python/multibody/frame.hpp +++ b/include/pinocchio/bindings/python/multibody/frame.hpp @@ -12,7 +12,6 @@ #include "pinocchio/bindings/python/utils/cast.hpp" #include "pinocchio/bindings/python/utils/copyable.hpp" #include "pinocchio/bindings/python/utils/printable.hpp" -#include "pinocchio/bindings/python/utils/registration.hpp" namespace pinocchio { diff --git a/include/pinocchio/bindings/python/multibody/geometry-data.hpp b/include/pinocchio/bindings/python/multibody/geometry-data.hpp index 34c5147b39..8ff33bc675 100644 --- a/include/pinocchio/bindings/python/multibody/geometry-data.hpp +++ b/include/pinocchio/bindings/python/multibody/geometry-data.hpp @@ -1,19 +1,18 @@ // -// Copyright (c) 2015-2022 CNRS INRIA +// Copyright (c) 2015-2022 CNRS INRIA, 2025 INRIA // #ifndef __pinocchio_python_geometry_data_hpp__ #define __pinocchio_python_geometry_data_hpp__ #include +#include #include "pinocchio/serialization/geometry.hpp" #include "pinocchio/bindings/python/utils/address.hpp" #include "pinocchio/bindings/python/utils/printable.hpp" -#include "pinocchio/bindings/python/utils/copyable.hpp" #include "pinocchio/bindings/python/utils/std-vector.hpp" -#include "pinocchio/bindings/python/utils/registration.hpp" #include "pinocchio/bindings/python/serialization/serializable.hpp" #if EIGENPY_VERSION_AT_MOST(2, 8, 1) @@ -25,6 +24,7 @@ namespace pinocchio namespace python { namespace bp = boost::python; + using eigenpy::CopyableVisitor; /* --- COLLISION PAIR --------------------------------------------------- */ /* --- COLLISION PAIR --------------------------------------------------- */ @@ -89,9 +89,18 @@ namespace pinocchio "(e.g. the two hands can have a large security margin while the two hips cannot.)") .def_readwrite( "collisionResults", &GeometryData::collisionResults, "Vector of collision results.") + .def_readwrite( + "contactPatchRequests", &GeometryData::contactPatchRequests, + "Defines which information should be computed by FCL for contact patch requests.\n") + .def_readwrite( + "contactPatchResults", &GeometryData::contactPatchResults, + "Vector of contact patch results.") .def_readwrite( "collision_functors", &GeometryData::collision_functors, "Vector of collision functors.") + .def_readwrite( + "contact_patch_functors", &GeometryData::contact_patch_functors, + "Vector of contact patch functors.") .def_readwrite( "distance_functors", &GeometryData::distance_functors, "Vector of distance functors.") .def_readwrite( @@ -114,8 +123,8 @@ namespace pinocchio .def( "setGeometryCollisionStatus", &GeometryData::setGeometryCollisionStatus, bp::args("self", "geom_model", "geom_id", "enable_collision"), - "Enable or disable collision for the given geometry given by its geometry id with " - "all the other geometries registered in the list of collision pairs.") + "Enable or disable collision for the given geometry given by its geometry id with all " + "the other geometries registered in the list of collision pairs.") .def( "setActiveCollisionPairs", &GeometryData::setActiveCollisionPairs, (bp::arg("self"), bp::arg("geometry_model"), bp::arg("collision_map"), diff --git a/include/pinocchio/bindings/python/multibody/geometry-model.hpp b/include/pinocchio/bindings/python/multibody/geometry-model.hpp index 5eecaf8c98..add01d3939 100644 --- a/include/pinocchio/bindings/python/multibody/geometry-model.hpp +++ b/include/pinocchio/bindings/python/multibody/geometry-model.hpp @@ -10,7 +10,7 @@ #include "pinocchio/bindings/python/utils/address.hpp" #include "pinocchio/bindings/python/utils/printable.hpp" #include "pinocchio/bindings/python/utils/copyable.hpp" -#include "pinocchio/bindings/python/utils/registration.hpp" + #include "pinocchio/bindings/python/utils/pickle.hpp" #include "pinocchio/bindings/python/serialization/serializable.hpp" @@ -56,8 +56,8 @@ namespace pinocchio static_cast(&GeometryModel::addGeometryObject), bp::args("self", "geometry_object", "model"), - "Add a GeometryObject to a GeometryModel and set its parent joint by reading its " - "value in the model.\n" + "Add a GeometryObject to a GeometryModel and set its parent joint by reading its value " + "in the model.\n" "Parameters\n" "\tgeometry_object : a GeometryObject\n" "\tmodel : a Model of the system\n") diff --git a/include/pinocchio/bindings/python/multibody/geometry-object.hpp b/include/pinocchio/bindings/python/multibody/geometry-object.hpp index 3b4e78e37b..83326a3e6b 100644 --- a/include/pinocchio/bindings/python/multibody/geometry-object.hpp +++ b/include/pinocchio/bindings/python/multibody/geometry-object.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2017-2023 CNRS INRIA +// Copyright (c) 2017-2023 CNRS INRIA, 2025 INRIA // #ifndef __pinocchio_python_geometry_object_hpp__ @@ -9,11 +9,10 @@ #include #include #include +#include +#include #include "pinocchio/bindings/python/utils/address.hpp" -#include "pinocchio/bindings/python/utils/copyable.hpp" -#include "pinocchio/bindings/python/utils/registration.hpp" -#include "pinocchio/bindings/python/utils/deprecation.hpp" #include "pinocchio/bindings/python/utils/pickle.hpp" #include "pinocchio/bindings/python/serialization/serializable.hpp" @@ -28,6 +27,8 @@ namespace pinocchio namespace python { namespace bp = boost::python; + using eigenpy::CopyableVisitor; + using eigenpy::deprecated_function; struct GeometryObjectPythonVisitor : public boost::python::def_visitor @@ -107,14 +108,14 @@ namespace pinocchio .def_readwrite("meshPath", &GeometryObject::meshPath, "Path to the mesh file.") .def_readwrite( "overrideMaterial", &GeometryObject::overrideMaterial, - "Boolean that tells whether material information is stored inside the " - "given GeometryObject.") + "Boolean that tells whether material information is stored inside the given " + "GeometryObject.") .def_readwrite( "meshTexturePath", &GeometryObject::meshTexturePath, "Path to the mesh texture file.") .def_readwrite( "disableCollision", &GeometryObject::disableCollision, - "If true, no collision or distance check will be done between the " - "Geometry and any other geometry.") + "If true, no collision or distance check will be done between the Geometry and any " + "other geometry.") .def( "clone", &GeometryObject::clone, bp::arg("self"), "Perform a deep copy of this. It will create a copy of the underlying FCL geometry.") @@ -123,6 +124,9 @@ namespace pinocchio bp::make_getter(&GeometryObject::meshMaterial, Converter::return_internal_reference()), bp::make_setter(&GeometryObject::meshMaterial), "Material associated to the mesh (applied only if overrideMaterial is True)") + .def_readwrite( + "physicsMaterial", &GeometryObject::physicsMaterial, + "Physics material of the GeometryObject.") .def(bp::self == bp::self) .def(bp::self != bp::self) @@ -158,8 +162,8 @@ namespace pinocchio { bp::class_( "GeometryObject", - "A wrapper on a collision geometry including its parent " - "joint, parent frame, placement in parent joint's frame.\n\n", + "A wrapper on a collision geometry including its parent joint, parent frame, placement " + "in parent joint's frame.\n\n", bp::no_init) .def(GeometryObjectPythonVisitor()) .def(CopyableVisitor()) @@ -229,6 +233,28 @@ namespace pinocchio .value("COLLISION", COLLISION) .export_values(); } + + if (!register_symbolic_link_to_registered_type()) + { + bp::enum_("PhysicsMaterialType") + .value("ICE", ICE) + .value("METAL", METAL) + .value("PLASTIC", PLASTIC) + .value("WOOD", WOOD) + .value("CONCRETE", CONCRETE) + .export_values(); + } + + if (!register_symbolic_link_to_registered_type()) + { + bp::class_("PhysicsMaterial", bp::init<>()) + .def(bp::init()) + .def(bp::init()) + .def_readwrite("materialType", &PhysicsMaterial::materialType, "Type of the material") + .def_readwrite("compliance", &PhysicsMaterial::compliance, "Compliance of the material") + .def_readwrite( + "elasticity", &PhysicsMaterial::elasticity, "Elasticity of the material"); + } } }; diff --git a/include/pinocchio/bindings/python/multibody/joint/joint-derived.hpp b/include/pinocchio/bindings/python/multibody/joint/joint-derived.hpp index 2d254c77bc..7a2e9a7da1 100644 --- a/include/pinocchio/bindings/python/multibody/joint/joint-derived.hpp +++ b/include/pinocchio/bindings/python/multibody/joint/joint-derived.hpp @@ -64,8 +64,8 @@ namespace pinocchio "with X, Y, nor Z" "\n\t- JointModelRUB[*]: Unbounded revolute Joint (without position limits), with " "rotation axis [*] ∈ [X,Y,Z]" - "\n\t- JointModelRevoluteUnboundedUnaligned: Unbounded revolute Joint, with " - "rotation axis not aligned with X, Y, nor Z" + "\n\t- JointModelRevoluteUnboundedUnaligned: Unbounded revolute Joint, with rotation " + "axis not aligned with X, Y, nor Z" "\n\t- JointModelP[*]: Prismatic Joint, with rotation axis [*] ∈ [X,Y,Z]" "\n\t- JointModelPlanar: Planar joint" "\n\t- JointModelPrismaticUnaligned: Prismatic joint, with translation axis not " diff --git a/include/pinocchio/bindings/python/multibody/joint/joint-model.hpp b/include/pinocchio/bindings/python/multibody/joint/joint-model.hpp index bce6c4f27a..64edad2d98 100644 --- a/include/pinocchio/bindings/python/multibody/joint/joint-model.hpp +++ b/include/pinocchio/bindings/python/multibody/joint/joint-model.hpp @@ -7,6 +7,7 @@ #include "pinocchio/multibody/joint/joint-generic.hpp" #include "pinocchio/bindings/python/multibody/joint/joint-derived.hpp" +#include "pinocchio/bindings/python/multibody/joint/joints-liegroup.hpp" #include "pinocchio/bindings/python/utils/printable.hpp" namespace pinocchio @@ -45,6 +46,7 @@ namespace pinocchio .def(bp::init(bp::args("self", "other"), "Copy constructor")) .def(JointModelBasePythonVisitor()) .def(PrintableVisitor()) + .def(JointModelLieGroupPythonVisitor()) .def( "extract", ExtractJointModelVariantTypeVisitor::extract, bp::arg("self"), "Returns a reference of the internal joint managed by the JointModel", diff --git a/include/pinocchio/bindings/python/multibody/joint/joint.hpp b/include/pinocchio/bindings/python/multibody/joint/joint.hpp index e0dd2af48c..cd84a68bfd 100644 --- a/include/pinocchio/bindings/python/multibody/joint/joint.hpp +++ b/include/pinocchio/bindings/python/multibody/joint/joint.hpp @@ -50,8 +50,8 @@ namespace pinocchio "with X, Y, nor Z" "\n\t- JointModelRUB[*]: Unbounded revolute Joint (without position limits), with " "rotation axis [*] ∈ [X,Y,Z]" - "\n\t- JointModelRevoluteUnboundedUnaligned: Unbounded revolute Joint, with " - "rotation axis not aligned with X, Y, nor Z" + "\n\t- JointModelRevoluteUnboundedUnaligned: Unbounded revolute Joint, with rotation " + "axis not aligned with X, Y, nor Z" "\n\t- JointModelP[*]: Prismatic Joint, with rotation axis [*] ∈ [X,Y,Z]" "\n\t- JointModelPlanar: Planar joint" "\n\t- JointModelPrismaticUnaligned: Prismatic joint, with translation axis not " diff --git a/include/pinocchio/bindings/python/multibody/joint/joints-liegroup.hpp b/include/pinocchio/bindings/python/multibody/joint/joints-liegroup.hpp new file mode 100644 index 0000000000..e16429c00e --- /dev/null +++ b/include/pinocchio/bindings/python/multibody/joint/joints-liegroup.hpp @@ -0,0 +1,111 @@ +// +// Copyright (c) 2015-2021 CNRS INRIA +// + +#ifndef __pinocchio_python_multibody_joint_joints_liegroup_hpp__ +#define __pinocchio_python_multibody_joint_joints_liegroup_hpp__ + +#include + +#include "pinocchio/bindings/python/fwd.hpp" +#include "pinocchio/multibody/joint/joint-generic.hpp" +#include "pinocchio/multibody/liegroup/liegroup-joint.hpp" + +namespace pinocchio +{ + namespace python + { + namespace bp = boost::python; + + template + struct JointModelLieGroupPythonVisitor + : public boost::python::def_visitor> + { + public: + typedef + typename LieGroupMap::template operationProduct::type + LieGroupOperation; + + template + void visit(PyClass & cl) const + { + cl.def("lieGroup", &lieGroup); + } + + static LieGroupOperation lieGroup(const JointModelDerived & self) + { + return LieGroupOperation(self.template lieGroup()); + } + }; + + template<> + struct JointModelLieGroupPythonVisitor + : public boost::python::def_visitor< + JointModelLieGroupPythonVisitor> + { + public: + typedef context::JointModelComposite Self; + typedef + typename LieGroupMap::template operationProduct::type + LieGroupOperation; + + template + void visit(PyClass & cl) const + { + cl.def("lieGroup", &lieGroup); + } + + static LieGroupOperation lieGroup(const Self & self) + { + return self.template lieGroup(); + } + }; + + template<> + struct JointModelLieGroupPythonVisitor + : public boost::python::def_visitor> + { + public: + typedef context::JointModel Self; + typedef + typename LieGroupMap::template operationProduct::type + LieGroupOperation; + + template + void visit(PyClass & cl) const + { + cl.def("lieGroup", &lieGroup); + } + + static LieGroupOperation lieGroup(const Self & self) + { + return self.template lieGroup(); + } + }; + + template<> + struct JointModelLieGroupPythonVisitor + : public boost::python::def_visitor> + { + public: + typedef context::JointModelMimic Self; + typedef + typename LieGroupMap::template operationProduct::type + LieGroupOperation; + + template + void visit(PyClass & cl) const + { + cl.def("lieGroup", &lieGroup); + } + + static LieGroupOperation lieGroup(const Self & self) + { + return self.template lieGroup(); + } + }; + + } // namespace python +} // namespace pinocchio + +#endif // ifndef __pinocchio_python_multibody_joint_joints_liegroup_hpp__ diff --git a/include/pinocchio/bindings/python/multibody/joint/joints-variant.hpp b/include/pinocchio/bindings/python/multibody/joint/joints-variant.hpp index 57e9425861..863d53f9a0 100644 --- a/include/pinocchio/bindings/python/multibody/joint/joints-variant.hpp +++ b/include/pinocchio/bindings/python/multibody/joint/joints-variant.hpp @@ -12,6 +12,7 @@ #include "pinocchio/multibody/joint/joint-collection.hpp" #include "pinocchio/bindings/python/multibody/joint/joints-models.hpp" #include "pinocchio/bindings/python/multibody/joint/joints-datas.hpp" +#include "pinocchio/bindings/python/multibody/joint/joints-liegroup.hpp" #include "pinocchio/bindings/python/utils/printable.hpp" namespace pinocchio @@ -66,6 +67,7 @@ namespace pinocchio bp::class_( sanitizedClassname().c_str(), sanitizedClassname().c_str(), bp::no_init) .def(JointModelBasePythonVisitor()) + .def(JointModelLieGroupPythonVisitor()) .def(PrintableVisitor())); bp::implicitly_convertible(); } diff --git a/include/pinocchio/bindings/python/multibody/liegroups.hpp b/include/pinocchio/bindings/python/multibody/liegroups.hpp index 275233ac82..1150bff62b 100644 --- a/include/pinocchio/bindings/python/multibody/liegroups.hpp +++ b/include/pinocchio/bindings/python/multibody/liegroups.hpp @@ -189,6 +189,28 @@ namespace pinocchio lg.dIntegrateTransport(q, v, J, Jout, arg); return Jout; } + static JacobianMatrix_t tangentMap(const LieGroupType & lg, const ConfigVector_t & q) + { + JacobianMatrix_t TM(lg.nq(), lg.nv()); + lg.tangentMap(q, TM, SETTO); + return TM; + } + + static JacobianMatrix_t tangentMapProduct( + const LieGroupType & lg, const ConfigVector_t & q, const JacobianMatrix_t & Min) + { + JacobianMatrix_t Mout(lg.nq(), Min.cols()); + lg.tangentMapProduct(q, Min, Mout, SETTO); + return Mout; + } + + static JacobianMatrix_t tangentMapTransposeProduct( + const LieGroupType & lg, const ConfigVector_t & q, const JacobianMatrix_t & Min) + { + JacobianMatrix_t Mout(lg.nv(), Min.cols()); + lg.tangentMapTransposeProduct(q, Min, Mout, SETTO); + return Mout; + } }; template @@ -217,6 +239,9 @@ namespace pinocchio .def("dDifference", LieGroupWrapper::dDifference1) .def("dDifference", LieGroupWrapper::dDifference2) .def("dDifference", LieGroupWrapper::dDifference3) + .def("tangentMap", LieGroupWrapper::tangentMap) + .def("tangentMapProduct", LieGroupWrapper::tangentMapProduct) + .def("tangentMapTransposeProduct", LieGroupWrapper::tangentMapTransposeProduct) .def("interpolate", LieGroupWrapper::interpolate) diff --git a/include/pinocchio/bindings/python/multibody/model.hpp b/include/pinocchio/bindings/python/multibody/model.hpp index 732bf977bf..6af0d28a6c 100644 --- a/include/pinocchio/bindings/python/multibody/model.hpp +++ b/include/pinocchio/bindings/python/multibody/model.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2015-2023 CNRS INRIA +// Copyright (c) 2015-2024 CNRS INRIA // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France. // @@ -97,12 +97,12 @@ namespace pinocchio "nvExtendeds", &Model::nvExtendeds, "Dimension of the *i*th joint jacobian subspace.") .add_property( "parents", &Model::parents, - "Vector of parent joint indexes. The parent of joint *i*, denoted *li*, " - "corresponds to li==parents[i].") + "Vector of parent joint indexes. The parent of joint *i*, denoted *li*, corresponds to " + "li==parents[i].") .add_property( "children", &Model::children, - "Vector of children index. Chidren of the *i*th joint, denoted *mu(i)* " - "corresponds to the set (i==parents[k] for k in mu(i)).") + "Vector of children index. Chidren of the *i*th joint, denoted *mu(i)* corresponds to " + "the set (i==parents[k] for k in mu(i)).") .add_property("names", &Model::names, "Name of the joints.") .def_readwrite("name", &Model::name, "Name of the model.") .def_readwrite( @@ -114,21 +114,37 @@ namespace pinocchio "rotorInertia", &Model::rotorInertia, "Vector of rotor inertia parameters.") .def_readwrite( "rotorGearRatio", &Model::rotorGearRatio, "Vector of rotor gear ratio parameters.") - .def_readwrite("friction", &Model::friction, "Vector of joint friction parameters.") + .def_readwrite( + "friction", &Model::upperDryFrictionLimit, + "Deprecated member. Vector of joint friction parameters.") + .def_readwrite( + "upperDryFrictionLimit", &Model::upperDryFrictionLimit, + "Vector of maximum joint friction.") + .def_readwrite( + "lowerDryFrictionLimit", &Model::lowerDryFrictionLimit, + "Vector of minimum joint friction.") .def_readwrite("damping", &Model::damping, "Vector of joint damping parameters.") - .def_readwrite("effortLimit", &Model::effortLimit, "Joint max effort.") - .def_readwrite("velocityLimit", &Model::velocityLimit, "Joint max velocity.") + .def_readwrite( + "effortLimit", &Model::upperEffortLimit, "Deprecated member. Joint max effort.") + .def_readwrite("upperEffortLimit", &Model::upperEffortLimit, "Joint max effort.") + .def_readwrite("lowerEffortLimit", &Model::lowerEffortLimit, "Joint min effort.") + .def_readwrite( + "velocityLimit", &Model::upperVelocityLimit, "Deprecated member. Joint max velocity.") + .def_readwrite("lowerVelocityLimit", &Model::lowerVelocityLimit, "Joint min velocity.") + .def_readwrite("upperVelocityLimit", &Model::upperVelocityLimit, "Joint max velocity.") .def_readwrite( "lowerPositionLimit", &Model::lowerPositionLimit, "Limit for joint lower position.") .def_readwrite( "upperPositionLimit", &Model::upperPositionLimit, "Limit for joint upper position.") + .def_readwrite( + "positionLimitMargin", &Model::positionLimitMargin, "Margin for joint position limit.") .def_readwrite("frames", &Model::frames, "Vector of frames contained in the model.") .def_readwrite( "supports", &Model::supports, - "Vector of supports. supports[j] corresponds to the list of joints on the " - "path between\n" + "Vector of supports. supports[j] corresponds to the list of joints on the path " + "between\n" "the current *j* to the root of the kinematic tree.") .def_readwrite( @@ -160,8 +176,8 @@ namespace pinocchio .def( "addJoint", &ModelPythonVisitor::addJoint0, bp::args("self", "parent_id", "joint_model", "joint_placement", "joint_name"), - "Adds a joint to the kinematic tree. The joint is defined by its placement relative " - "to its parent joint and its name.") + "Adds a joint to the kinematic tree. The joint is defined by its placement relative to " + "its parent joint and its name.") .def( "addJoint", &ModelPythonVisitor::addJoint1, bp::args( @@ -169,17 +185,29 @@ namespace pinocchio "max_velocity", "min_config", "max_config"), "Adds a joint to the kinematic tree with given bounds. The joint is defined by its " "placement relative to its parent joint and its name." - "This signature also takes as input effort, velocity limits as well as the bounds " - "on the joint configuration.") + "This signature also takes as input effort, velocity limits as well as the bounds on " + "the joint configuration.") .def( "addJoint", &ModelPythonVisitor::addJoint2, bp::args( - "self", "parent_id", "joint_model", "joint_placement", "joint_name", "max_effort", - "max_velocity", "min_config", "max_config", "friction", "damping"), + "self", "parent_id", "joint_model", "joint_placement", "joint_name", "min_effort", + "max_effort", "min_velocity", "max_velocity", "min_config", "max_config", + "min_friction", "max_friction", "damping"), "Adds a joint to the kinematic tree with given bounds. The joint is defined by its " "placement relative to its parent joint and its name.\n" - "This signature also takes as input effort, velocity limits as well as the bounds " - "on the joint configuration.\n" + "This signature also takes as input effort, velocity limits as well as the bounds on " + "the joint configuration.\n" + "The user should also provide the friction and damping related to the joint.") + .def( + "addJoint", &ModelPythonVisitor::addJoint3, + bp::args( + "self", "parent_id", "joint_model", "joint_placement", "joint_name", "min_effort", + "max_effort", "min_velocity", "max_velocity", "min_config", "max_config", + "config_limit_margin", "min_friction", "max_friction", "damping"), + "Adds a joint to the kinematic tree with given bounds. The joint is defined by its " + "placement relative to its parent joint and its name.\n" + "This signature also takes as input effort, velocity limits, bounds on " + "the joint configuration as well as margin on these bounds.\n" "The user should also provide the friction and damping related to the joint.") .def( "addJointFrame", &Model::addJointFrame, @@ -189,8 +217,8 @@ namespace pinocchio .def( "appendBodyToJoint", &Model::appendBodyToJoint, bp::args("self", "joint_id", "body_inertia", "body_placement"), - "Appends a body to the joint given by its index. The body is defined by its " - "inertia, its relative placement regarding to the joint and its name.") + "Appends a body to the joint given by its index. The body is defined by its inertia, " + "its relative placement regarding to the joint and its name.") .def( "addBodyFrame", &Model::addBodyFrame, @@ -214,8 +242,8 @@ namespace pinocchio (bp::arg("self"), bp::arg("name"), bp::arg("type") = (FrameType)(JOINT | FIXED_JOINT | BODY | OP_FRAME | SENSOR)), "Returns the index of the frame given by its name and its type." - "If the frame is not in the frames vector, it returns the current size of the " - "frames vector.") + "If the frame is not in the frames vector, it returns the current size of the frames " + "vector.") .def( "existFrame", &Model::existFrame, @@ -232,7 +260,7 @@ namespace pinocchio "parent joint.") .def( - "createData", &ModelPythonVisitor::createData, bp::arg("self"), + "createData", &Model::createData, bp::arg("self"), "Create a Data object for the given model.") .def( @@ -245,7 +273,10 @@ namespace pinocchio .def( "hasConfigurationLimitInTangent", &Model::hasConfigurationLimitInTangent, bp::args("self"), - "Returns list of boolean if joints have configuration limit in tangent space .") + "Returns list of boolean if joints have configuration limit in tangent space.") + .def( + "getChildJoints", &Model::getChildJoints, bp::args("self"), + "Returns a vector of the children joints of the kinematic tree..") #ifndef PINOCCHIO_PYTHON_SKIP_COMPARISON_OPERATIONS @@ -291,21 +322,42 @@ namespace pinocchio const JointModel & jmodel, const SE3 & joint_placement, const std::string & joint_name, + const VectorXs & min_effort, const VectorXs & max_effort, + const VectorXs & min_velocity, const VectorXs & max_velocity, const VectorXs & min_config, const VectorXs & max_config, - const VectorXs & friction, + const VectorXs & min_friction, + const VectorXs & max_friction, const VectorXs & damping) { return model.addJoint( - parent_id, jmodel, joint_placement, joint_name, max_effort, max_velocity, min_config, - max_config, friction, damping); + parent_id, jmodel, joint_placement, joint_name, min_effort, max_effort, min_velocity, + max_velocity, min_config, max_config, min_friction, max_friction, damping); } - static Data createData(const Model & model) + static JointIndex addJoint3( + Model & model, + JointIndex parent_id, + const JointModel & jmodel, + const SE3 & joint_placement, + const std::string & joint_name, + const VectorXs & min_effort, + const VectorXs & max_effort, + const VectorXs & min_velocity, + const VectorXs & max_velocity, + const VectorXs & min_config, + const VectorXs & max_config, + const VectorXs & config_limit_margin, + const VectorXs & min_friction, + const VectorXs & max_friction, + const VectorXs & damping) { - return Data(model); + return model.addJoint( + parent_id, jmodel, joint_placement, joint_name, min_effort, max_effort, min_velocity, + max_velocity, min_config, max_config, config_limit_margin, min_friction, max_friction, + damping); } /// diff --git a/include/pinocchio/bindings/python/parsers/python.hpp b/include/pinocchio/bindings/python/parsers/python.hpp index f0571388ab..29dce53216 100644 --- a/include/pinocchio/bindings/python/parsers/python.hpp +++ b/include/pinocchio/bindings/python/parsers/python.hpp @@ -8,7 +8,7 @@ #include "pinocchio/macros.hpp" // clang-format off -PINOCCHIO_PRAGMA_DEPRECATED_HEADER(pinocchio/bindings/python/parsers/python.hpp, pinocchio/parsers/python.hpp) +PINOCCHIO_DEPRECATED_MOVED_HEADER(pinocchio/bindings/python/parsers/python.hpp, pinocchio/parsers/python.hpp) // clang-format on #include "pinocchio/parsers/python.hpp" diff --git a/include/pinocchio/bindings/python/spatial/force.hpp b/include/pinocchio/bindings/python/spatial/force.hpp index 52ff424eb3..8b2bcb4c24 100644 --- a/include/pinocchio/bindings/python/spatial/force.hpp +++ b/include/pinocchio/bindings/python/spatial/force.hpp @@ -85,15 +85,15 @@ namespace pinocchio bp::make_function( &ForcePythonVisitor::getLinear, bp::with_custodian_and_ward_postcall<0, 1>()), &ForcePythonVisitor::setLinear, - "Linear part of a *this, corresponding to the linear velocity in case of a " - "Spatial velocity.") + "Linear part of a *this, corresponding to the linear velocity in case of a Spatial " + "velocity.") .add_property( "angular", bp::make_function( &ForcePythonVisitor::getAngular, bp::with_custodian_and_ward_postcall<0, 1>()), &ForcePythonVisitor::setAngular, - "Angular part of a *this, corresponding to the angular velocity in case of " - "a Spatial velocity.") + "Angular part of a *this, corresponding to the angular velocity in case of a Spatial " + "velocity.") .add_property( "vector", bp::make_function( @@ -143,13 +143,13 @@ namespace pinocchio .def( "isApprox", &call::isApprox, (bp::arg("self"), bp::arg("other"), bp::arg("prec") = dummy_precision), - "Returns true if *this is approximately equal to other, within the precision given " - "by prec.") + "Returns true if *this is approximately equal to other, within the precision given by " + "prec.") .def( "isZero", &call::isZero, (bp::arg("self"), bp::arg("prec") = dummy_precision), - "Returns true if *this is approximately equal to the zero Force, within the " - "precision given by prec.") + "Returns true if *this is approximately equal to the zero Force, within the precision " + "given by prec.") #endif .def("Random", &Force::Random, "Returns a random Force.") diff --git a/include/pinocchio/bindings/python/spatial/inertia.hpp b/include/pinocchio/bindings/python/spatial/inertia.hpp index 6023575c89..d18a1d5fe9 100644 --- a/include/pinocchio/bindings/python/spatial/inertia.hpp +++ b/include/pinocchio/bindings/python/spatial/inertia.hpp @@ -74,8 +74,8 @@ namespace pinocchio "center of mass regarding to the frame where the Spatial Inertia is expressed.") .add_property( "inertia", &InertiaPythonVisitor::getInertia, &InertiaPythonVisitor::setInertia, - "Rotational part of the Spatial Inertia, i.e. a symmetric matrix " - "representing the rotational inertia around the center of mass.") + "Rotational part of the Spatial Inertia, i.e. a symmetric matrix representing the " + "rotational inertia around the center of mass.") .def("matrix", (Matrix6(Inertia::*)() const)&Inertia::matrix, bp::arg("self")) .def("inverse", (Matrix6(Inertia::*)() const)&Inertia::inverse, bp::arg("self")) @@ -132,8 +132,8 @@ namespace pinocchio .def( "isApprox", &Inertia::isApprox, (bp::arg("self"), bp::arg("other"), bp::arg("prec") = dummy_precision), - "Returns true if *this is approximately equal to other, within the precision given " - "by prec.") + "Returns true if *this is approximately equal to other, within the precision given by " + "prec.") .def( "isZero", &Inertia::isZero, (bp::arg("self"), bp::arg("prec") = dummy_precision), @@ -171,13 +171,13 @@ namespace pinocchio .def( "FromEllipsoid", &Inertia::FromEllipsoid, bp::args("mass", "length_x", "length_y", "length_z"), - "Returns the Inertia of an ellipsoid shape defined by a mass and given dimensions " - "the semi-axis of values length_{x,y,z}.") + "Returns the Inertia of an ellipsoid shape defined by a mass and given dimensions the " + "semi-axis of values length_{x,y,z}.") .staticmethod("FromEllipsoid") .def( "FromCylinder", &Inertia::FromCylinder, bp::args("mass", "radius", "length"), - "Returns the Inertia of a cylinder defined by its mass, radius and length along the " - "Z axis.") + "Returns the Inertia of a cylinder defined by its mass, radius and length along the Z " + "axis.") .staticmethod("FromCylinder") .def( "FromBox", &Inertia::FromBox, bp::args("mass", "length_x", "length_y", "length_z"), @@ -186,8 +186,8 @@ namespace pinocchio .staticmethod("FromBox") .def( "FromCapsule", &Inertia::FromCapsule, bp::args("mass", "radius", "height"), - "Computes the Inertia of a capsule defined by its mass, radius and length along the " - "Z axis. Assumes a uniform density.") + "Computes the Inertia of a capsule defined by its mass, radius and length along the Z " + "axis. Assumes a uniform density.") .staticmethod("FromCapsule") .def( diff --git a/include/pinocchio/bindings/python/spatial/motion.hpp b/include/pinocchio/bindings/python/spatial/motion.hpp index 9f3b1f781f..415a76511e 100644 --- a/include/pinocchio/bindings/python/spatial/motion.hpp +++ b/include/pinocchio/bindings/python/spatial/motion.hpp @@ -90,15 +90,15 @@ namespace pinocchio bp::make_function( &MotionPythonVisitor::getLinear, bp::with_custodian_and_ward_postcall<0, 1>()), &MotionPythonVisitor::setLinear, - "Linear part of a *this, corresponding to the linear velocity in case of a " - "Spatial velocity.") + "Linear part of a *this, corresponding to the linear velocity in case of a Spatial " + "velocity.") .add_property( "angular", bp::make_function( &MotionPythonVisitor::getAngular, bp::with_custodian_and_ward_postcall<0, 1>()), &MotionPythonVisitor::setAngular, - "Angular part of a *this, corresponding to the angular velocity in case of " - "a Spatial velocity.") + "Angular part of a *this, corresponding to the angular velocity in case of a Spatial " + "velocity.") .add_property( "vector", bp::make_function( @@ -166,13 +166,13 @@ namespace pinocchio .def( "isApprox", &call::isApprox, (bp::arg("self"), bp::arg("other"), bp::arg("prec") = dummy_precision), - "Returns true if *this is approximately equal to other, within the precision given " - "by prec.") + "Returns true if *this is approximately equal to other, within the precision given by " + "prec.") .def( "isZero", &call::isZero, (bp::arg("self"), bp::arg("prec") = dummy_precision), - "Returns true if *this is approximately equal to the zero Motion, within the " - "precision given by prec.") + "Returns true if *this is approximately equal to the zero Motion, within the precision " + "given by prec.") #endif .def("Random", &Motion::Random, "Returns a random Motion.") diff --git a/include/pinocchio/bindings/python/spatial/se3.hpp b/include/pinocchio/bindings/python/spatial/se3.hpp index 646a61f7bd..82f16bbf77 100644 --- a/include/pinocchio/bindings/python/spatial/se3.hpp +++ b/include/pinocchio/bindings/python/spatial/se3.hpp @@ -158,8 +158,8 @@ namespace pinocchio .def( "isApprox", &SE3::isApprox, (bp::arg("self"), bp::arg("other"), bp::arg("prec") = dummy_precision), - "Returns true if *this is approximately equal to other, within the precision given " - "by prec.") + "Returns true if *this is approximately equal to other, within the precision given by " + "prec.") .def( "isIdentity", &SE3::isIdentity, (bp::arg("self"), bp::arg("prec") = dummy_precision), @@ -187,8 +187,8 @@ namespace pinocchio .def( "Interpolate", &SE3::template Interpolate, bp::args("A", "B", "alpha"), "Linear interpolation on the SE3 manifold.\n\n" - "This method computes the linear interpolation between A and B, such that the " - "result C = A + (B-A)*t if it would be applied on classic Euclidian space.\n" + "This method computes the linear interpolation between A and B, such that the result C " + "= A + (B-A)*t if it would be applied on classic Euclidian space.\n" "This operation is very similar to the SLERP operation on Rotations.\n" "Parameters:\n" "\tA: Initial transformation\n" diff --git a/include/pinocchio/bindings/python/spatial/symmetric3.hpp b/include/pinocchio/bindings/python/spatial/symmetric3.hpp index 5fc4422062..bc94d4f86e 100644 --- a/include/pinocchio/bindings/python/spatial/symmetric3.hpp +++ b/include/pinocchio/bindings/python/spatial/symmetric3.hpp @@ -85,12 +85,12 @@ namespace pinocchio .def( "isApprox", &Symmetric3::isApprox, (bp::arg("self"), bp::arg("other"), bp::arg("prec") = dummy_precision), - "Returns true if *this is approximately equal to other, within the precision given " - "by prec.") + "Returns true if *this is approximately equal to other, within the precision given by " + "prec.") .def( "isZero", &Symmetric3::isZero, (bp::arg("self"), bp::arg("prec") = dummy_precision), - "Returns true if *this is approximately equal to the zero matrix, within the " - "precision given by prec.") + "Returns true if *this is approximately equal to the zero matrix, within the precision " + "given by prec.") #endif .def( "setDiagonal", &Symmetric3::template setDiagonal, bp::args("self", "diag"), @@ -112,8 +112,8 @@ namespace pinocchio .def("vtiv", &Symmetric3::vtiv, bp::args("self", "v")) .def( "vxs", &Symmetric3::template vxs, bp::args("v", "S3"), - "Performs the operation \f$ M = [v]_{\times} S_{3} \f$., Apply the cross product of " - "v on each column of S and return result matrix M.") + "Performs the operation \f$ M = [v]_{\times} S_{3} \f$., Apply the cross product of v " + "on each column of S and return result matrix M.") .staticmethod("vxs") .def( "svx", &Symmetric3::template vxs, bp::args("v", "S3"), diff --git a/include/pinocchio/bindings/python/utils/copyable.hpp b/include/pinocchio/bindings/python/utils/copyable.hpp index d33b4127de..4443209ff3 100644 --- a/include/pinocchio/bindings/python/utils/copyable.hpp +++ b/include/pinocchio/bindings/python/utils/copyable.hpp @@ -1,44 +1,21 @@ // -// Copyright (c) 2016-2023 CNRS INRIA +// Copyright (c) 2016-2023 CNRS INRIA, 2025 INRIA // #ifndef __pinocchio_python_utils_copyable_hpp__ #define __pinocchio_python_utils_copyable_hpp__ -#include +#include + +#include "pinocchio/deprecated.hpp" + +PINOCCHIO_DEPRECATED_HEADER("Directly include instead.") namespace pinocchio { namespace python { - - namespace bp = boost::python; - - /// - /// \brief Add the Python method copy to allow a copy of this by calling the copy constructor. - /// - template - struct CopyableVisitor : public bp::def_visitor> - { - template - void visit(PyClass & cl) const - { - cl.def("copy", ©, bp::arg("self"), "Returns a copy of *this."); - cl.def("__copy__", ©, bp::arg("self"), "Returns a copy of *this."); - cl.def( - "__deepcopy__", &deepcopy, bp::args("self", "memo"), "Returns a deep copy of *this."); - } - - private: - static C copy(const C & self) - { - return C(self); - } - static C deepcopy(const C & self, bp::dict) - { - return C(self); - } - }; + using eigenpy::CopyableVisitor; } // namespace python } // namespace pinocchio diff --git a/include/pinocchio/bindings/python/utils/deprecation.hpp b/include/pinocchio/bindings/python/utils/deprecation.hpp index 31141f8886..101ae4bdf3 100644 --- a/include/pinocchio/bindings/python/utils/deprecation.hpp +++ b/include/pinocchio/bindings/python/utils/deprecation.hpp @@ -1,62 +1,25 @@ // -// Copyright (c) 2020 INRIA +// Copyright (c) 2020-2025 INRIA // #ifndef __pinocchio_python_utils_deprecation_hpp__ #define __pinocchio_python_utils_deprecation_hpp__ -#include -#include -#include +#include +#include +#include "pinocchio/deprecated.hpp" + +PINOCCHIO_DEPRECATED_HEADER("Directly include instead.") namespace pinocchio { namespace python { - template - struct deprecated_warning_policy : Policy - { - deprecated_warning_policy(const std::string & warning_message = "") - : Policy() - , m_warning_message(warning_message) - { - } - - template - bool precall(ArgumentPackage const & args) const - { - PyErr_WarnEx(PyExc_UserWarning, m_warning_message.c_str(), 1); - return static_cast(this)->precall(args); - } - - typedef typename Policy::result_converter result_converter; - typedef typename Policy::argument_package argument_package; - - protected: - const std::string m_warning_message; - }; - - template - struct deprecated_member : deprecated_warning_policy - { - deprecated_member( - const std::string & warning_message = "This class member has been marked as deprecated and " - "will be removed in a future release.") - : deprecated_warning_policy(warning_message) - { - } - }; - - template - struct deprecated_function : deprecated_warning_policy - { - deprecated_function( - const std::string & warning_message = - "This function has been marked as deprecated and will be removed in a future release.") - : deprecated_warning_policy(warning_message) - { - } - }; + template + using deprecated_warning_policy = + eigenpy::deprecation_warning_policy; + using eigenpy::deprecated_function; + using eigenpy::deprecated_member; } // namespace python } // namespace pinocchio diff --git a/include/pinocchio/bindings/python/utils/eigen.hpp b/include/pinocchio/bindings/python/utils/eigen.hpp index 3a40dc9b2e..69f3316c4a 100644 --- a/include/pinocchio/bindings/python/utils/eigen.hpp +++ b/include/pinocchio/bindings/python/utils/eigen.hpp @@ -1,47 +1,51 @@ // -// Copyright (c) 2020-2021 INRIA +// Copyright (c) 2020-2025 INRIA // #ifndef __pinocchio_python_utils_eigen_hpp__ #define __pinocchio_python_utils_eigen_hpp__ -#include "pinocchio/bindings/python/fwd.hpp" -#include +#include +#include + +#include "pinocchio/math/matrix.hpp" namespace pinocchio { namespace python { - - template - Eigen::Ref make_ref(const Eigen::PlainObjectBase & mat) + template + std::string getEigenTypeName() { - typedef Eigen::Ref ReturnType; - return ReturnType(mat.const_cast_derived()); - } + std::stringstream ss; + if (::pinocchio::is_eigen_ref::value) + { + ss << "Ref"; + } - template - void make_symmetric(const Eigen::MatrixBase & mat, const int mode = Eigen::Upper) - { - if (mode == Eigen::Upper) + if (MatrixLike::IsRowMajor) + ss << "Row"; + + if (MatrixLike::IsVectorAtCompileTime) { - mat.const_cast_derived().template triangularView() = - mat.transpose().template triangularView(); + ss << "Vector"; } - else if (mode == Eigen::Lower) + else { - mat.const_cast_derived().template triangularView() = - mat.transpose().template triangularView(); + ss << "Matrix"; } - } - template - typename PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix) make_copy(const Eigen::MatrixBase & mat) - { - typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix) ReturnType; - return ReturnType(mat); - } + if (MatrixLike::SizeAtCompileTime == Eigen::Dynamic) + { + ss << "X"; + } + else + { + ss << std::to_string(MatrixLike::SizeAtCompileTime); + } + return ss.str(); + } } // namespace python } // namespace pinocchio diff --git a/include/pinocchio/bindings/python/utils/keep-alive.hpp b/include/pinocchio/bindings/python/utils/keep-alive.hpp new file mode 100644 index 0000000000..853cf0a33a --- /dev/null +++ b/include/pinocchio/bindings/python/utils/keep-alive.hpp @@ -0,0 +1,74 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_python_utils_keep_alive_hpp__ +#define __pinocchio_python_utils_keep_alive_hpp__ + +#include + +namespace pinocchio +{ + namespace python + { + template< + typename ReturnType, + std::size_t custodian, + std::size_t ward, + class BasePolicy_ = boost::python::default_call_policies> + struct keep_alive; + + template + struct keep_alive : BasePolicy_ + { + BOOST_STATIC_ASSERT(custodian != ward); + + template + static PyObject * postcall(ArgumentPackage const & args_, PyObject * result) + { + std::size_t arity_ = boost::python::detail::arity(args_); + // check if either custodian or ward exceeds the arity + // (this weird formulation avoids "always false" warnings + // for arity_ = 0) + if ((std::max)(custodian, ward) > arity_) + { + PyErr_SetString(PyExc_IndexError, "keep_alive_with_tuple: argument index out of range"); + return 0; + } + + if (!PyTuple_Check(result)) + { + PyErr_SetString(PyExc_RuntimeError, "keep_alive_with_tuple: result is not a tuple"); + return 0; + } + + int tuple_size = PyTuple_Size(result); + PINOCCHIO_THROW_PRETTY_IF( + custodian >= std::size_t(tuple_size), std::runtime_error, + "custodian is greater than tuple_size."); + + // keep_alive indicates that the argument with index Patient should be kept + // alive at least until the argument with index Nurse is freed by the garbage collector. + PyObject * patient = boost::python::detail::get_prev::execute(args_, result); + PyObject * nurse = PyTuple_GetItem(result, custodian); + + if (nurse == 0) + return 0; + + nurse = BasePolicy_::postcall(args_, nurse); + if (nurse == 0) + return 0; + + if (boost::python::objects::make_nurse_and_patient(nurse, patient) == 0) + { + Py_XDECREF(nurse); + return 0; + } + return result; + } + }; + + } // namespace python +} // namespace pinocchio + +#endif // ifndef __pinocchio_python_utils_keep_alive_hpp__ diff --git a/include/pinocchio/bindings/python/utils/registration.hpp b/include/pinocchio/bindings/python/utils/registration.hpp index 443955a449..e549a1ecbc 100644 --- a/include/pinocchio/bindings/python/utils/registration.hpp +++ b/include/pinocchio/bindings/python/utils/registration.hpp @@ -1,33 +1,20 @@ // -// Copyright (c) 2019-2020 INRIA +// Copyright (c) 2019-2025 INRIA // #ifndef __pinocchio_python_utils_registration_hpp__ #define __pinocchio_python_utils_registration_hpp__ +#include "pinocchio/deprecated.hpp" #include +PINOCCHIO_DEPRECATED_HEADER("Directly include instead.") + namespace pinocchio { namespace python { - - template - inline bool register_symbolic_link_to_registered_type() - { - namespace bp = boost::python; - if (eigenpy::check_registration()) - { - const bp::type_info info = bp::type_id(); - const bp::converter::registration * reg = bp::converter::registry::query(info); - bp::handle<> class_obj(bp::borrowed(reg->get_class_object())); - bp::scope().attr(reg->get_class_object()->tp_name) = bp::object(class_obj); - return true; - } - - return false; - } - + using eigenpy::register_symbolic_link_to_registered_type; } // namespace python } // namespace pinocchio diff --git a/include/pinocchio/bindings/python/visualizers/visualizer-visitor.hpp b/include/pinocchio/bindings/python/visualizers/visualizer-visitor.hpp index e153791538..d1697e7ac1 100644 --- a/include/pinocchio/bindings/python/visualizers/visualizer-visitor.hpp +++ b/include/pinocchio/bindings/python/visualizers/visualizer-visitor.hpp @@ -52,9 +52,9 @@ namespace pinocchio bp::make_function( \ +[](Visualizer & v) -> auto & { return v.name(); }, bp::return_internal_reference<>())) - cl.def("initViewer", &Visualizer::initViewer) - .def("loadViewerModel", &Visualizer::loadViewerModel) - .def("rebuildData", &Visualizer::rebuildData) + cl.def("initViewer", &Visualizer::initViewer, bp::arg("self")) + .def("loadViewerModel", &Visualizer::loadViewerModel, bp::arg("self")) + .def("rebuildData", &Visualizer::rebuildData, bp::arg("self")) .def( "display", +[](Visualizer & v, const ConstVectorRef & q) { v.display(q); }, (bp::arg("self"), bp::arg("q") = boost::none)) @@ -65,7 +65,7 @@ namespace pinocchio .def("setCameraPose", setCameraPose_proxy2, (bp::arg("self"), "pose")) .def("setCameraZoom", &Visualizer::setCameraZoom, (bp::arg("self"), "value")) .def("clean", &Visualizer::clean, bp::arg("self")) - .def("hasExternalData", &Visualizer::hasExternalData) + .def("hasExternalData", &Visualizer::hasExternalData, bp::arg("self")) .DEF_PROP_PROXY(model) .DEF_PROP_PROXY(visualModel) .DEF_PROP_PROXY(collisionModel) diff --git a/include/pinocchio/collision/broadphase-callbacks.hpp b/include/pinocchio/collision/broadphase-callbacks.hpp index 82fa01fd81..6da648a045 100644 --- a/include/pinocchio/collision/broadphase-callbacks.hpp +++ b/include/pinocchio/collision/broadphase-callbacks.hpp @@ -123,7 +123,7 @@ namespace pinocchio fcl::CollisionRequest collision_request( geometry_data_ptr->collisionRequests[size_t(pair_index)]); - collision_request.gjk_variant = fcl::GJKVariant::NesterovAcceleration; + // collision_request.gjk_variant = fcl::GJKVariant::PolyakAcceleration; // collision_request.gjk_initial_guess = fcl::GJKInitialGuess::BoundingVolumeGuess; if ( @@ -193,6 +193,83 @@ namespace pinocchio // Eigen::MatrixXd visited; }; + /// @brief This callback appends collision pairs when the broad phase finds them in collision. + /// A narrow phase pass must then be run on all appended collision pairs to complete the full + /// collision detection check. + struct CollisionCallBackCollect : CollisionCallBackBase + { + /// @brief Default constructor. + /// This constructor allocates pair_indexes depending on geometry_model and geometry_data. + CollisionCallBackCollect(const GeometryModel & geometry_model, GeometryData & geometry_data) + : CollisionCallBackBase(geometry_model, geometry_data) + { + this->pair_indexes.reserve(geometry_model.collisionPairs.size()); + } + + /// @brief Constructor based on a given max_num_pairs. + CollisionCallBackCollect( + const GeometryModel & geometry_model, GeometryData & geometry_data, const int max_num_pairs) + : CollisionCallBackBase(geometry_model, geometry_data) + { + this->pair_indexes.reserve(size_t(max_num_pairs)); + } + + /// @brief This method is called at the beginning of any broad phase call. + void init() + { + this->pair_indexes.clear(); + } + + /// @brief This method is called when two leafs of the broad phase are found to be in collision + /// (i.e. when two AABBs of a geometry_model's geometries are colliding). + bool collide(hpp::fcl::CollisionObject * o1, hpp::fcl::CollisionObject * o2) + { + assert(!stop() && "must never happened"); + + CollisionObject & co1 = reinterpret_cast(*o1); + CollisionObject & co2 = reinterpret_cast(*o2); + + const Eigen::DenseIndex go1_index = (Eigen::DenseIndex)co1.geometryObjectIndex; + const Eigen::DenseIndex go2_index = (Eigen::DenseIndex)co2.geometryObjectIndex; + + const GeometryModel & geometry_model = this->getGeometryModel(); + + PINOCCHIO_CHECK_INPUT_ARGUMENT( + go1_index < (Eigen::DenseIndex)geometry_model.ngeoms && go1_index >= 0); + PINOCCHIO_CHECK_INPUT_ARGUMENT( + go2_index < (Eigen::DenseIndex)geometry_model.ngeoms && go2_index >= 0); + + const int pair_index_ = geometry_model.collisionPairMapping(go1_index, go2_index); + if (pair_index_ == -1) + return false; + + const PairIndex pair_index = PairIndex(pair_index_); + const GeometryData & geometry_data = this->getGeometryData(); + const CollisionPair & cp = geometry_model.collisionPairs[pair_index]; + const bool do_collision_check = + geometry_data.activeCollisionPairs[pair_index] + && !( + geometry_model.geometryObjects[cp.first].disableCollision + || geometry_model.geometryObjects[cp.second].disableCollision); + + if (do_collision_check) + { + this->pair_indexes.push_back(pair_index); + } + + return false; + } + + bool stop() const final + { + return false; + } + + /// @brief Vector of pairs that where found in collision by the broad phase. + /// These pairs must then be sent to the narrow phase for a complete collision detection check. + std::vector pair_indexes; + }; + } // namespace pinocchio /* --- Details -------------------------------------------------------------------- */ diff --git a/include/pinocchio/collision/collision.hpp b/include/pinocchio/collision/collision.hpp index db76242ab3..9ce629922c 100644 --- a/include/pinocchio/collision/collision.hpp +++ b/include/pinocchio/collision/collision.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2015-2021 CNRS INRIA +// Copyright (c) 2015-2024 CNRS INRIA // #ifndef __pinocchio_collision_collision_hpp__ @@ -20,8 +20,8 @@ namespace pinocchio /// \brief Compute the collision status between a *SINGLE* collision pair. /// The result is store in the collisionResults vector. /// - /// \param[in] GeomModel the geometry model (const) - /// \param[out] GeomData the corresponding geometry data, where computations are done. + /// \param[in] geom_model the geometry model (const) + /// \param[out] geom_data the corresponding geometry data, where computations are done. /// \param[in] pair_id The collsion pair index in the GeometryModel. /// \param[in] collision_request The collision request associated to the collision pair. /// @@ -38,8 +38,8 @@ namespace pinocchio /// \brief Compute the collision status between a *SINGLE* collision pair. /// The result is store in the collisionResults vector. /// - /// \param[in] GeomModel the geometry model (const) - /// \param[out] GeomData the corresponding geometry data, where computations are done. + /// \param[in] geom_model the geometry model (const) + /// \param[out] geom_data the corresponding geometry data, where computations are done. /// \param[in] pair_id The collsion pair index in the GeometryModel. /// /// \return Return true is the collision objects are colliding. @@ -98,6 +98,30 @@ namespace pinocchio const Eigen::MatrixBase & q, const bool stopAtFirstCollision = false); + /// + /// \brief Compute the contact patch info associated with the collision pair given by pair_id. + /// Note that an actual computation will only occur if the collision pair is indeed in collision + /// (i.e. only if geom_data.collisionResult[pair_id].isCollision() is true). + /// + /// \param[in] geom_model the geometry model (const) + /// \param[out] geom_data the corresponding geometry data, where computations are done. + /// \param[in] pair_id The collsion pair index in the GeometryModel. + /// + /// \note The complete contact patch result is available in geom_data.contactPatchResults[pair_id] + /// + void computeContactPatch( + const GeometryModel & geom_model, GeometryData & geom_data, const PairIndex pair_id); + + /// + /// \brief Calls computeContactPatch for every collision pair. + /// + /// \param[in] geom_model the geometry model (const) + /// \param[out] geom_data the corresponding geometry data, where computations are done. + /// + /// \note This function must be called after computeCollisions. + /// + void computeContactPatches(const GeometryModel & geom_model, GeometryData & geom_data); + /// /// Compute the radius of the geometry volumes attached to every joints. /// diff --git a/include/pinocchio/collision/collision.hxx b/include/pinocchio/collision/collision.hxx index 113ed301de..3ed5fa060d 100644 --- a/include/pinocchio/collision/collision.hxx +++ b/include/pinocchio/collision/collision.hxx @@ -1,5 +1,5 @@ // -// Copyright (c) 2015-2021 CNRS INRIA +// Copyright (c) 2015-2024 CNRS INRIA // #ifndef __pinocchio_collision_collision_hxx__ @@ -15,6 +15,39 @@ namespace pinocchio { + inline void computeContactPatch( + const GeometryModel & geom_model, GeometryData & geom_data, const PairIndex pair_id) + { + const CollisionPair & pair = geom_model.collisionPairs[pair_id]; + fcl::CollisionResult & collision_result = geom_data.collisionResults[pair_id]; + const fcl::ContactPatchRequest & patch_request = geom_data.contactPatchRequests[pair_id]; + fcl::ContactPatchResult & patch_result = geom_data.contactPatchResults[pair_id]; + patch_result.clear(); // if a collision did not occur, we still want to clear the patch result + if (collision_result.isCollision() && patch_request.max_num_patch > 0) + { + fcl::Transform3f oM1(toFclTransform3f(geom_data.oMg[pair.first])); + fcl::Transform3f oM2(toFclTransform3f(geom_data.oMg[pair.second])); + GeometryData::ComputeContactPatch & contact_patch_functor = + geom_data.contact_patch_functors[pair_id]; + contact_patch_functor(oM1, oM2, collision_result, patch_request, patch_result); + } + } + + inline void computeContactPatches(const GeometryModel & geom_model, GeometryData & geom_data) + { + PINOCCHIO_CHECK_INPUT_ARGUMENT( + geom_model.collisionPairs.size() == geom_data.contactPatchResults.size()); + PINOCCHIO_CHECK_INPUT_ARGUMENT( + geom_model.collisionPairs.size() == geom_data.contactPatchRequests.size()); + PINOCCHIO_CHECK_INPUT_ARGUMENT( + geom_model.collisionPairs.size() == geom_data.contact_patch_functors.size()); + + for (std::size_t pair_id = 0; pair_id < geom_model.collisionPairs.size(); ++pair_id) + { + computeContactPatch(geom_model, geom_data, pair_id); + } + } + inline bool computeCollision( const GeometryModel & geom_model, GeometryData & geom_data, @@ -41,8 +74,8 @@ namespace pinocchio try { - GeometryData::ComputeCollision & do_computations = geom_data.collision_functors[pair_id]; - do_computations(oM1, oM2, collision_request, collision_result); + GeometryData::ComputeCollision & calc_collision = geom_data.collision_functors[pair_id]; + calc_collision(oM1, oM2, collision_request, collision_result); } catch (std::invalid_argument & e) { diff --git a/include/pinocchio/collision/parallel/broadphase.hpp b/include/pinocchio/collision/parallel/broadphase.hpp index ee69d25ccc..40ed8579f2 100644 --- a/include/pinocchio/collision/parallel/broadphase.hpp +++ b/include/pinocchio/collision/parallel/broadphase.hpp @@ -8,7 +8,7 @@ #include "pinocchio/collision/pool/broadphase-manager.hpp" #include "pinocchio/collision/broadphase.hpp" #include "pinocchio/algorithm/geometry.hpp" -#include "pinocchio/algorithm/parallel/omp.hpp" +#include "pinocchio/utils/openmp.hpp" #include @@ -50,13 +50,19 @@ namespace pinocchio PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), res.size()); res_.fill(false); - set_default_omp_options(num_threads); + setDefaultOpenMPSettings(num_threads); const Eigen::DenseIndex batch_size = res.size(); + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorPool) ConfigVectorPoolPlain; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConfigVectorPoolPlain) q_thread(num_threads, q); + + OpenMPException openmp_exception; + if (stopAtFirstCollisionInBatch) { bool is_colliding = false; Eigen::DenseIndex i = 0; + #pragma omp parallel for schedule(static) for (i = 0; i < batch_size; i++) { @@ -64,16 +70,24 @@ namespace pinocchio continue; const int thread_id = omp_get_thread_num(); + const Model & model = models[(size_t)thread_id]; Data & data = datas[(size_t)thread_id]; BroadPhaseManager & manager = broadphase_managers[(size_t)thread_id]; - res_[i] = - computeCollisions(model, data, manager, q.col(i), stopAtFirstCollisionInConfiguration); + const ConfigVectorPoolPlain & q = q_thread[size_t(thread_id)]; - if (res_[i]) - { - is_colliding = true; - } + openmp_exception.run([=, &is_colliding, &model, &data, &manager, &q, &res_] { + // lambda start corpus + + res_[i] = + computeCollisions(model, data, manager, q.col(i), stopAtFirstCollisionInConfiguration); + + if (res_[i]) + { + is_colliding = true; + } + // lambda end corpus + }); } } else @@ -83,13 +97,22 @@ namespace pinocchio for (i = 0; i < batch_size; i++) { const int thread_id = omp_get_thread_num(); + const Model & model = models[(size_t)thread_id]; Data & data = datas[(size_t)thread_id]; BroadPhaseManager & manager = broadphase_managers[(size_t)thread_id]; - res_[i] = - computeCollisions(model, data, manager, q.col(i), stopAtFirstCollisionInConfiguration); + const ConfigVectorPoolPlain & q = q_thread[size_t(thread_id)]; + + openmp_exception.run([=, &model, &data, &manager, &q, &res_] { + // lambda start corpus + res_[i] = + computeCollisions(model, data, manager, q.col(i), stopAtFirstCollisionInConfiguration); + // lambda end corpus + }); } } + + openmp_exception.rethrowException(); } /// @@ -131,20 +154,17 @@ namespace pinocchio PINOCCHIO_CHECK_ARGUMENT_SIZE(trajectories[k].rows(), model_check.nq); } - set_default_omp_options(num_threads); - const int64_t batch_size = static_cast(trajectories.size()); + setDefaultOpenMPSettings(num_threads); + const size_t batch_size = trajectories.size(); + + OpenMPException openmp_exception; - int64_t omp_i = 0; - // Visual studio support OpenMP 2 that only support signed indexes in for loops - // See - // https://stackoverflow.com/questions/2820621/why-arent-unsigned-openmp-index-variables-allowed - // -openmp:llvm could solve this: - // https://learn.microsoft.com/en-us/cpp/build/reference/openmp-enable-openmp-2-0-support?view=msvc-160 + size_t i = 0; #pragma omp parallel for schedule(static) - for (omp_i = 0; omp_i < batch_size; omp_i++) + for (i = 0; i < batch_size; i++) { - size_t i = static_cast(omp_i); const int thread_id = omp_get_thread_num(); + const Model & model = models[size_t(thread_id)]; Data & data = datas[(size_t)thread_id]; const Eigen::MatrixXd & current_traj = trajectories[i]; @@ -152,14 +172,21 @@ namespace pinocchio res_current_traj.fill(false); BroadPhaseManager & manager = broadphase_managers[size_t(thread_id)]; - for (Eigen::DenseIndex col_id = 0; col_id < current_traj.cols(); ++col_id) - { - res_current_traj[col_id] = - computeCollisions(model, data, manager, current_traj.col(col_id), true); - if (res_current_traj[col_id] && stopAtFirstCollisionInTrajectory) - break; - } + openmp_exception.run([=, &model, &data, &manager, ¤t_traj, &res_current_traj] { + // lambda start corpus + for (Eigen::DenseIndex col_id = 0; col_id < current_traj.cols(); ++col_id) + { + res_current_traj[col_id] = + computeCollisions(model, data, manager, current_traj.col(col_id), true); + + if (res_current_traj[col_id] && stopAtFirstCollisionInTrajectory) + break; + } + // lambda end corpus + }); } + + openmp_exception.rethrowException(); } } // namespace pinocchio diff --git a/include/pinocchio/collision/parallel/geometry.hpp b/include/pinocchio/collision/parallel/geometry.hpp index 3d0e5a4192..2afbdff0bb 100644 --- a/include/pinocchio/collision/parallel/geometry.hpp +++ b/include/pinocchio/collision/parallel/geometry.hpp @@ -8,7 +8,7 @@ #include "pinocchio/multibody/pool/geometry.hpp" #include "pinocchio/algorithm/geometry.hpp" #include "pinocchio/collision/collision.hpp" -#include "pinocchio/algorithm/parallel/omp.hpp" +#include "pinocchio/utils/openmp.hpp" #include @@ -23,39 +23,40 @@ namespace pinocchio { bool is_colliding = false; - set_default_omp_options(num_threads); - const int64_t batch_size = static_cast(geom_model.collisionPairs.size()); - int64_t omp_cp_index = 0; - // Visual studio support OpenMP 2 that only support signed indexes in for loops - // See - // https://stackoverflow.com/questions/2820621/why-arent-unsigned-openmp-index-variables-allowed - // -openmp:llvm could solve this: - // https://learn.microsoft.com/en-us/cpp/build/reference/openmp-enable-openmp-2-0-support?view=msvc-160 + setDefaultOpenMPSettings(num_threads); + std::size_t cp_index = 0; + + OpenMPException openmp_exception; + #pragma omp parallel for schedule(dynamic) - for (omp_cp_index = 0; omp_cp_index < batch_size; ++omp_cp_index) + for (cp_index = 0; cp_index < geom_model.collisionPairs.size(); ++cp_index) { - size_t cp_index = static_cast(omp_cp_index); - if (stopAtFirstCollision && is_colliding) continue; - const CollisionPair & collision_pair = geom_model.collisionPairs[cp_index]; + openmp_exception.run([=, &is_colliding, &geom_model, &geom_data] { + // lambda start corpus + const CollisionPair & collision_pair = geom_model.collisionPairs[cp_index]; - if ( - geom_data.activeCollisionPairs[cp_index] - && !( - geom_model.geometryObjects[collision_pair.first].disableCollision - || geom_model.geometryObjects[collision_pair.second].disableCollision)) - { - bool res = computeCollision(geom_model, geom_data, cp_index); - if (!is_colliding && res) + if ( + geom_data.activeCollisionPairs[cp_index] + && !( + geom_model.geometryObjects[collision_pair.first].disableCollision + || geom_model.geometryObjects[collision_pair.second].disableCollision)) { - is_colliding = true; - geom_data.collisionPairIndex = cp_index; // first pair to be in collision + bool res = computeCollision(geom_model, geom_data, cp_index); + if (!is_colliding && res) + { + is_colliding = true; + geom_data.collisionPairIndex = cp_index; // first pair to be in collision + } } - } + // lambda end corpus + }); } + openmp_exception.rethrowException(); + return is_colliding; } @@ -115,9 +116,15 @@ namespace pinocchio PINOCCHIO_CHECK_ARGUMENT_SIZE(q.cols(), res.size()); res_.fill(false); - set_default_omp_options(num_threads); + setDefaultOpenMPSettings(num_threads); const Eigen::DenseIndex batch_size = res.size(); + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorPool) ConfigVectorPoolPlain; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConfigVectorPoolPlain) q_thread(num_threads, q); + + OpenMPException openmp_exception; + + // TODO(jcarpent): set one res_ per thread to enhance efficiency if (stopAtFirstCollisionInBatch) { bool is_colliding = false; @@ -130,18 +137,26 @@ namespace pinocchio const int thread_id = omp_get_thread_num(); - const Model & model = models[(size_t)thread_id]; - Data & data = datas[(size_t)thread_id]; - const GeometryModel & geometry_model = geometry_models[(size_t)thread_id]; - GeometryData & geometry_data = geometry_datas[(size_t)thread_id]; - res_[i] = computeCollisions( - model, data, geometry_model, geometry_data, q.col(i), - stopAtFirstCollisionInConfiguration); - - if (res_[i]) - { - is_colliding = true; - } + const Model & model = models[size_t(thread_id)]; + Data & data = datas[size_t(thread_id)]; + const GeometryModel & geometry_model = geometry_models[size_t(thread_id)]; + GeometryData & geometry_data = geometry_datas[size_t(thread_id)]; + const ConfigVectorPoolPlain & q = q_thread[size_t(thread_id)]; + + openmp_exception.run( + [=, &is_colliding, &model, &data, &geometry_model, &geometry_data, &q, &res_] { + // lambda start corpus + + res_[i] = computeCollisions( + model, data, geometry_model, geometry_data, q.col(i), + stopAtFirstCollisionInConfiguration); + + if (res_[i]) + { + is_colliding = true; + } + // lambda end corpus + }); } } else @@ -156,11 +171,19 @@ namespace pinocchio Data & data = datas[(size_t)thread_id]; const GeometryModel & geometry_model = geometry_models[(size_t)thread_id]; GeometryData & geometry_data = geometry_datas[(size_t)thread_id]; - res_[i] = computeCollisions( - model, data, geometry_model, geometry_data, q.col(i), - stopAtFirstCollisionInConfiguration); + const ConfigVectorPoolPlain & q = q_thread[size_t(thread_id)]; + + openmp_exception.run([=, &model, &data, &geometry_model, &geometry_data, &q, &res_] { + // lambda start corpus + res_[i] = computeCollisions( + model, data, geometry_model, geometry_data, q.col(i), + stopAtFirstCollisionInConfiguration); + // lambda end corpus + }); } } + + openmp_exception.rethrowException(); } } // namespace pinocchio diff --git a/include/pinocchio/common/data-entity.hpp b/include/pinocchio/common/data-entity.hpp new file mode 100644 index 0000000000..d4a433e6b9 --- /dev/null +++ b/include/pinocchio/common/data-entity.hpp @@ -0,0 +1,32 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_common_data_entity_hpp__ +#define __pinocchio_common_data_entity_hpp__ + +#include "pinocchio/common/fwd.hpp" + +namespace pinocchio +{ + + template + struct DataEntity + { + typedef typename traits::Scalar Scalar; + typedef typename traits::Model Model; + + Derived & derived() + { + return static_cast(*this); + } + + const Derived & derived() const + { + return static_cast(*this); + } + }; + +} // namespace pinocchio + +#endif // ifndef __pinocchio_common_data_entity_hpp__ diff --git a/include/pinocchio/common/fwd.hpp b/include/pinocchio/common/fwd.hpp new file mode 100644 index 0000000000..c39ea44c77 --- /dev/null +++ b/include/pinocchio/common/fwd.hpp @@ -0,0 +1,20 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_common_fwd_hpp__ +#define __pinocchio_common_fwd_hpp__ + +#include "pinocchio/fwd.hpp" + +namespace pinocchio +{ + + template + struct DataEntity; + template + struct ModelEntity; + +} // namespace pinocchio + +#endif // ifndef __pinocchio_common_fwd_hpp__ diff --git a/include/pinocchio/common/model-entity.hpp b/include/pinocchio/common/model-entity.hpp new file mode 100644 index 0000000000..3535f66e4c --- /dev/null +++ b/include/pinocchio/common/model-entity.hpp @@ -0,0 +1,43 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_common_model_entity_hpp__ +#define __pinocchio_common_model_entity_hpp__ + +#include "pinocchio/common/fwd.hpp" + +namespace pinocchio +{ + + template + struct ModelEntity + { + typedef typename traits::Scalar Scalar; + typedef typename traits::Data Data; + + Derived & derived() + { + return static_cast(*this); + } + + const Derived & derived() const + { + return static_cast(*this); + } + + Data createData() const + { + derived().createData(); + } + }; + + template + typename traits::Data createData(const ModelEntity & entity) + { + return entity.createData(); + } + +} // namespace pinocchio + +#endif // ifndef __pinocchio_common_model_entity_hpp__ diff --git a/include/pinocchio/container/double-entry-container.hpp b/include/pinocchio/container/double-entry-container.hpp new file mode 100644 index 0000000000..6815118173 --- /dev/null +++ b/include/pinocchio/container/double-entry-container.hpp @@ -0,0 +1,297 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_container_double_entry_container_hpp__ +#define __pinocchio_container_double_entry_container_hpp__ + +#include "pinocchio/fwd.hpp" +#include +#include + +namespace pinocchio +{ + namespace container + { + template> + struct DoubleEntryContainer; + + template + struct DoubleEntryContainer + { + typedef Eigen::Array Array; + typedef std::vector Vector; + typedef Eigen::Index Index; + typedef std::pair IndexPair; + typedef typename Vector::iterator iterator; + typedef typename Vector::const_iterator const_iterator; + + /// \brief Empty constructor + DoubleEntryContainer() + { + } + + /// \brief Default contructor from two array dimension + DoubleEntryContainer(const Index nrows, const Index ncols) + : m_keys(Array::Constant(nrows, ncols, -1)) + { + } + + /// \brief Equality comparison operator + bool operator==(const DoubleEntryContainer & other) const + { + return (m_keys == other.m_keys).all() && m_values == other.m_values; + } + + bool operator!=(const DoubleEntryContainer & other) const + { + return !(*this == other); + } + + /// \brief Returns the number of rows of the double entry table. + Eigen::Index rows() const + { + return m_keys.rows(); + } + + /// \brief Returns the number of columns of the double entry table. + Eigen::Index cols() const + { + return m_keys.cols(); + } + + /// \brief Returns the current size of the double entry table. + size_t size() const + { + return m_values.size(); + } + + /// \brief Clear the content of the double entry table. + void clear() + { + m_keys.fill(-1); + m_values.clear(); + } + + /// \brief Fill with the same input value all the elements of the double entry table. + void fill(const T & new_value) + { + std::fill(begin(), end(), new_value); + } + + /// \brief Returns a const reference to the array of keys. + const Array & keys() const + { + return m_keys; + } + + /// \brief Returns a reference to the array of keys. + Array & keys() + { + return m_keys; + } + + /// \brief Returns the vector of values contained in the double entry table. + const Vector & values() const + { + return m_values; + } + /// \brief Returns the vector of values contained in the double entry table. + Vector & values() + { + return m_values; + } + + ///  \brief Returns true if the key (entry1,entry2) has been succesfully added. + bool insert(const Index entry1, const Index entry2, const T & value = T()) + { + if (!(entry1 >= 0 && entry1 < rows()) || !(entry2 >= 0 && entry2 < cols())) + return false; + if (m_keys(entry1, entry2) >= 0) + return false; + + m_keys(entry1, entry2) = long(m_values.size()); + m_values.push_back(value); + return true; + } + + bool insert(const IndexPair & key, const T & value = T()) + { + return this->insert(key.first, key.second, value); + } + + ///  \brief Returns true if the key (entry1,entry2) has been succesfully removed. + bool remove(const Index entry1, const Index entry2) + { + if (!(entry1 >= 0 && entry1 < rows()) || !(entry2 >= 0 && entry2 < cols())) + return false; + const long index = m_keys(entry1, entry2); + if (index < 0) + return false; + + m_values.erase(std::next(m_values.begin(), index)); + m_keys.coeffRef(entry1, entry2) = -1; + + typedef Eigen::Array OneDArray; + typedef Eigen::Map OneDArrayMap; + OneDArrayMap keys_map = OneDArrayMap(m_keys.data(), m_keys.size(), 1); + + for (Eigen::Index elt_id = 0; elt_id < keys_map.size(); ++elt_id) + { + if (keys_map[elt_id] > index) + { + keys_map[elt_id]--; + } + } + + return true; + } + + bool remove(const IndexPair & key) + { + return this->remove(key.first, key.second); + } + + /// \brief Finds the element associated with the given input key (entry1,entry2). + /// \returns an iterator to the element associated with the input key if it exists. + iterator find(const Index entry1, const Index entry2) + { + if (!(entry1 >= 0 && entry1 < rows()) || !(entry2 >= 0 && entry2 < cols())) + return m_values.end(); + + const long index = m_keys(entry1, entry2); + if (index < 0) + return m_values.end(); + + return std::next(m_values.begin(), index); + } + + iterator find(const IndexPair & key) + { + return this->find(key.first, key.second); + } + + /// \brief Finds the element associated with the given input key (entry1,entry2). + /// \returns an iterator to the element associated with the input key if it exists. + const_iterator find(const Index entry1, const Index entry2) const + { + if (!(entry1 >= 0 && entry1 < rows()) || !(entry2 >= 0 && entry2 < cols())) + return m_values.end(); + + const long index = m_keys(entry1, entry2); + if (index < 0) + return m_values.end(); + + return std::next(m_values.begin(), index); + } + + const_iterator find(const IndexPair & key) const + { + return this->find(key.first, key.second); + } + + /// \brief Check whether the key (entry1,entry2) exists. + bool exist(const Index entry1, const Index entry2) const + { + if (!(entry1 >= 0 && entry1 < rows()) || !(entry2 >= 0 && entry2 < cols())) + return false; + if (m_keys(entry1, entry2) < 0) + return false; + + return true; + } + + bool exist(const IndexPair & key) const + { + return exist(key.first, key.second); + } + + T & operator[](const IndexPair & key) + { + const Index entry1 = key.first; + const Index entry2 = key.second; + + if (!this->exist(entry1, entry2)) + this->insert(entry1, entry2); + + const long index = m_keys(entry1, entry2); + + return m_values[size_t(index)]; + } + + /// \brief Getter to access to a given value referenced by the input key without prior check. + T & get(const IndexPair & key) + { + assert(this->exist(key)); + const Index entry1 = key.first; + const Index entry2 = key.second; + const long index = m_keys(entry1, entry2); + + return m_values[size_t(index)]; + } + + /// \brief Getter to access to a given value referenced by the input key without prior check. + const T & get(const IndexPair & key) const + { + assert(this->exist(key)); + const Index entry1 = key.first; + const Index entry2 = key.second; + const long index = m_keys(entry1, entry2); + + return m_values[size_t(index)]; + } + +#ifdef PINOCCHIO_WITH_CXX23_SUPPORT + T & operator[](const Index entry1, const Index entry2) + { + return this->operator[]({entry1, entry2}); + } +#endif + + iterator begin() + { + return m_values.begin(); + } + + iterator end() + { + return m_values.end(); + } + + iterator rbegin() + { + return m_values.cbegin(); + } + + iterator rend() + { + return m_values.cend(); + } + + /// \brief Increase the capacity of the vector (the total number of elements that the vector + /// can hold without requiring reallocation) to a value that's greater or equal to new_cap + void reserve(const size_t new_cap) + { + m_values.reserve(new_cap); + } + + void apply(const std::function & func) + { + std::for_each(begin(), end(), func); + } + + void apply(const std::function & func) const + { + std::for_each(begin(), end(), func); + } + + protected: + Array m_keys; + Vector m_values; + }; + + } // namespace container + +} // namespace pinocchio + +#endif // ifndef __pinocchio_container_double_entry_container_hpp__ diff --git a/include/pinocchio/container/storage.hpp b/include/pinocchio/container/storage.hpp new file mode 100644 index 0000000000..1465b8d686 --- /dev/null +++ b/include/pinocchio/container/storage.hpp @@ -0,0 +1,302 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_container_storage_hpp__ +#define __pinocchio_container_storage_hpp__ + +#include "pinocchio/fwd.hpp" + +namespace pinocchio +{ + + template + struct EigenStorageTpl; + + template + struct CastType> + { + enum + { + RowsAtCompileTime = MatrixLike::RowsAtCompileTime, + ColsAtCompileTime = MatrixLike::ColsAtCompileTime, + Options = MatrixLike::Options + }; + + typedef Eigen::Matrix NewVectorType; + typedef EigenStorageTpl type; + }; + + template + struct EigenStorageTpl + { + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixLike) PlainMatrixType; + typedef typename MatrixLike::Scalar Scalar; + + typedef Eigen::Map MapType; + typedef Eigen::Map & RefMapType; + typedef const Eigen::Map & ConstRefMapType; + typedef const Eigen::Map ConstMapType; + typedef Eigen::DenseIndex Index; + + enum + { + MaxSizeAtCompileTime = + ((PlainMatrixType::MaxRowsAtCompileTime != Eigen::Dynamic) + && (PlainMatrixType::MaxRowsAtCompileTime != Eigen::Dynamic)) + ? PlainMatrixType::MaxRowsAtCompileTime * PlainMatrixType::MaxColsAtCompileTime + : Eigen::Dynamic, + IsVectorAtCompileTime = MatrixLike::IsVectorAtCompileTime, + Options = PlainMatrixType::Options & ~Eigen::RowMajorBit + }; + + typedef Eigen::Matrix StorageVector; + + /// \brief Default constructor from given matrix dimension (rows, cols) and maximum rows and + /// columns + /// + /// \param[in] rows Number of rows + /// \param[in] cols Number of columns + /// \param[in] max_rows Maximum number of rows + /// \param[in] max_cols Maximum number of columns + /// + EigenStorageTpl(const Index rows, const Index cols, const Index max_rows, const Index max_cols) + : m_storage(max_rows * max_cols) + , m_map(MapType(m_storage.data(), rows, cols)) + { + } + +#ifdef PINOCCHIO_PARSED_BY_DOXYGEN + /// \brief Default constructor from given matrix dimension (rows, cols). + /// + /// \param[in] rows Number of rows. + /// \param[in] cols Number of columns. + /// + EigenStorageTpl(const Index rows, const Index cols) + : m_map(NULL, rows, cols) + { + _init2(rows, cols); + } + + /// \brief Default constructor from given matrix dimension (rows, cols). + /// + /// \param[in] rows Number of rows. + /// \param[in] cols Number of columns. + /// + EigenStorageTpl(const Index size, const Index max_size) + : m_map(NULL, size) + { + _init2(rows, cols); + } +#else + EigenStorageTpl(const Index arg0, const Index arg1) + : m_map(NULL, arg0, arg1) + { + _init2(arg0, arg1); + } +#endif + + /// \brief Default constructor + EigenStorageTpl() + : m_map(NULL, 0, IsVectorAtCompileTime ? 1 : 0) + { + } + + /// \brief Constructor from a given size. For vector only. + explicit EigenStorageTpl(const Index size) + : m_storage(size) + , m_map(m_storage.data(), size) + { + } + + /// \brief Copy constructor (only consider the active part of storage) + EigenStorageTpl(const EigenStorageTpl & other) + : m_storage(other.m_storage.head(other.m_map.size())) + , m_map(m_storage.data(), other.m_map.rows(), other.m_map.cols()) + { + } + + /// \brief Move constructor + EigenStorageTpl(EigenStorageTpl && other) = default; + + EigenStorageTpl & operator=(const EigenStorageTpl & other) + { + m_storage = other.m_storage.head(other.m_map.size()); + new (&m_map) MapType(m_storage.data(), other.m_map.rows(), other.m_map.cols()); + + return *this; + } + + /// \brief Cast operator + template + typename CastType::type cast() const + { + typedef typename CastType::type ReturnType; + ReturnType res = ReturnType(rows(), cols()); + res.m_storage.head(size()) = m_storage.head(size()).template cast(); + return res; + } + + /// \brief Resize the current capacity of the internal storage. + /// + /// \remarks The resizing only happens when the new_size is greater than the current capacity + void resize(const Index rows, const Index cols) + { + const Index new_size = rows * cols; + if (new_size > capacity()) + m_storage.resize(2 * new_size); // Double the size of the storage + new (&m_map) MapType(m_storage.data(), rows, cols); + } + + void resize(const Index new_size) + { + EIGEN_STATIC_ASSERT_VECTOR_ONLY(MatrixLike) + if (new_size > capacity()) + m_storage.resize(2 * new_size); // Double the size of the storage + new (&m_map) MapType(m_storage.data(), new_size); + } + + /// \brief Reserve some place if the capacity is not enough. + /// + /// \remarks This is not data conservative + void reserve(const Index rows, const Index cols) + { + const Index new_size = rows * cols; + if (new_size > capacity()) + { + m_storage.resize(new_size); + new (&m_map) MapType(m_storage.data(), m_map.rows(), m_map.cols()); + } + } + + void reserve(const Index new_size) + { + EIGEN_STATIC_ASSERT_VECTOR_ONLY(MatrixLike) + if (new_size > capacity()) + { + m_storage.resize(new_size); + new (&m_map) MapType(m_storage.data(), m_map.size()); + } + } + + /// \brief Conservative resize of the current capacity of the internal storage. The data are + /// kepts in memory. + /// + /// \remarks The resizing only happens when the new_size is greater than the current capacity + void conservativeResize(const Index rows, const Index cols) + { + const Index old_rows = this->rows(), old_cols = this->cols(); + const PlainMatrixType copy(map()); // save current value in the storage + this->resize(rows, cols); + + // copy back values + const Index min_rows = (std::min)(rows, old_rows), min_cols = (std::min)(cols, old_cols); + map().topLeftCorner(min_rows, min_cols) = copy.topLeftCorner(min_rows, min_cols); + } + + /// \brief Conservative resize of the current capacity of the internal storage. The data are + /// kepts in memory. + /// + /// \remarks The resizing only happens when the new_size is greater than the current capacity + void conservativeResize(const Index new_size) + { + EIGEN_STATIC_ASSERT_VECTOR_ONLY(MatrixLike) + const Index old_size = this->size(); + const PlainMatrixType copy(map()); // save current value in the storage + this->resize(new_size); + + // copy back values + const Index min_size = (std::min)(new_size, old_size); + map().head(min_size) = copy.head(min_size); + } + + ///  \brief Returns the size of the storage space currently allocated. + Index capacity() const + { + return m_storage.size(); + } + + /// \brief Returns a const reference of the internal storage. + const StorageVector & storage() const + { + return m_storage; + } + + /// \brief Returns the internal pointer to the data. + const Scalar * data() const + { + return m_storage.data(); + } + + /// \brief Returns a map toward the internal matrix. + ConstRefMapType map() const + { + return m_map; + } + + /// \brief Returns a map toward the internal matrix. + RefMapType map() + { + return m_map; + } + + /// \brief Returns the number of rows + Index rows() const + { + return map().rows(); + } + + /// \brief Returns the number of columns + Index cols() const + { + return map().cols(); + } + + ///  \brief Returns the size of the underlying matrix or vector. + Index size() const + { + return map().size(); + } + + /// \brief Whether the internal map points towards a valid data. + bool isValid() const + { + return data() != NULL; + } + + template + friend struct EigenStorageTpl; + + /// \brief Comparison operator. + template + bool operator==(const EigenStorageTpl & other) const + { + return rows() == other.rows() && cols() == other.cols() + && m_storage.head(size()) == other.m_storage.head(size()); + } + + protected: + /// \brief Internal vector containing the stored quantities + StorageVector m_storage; + + /// \brief Map + MapType m_map; + + template + void _init2(const T rows, const T cols, std::enable_if_t * = 0) + { + m_storage = StorageVector(Eigen::DenseIndex(rows * cols)); + new (&m_map) MapType(m_storage.data(), rows, cols); + } + + template + void _init2(const T size, const T max_size, std::enable_if_t * = 0) + { + m_storage = StorageVector(max_size); + new (&m_map) MapType(m_storage.data(), size); + } + }; // struct EigenStorageTpl + +} // namespace pinocchio + +#endif // ifndef __pinocchio_container_storage_hpp__ diff --git a/include/pinocchio/context/generic.hpp b/include/pinocchio/context/generic.hpp index 5615d41d2b..4c8910516a 100644 --- a/include/pinocchio/context/generic.hpp +++ b/include/pinocchio/context/generic.hpp @@ -5,7 +5,7 @@ #ifndef __pinocchio_context_generic_hpp__ #define __pinocchio_context_generic_hpp__ -#include +#include "pinocchio/fwd.hpp" #include "pinocchio/container/aligned-vector.hpp" namespace pinocchio @@ -32,12 +32,16 @@ namespace pinocchio template struct InertiaTpl; template + struct InertiaTpl; + template struct RigidConstraintModelTpl; template struct RigidConstraintDataTpl; template struct CoulombFrictionConeTpl; + template + struct BoxSetTpl; template struct DualCoulombFrictionConeTpl; @@ -72,7 +76,9 @@ namespace pinocchio typedef SE3Tpl SE3; \ typedef MotionTpl Motion; \ typedef ForceTpl Force; \ - typedef InertiaTpl Inertia; + typedef InertiaTpl Inertia; \ + \ + typedef BoxSetTpl BoxSet; namespace context { diff --git a/include/pinocchio/deprecated-macros.hpp b/include/pinocchio/deprecated-macros.hpp deleted file mode 100644 index d25841e521..0000000000 --- a/include/pinocchio/deprecated-macros.hpp +++ /dev/null @@ -1,20 +0,0 @@ -// -// Copyright (c) 2018 INRIA -// - -#ifndef __pinocchio_deprecated_macros_hpp__ -#define __pinocchio_deprecated_macros_hpp__ - -#ifdef PINOCCHIO_WITH_HPP_FCL - #ifdef PINOCCHIO_ENABLE_COMPATIBILITY_WITH_VERSION_1 // for backward compatibility - #define WITH_HPP_FCL - #endif -#endif - -#ifdef PINOCCHIO_WITH_URDFDOM - #ifdef PINOCCHIO_ENABLE_COMPATIBILITY_WITH_VERSION_1 // for backward compatibility - #define WITH_URDFDOM - #endif -#endif - -#endif // ifndef __pinocchio_deprecated_macros_hpp__ diff --git a/include/pinocchio/deprecated-namespaces.hpp b/include/pinocchio/deprecated-namespaces.hpp deleted file mode 100644 index 951fd62799..0000000000 --- a/include/pinocchio/deprecated-namespaces.hpp +++ /dev/null @@ -1,12 +0,0 @@ -// -// Copyright (c) 2018 INRIA -// - -#ifndef __pinocchio_deprecated_namespaces_hpp__ -#define __pinocchio_deprecated_namespaces_hpp__ - -#if PINOCCHIO_ENABLE_COMPATIBILITY_WITH_VERSION_1 // do not warn -namespace se3 = ::pinocchio; -#endif - -#endif // ifndef __pinocchio_deprecated_namespaces_hpp__ diff --git a/include/pinocchio/deprecation.hpp b/include/pinocchio/deprecation.hpp deleted file mode 100644 index e2d6ba1ffc..0000000000 --- a/include/pinocchio/deprecation.hpp +++ /dev/null @@ -1,12 +0,0 @@ -// -// Copyright (c) 2018 INRIA -// - -#ifndef __pinocchio_deprecation_hpp__ -#define __pinocchio_deprecation_hpp__ - -#include "pinocchio/deprecated.hpp" -#include "pinocchio/deprecated-macros.hpp" -#include "pinocchio/deprecated-namespaces.hpp" - -#endif // ifndef __pinocchio_deprecation_hpp__ diff --git a/include/pinocchio/extra/reachable-workspace.hpp b/include/pinocchio/extra/reachable-workspace.hpp index 1f50d5cc3e..07cff8b983 100644 --- a/include/pinocchio/extra/reachable-workspace.hpp +++ b/include/pinocchio/extra/reachable-workspace.hpp @@ -15,8 +15,6 @@ #include "pinocchio/collision/collision.hpp" #endif // PINOCCHIO_WITH_HPP_FCL -#include - namespace pinocchio { /// @brief Structure containing the return value for the reachable algorithm diff --git a/include/pinocchio/extra/reachable-workspace.hxx b/include/pinocchio/extra/reachable-workspace.hxx index d2b3996f57..3d56cff700 100644 --- a/include/pinocchio/extra/reachable-workspace.hxx +++ b/include/pinocchio/extra/reachable-workspace.hxx @@ -135,8 +135,8 @@ namespace pinocchio Data data(model); // // Get limits - VectorXs dq_max = model.velocityLimit; - VectorXs dq_min = -model.velocityLimit; + VectorXs dq_max = model.upperVelocityLimit; + VectorXs dq_min = model.lowerVelocityLimit; double time_pin = 1; // pinocchio unit time in s used in integrate and difference double time_percent = time_horizon / time_pin; diff --git a/include/pinocchio/fwd.hpp b/include/pinocchio/fwd.hpp index bc11e74b89..cbee40d165 100644 --- a/include/pinocchio/fwd.hpp +++ b/include/pinocchio/fwd.hpp @@ -18,12 +18,35 @@ namespace pinocchio #include +#ifdef PINOCCHIO_EIGEN_CHECK_MALLOC + #ifndef EIGEN_RUNTIME_NO_MALLOC + #define EIGEN_RUNTIME_NO_MALLOC_WAS_NOT_DEFINED + #define EIGEN_RUNTIME_NO_MALLOC + #endif +#endif + #include "pinocchio/macros.hpp" -#include "pinocchio/deprecation.hpp" +#include "pinocchio/deprecated.hpp" #include "pinocchio/warning.hpp" #include "pinocchio/config.hpp" #include "pinocchio/unsupported.hpp" +// Include Eigen components +#include +#include +#include +#include +#include + +#ifdef PINOCCHIO_WITH_ACCELERATE_SUPPORT + #include +#endif + +#include "pinocchio/eigen-macros.hpp" +#ifdef PINOCCHIO_WITH_EIGEN_TENSOR_MODULE + #include +#endif + #include "pinocchio/utils/helpers.hpp" #include "pinocchio/utils/cast.hpp" #include "pinocchio/utils/check.hpp" @@ -37,7 +60,6 @@ namespace pinocchio #endif #endif -#include #include #include @@ -52,11 +74,6 @@ namespace pinocchio #endif #endif -#include "pinocchio/eigen-macros.hpp" -#ifdef PINOCCHIO_WITH_EIGEN_TENSOR_MODULE - #include -#endif - #include "pinocchio/core/binary-op.hpp" #include "pinocchio/core/unary-op.hpp" @@ -127,6 +144,8 @@ namespace pinocchio ARG4 = 4 }; + /// \brief Assignment operator list. + /// enum AssignmentOperatorType { SETTO, @@ -134,18 +153,29 @@ namespace pinocchio RMTO }; + ///  \brief Assignment operator tags + template + struct AssignmentOperatorTag + { + }; + + using SetTo = AssignmentOperatorTag; + using AddTo = AssignmentOperatorTag; + using RmTo = AssignmentOperatorTag; + /** This value means that a positive quantity (e.g., a size) is not known at compile-time, and * that instead the value is stored in some runtime variable. */ const int Dynamic = -1; - /// \brief Return type undefined + /// \brief Undefined return type /// This is an helper structure to help internal diagnosis. - struct ReturnTypeNotDefined; + struct UndefinedReturnType; typedef Eigen::Matrix VectorXb; } // namespace pinocchio #include "pinocchio/context.hpp" +#include "pinocchio/alloca.hpp" #endif // #ifndef __pinocchio_fwd_hpp__ diff --git a/include/pinocchio/macros.hpp b/include/pinocchio/macros.hpp index 3fcb29ad4c..6020cc8487 100644 --- a/include/pinocchio/macros.hpp +++ b/include/pinocchio/macros.hpp @@ -1,16 +1,22 @@ // -// Copyright (c) 2017-2022 CNRS INRIA +// Copyright (c) 2018-2025 INRIA +// Copyright (c) 2017-2018 CNRS // #ifndef __pinocchio_macros_hpp__ #define __pinocchio_macros_hpp__ -#include +#include "pinocchio/deprecated.hpp" +#include "pinocchio/warning.hpp" // On Windows, __cplusplus is not necessarily set to the C++ version being used. // See https://docs.microsoft.com/fr-fr/cpp/build/reference/zc-cplusplus?view=vs-2019 for further // information. +#if (__cplusplus >= 202302L) + #define PINOCCHIO_WITH_CXX23_SUPPORT +#endif + #if (__cplusplus >= 202002L) #define PINOCCHIO_WITH_CXX20_SUPPORT #endif @@ -27,27 +33,12 @@ #define PINOCCHIO_WITH_CXX11_SUPPORT #endif -#define PINOCCHIO_STRING_LITERAL(string) #string - -// For more details, visit -// https://stackoverflow.com/questions/171435/portability-of-warning-preprocessor-directive -#if defined(__GNUC__) || defined(__clang__) - #define PINOCCHIO_PRAGMA(x) _Pragma(#x) - #define PINOCCHIO_PRAGMA_MESSAGE(the_message) PINOCCHIO_PRAGMA(GCC message #the_message) - #define PINOCCHIO_PRAGMA_WARNING(the_message) PINOCCHIO_PRAGMA(GCC warning #the_message) - #define PINOCCHIO_PRAGMA_DEPRECATED(the_message) \ - PINOCCHIO_PRAGMA_WARNING(Deprecated : #the_message) - #define PINOCCHIO_PRAGMA_DEPRECATED_HEADER(old_header, new_header) \ - PINOCCHIO_PRAGMA_WARNING(Deprecated header file : #old_header has been replaced \ - by #new_header.\n Please use #new_header instead of #old_header.) -#else - #define PINOCCHIO_PRAGMA(x) - #define PINOCCHIO_PRAGMA_MESSAGE(the_message) - #define PINOCCHIO_PRAGMA_WARNING(the_message) - #define PINOCCHIO_PRAGMA_DEPRECATED(the_message) - #define PINOCCHIO_PRAGMA_DEPRECATED_HEADER(old_header, new_header) +#if defined(__APPLE__) && defined(__aarch64__) + #define PINOCCHIO_MAC_ARM64 #endif +#define PINOCCHIO_NOEXCEPT noexcept + /// \brief Function attribute to forbid inlining. /// This is a compiler hint that can be not respected. #define PINOCCHIO_DONT_INLINE EIGEN_DONT_INLINE @@ -74,6 +65,20 @@ namespace pinocchio /// \brief Helper to declare that a parameter is unused #define PINOCCHIO_UNUSED_VARIABLE(var) (void)(var) +#ifndef NDEBUG + #define PINOCCHIO_ONLY_USED_FOR_DEBUG(var) +#else + #define PINOCCHIO_ONLY_USED_FOR_DEBUG(var) PINOCCHIO_UNUSED_VARIABLE(var) +#endif + +#ifdef PINOCCHIO_WITH_CXX17_SUPPORT + #define PINOCCHIO_MAYBE_UNUSED [[maybe_unused]] +#else + #define PINOCCHIO_MAYBE_UNUSED +#endif + +#define PINOCCHIO_DEPRECATED_MOVED_HEADER(old_header, new_header) \ + PINOCCHIO_DEPRECATED_HEADER("#old_header has been replaced by #new_header.") /// Ensure that a matrix (or vector) is of correct size (compile-time and run-time assertion) #define PINOCCHIO_ASSERT_MATRIX_SPECIFIC_SIZE(type, M, nrows, ncols) \ @@ -159,11 +164,15 @@ PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_VARIADIC_MACROS /// \brief Generic macro to throw an exception in Pinocchio if the condition is not met with a given /// input message. #if !defined(PINOCCHIO_NO_THROW) - #define PINOCCHIO_THROW(condition, exception_type, message) \ - if (!(condition)) \ + #define PINOCCHIO_THROW(exception_type, message) \ { \ throw exception_type(message); \ } + #define PINOCCHIO_THROW_IF(condition, exception_type, message) \ + if (condition) \ + { \ + PINOCCHIO_THROW(exception_type, message); \ + } #define PINOCCHIO_THROW_PRETTY(exception, message) \ { \ @@ -171,19 +180,26 @@ PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_VARIADIC_MACROS ss << "From file: " << __FILE__ << "\n"; \ ss << "in function: " << PINOCCHIO_PRETTY_FUNCTION << "\n"; \ ss << "at line: " << __LINE__ << "\n"; \ - ss << "message: " << message << "\n"; \ + ss << "message:\n" << message << "\n"; \ throw exception(ss.str()); \ } + #define PINOCCHIO_THROW_PRETTY_IF(condition, exception_type, message) \ + if (condition) \ + { \ + PINOCCHIO_THROW_PRETTY(exception_type, message); \ + } #else - #define PINOCCHIO_THROW(condition, exception_type, message) + #define PINOCCHIO_THROW(exception_type, message) + #define PINOCCHIO_THROW_IF(condition, exception_type, message) #define PINOCCHIO_THROW_PRETTY(exception, message) + #define PINOCCHIO_THROW_PRETTY_IF(condition, exception, message) #endif #define _PINOCCHIO_EXPAND(x) x #define _PINOCCHIO_GET_OVERRIDE_FOR_CHECK_INPUT_ARGUMENT(_1, _2, MACRO_NAME, ...) MACRO_NAME #define _PINOCCHIO_CHECK_INPUT_ARGUMENT_2(condition, message) \ - PINOCCHIO_THROW(condition, std::invalid_argument, message) + {PINOCCHIO_THROW_IF(!(condition), std::invalid_argument, message)} #define _PINOCCHIO_CHECK_INPUT_ARGUMENT_1(condition) \ _PINOCCHIO_CHECK_INPUT_ARGUMENT_2( \ @@ -206,13 +222,13 @@ PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_VARIADIC_MACROS std::ostringstream oss; \ oss << "wrong argument size: expected " << expected_size << ", got " << size << std::endl; \ oss << "hint: " << message << std::endl; \ - PINOCCHIO_THROW(false, std::invalid_argument, oss.str()); \ + PINOCCHIO_THROW(std::invalid_argument, oss.str()); \ } #define _PINOCCHIO_CHECK_ARGUMENT_SIZE_2(size, expected_size) \ _PINOCCHIO_CHECK_ARGUMENT_SIZE_3( \ size, expected_size, \ - PINOCCHIO_STRING_LITERAL(size) " is different from " PINOCCHIO_STRING_LITERAL(expected_size)) + PINOCCHIO_WARN_STRINGISE(size) " is different from " PINOCCHIO_WARN_STRINGISE(expected_size)) #define _PINOCCHIO_CHECK_ARGUMENT_SIZE_1 @@ -222,6 +238,26 @@ PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_VARIADIC_MACROS __VA_ARGS__, _PINOCCHIO_CHECK_ARGUMENT_SIZE_3, _PINOCCHIO_CHECK_ARGUMENT_SIZE_2, \ _PINOCCHIO_CHECK_ARGUMENT_SIZE_1))(__VA_ARGS__)) +/// \brief Macro to check whether two matrices have the same size. +#define PINOCCHIO_CHECK_SAME_MATRIX_SIZE(mat1, mat2) \ + if (mat1.rows() != mat2.rows() || mat1.cols() != mat2.cols()) \ + { \ + std::ostringstream oss; \ + oss << "wrong matrix size: expected (" << mat1.rows() << ", " << mat1.cols() << "), got (" \ + << mat2.rows() << ", " << mat2.cols() << ")" << std::endl; \ + PINOCCHIO_THROW_PRETTY(std::invalid_argument, oss.str()); \ + } + +/// \brief Macro to check whether a given matrix is square +#define PINOCCHIO_CHECK_SQUARE_MATRIX(mat) \ + if (mat.rows() != mat.cols()) \ + { \ + std::ostringstream oss; \ + oss << "the matrix is not square: expected (" << mat.rows() << " == " << mat.cols() \ + << "), got (" << mat.rows() << " != " << mat.cols() << ")" << std::endl; \ + PINOCCHIO_THROW_PRETTY(std::invalid_argument, oss.str()); \ + } + PINOCCHIO_COMPILER_DIAGNOSTIC_POP #endif // ifndef __pinocchio_macros_hpp__ diff --git a/include/pinocchio/math/arithmetic-operators.hpp b/include/pinocchio/math/arithmetic-operators.hpp new file mode 100644 index 0000000000..c5ad9a030f --- /dev/null +++ b/include/pinocchio/math/arithmetic-operators.hpp @@ -0,0 +1,25 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_math_arithmetic_operators_hpp__ +#define __pinocchio_math_arithmetic_operators_hpp__ + +#include "pinocchio/math/matrix.hpp" + +namespace pinocchio +{ + template + struct MultiplicationOperatorReturnType; + + template + struct MultiplicationOperatorReturnType< + Eigen::MatrixBase, + Eigen::MatrixBase> : MatrixMatrixProduct + { + typedef MatrixMatrixProduct Base; + typedef typename Base::type type; + }; +} // namespace pinocchio + +#endif // #ifndef __pinocchio_math_arithmetic_operators_hpp__ diff --git a/include/pinocchio/math/casadi.hpp b/include/pinocchio/math/casadi.hpp index 385627380f..451e1faa28 100644 --- a/include/pinocchio/math/casadi.hpp +++ b/include/pinocchio/math/casadi.hpp @@ -8,7 +8,7 @@ #include "pinocchio/macros.hpp" // clang-format off -PINOCCHIO_PRAGMA_DEPRECATED_HEADER(pinocchio/math/casadi.hpp, pinocchio/autodiff/casadi.hpp) +PINOCCHIO_DEPRECATED_HEADER(pinocchio/math/casadi.hpp, pinocchio/autodiff/casadi.hpp) // clang-format on #include "pinocchio/autodiff/casadi.hpp" diff --git a/include/pinocchio/math/cppad.hpp b/include/pinocchio/math/cppad.hpp index 7994119ddd..8555cbe2e9 100644 --- a/include/pinocchio/math/cppad.hpp +++ b/include/pinocchio/math/cppad.hpp @@ -8,7 +8,7 @@ #include "pinocchio/macros.hpp" // clang-format off -PINOCCHIO_PRAGMA_DEPRECATED_HEADER(pinocchio/math/cppad.hpp, pinocchio/autodiff/cppad.hpp) +PINOCCHIO_DEPRECATED_MOVED_HEADER(pinocchio/math/cppad.hpp, pinocchio/autodiff/cppad.hpp) // clang-format on #include "pinocchio/autodiff/cppad.hpp" diff --git a/include/pinocchio/math/cppadcg.hpp b/include/pinocchio/math/cppadcg.hpp index 4ea53f4201..3ba14bb908 100644 --- a/include/pinocchio/math/cppadcg.hpp +++ b/include/pinocchio/math/cppadcg.hpp @@ -8,7 +8,7 @@ #include "pinocchio/macros.hpp" // clang-format off -PINOCCHIO_PRAGMA_DEPRECATED_HEADER(pinocchio/math/cppadcg.hpp, pinocchio/codegen/cppadcg.hpp) +PINOCCHIO_DEPRECATED_MOVED_HEADER(pinocchio/math/cppadcg.hpp, pinocchio/codegen/cppadcg.hpp) // clang-format on #include "pinocchio/codegen/cppadcg.hpp" diff --git a/include/pinocchio/math/details/matrix-inverse-10x10.hpp b/include/pinocchio/math/details/matrix-inverse-10x10.hpp new file mode 100644 index 0000000000..49e483e72c --- /dev/null +++ b/include/pinocchio/math/details/matrix-inverse-10x10.hpp @@ -0,0 +1,1280 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_math_details_matrix_inversion_10x10_hpp__ +#define __pinocchio_math_details_matrix_inversion_10x10_hpp__ + +#include "pinocchio/math/matrix.hpp" + +namespace pinocchio +{ + namespace internal + { + template<> + struct MatrixInversionCodeGeneratedImpl<10> + { + template + static void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse_) + { + typedef typename M1::Scalar Scalar; + + assert(is_symmetric(matrix, math::sqrt(dummy_precision()))); + + const auto & input_vec = matrix.reshaped(); + auto & matrix_inverse = matrix_inverse_.const_cast_derived(); + auto output_vec = matrix_inverse.reshaped(); + + Scalar a000, a001, a002, a003, a004, a005, a006, a007, a008, a009, a010, a011; + Scalar a012, a013, a014, a015, a016, a017, a018, a019, a020, a021, a022, a023; + Scalar a024, a025, a026, a027, a028, a029, a030, a031, a032, a033, a034, a035; + Scalar a036, a037, a038, a039, a040, a041, a042, a043, a044, a045, a046, a047; + Scalar a048, a049, a050, a051, a052, a053, a054, a055, a056, a057, a058, a059; + Scalar a060, a061, a062, a063, a064, a065, a066, a067, a068, a069, a070, a071; + Scalar a072, a073, a074, a075, a076, a077, a078, a079, a080, a081, a082, a083; + Scalar a084, a085, a086, a087, a088, a089, a090, a091, a092, a093, a094, a095; + Scalar a096, a097, a098, a099, a100, a101; + a000 = input_vec[0]; + a001 = input_vec[11]; + a002 = input_vec[22]; + a003 = input_vec[33]; + a004 = input_vec[44]; + a005 = input_vec[55]; + a006 = input_vec[66]; + a007 = input_vec[77]; + a008 = input_vec[88]; + a009 = input_vec[99]; + a010 = input_vec[98]; + a010 = (a010 / a009); + a011 = math::square(a010); + a011 = (a009 * a011); + a008 = (a008 - a011); + a011 = input_vec[87]; + a012 = input_vec[97]; + a013 = (a012 * a010); + a011 = (a011 - a013); + a011 = (a011 / a008); + a013 = math::square(a011); + a013 = (a008 * a013); + a012 = (a012 / a009); + a014 = math::square(a012); + a014 = (a009 * a014); + a013 = (a013 + a014); + a007 = (a007 - a013); + a013 = input_vec[76]; + a014 = input_vec[86]; + a015 = input_vec[96]; + a016 = (a015 * a010); + a014 = (a014 - a016); + a016 = (a014 * a011); + a017 = (a015 * a012); + a016 = (a016 + a017); + a013 = (a013 - a016); + a013 = (a013 / a007); + a016 = math::square(a013); + a016 = (a007 * a016); + a014 = (a014 / a008); + a017 = math::square(a014); + a017 = (a008 * a017); + a016 = (a016 + a017); + a015 = (a015 / a009); + a017 = math::square(a015); + a017 = (a009 * a017); + a016 = (a016 + a017); + a006 = (a006 - a016); + a016 = input_vec[65]; + a017 = input_vec[75]; + a018 = input_vec[85]; + a019 = input_vec[95]; + a020 = (a019 * a010); + a018 = (a018 - a020); + a020 = (a018 * a011); + a021 = (a019 * a012); + a020 = (a020 + a021); + a017 = (a017 - a020); + a020 = (a017 * a013); + a021 = (a018 * a014); + a020 = (a020 + a021); + a021 = (a019 * a015); + a020 = (a020 + a021); + a016 = (a016 - a020); + a016 = (a016 / a006); + a020 = math::square(a016); + a020 = (a006 * a020); + a017 = (a017 / a007); + a021 = math::square(a017); + a021 = (a007 * a021); + a020 = (a020 + a021); + a018 = (a018 / a008); + a021 = math::square(a018); + a021 = (a008 * a021); + a020 = (a020 + a021); + a019 = (a019 / a009); + a021 = math::square(a019); + a021 = (a009 * a021); + a020 = (a020 + a021); + a005 = (a005 - a020); + a020 = input_vec[54]; + a021 = input_vec[64]; + a022 = input_vec[74]; + a023 = input_vec[84]; + a024 = input_vec[94]; + a025 = (a024 * a010); + a023 = (a023 - a025); + a025 = (a023 * a011); + a026 = (a024 * a012); + a025 = (a025 + a026); + a022 = (a022 - a025); + a025 = (a022 * a013); + a026 = (a023 * a014); + a025 = (a025 + a026); + a026 = (a024 * a015); + a025 = (a025 + a026); + a021 = (a021 - a025); + a025 = (a021 * a016); + a026 = (a022 * a017); + a025 = (a025 + a026); + a026 = (a023 * a018); + a025 = (a025 + a026); + a026 = (a024 * a019); + a025 = (a025 + a026); + a020 = (a020 - a025); + a020 = (a020 / a005); + a025 = math::square(a020); + a025 = (a005 * a025); + a021 = (a021 / a006); + a026 = math::square(a021); + a026 = (a006 * a026); + a025 = (a025 + a026); + a022 = (a022 / a007); + a026 = math::square(a022); + a026 = (a007 * a026); + a025 = (a025 + a026); + a023 = (a023 / a008); + a026 = math::square(a023); + a026 = (a008 * a026); + a025 = (a025 + a026); + a024 = (a024 / a009); + a026 = math::square(a024); + a026 = (a009 * a026); + a025 = (a025 + a026); + a004 = (a004 - a025); + a025 = input_vec[43]; + a026 = input_vec[53]; + a027 = input_vec[63]; + a028 = input_vec[73]; + a029 = input_vec[83]; + a030 = input_vec[93]; + a031 = (a030 * a010); + a029 = (a029 - a031); + a031 = (a029 * a011); + a032 = (a030 * a012); + a031 = (a031 + a032); + a028 = (a028 - a031); + a031 = (a028 * a013); + a032 = (a029 * a014); + a031 = (a031 + a032); + a032 = (a030 * a015); + a031 = (a031 + a032); + a027 = (a027 - a031); + a031 = (a027 * a016); + a032 = (a028 * a017); + a031 = (a031 + a032); + a032 = (a029 * a018); + a031 = (a031 + a032); + a032 = (a030 * a019); + a031 = (a031 + a032); + a026 = (a026 - a031); + a031 = (a026 * a020); + a032 = (a027 * a021); + a031 = (a031 + a032); + a032 = (a028 * a022); + a031 = (a031 + a032); + a032 = (a029 * a023); + a031 = (a031 + a032); + a032 = (a030 * a024); + a031 = (a031 + a032); + a025 = (a025 - a031); + a025 = (a025 / a004); + a031 = math::square(a025); + a031 = (a004 * a031); + a026 = (a026 / a005); + a032 = math::square(a026); + a032 = (a005 * a032); + a031 = (a031 + a032); + a027 = (a027 / a006); + a032 = math::square(a027); + a032 = (a006 * a032); + a031 = (a031 + a032); + a028 = (a028 / a007); + a032 = math::square(a028); + a032 = (a007 * a032); + a031 = (a031 + a032); + a029 = (a029 / a008); + a032 = math::square(a029); + a032 = (a008 * a032); + a031 = (a031 + a032); + a030 = (a030 / a009); + a032 = math::square(a030); + a032 = (a009 * a032); + a031 = (a031 + a032); + a003 = (a003 - a031); + a031 = input_vec[32]; + a032 = input_vec[42]; + a033 = input_vec[52]; + a034 = input_vec[62]; + a035 = input_vec[72]; + a036 = input_vec[82]; + a037 = input_vec[92]; + a038 = (a037 * a010); + a036 = (a036 - a038); + a038 = (a036 * a011); + a039 = (a037 * a012); + a038 = (a038 + a039); + a035 = (a035 - a038); + a038 = (a035 * a013); + a039 = (a036 * a014); + a038 = (a038 + a039); + a039 = (a037 * a015); + a038 = (a038 + a039); + a034 = (a034 - a038); + a038 = (a034 * a016); + a039 = (a035 * a017); + a038 = (a038 + a039); + a039 = (a036 * a018); + a038 = (a038 + a039); + a039 = (a037 * a019); + a038 = (a038 + a039); + a033 = (a033 - a038); + a038 = (a033 * a020); + a039 = (a034 * a021); + a038 = (a038 + a039); + a039 = (a035 * a022); + a038 = (a038 + a039); + a039 = (a036 * a023); + a038 = (a038 + a039); + a039 = (a037 * a024); + a038 = (a038 + a039); + a032 = (a032 - a038); + a038 = (a032 * a025); + a039 = (a033 * a026); + a038 = (a038 + a039); + a039 = (a034 * a027); + a038 = (a038 + a039); + a039 = (a035 * a028); + a038 = (a038 + a039); + a039 = (a036 * a029); + a038 = (a038 + a039); + a039 = (a037 * a030); + a038 = (a038 + a039); + a031 = (a031 - a038); + a031 = (a031 / a003); + a038 = math::square(a031); + a038 = (a003 * a038); + a032 = (a032 / a004); + a039 = math::square(a032); + a039 = (a004 * a039); + a038 = (a038 + a039); + a033 = (a033 / a005); + a039 = math::square(a033); + a039 = (a005 * a039); + a038 = (a038 + a039); + a034 = (a034 / a006); + a039 = math::square(a034); + a039 = (a006 * a039); + a038 = (a038 + a039); + a035 = (a035 / a007); + a039 = math::square(a035); + a039 = (a007 * a039); + a038 = (a038 + a039); + a036 = (a036 / a008); + a039 = math::square(a036); + a039 = (a008 * a039); + a038 = (a038 + a039); + a037 = (a037 / a009); + a039 = math::square(a037); + a039 = (a009 * a039); + a038 = (a038 + a039); + a002 = (a002 - a038); + a038 = input_vec[21]; + a039 = input_vec[31]; + a040 = input_vec[41]; + a041 = input_vec[51]; + a042 = input_vec[61]; + a043 = input_vec[71]; + a044 = input_vec[81]; + a045 = input_vec[91]; + a046 = (a045 * a010); + a044 = (a044 - a046); + a046 = (a044 * a011); + a047 = (a045 * a012); + a046 = (a046 + a047); + a043 = (a043 - a046); + a046 = (a043 * a013); + a047 = (a044 * a014); + a046 = (a046 + a047); + a047 = (a045 * a015); + a046 = (a046 + a047); + a042 = (a042 - a046); + a046 = (a042 * a016); + a047 = (a043 * a017); + a046 = (a046 + a047); + a047 = (a044 * a018); + a046 = (a046 + a047); + a047 = (a045 * a019); + a046 = (a046 + a047); + a041 = (a041 - a046); + a046 = (a041 * a020); + a047 = (a042 * a021); + a046 = (a046 + a047); + a047 = (a043 * a022); + a046 = (a046 + a047); + a047 = (a044 * a023); + a046 = (a046 + a047); + a047 = (a045 * a024); + a046 = (a046 + a047); + a040 = (a040 - a046); + a046 = (a040 * a025); + a047 = (a041 * a026); + a046 = (a046 + a047); + a047 = (a042 * a027); + a046 = (a046 + a047); + a047 = (a043 * a028); + a046 = (a046 + a047); + a047 = (a044 * a029); + a046 = (a046 + a047); + a047 = (a045 * a030); + a046 = (a046 + a047); + a039 = (a039 - a046); + a046 = (a039 * a031); + a047 = (a040 * a032); + a046 = (a046 + a047); + a047 = (a041 * a033); + a046 = (a046 + a047); + a047 = (a042 * a034); + a046 = (a046 + a047); + a047 = (a043 * a035); + a046 = (a046 + a047); + a047 = (a044 * a036); + a046 = (a046 + a047); + a047 = (a045 * a037); + a046 = (a046 + a047); + a038 = (a038 - a046); + a038 = (a038 / a002); + a046 = math::square(a038); + a046 = (a002 * a046); + a039 = (a039 / a003); + a047 = math::square(a039); + a047 = (a003 * a047); + a046 = (a046 + a047); + a040 = (a040 / a004); + a047 = math::square(a040); + a047 = (a004 * a047); + a046 = (a046 + a047); + a041 = (a041 / a005); + a047 = math::square(a041); + a047 = (a005 * a047); + a046 = (a046 + a047); + a042 = (a042 / a006); + a047 = math::square(a042); + a047 = (a006 * a047); + a046 = (a046 + a047); + a043 = (a043 / a007); + a047 = math::square(a043); + a047 = (a007 * a047); + a046 = (a046 + a047); + a044 = (a044 / a008); + a047 = math::square(a044); + a047 = (a008 * a047); + a046 = (a046 + a047); + a045 = (a045 / a009); + a047 = math::square(a045); + a047 = (a009 * a047); + a046 = (a046 + a047); + a001 = (a001 - a046); + a046 = input_vec[10]; + a047 = input_vec[20]; + a048 = input_vec[30]; + a049 = input_vec[40]; + a050 = input_vec[50]; + a051 = input_vec[60]; + a052 = input_vec[70]; + a053 = input_vec[80]; + a054 = input_vec[90]; + a055 = (a054 * a010); + a053 = (a053 - a055); + a055 = (a053 * a011); + a056 = (a054 * a012); + a055 = (a055 + a056); + a052 = (a052 - a055); + a055 = (a052 * a013); + a056 = (a053 * a014); + a055 = (a055 + a056); + a056 = (a054 * a015); + a055 = (a055 + a056); + a051 = (a051 - a055); + a055 = (a051 * a016); + a056 = (a052 * a017); + a055 = (a055 + a056); + a056 = (a053 * a018); + a055 = (a055 + a056); + a056 = (a054 * a019); + a055 = (a055 + a056); + a050 = (a050 - a055); + a055 = (a050 * a020); + a056 = (a051 * a021); + a055 = (a055 + a056); + a056 = (a052 * a022); + a055 = (a055 + a056); + a056 = (a053 * a023); + a055 = (a055 + a056); + a056 = (a054 * a024); + a055 = (a055 + a056); + a049 = (a049 - a055); + a055 = (a049 * a025); + a056 = (a050 * a026); + a055 = (a055 + a056); + a056 = (a051 * a027); + a055 = (a055 + a056); + a056 = (a052 * a028); + a055 = (a055 + a056); + a056 = (a053 * a029); + a055 = (a055 + a056); + a056 = (a054 * a030); + a055 = (a055 + a056); + a048 = (a048 - a055); + a055 = (a048 * a031); + a056 = (a049 * a032); + a055 = (a055 + a056); + a056 = (a050 * a033); + a055 = (a055 + a056); + a056 = (a051 * a034); + a055 = (a055 + a056); + a056 = (a052 * a035); + a055 = (a055 + a056); + a056 = (a053 * a036); + a055 = (a055 + a056); + a056 = (a054 * a037); + a055 = (a055 + a056); + a047 = (a047 - a055); + a055 = (a047 * a038); + a056 = (a048 * a039); + a055 = (a055 + a056); + a056 = (a049 * a040); + a055 = (a055 + a056); + a056 = (a050 * a041); + a055 = (a055 + a056); + a056 = (a051 * a042); + a055 = (a055 + a056); + a056 = (a052 * a043); + a055 = (a055 + a056); + a056 = (a053 * a044); + a055 = (a055 + a056); + a056 = (a054 * a045); + a055 = (a055 + a056); + a046 = (a046 - a055); + a046 = (a046 / a001); + a055 = math::square(a046); + a055 = (a001 * a055); + a047 = (a047 / a002); + a056 = math::square(a047); + a056 = (a002 * a056); + a055 = (a055 + a056); + a048 = (a048 / a003); + a056 = math::square(a048); + a056 = (a003 * a056); + a055 = (a055 + a056); + a049 = (a049 / a004); + a056 = math::square(a049); + a056 = (a004 * a056); + a055 = (a055 + a056); + a050 = (a050 / a005); + a056 = math::square(a050); + a056 = (a005 * a056); + a055 = (a055 + a056); + a051 = (a051 / a006); + a056 = math::square(a051); + a056 = (a006 * a056); + a055 = (a055 + a056); + a052 = (a052 / a007); + a056 = math::square(a052); + a056 = (a007 * a056); + a055 = (a055 + a056); + a053 = (a053 / a008); + a056 = math::square(a053); + a056 = (a008 * a056); + a055 = (a055 + a056); + a054 = (a054 / a009); + a056 = math::square(a054); + a056 = (a009 * a056); + a055 = (a055 + a056); + a000 = (a000 - a055); + a055 = (1. / a000); + output_vec[0] = a055; + a055 = (a046 / a000); + a056 = (-a055); + output_vec[1] = a056; + a057 = (a046 * a038); + a057 = (a047 - a057); + a057 = (a057 / a000); + a058 = (-a057); + output_vec[2] = a058; + a059 = (a038 * a031); + a059 = (a039 - a059); + a060 = (a046 * a059); + a061 = (a047 * a031); + a060 = (a060 + a061); + a060 = (a048 - a060); + a060 = (a060 / a000); + a061 = (-a060); + output_vec[3] = a061; + a062 = (a031 * a025); + a062 = (a032 - a062); + a063 = (a038 * a062); + a064 = (a039 * a025); + a063 = (a063 + a064); + a063 = (a040 - a063); + a064 = (a046 * a063); + a065 = (a047 * a062); + a064 = (a064 + a065); + a065 = (a048 * a025); + a064 = (a064 + a065); + a064 = (a049 - a064); + a064 = (a064 / a000); + a065 = (-a064); + output_vec[4] = a065; + a066 = (a025 * a020); + a066 = (a026 - a066); + a067 = (a031 * a066); + a068 = (a032 * a020); + a067 = (a067 + a068); + a067 = (a033 - a067); + a068 = (a038 * a067); + a069 = (a039 * a066); + a068 = (a068 + a069); + a069 = (a040 * a020); + a068 = (a068 + a069); + a068 = (a041 - a068); + a069 = (a046 * a068); + a070 = (a047 * a067); + a069 = (a069 + a070); + a070 = (a048 * a066); + a069 = (a069 + a070); + a070 = (a049 * a020); + a069 = (a069 + a070); + a069 = (a050 - a069); + a069 = (a069 / a000); + a070 = (-a069); + output_vec[5] = a070; + a071 = (a020 * a016); + a071 = (a021 - a071); + a072 = (a025 * a071); + a073 = (a026 * a016); + a072 = (a072 + a073); + a072 = (a027 - a072); + a073 = (a031 * a072); + a074 = (a032 * a071); + a073 = (a073 + a074); + a074 = (a033 * a016); + a073 = (a073 + a074); + a073 = (a034 - a073); + a074 = (a038 * a073); + a075 = (a039 * a072); + a074 = (a074 + a075); + a075 = (a040 * a071); + a074 = (a074 + a075); + a075 = (a041 * a016); + a074 = (a074 + a075); + a074 = (a042 - a074); + a075 = (a046 * a074); + a076 = (a047 * a073); + a075 = (a075 + a076); + a076 = (a048 * a072); + a075 = (a075 + a076); + a076 = (a049 * a071); + a075 = (a075 + a076); + a076 = (a050 * a016); + a075 = (a075 + a076); + a075 = (a051 - a075); + a075 = (a075 / a000); + a076 = (-a075); + output_vec[6] = a076; + a077 = (a016 * a013); + a077 = (a017 - a077); + a078 = (a020 * a077); + a079 = (a021 * a013); + a078 = (a078 + a079); + a078 = (a022 - a078); + a079 = (a025 * a078); + a080 = (a026 * a077); + a079 = (a079 + a080); + a080 = (a027 * a013); + a079 = (a079 + a080); + a079 = (a028 - a079); + a080 = (a031 * a079); + a081 = (a032 * a078); + a080 = (a080 + a081); + a081 = (a033 * a077); + a080 = (a080 + a081); + a081 = (a034 * a013); + a080 = (a080 + a081); + a080 = (a035 - a080); + a081 = (a038 * a080); + a082 = (a039 * a079); + a081 = (a081 + a082); + a082 = (a040 * a078); + a081 = (a081 + a082); + a082 = (a041 * a077); + a081 = (a081 + a082); + a082 = (a042 * a013); + a081 = (a081 + a082); + a081 = (a043 - a081); + a082 = (a046 * a081); + a083 = (a047 * a080); + a082 = (a082 + a083); + a083 = (a048 * a079); + a082 = (a082 + a083); + a083 = (a049 * a078); + a082 = (a082 + a083); + a083 = (a050 * a077); + a082 = (a082 + a083); + a083 = (a051 * a013); + a082 = (a082 + a083); + a082 = (a052 - a082); + a082 = (a082 / a000); + a083 = (-a082); + output_vec[7] = a083; + a084 = (a013 * a011); + a084 = (a014 - a084); + a085 = (a016 * a084); + a086 = (a017 * a011); + a085 = (a085 + a086); + a085 = (a018 - a085); + a086 = (a020 * a085); + a087 = (a021 * a084); + a086 = (a086 + a087); + a087 = (a022 * a011); + a086 = (a086 + a087); + a086 = (a023 - a086); + a087 = (a025 * a086); + a088 = (a026 * a085); + a087 = (a087 + a088); + a088 = (a027 * a084); + a087 = (a087 + a088); + a088 = (a028 * a011); + a087 = (a087 + a088); + a087 = (a029 - a087); + a088 = (a031 * a087); + a089 = (a032 * a086); + a088 = (a088 + a089); + a089 = (a033 * a085); + a088 = (a088 + a089); + a089 = (a034 * a084); + a088 = (a088 + a089); + a089 = (a035 * a011); + a088 = (a088 + a089); + a088 = (a036 - a088); + a089 = (a038 * a088); + a090 = (a039 * a087); + a089 = (a089 + a090); + a090 = (a040 * a086); + a089 = (a089 + a090); + a090 = (a041 * a085); + a089 = (a089 + a090); + a090 = (a042 * a084); + a089 = (a089 + a090); + a090 = (a043 * a011); + a089 = (a089 + a090); + a089 = (a044 - a089); + a090 = (a046 * a089); + a091 = (a047 * a088); + a090 = (a090 + a091); + a091 = (a048 * a087); + a090 = (a090 + a091); + a091 = (a049 * a086); + a090 = (a090 + a091); + a091 = (a050 * a085); + a090 = (a090 + a091); + a091 = (a051 * a084); + a090 = (a090 + a091); + a091 = (a052 * a011); + a090 = (a090 + a091); + a090 = (a053 - a090); + a090 = (a090 / a000); + a091 = (-a090); + output_vec[8] = a091; + a092 = (a011 * a010); + a092 = (a012 - a092); + a093 = (a013 * a092); + a094 = (a014 * a010); + a093 = (a093 + a094); + a093 = (a015 - a093); + a094 = (a016 * a093); + a095 = (a017 * a092); + a094 = (a094 + a095); + a095 = (a018 * a010); + a094 = (a094 + a095); + a094 = (a019 - a094); + a095 = (a020 * a094); + a096 = (a021 * a093); + a095 = (a095 + a096); + a096 = (a022 * a092); + a095 = (a095 + a096); + a096 = (a023 * a010); + a095 = (a095 + a096); + a095 = (a024 - a095); + a096 = (a025 * a095); + a097 = (a026 * a094); + a096 = (a096 + a097); + a097 = (a027 * a093); + a096 = (a096 + a097); + a097 = (a028 * a092); + a096 = (a096 + a097); + a097 = (a029 * a010); + a096 = (a096 + a097); + a096 = (a030 - a096); + a097 = (a031 * a096); + a098 = (a032 * a095); + a097 = (a097 + a098); + a098 = (a033 * a094); + a097 = (a097 + a098); + a098 = (a034 * a093); + a097 = (a097 + a098); + a098 = (a035 * a092); + a097 = (a097 + a098); + a098 = (a036 * a010); + a097 = (a097 + a098); + a097 = (a037 - a097); + a098 = (a038 * a097); + a099 = (a039 * a096); + a098 = (a098 + a099); + a099 = (a040 * a095); + a098 = (a098 + a099); + a099 = (a041 * a094); + a098 = (a098 + a099); + a099 = (a042 * a093); + a098 = (a098 + a099); + a099 = (a043 * a092); + a098 = (a098 + a099); + a099 = (a044 * a010); + a098 = (a098 + a099); + a098 = (a045 - a098); + a099 = (a046 * a098); + a100 = (a047 * a097); + a099 = (a099 + a100); + a100 = (a048 * a096); + a099 = (a099 + a100); + a100 = (a049 * a095); + a099 = (a099 + a100); + a100 = (a050 * a094); + a099 = (a099 + a100); + a100 = (a051 * a093); + a099 = (a099 + a100); + a100 = (a052 * a092); + a099 = (a099 + a100); + a100 = (a053 * a010); + a099 = (a099 + a100); + a099 = (a054 - a099); + a099 = (a099 / a000); + a000 = (-a099); + output_vec[9] = a000; + output_vec[10] = a056; + a056 = (1. / a001); + a055 = (a046 * a055); + a056 = (a056 + a055); + output_vec[11] = a056; + a056 = (a046 * a057); + a055 = (a038 / a001); + a056 = (a056 - a055); + output_vec[12] = a056; + a055 = (a046 * a060); + a059 = (a059 / a001); + a055 = (a055 - a059); + output_vec[13] = a055; + a059 = (a046 * a064); + a063 = (a063 / a001); + a059 = (a059 - a063); + output_vec[14] = a059; + a063 = (a046 * a069); + a068 = (a068 / a001); + a063 = (a063 - a068); + output_vec[15] = a063; + a068 = (a046 * a075); + a074 = (a074 / a001); + a068 = (a068 - a074); + output_vec[16] = a068; + a074 = (a046 * a082); + a081 = (a081 / a001); + a074 = (a074 - a081); + output_vec[17] = a074; + a081 = (a046 * a090); + a089 = (a089 / a001); + a081 = (a081 - a089); + output_vec[18] = a081; + a046 = (a046 * a099); + a098 = (a098 / a001); + a046 = (a046 - a098); + output_vec[19] = a046; + output_vec[20] = a058; + output_vec[21] = a056; + a058 = (1. / a002); + a056 = (a038 * a056); + a057 = (a047 * a057); + a056 = (a056 - a057); + a058 = (a058 - a056); + output_vec[22] = a058; + a058 = (a031 / a002); + a056 = (a038 * a055); + a057 = (a047 * a060); + a056 = (a056 - a057); + a058 = (a058 + a056); + a056 = (-a058); + output_vec[23] = a056; + a062 = (a062 / a002); + a057 = (a038 * a059); + a098 = (a047 * a064); + a057 = (a057 - a098); + a062 = (a062 + a057); + a057 = (-a062); + output_vec[24] = a057; + a067 = (a067 / a002); + a098 = (a038 * a063); + a001 = (a047 * a069); + a098 = (a098 - a001); + a067 = (a067 + a098); + a098 = (-a067); + output_vec[25] = a098; + a073 = (a073 / a002); + a001 = (a038 * a068); + a089 = (a047 * a075); + a001 = (a001 - a089); + a073 = (a073 + a001); + a001 = (-a073); + output_vec[26] = a001; + a080 = (a080 / a002); + a089 = (a038 * a074); + a100 = (a047 * a082); + a089 = (a089 - a100); + a080 = (a080 + a089); + a089 = (-a080); + output_vec[27] = a089; + a088 = (a088 / a002); + a100 = (a038 * a081); + a101 = (a047 * a090); + a100 = (a100 - a101); + a088 = (a088 + a100); + a100 = (-a088); + output_vec[28] = a100; + a097 = (a097 / a002); + a038 = (a038 * a046); + a047 = (a047 * a099); + a038 = (a038 - a047); + a097 = (a097 + a038); + a038 = (-a097); + output_vec[29] = a038; + output_vec[30] = a061; + output_vec[31] = a055; + output_vec[32] = a056; + a056 = (1. / a003); + a055 = (a039 * a055); + a060 = (a048 * a060); + a055 = (a055 - a060); + a058 = (a031 * a058); + a055 = (a055 - a058); + a056 = (a056 - a055); + output_vec[33] = a056; + a056 = (a025 / a003); + a055 = (a039 * a059); + a058 = (a048 * a064); + a055 = (a055 - a058); + a058 = (a031 * a062); + a055 = (a055 - a058); + a056 = (a056 + a055); + a055 = (-a056); + output_vec[34] = a055; + a066 = (a066 / a003); + a058 = (a039 * a063); + a060 = (a048 * a069); + a058 = (a058 - a060); + a060 = (a031 * a067); + a058 = (a058 - a060); + a066 = (a066 + a058); + a058 = (-a066); + output_vec[35] = a058; + a072 = (a072 / a003); + a060 = (a039 * a068); + a061 = (a048 * a075); + a060 = (a060 - a061); + a061 = (a031 * a073); + a060 = (a060 - a061); + a072 = (a072 + a060); + a060 = (-a072); + output_vec[36] = a060; + a079 = (a079 / a003); + a061 = (a039 * a074); + a047 = (a048 * a082); + a061 = (a061 - a047); + a047 = (a031 * a080); + a061 = (a061 - a047); + a079 = (a079 + a061); + a061 = (-a079); + output_vec[37] = a061; + a087 = (a087 / a003); + a047 = (a039 * a081); + a002 = (a048 * a090); + a047 = (a047 - a002); + a002 = (a031 * a088); + a047 = (a047 - a002); + a087 = (a087 + a047); + a047 = (-a087); + output_vec[38] = a047; + a096 = (a096 / a003); + a039 = (a039 * a046); + a048 = (a048 * a099); + a039 = (a039 - a048); + a031 = (a031 * a097); + a039 = (a039 - a031); + a096 = (a096 + a039); + a039 = (-a096); + output_vec[39] = a039; + output_vec[40] = a065; + output_vec[41] = a059; + output_vec[42] = a057; + output_vec[43] = a055; + a055 = (1. / a004); + a059 = (a040 * a059); + a064 = (a049 * a064); + a059 = (a059 - a064); + a062 = (a032 * a062); + a059 = (a059 - a062); + a056 = (a025 * a056); + a059 = (a059 - a056); + a055 = (a055 - a059); + output_vec[44] = a055; + a055 = (a020 / a004); + a059 = (a040 * a063); + a056 = (a049 * a069); + a059 = (a059 - a056); + a056 = (a032 * a067); + a059 = (a059 - a056); + a056 = (a025 * a066); + a059 = (a059 - a056); + a055 = (a055 + a059); + a059 = (-a055); + output_vec[45] = a059; + a071 = (a071 / a004); + a056 = (a040 * a068); + a062 = (a049 * a075); + a056 = (a056 - a062); + a062 = (a032 * a073); + a056 = (a056 - a062); + a062 = (a025 * a072); + a056 = (a056 - a062); + a071 = (a071 + a056); + a056 = (-a071); + output_vec[46] = a056; + a078 = (a078 / a004); + a062 = (a040 * a074); + a064 = (a049 * a082); + a062 = (a062 - a064); + a064 = (a032 * a080); + a062 = (a062 - a064); + a064 = (a025 * a079); + a062 = (a062 - a064); + a078 = (a078 + a062); + a062 = (-a078); + output_vec[47] = a062; + a086 = (a086 / a004); + a064 = (a040 * a081); + a057 = (a049 * a090); + a064 = (a064 - a057); + a057 = (a032 * a088); + a064 = (a064 - a057); + a057 = (a025 * a087); + a064 = (a064 - a057); + a086 = (a086 + a064); + a064 = (-a086); + output_vec[48] = a064; + a095 = (a095 / a004); + a040 = (a040 * a046); + a049 = (a049 * a099); + a040 = (a040 - a049); + a032 = (a032 * a097); + a040 = (a040 - a032); + a025 = (a025 * a096); + a040 = (a040 - a025); + a095 = (a095 + a040); + a040 = (-a095); + output_vec[49] = a040; + output_vec[50] = a070; + output_vec[51] = a063; + output_vec[52] = a098; + output_vec[53] = a058; + output_vec[54] = a059; + a059 = (1. / a005); + a063 = (a041 * a063); + a069 = (a050 * a069); + a063 = (a063 - a069); + a067 = (a033 * a067); + a063 = (a063 - a067); + a066 = (a026 * a066); + a063 = (a063 - a066); + a055 = (a020 * a055); + a063 = (a063 - a055); + a059 = (a059 - a063); + output_vec[55] = a059; + a059 = (a016 / a005); + a063 = (a041 * a068); + a055 = (a050 * a075); + a063 = (a063 - a055); + a055 = (a033 * a073); + a063 = (a063 - a055); + a055 = (a026 * a072); + a063 = (a063 - a055); + a055 = (a020 * a071); + a063 = (a063 - a055); + a059 = (a059 + a063); + a063 = (-a059); + output_vec[56] = a063; + a077 = (a077 / a005); + a055 = (a041 * a074); + a066 = (a050 * a082); + a055 = (a055 - a066); + a066 = (a033 * a080); + a055 = (a055 - a066); + a066 = (a026 * a079); + a055 = (a055 - a066); + a066 = (a020 * a078); + a055 = (a055 - a066); + a077 = (a077 + a055); + a055 = (-a077); + output_vec[57] = a055; + a085 = (a085 / a005); + a066 = (a041 * a081); + a067 = (a050 * a090); + a066 = (a066 - a067); + a067 = (a033 * a088); + a066 = (a066 - a067); + a067 = (a026 * a087); + a066 = (a066 - a067); + a067 = (a020 * a086); + a066 = (a066 - a067); + a085 = (a085 + a066); + a066 = (-a085); + output_vec[58] = a066; + a094 = (a094 / a005); + a041 = (a041 * a046); + a050 = (a050 * a099); + a041 = (a041 - a050); + a033 = (a033 * a097); + a041 = (a041 - a033); + a026 = (a026 * a096); + a041 = (a041 - a026); + a020 = (a020 * a095); + a041 = (a041 - a020); + a094 = (a094 + a041); + a041 = (-a094); + output_vec[59] = a041; + output_vec[60] = a076; + output_vec[61] = a068; + output_vec[62] = a001; + output_vec[63] = a060; + output_vec[64] = a056; + output_vec[65] = a063; + a063 = (1. / a006); + a068 = (a042 * a068); + a075 = (a051 * a075); + a068 = (a068 - a075); + a073 = (a034 * a073); + a068 = (a068 - a073); + a072 = (a027 * a072); + a068 = (a068 - a072); + a071 = (a021 * a071); + a068 = (a068 - a071); + a059 = (a016 * a059); + a068 = (a068 - a059); + a063 = (a063 - a068); + output_vec[66] = a063; + a063 = (a013 / a006); + a068 = (a042 * a074); + a059 = (a051 * a082); + a068 = (a068 - a059); + a059 = (a034 * a080); + a068 = (a068 - a059); + a059 = (a027 * a079); + a068 = (a068 - a059); + a059 = (a021 * a078); + a068 = (a068 - a059); + a059 = (a016 * a077); + a068 = (a068 - a059); + a063 = (a063 + a068); + a068 = (-a063); + output_vec[67] = a068; + a084 = (a084 / a006); + a059 = (a042 * a081); + a071 = (a051 * a090); + a059 = (a059 - a071); + a071 = (a034 * a088); + a059 = (a059 - a071); + a071 = (a027 * a087); + a059 = (a059 - a071); + a071 = (a021 * a086); + a059 = (a059 - a071); + a071 = (a016 * a085); + a059 = (a059 - a071); + a084 = (a084 + a059); + a059 = (-a084); + output_vec[68] = a059; + a093 = (a093 / a006); + a042 = (a042 * a046); + a051 = (a051 * a099); + a042 = (a042 - a051); + a034 = (a034 * a097); + a042 = (a042 - a034); + a027 = (a027 * a096); + a042 = (a042 - a027); + a021 = (a021 * a095); + a042 = (a042 - a021); + a016 = (a016 * a094); + a042 = (a042 - a016); + a093 = (a093 + a042); + a042 = (-a093); + output_vec[69] = a042; + output_vec[70] = a083; + output_vec[71] = a074; + output_vec[72] = a089; + output_vec[73] = a061; + output_vec[74] = a062; + output_vec[75] = a055; + output_vec[76] = a068; + a068 = (1. / a007); + a074 = (a043 * a074); + a082 = (a052 * a082); + a074 = (a074 - a082); + a080 = (a035 * a080); + a074 = (a074 - a080); + a079 = (a028 * a079); + a074 = (a074 - a079); + a078 = (a022 * a078); + a074 = (a074 - a078); + a077 = (a017 * a077); + a074 = (a074 - a077); + a063 = (a013 * a063); + a074 = (a074 - a063); + a068 = (a068 - a074); + output_vec[77] = a068; + a068 = (a011 / a007); + a074 = (a043 * a081); + a063 = (a052 * a090); + a074 = (a074 - a063); + a063 = (a035 * a088); + a074 = (a074 - a063); + a063 = (a028 * a087); + a074 = (a074 - a063); + a063 = (a022 * a086); + a074 = (a074 - a063); + a063 = (a017 * a085); + a074 = (a074 - a063); + a063 = (a013 * a084); + a074 = (a074 - a063); + a068 = (a068 + a074); + a074 = (-a068); + output_vec[78] = a074; + a092 = (a092 / a007); + a043 = (a043 * a046); + a052 = (a052 * a099); + a043 = (a043 - a052); + a035 = (a035 * a097); + a043 = (a043 - a035); + a028 = (a028 * a096); + a043 = (a043 - a028); + a022 = (a022 * a095); + a043 = (a043 - a022); + a017 = (a017 * a094); + a043 = (a043 - a017); + a013 = (a013 * a093); + a043 = (a043 - a013); + a092 = (a092 + a043); + a043 = (-a092); + output_vec[79] = a043; + output_vec[80] = a091; + output_vec[81] = a081; + output_vec[82] = a100; + output_vec[83] = a047; + output_vec[84] = a064; + output_vec[85] = a066; + output_vec[86] = a059; + output_vec[87] = a074; + a074 = (1. / a008); + a081 = (a044 * a081); + a090 = (a053 * a090); + a081 = (a081 - a090); + a088 = (a036 * a088); + a081 = (a081 - a088); + a087 = (a029 * a087); + a081 = (a081 - a087); + a086 = (a023 * a086); + a081 = (a081 - a086); + a085 = (a018 * a085); + a081 = (a081 - a085); + a084 = (a014 * a084); + a081 = (a081 - a084); + a068 = (a011 * a068); + a081 = (a081 - a068); + a074 = (a074 - a081); + output_vec[88] = a074; + a008 = (a010 / a008); + a044 = (a044 * a046); + a053 = (a053 * a099); + a044 = (a044 - a053); + a036 = (a036 * a097); + a044 = (a044 - a036); + a029 = (a029 * a096); + a044 = (a044 - a029); + a023 = (a023 * a095); + a044 = (a044 - a023); + a018 = (a018 * a094); + a044 = (a044 - a018); + a014 = (a014 * a093); + a044 = (a044 - a014); + a011 = (a011 * a092); + a044 = (a044 - a011); + a008 = (a008 + a044); + a044 = (-a008); + output_vec[89] = a044; + output_vec[90] = a000; + output_vec[91] = a046; + output_vec[92] = a038; + output_vec[93] = a039; + output_vec[94] = a040; + output_vec[95] = a041; + output_vec[96] = a042; + output_vec[97] = a043; + output_vec[98] = a044; + a009 = (1. / a009); + a045 = (a045 * a046); + a054 = (a054 * a099); + a045 = (a045 - a054); + a037 = (a037 * a097); + a045 = (a045 - a037); + a030 = (a030 * a096); + a045 = (a045 - a030); + a024 = (a024 * a095); + a045 = (a045 - a024); + a019 = (a019 * a094); + a045 = (a045 - a019); + a015 = (a015 * a093); + a045 = (a045 - a015); + a012 = (a012 * a092); + a045 = (a045 - a012); + a010 = (a010 * a008); + a045 = (a045 - a010); + a009 = (a009 - a045); + output_vec[99] = a009; + } + }; + } // namespace internal +} // namespace pinocchio + +#endif // ifndef __pinocchio_math_details_matrix_inversion_10x10_hpp__ diff --git a/include/pinocchio/math/details/matrix-inverse-11x11.hpp b/include/pinocchio/math/details/matrix-inverse-11x11.hpp new file mode 100644 index 0000000000..38477ceaf1 --- /dev/null +++ b/include/pinocchio/math/details/matrix-inverse-11x11.hpp @@ -0,0 +1,1664 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_math_details_matrix_inversion_11x11_hpp__ +#define __pinocchio_math_details_matrix_inversion_11x11_hpp__ + +#include "pinocchio/math/matrix.hpp" + +namespace pinocchio +{ + namespace internal + { + template<> + struct MatrixInversionCodeGeneratedImpl<11> + { + template + static void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse_) + { + typedef typename M1::Scalar Scalar; + + assert(is_symmetric(matrix, math::sqrt(dummy_precision()))); + + const auto & input_vec = matrix.reshaped(); + auto & matrix_inverse = matrix_inverse_.const_cast_derived(); + auto output_vec = matrix_inverse.reshaped(); + + Scalar a000, a001, a002, a003, a004, a005, a006, a007, a008, a009, a010, a011; + Scalar a012, a013, a014, a015, a016, a017, a018, a019, a020, a021, a022, a023; + Scalar a024, a025, a026, a027, a028, a029, a030, a031, a032, a033, a034, a035; + Scalar a036, a037, a038, a039, a040, a041, a042, a043, a044, a045, a046, a047; + Scalar a048, a049, a050, a051, a052, a053, a054, a055, a056, a057, a058, a059; + Scalar a060, a061, a062, a063, a064, a065, a066, a067, a068, a069, a070, a071; + Scalar a072, a073, a074, a075, a076, a077, a078, a079, a080, a081, a082, a083; + Scalar a084, a085, a086, a087, a088, a089, a090, a091, a092, a093, a094, a095; + Scalar a096, a097, a098, a099, a100, a101, a102, a103, a104, a105, a106, a107; + Scalar a108, a109, a110, a111, a112, a113, a114, a115, a116, a117, a118, a119; + Scalar a120, a121, a122, a123; + a000 = input_vec[0]; + a001 = input_vec[12]; + a002 = input_vec[24]; + a003 = input_vec[36]; + a004 = input_vec[48]; + a005 = input_vec[60]; + a006 = input_vec[72]; + a007 = input_vec[84]; + a008 = input_vec[96]; + a009 = input_vec[108]; + a010 = input_vec[120]; + a011 = input_vec[119]; + a011 = (a011 / a010); + a012 = math::square(a011); + a012 = (a010 * a012); + a009 = (a009 - a012); + a012 = input_vec[107]; + a013 = input_vec[118]; + a014 = (a013 * a011); + a012 = (a012 - a014); + a012 = (a012 / a009); + a014 = math::square(a012); + a014 = (a009 * a014); + a013 = (a013 / a010); + a015 = math::square(a013); + a015 = (a010 * a015); + a014 = (a014 + a015); + a008 = (a008 - a014); + a014 = input_vec[95]; + a015 = input_vec[106]; + a016 = input_vec[117]; + a017 = (a016 * a011); + a015 = (a015 - a017); + a017 = (a015 * a012); + a018 = (a016 * a013); + a017 = (a017 + a018); + a014 = (a014 - a017); + a014 = (a014 / a008); + a017 = math::square(a014); + a017 = (a008 * a017); + a015 = (a015 / a009); + a018 = math::square(a015); + a018 = (a009 * a018); + a017 = (a017 + a018); + a016 = (a016 / a010); + a018 = math::square(a016); + a018 = (a010 * a018); + a017 = (a017 + a018); + a007 = (a007 - a017); + a017 = input_vec[83]; + a018 = input_vec[94]; + a019 = input_vec[105]; + a020 = input_vec[116]; + a021 = (a020 * a011); + a019 = (a019 - a021); + a021 = (a019 * a012); + a022 = (a020 * a013); + a021 = (a021 + a022); + a018 = (a018 - a021); + a021 = (a018 * a014); + a022 = (a019 * a015); + a021 = (a021 + a022); + a022 = (a020 * a016); + a021 = (a021 + a022); + a017 = (a017 - a021); + a017 = (a017 / a007); + a021 = math::square(a017); + a021 = (a007 * a021); + a018 = (a018 / a008); + a022 = math::square(a018); + a022 = (a008 * a022); + a021 = (a021 + a022); + a019 = (a019 / a009); + a022 = math::square(a019); + a022 = (a009 * a022); + a021 = (a021 + a022); + a020 = (a020 / a010); + a022 = math::square(a020); + a022 = (a010 * a022); + a021 = (a021 + a022); + a006 = (a006 - a021); + a021 = input_vec[71]; + a022 = input_vec[82]; + a023 = input_vec[93]; + a024 = input_vec[104]; + a025 = input_vec[115]; + a026 = (a025 * a011); + a024 = (a024 - a026); + a026 = (a024 * a012); + a027 = (a025 * a013); + a026 = (a026 + a027); + a023 = (a023 - a026); + a026 = (a023 * a014); + a027 = (a024 * a015); + a026 = (a026 + a027); + a027 = (a025 * a016); + a026 = (a026 + a027); + a022 = (a022 - a026); + a026 = (a022 * a017); + a027 = (a023 * a018); + a026 = (a026 + a027); + a027 = (a024 * a019); + a026 = (a026 + a027); + a027 = (a025 * a020); + a026 = (a026 + a027); + a021 = (a021 - a026); + a021 = (a021 / a006); + a026 = math::square(a021); + a026 = (a006 * a026); + a022 = (a022 / a007); + a027 = math::square(a022); + a027 = (a007 * a027); + a026 = (a026 + a027); + a023 = (a023 / a008); + a027 = math::square(a023); + a027 = (a008 * a027); + a026 = (a026 + a027); + a024 = (a024 / a009); + a027 = math::square(a024); + a027 = (a009 * a027); + a026 = (a026 + a027); + a025 = (a025 / a010); + a027 = math::square(a025); + a027 = (a010 * a027); + a026 = (a026 + a027); + a005 = (a005 - a026); + a026 = input_vec[59]; + a027 = input_vec[70]; + a028 = input_vec[81]; + a029 = input_vec[92]; + a030 = input_vec[103]; + a031 = input_vec[114]; + a032 = (a031 * a011); + a030 = (a030 - a032); + a032 = (a030 * a012); + a033 = (a031 * a013); + a032 = (a032 + a033); + a029 = (a029 - a032); + a032 = (a029 * a014); + a033 = (a030 * a015); + a032 = (a032 + a033); + a033 = (a031 * a016); + a032 = (a032 + a033); + a028 = (a028 - a032); + a032 = (a028 * a017); + a033 = (a029 * a018); + a032 = (a032 + a033); + a033 = (a030 * a019); + a032 = (a032 + a033); + a033 = (a031 * a020); + a032 = (a032 + a033); + a027 = (a027 - a032); + a032 = (a027 * a021); + a033 = (a028 * a022); + a032 = (a032 + a033); + a033 = (a029 * a023); + a032 = (a032 + a033); + a033 = (a030 * a024); + a032 = (a032 + a033); + a033 = (a031 * a025); + a032 = (a032 + a033); + a026 = (a026 - a032); + a026 = (a026 / a005); + a032 = math::square(a026); + a032 = (a005 * a032); + a027 = (a027 / a006); + a033 = math::square(a027); + a033 = (a006 * a033); + a032 = (a032 + a033); + a028 = (a028 / a007); + a033 = math::square(a028); + a033 = (a007 * a033); + a032 = (a032 + a033); + a029 = (a029 / a008); + a033 = math::square(a029); + a033 = (a008 * a033); + a032 = (a032 + a033); + a030 = (a030 / a009); + a033 = math::square(a030); + a033 = (a009 * a033); + a032 = (a032 + a033); + a031 = (a031 / a010); + a033 = math::square(a031); + a033 = (a010 * a033); + a032 = (a032 + a033); + a004 = (a004 - a032); + a032 = input_vec[47]; + a033 = input_vec[58]; + a034 = input_vec[69]; + a035 = input_vec[80]; + a036 = input_vec[91]; + a037 = input_vec[102]; + a038 = input_vec[113]; + a039 = (a038 * a011); + a037 = (a037 - a039); + a039 = (a037 * a012); + a040 = (a038 * a013); + a039 = (a039 + a040); + a036 = (a036 - a039); + a039 = (a036 * a014); + a040 = (a037 * a015); + a039 = (a039 + a040); + a040 = (a038 * a016); + a039 = (a039 + a040); + a035 = (a035 - a039); + a039 = (a035 * a017); + a040 = (a036 * a018); + a039 = (a039 + a040); + a040 = (a037 * a019); + a039 = (a039 + a040); + a040 = (a038 * a020); + a039 = (a039 + a040); + a034 = (a034 - a039); + a039 = (a034 * a021); + a040 = (a035 * a022); + a039 = (a039 + a040); + a040 = (a036 * a023); + a039 = (a039 + a040); + a040 = (a037 * a024); + a039 = (a039 + a040); + a040 = (a038 * a025); + a039 = (a039 + a040); + a033 = (a033 - a039); + a039 = (a033 * a026); + a040 = (a034 * a027); + a039 = (a039 + a040); + a040 = (a035 * a028); + a039 = (a039 + a040); + a040 = (a036 * a029); + a039 = (a039 + a040); + a040 = (a037 * a030); + a039 = (a039 + a040); + a040 = (a038 * a031); + a039 = (a039 + a040); + a032 = (a032 - a039); + a032 = (a032 / a004); + a039 = math::square(a032); + a039 = (a004 * a039); + a033 = (a033 / a005); + a040 = math::square(a033); + a040 = (a005 * a040); + a039 = (a039 + a040); + a034 = (a034 / a006); + a040 = math::square(a034); + a040 = (a006 * a040); + a039 = (a039 + a040); + a035 = (a035 / a007); + a040 = math::square(a035); + a040 = (a007 * a040); + a039 = (a039 + a040); + a036 = (a036 / a008); + a040 = math::square(a036); + a040 = (a008 * a040); + a039 = (a039 + a040); + a037 = (a037 / a009); + a040 = math::square(a037); + a040 = (a009 * a040); + a039 = (a039 + a040); + a038 = (a038 / a010); + a040 = math::square(a038); + a040 = (a010 * a040); + a039 = (a039 + a040); + a003 = (a003 - a039); + a039 = input_vec[35]; + a040 = input_vec[46]; + a041 = input_vec[57]; + a042 = input_vec[68]; + a043 = input_vec[79]; + a044 = input_vec[90]; + a045 = input_vec[101]; + a046 = input_vec[112]; + a047 = (a046 * a011); + a045 = (a045 - a047); + a047 = (a045 * a012); + a048 = (a046 * a013); + a047 = (a047 + a048); + a044 = (a044 - a047); + a047 = (a044 * a014); + a048 = (a045 * a015); + a047 = (a047 + a048); + a048 = (a046 * a016); + a047 = (a047 + a048); + a043 = (a043 - a047); + a047 = (a043 * a017); + a048 = (a044 * a018); + a047 = (a047 + a048); + a048 = (a045 * a019); + a047 = (a047 + a048); + a048 = (a046 * a020); + a047 = (a047 + a048); + a042 = (a042 - a047); + a047 = (a042 * a021); + a048 = (a043 * a022); + a047 = (a047 + a048); + a048 = (a044 * a023); + a047 = (a047 + a048); + a048 = (a045 * a024); + a047 = (a047 + a048); + a048 = (a046 * a025); + a047 = (a047 + a048); + a041 = (a041 - a047); + a047 = (a041 * a026); + a048 = (a042 * a027); + a047 = (a047 + a048); + a048 = (a043 * a028); + a047 = (a047 + a048); + a048 = (a044 * a029); + a047 = (a047 + a048); + a048 = (a045 * a030); + a047 = (a047 + a048); + a048 = (a046 * a031); + a047 = (a047 + a048); + a040 = (a040 - a047); + a047 = (a040 * a032); + a048 = (a041 * a033); + a047 = (a047 + a048); + a048 = (a042 * a034); + a047 = (a047 + a048); + a048 = (a043 * a035); + a047 = (a047 + a048); + a048 = (a044 * a036); + a047 = (a047 + a048); + a048 = (a045 * a037); + a047 = (a047 + a048); + a048 = (a046 * a038); + a047 = (a047 + a048); + a039 = (a039 - a047); + a039 = (a039 / a003); + a047 = math::square(a039); + a047 = (a003 * a047); + a040 = (a040 / a004); + a048 = math::square(a040); + a048 = (a004 * a048); + a047 = (a047 + a048); + a041 = (a041 / a005); + a048 = math::square(a041); + a048 = (a005 * a048); + a047 = (a047 + a048); + a042 = (a042 / a006); + a048 = math::square(a042); + a048 = (a006 * a048); + a047 = (a047 + a048); + a043 = (a043 / a007); + a048 = math::square(a043); + a048 = (a007 * a048); + a047 = (a047 + a048); + a044 = (a044 / a008); + a048 = math::square(a044); + a048 = (a008 * a048); + a047 = (a047 + a048); + a045 = (a045 / a009); + a048 = math::square(a045); + a048 = (a009 * a048); + a047 = (a047 + a048); + a046 = (a046 / a010); + a048 = math::square(a046); + a048 = (a010 * a048); + a047 = (a047 + a048); + a002 = (a002 - a047); + a047 = input_vec[23]; + a048 = input_vec[34]; + a049 = input_vec[45]; + a050 = input_vec[56]; + a051 = input_vec[67]; + a052 = input_vec[78]; + a053 = input_vec[89]; + a054 = input_vec[100]; + a055 = input_vec[111]; + a056 = (a055 * a011); + a054 = (a054 - a056); + a056 = (a054 * a012); + a057 = (a055 * a013); + a056 = (a056 + a057); + a053 = (a053 - a056); + a056 = (a053 * a014); + a057 = (a054 * a015); + a056 = (a056 + a057); + a057 = (a055 * a016); + a056 = (a056 + a057); + a052 = (a052 - a056); + a056 = (a052 * a017); + a057 = (a053 * a018); + a056 = (a056 + a057); + a057 = (a054 * a019); + a056 = (a056 + a057); + a057 = (a055 * a020); + a056 = (a056 + a057); + a051 = (a051 - a056); + a056 = (a051 * a021); + a057 = (a052 * a022); + a056 = (a056 + a057); + a057 = (a053 * a023); + a056 = (a056 + a057); + a057 = (a054 * a024); + a056 = (a056 + a057); + a057 = (a055 * a025); + a056 = (a056 + a057); + a050 = (a050 - a056); + a056 = (a050 * a026); + a057 = (a051 * a027); + a056 = (a056 + a057); + a057 = (a052 * a028); + a056 = (a056 + a057); + a057 = (a053 * a029); + a056 = (a056 + a057); + a057 = (a054 * a030); + a056 = (a056 + a057); + a057 = (a055 * a031); + a056 = (a056 + a057); + a049 = (a049 - a056); + a056 = (a049 * a032); + a057 = (a050 * a033); + a056 = (a056 + a057); + a057 = (a051 * a034); + a056 = (a056 + a057); + a057 = (a052 * a035); + a056 = (a056 + a057); + a057 = (a053 * a036); + a056 = (a056 + a057); + a057 = (a054 * a037); + a056 = (a056 + a057); + a057 = (a055 * a038); + a056 = (a056 + a057); + a048 = (a048 - a056); + a056 = (a048 * a039); + a057 = (a049 * a040); + a056 = (a056 + a057); + a057 = (a050 * a041); + a056 = (a056 + a057); + a057 = (a051 * a042); + a056 = (a056 + a057); + a057 = (a052 * a043); + a056 = (a056 + a057); + a057 = (a053 * a044); + a056 = (a056 + a057); + a057 = (a054 * a045); + a056 = (a056 + a057); + a057 = (a055 * a046); + a056 = (a056 + a057); + a047 = (a047 - a056); + a047 = (a047 / a002); + a056 = math::square(a047); + a056 = (a002 * a056); + a048 = (a048 / a003); + a057 = math::square(a048); + a057 = (a003 * a057); + a056 = (a056 + a057); + a049 = (a049 / a004); + a057 = math::square(a049); + a057 = (a004 * a057); + a056 = (a056 + a057); + a050 = (a050 / a005); + a057 = math::square(a050); + a057 = (a005 * a057); + a056 = (a056 + a057); + a051 = (a051 / a006); + a057 = math::square(a051); + a057 = (a006 * a057); + a056 = (a056 + a057); + a052 = (a052 / a007); + a057 = math::square(a052); + a057 = (a007 * a057); + a056 = (a056 + a057); + a053 = (a053 / a008); + a057 = math::square(a053); + a057 = (a008 * a057); + a056 = (a056 + a057); + a054 = (a054 / a009); + a057 = math::square(a054); + a057 = (a009 * a057); + a056 = (a056 + a057); + a055 = (a055 / a010); + a057 = math::square(a055); + a057 = (a010 * a057); + a056 = (a056 + a057); + a001 = (a001 - a056); + a056 = input_vec[11]; + a057 = input_vec[22]; + a058 = input_vec[33]; + a059 = input_vec[44]; + a060 = input_vec[55]; + a061 = input_vec[66]; + a062 = input_vec[77]; + a063 = input_vec[88]; + a064 = input_vec[99]; + a065 = input_vec[110]; + a066 = (a065 * a011); + a064 = (a064 - a066); + a066 = (a064 * a012); + a067 = (a065 * a013); + a066 = (a066 + a067); + a063 = (a063 - a066); + a066 = (a063 * a014); + a067 = (a064 * a015); + a066 = (a066 + a067); + a067 = (a065 * a016); + a066 = (a066 + a067); + a062 = (a062 - a066); + a066 = (a062 * a017); + a067 = (a063 * a018); + a066 = (a066 + a067); + a067 = (a064 * a019); + a066 = (a066 + a067); + a067 = (a065 * a020); + a066 = (a066 + a067); + a061 = (a061 - a066); + a066 = (a061 * a021); + a067 = (a062 * a022); + a066 = (a066 + a067); + a067 = (a063 * a023); + a066 = (a066 + a067); + a067 = (a064 * a024); + a066 = (a066 + a067); + a067 = (a065 * a025); + a066 = (a066 + a067); + a060 = (a060 - a066); + a066 = (a060 * a026); + a067 = (a061 * a027); + a066 = (a066 + a067); + a067 = (a062 * a028); + a066 = (a066 + a067); + a067 = (a063 * a029); + a066 = (a066 + a067); + a067 = (a064 * a030); + a066 = (a066 + a067); + a067 = (a065 * a031); + a066 = (a066 + a067); + a059 = (a059 - a066); + a066 = (a059 * a032); + a067 = (a060 * a033); + a066 = (a066 + a067); + a067 = (a061 * a034); + a066 = (a066 + a067); + a067 = (a062 * a035); + a066 = (a066 + a067); + a067 = (a063 * a036); + a066 = (a066 + a067); + a067 = (a064 * a037); + a066 = (a066 + a067); + a067 = (a065 * a038); + a066 = (a066 + a067); + a058 = (a058 - a066); + a066 = (a058 * a039); + a067 = (a059 * a040); + a066 = (a066 + a067); + a067 = (a060 * a041); + a066 = (a066 + a067); + a067 = (a061 * a042); + a066 = (a066 + a067); + a067 = (a062 * a043); + a066 = (a066 + a067); + a067 = (a063 * a044); + a066 = (a066 + a067); + a067 = (a064 * a045); + a066 = (a066 + a067); + a067 = (a065 * a046); + a066 = (a066 + a067); + a057 = (a057 - a066); + a066 = (a057 * a047); + a067 = (a058 * a048); + a066 = (a066 + a067); + a067 = (a059 * a049); + a066 = (a066 + a067); + a067 = (a060 * a050); + a066 = (a066 + a067); + a067 = (a061 * a051); + a066 = (a066 + a067); + a067 = (a062 * a052); + a066 = (a066 + a067); + a067 = (a063 * a053); + a066 = (a066 + a067); + a067 = (a064 * a054); + a066 = (a066 + a067); + a067 = (a065 * a055); + a066 = (a066 + a067); + a056 = (a056 - a066); + a056 = (a056 / a001); + a066 = math::square(a056); + a066 = (a001 * a066); + a057 = (a057 / a002); + a067 = math::square(a057); + a067 = (a002 * a067); + a066 = (a066 + a067); + a058 = (a058 / a003); + a067 = math::square(a058); + a067 = (a003 * a067); + a066 = (a066 + a067); + a059 = (a059 / a004); + a067 = math::square(a059); + a067 = (a004 * a067); + a066 = (a066 + a067); + a060 = (a060 / a005); + a067 = math::square(a060); + a067 = (a005 * a067); + a066 = (a066 + a067); + a061 = (a061 / a006); + a067 = math::square(a061); + a067 = (a006 * a067); + a066 = (a066 + a067); + a062 = (a062 / a007); + a067 = math::square(a062); + a067 = (a007 * a067); + a066 = (a066 + a067); + a063 = (a063 / a008); + a067 = math::square(a063); + a067 = (a008 * a067); + a066 = (a066 + a067); + a064 = (a064 / a009); + a067 = math::square(a064); + a067 = (a009 * a067); + a066 = (a066 + a067); + a065 = (a065 / a010); + a067 = math::square(a065); + a067 = (a010 * a067); + a066 = (a066 + a067); + a000 = (a000 - a066); + a066 = (1. / a000); + output_vec[0] = a066; + a066 = (a056 / a000); + a067 = (-a066); + output_vec[1] = a067; + a068 = (a056 * a047); + a068 = (a057 - a068); + a068 = (a068 / a000); + a069 = (-a068); + output_vec[2] = a069; + a070 = (a047 * a039); + a070 = (a048 - a070); + a071 = (a056 * a070); + a072 = (a057 * a039); + a071 = (a071 + a072); + a071 = (a058 - a071); + a071 = (a071 / a000); + a072 = (-a071); + output_vec[3] = a072; + a073 = (a039 * a032); + a073 = (a040 - a073); + a074 = (a047 * a073); + a075 = (a048 * a032); + a074 = (a074 + a075); + a074 = (a049 - a074); + a075 = (a056 * a074); + a076 = (a057 * a073); + a075 = (a075 + a076); + a076 = (a058 * a032); + a075 = (a075 + a076); + a075 = (a059 - a075); + a075 = (a075 / a000); + a076 = (-a075); + output_vec[4] = a076; + a077 = (a032 * a026); + a077 = (a033 - a077); + a078 = (a039 * a077); + a079 = (a040 * a026); + a078 = (a078 + a079); + a078 = (a041 - a078); + a079 = (a047 * a078); + a080 = (a048 * a077); + a079 = (a079 + a080); + a080 = (a049 * a026); + a079 = (a079 + a080); + a079 = (a050 - a079); + a080 = (a056 * a079); + a081 = (a057 * a078); + a080 = (a080 + a081); + a081 = (a058 * a077); + a080 = (a080 + a081); + a081 = (a059 * a026); + a080 = (a080 + a081); + a080 = (a060 - a080); + a080 = (a080 / a000); + a081 = (-a080); + output_vec[5] = a081; + a082 = (a026 * a021); + a082 = (a027 - a082); + a083 = (a032 * a082); + a084 = (a033 * a021); + a083 = (a083 + a084); + a083 = (a034 - a083); + a084 = (a039 * a083); + a085 = (a040 * a082); + a084 = (a084 + a085); + a085 = (a041 * a021); + a084 = (a084 + a085); + a084 = (a042 - a084); + a085 = (a047 * a084); + a086 = (a048 * a083); + a085 = (a085 + a086); + a086 = (a049 * a082); + a085 = (a085 + a086); + a086 = (a050 * a021); + a085 = (a085 + a086); + a085 = (a051 - a085); + a086 = (a056 * a085); + a087 = (a057 * a084); + a086 = (a086 + a087); + a087 = (a058 * a083); + a086 = (a086 + a087); + a087 = (a059 * a082); + a086 = (a086 + a087); + a087 = (a060 * a021); + a086 = (a086 + a087); + a086 = (a061 - a086); + a086 = (a086 / a000); + a087 = (-a086); + output_vec[6] = a087; + a088 = (a021 * a017); + a088 = (a022 - a088); + a089 = (a026 * a088); + a090 = (a027 * a017); + a089 = (a089 + a090); + a089 = (a028 - a089); + a090 = (a032 * a089); + a091 = (a033 * a088); + a090 = (a090 + a091); + a091 = (a034 * a017); + a090 = (a090 + a091); + a090 = (a035 - a090); + a091 = (a039 * a090); + a092 = (a040 * a089); + a091 = (a091 + a092); + a092 = (a041 * a088); + a091 = (a091 + a092); + a092 = (a042 * a017); + a091 = (a091 + a092); + a091 = (a043 - a091); + a092 = (a047 * a091); + a093 = (a048 * a090); + a092 = (a092 + a093); + a093 = (a049 * a089); + a092 = (a092 + a093); + a093 = (a050 * a088); + a092 = (a092 + a093); + a093 = (a051 * a017); + a092 = (a092 + a093); + a092 = (a052 - a092); + a093 = (a056 * a092); + a094 = (a057 * a091); + a093 = (a093 + a094); + a094 = (a058 * a090); + a093 = (a093 + a094); + a094 = (a059 * a089); + a093 = (a093 + a094); + a094 = (a060 * a088); + a093 = (a093 + a094); + a094 = (a061 * a017); + a093 = (a093 + a094); + a093 = (a062 - a093); + a093 = (a093 / a000); + a094 = (-a093); + output_vec[7] = a094; + a095 = (a017 * a014); + a095 = (a018 - a095); + a096 = (a021 * a095); + a097 = (a022 * a014); + a096 = (a096 + a097); + a096 = (a023 - a096); + a097 = (a026 * a096); + a098 = (a027 * a095); + a097 = (a097 + a098); + a098 = (a028 * a014); + a097 = (a097 + a098); + a097 = (a029 - a097); + a098 = (a032 * a097); + a099 = (a033 * a096); + a098 = (a098 + a099); + a099 = (a034 * a095); + a098 = (a098 + a099); + a099 = (a035 * a014); + a098 = (a098 + a099); + a098 = (a036 - a098); + a099 = (a039 * a098); + a100 = (a040 * a097); + a099 = (a099 + a100); + a100 = (a041 * a096); + a099 = (a099 + a100); + a100 = (a042 * a095); + a099 = (a099 + a100); + a100 = (a043 * a014); + a099 = (a099 + a100); + a099 = (a044 - a099); + a100 = (a047 * a099); + a101 = (a048 * a098); + a100 = (a100 + a101); + a101 = (a049 * a097); + a100 = (a100 + a101); + a101 = (a050 * a096); + a100 = (a100 + a101); + a101 = (a051 * a095); + a100 = (a100 + a101); + a101 = (a052 * a014); + a100 = (a100 + a101); + a100 = (a053 - a100); + a101 = (a056 * a100); + a102 = (a057 * a099); + a101 = (a101 + a102); + a102 = (a058 * a098); + a101 = (a101 + a102); + a102 = (a059 * a097); + a101 = (a101 + a102); + a102 = (a060 * a096); + a101 = (a101 + a102); + a102 = (a061 * a095); + a101 = (a101 + a102); + a102 = (a062 * a014); + a101 = (a101 + a102); + a101 = (a063 - a101); + a101 = (a101 / a000); + a102 = (-a101); + output_vec[8] = a102; + a103 = (a014 * a012); + a103 = (a015 - a103); + a104 = (a017 * a103); + a105 = (a018 * a012); + a104 = (a104 + a105); + a104 = (a019 - a104); + a105 = (a021 * a104); + a106 = (a022 * a103); + a105 = (a105 + a106); + a106 = (a023 * a012); + a105 = (a105 + a106); + a105 = (a024 - a105); + a106 = (a026 * a105); + a107 = (a027 * a104); + a106 = (a106 + a107); + a107 = (a028 * a103); + a106 = (a106 + a107); + a107 = (a029 * a012); + a106 = (a106 + a107); + a106 = (a030 - a106); + a107 = (a032 * a106); + a108 = (a033 * a105); + a107 = (a107 + a108); + a108 = (a034 * a104); + a107 = (a107 + a108); + a108 = (a035 * a103); + a107 = (a107 + a108); + a108 = (a036 * a012); + a107 = (a107 + a108); + a107 = (a037 - a107); + a108 = (a039 * a107); + a109 = (a040 * a106); + a108 = (a108 + a109); + a109 = (a041 * a105); + a108 = (a108 + a109); + a109 = (a042 * a104); + a108 = (a108 + a109); + a109 = (a043 * a103); + a108 = (a108 + a109); + a109 = (a044 * a012); + a108 = (a108 + a109); + a108 = (a045 - a108); + a109 = (a047 * a108); + a110 = (a048 * a107); + a109 = (a109 + a110); + a110 = (a049 * a106); + a109 = (a109 + a110); + a110 = (a050 * a105); + a109 = (a109 + a110); + a110 = (a051 * a104); + a109 = (a109 + a110); + a110 = (a052 * a103); + a109 = (a109 + a110); + a110 = (a053 * a012); + a109 = (a109 + a110); + a109 = (a054 - a109); + a110 = (a056 * a109); + a111 = (a057 * a108); + a110 = (a110 + a111); + a111 = (a058 * a107); + a110 = (a110 + a111); + a111 = (a059 * a106); + a110 = (a110 + a111); + a111 = (a060 * a105); + a110 = (a110 + a111); + a111 = (a061 * a104); + a110 = (a110 + a111); + a111 = (a062 * a103); + a110 = (a110 + a111); + a111 = (a063 * a012); + a110 = (a110 + a111); + a110 = (a064 - a110); + a110 = (a110 / a000); + a111 = (-a110); + output_vec[9] = a111; + a112 = (a012 * a011); + a112 = (a013 - a112); + a113 = (a014 * a112); + a114 = (a015 * a011); + a113 = (a113 + a114); + a113 = (a016 - a113); + a114 = (a017 * a113); + a115 = (a018 * a112); + a114 = (a114 + a115); + a115 = (a019 * a011); + a114 = (a114 + a115); + a114 = (a020 - a114); + a115 = (a021 * a114); + a116 = (a022 * a113); + a115 = (a115 + a116); + a116 = (a023 * a112); + a115 = (a115 + a116); + a116 = (a024 * a011); + a115 = (a115 + a116); + a115 = (a025 - a115); + a116 = (a026 * a115); + a117 = (a027 * a114); + a116 = (a116 + a117); + a117 = (a028 * a113); + a116 = (a116 + a117); + a117 = (a029 * a112); + a116 = (a116 + a117); + a117 = (a030 * a011); + a116 = (a116 + a117); + a116 = (a031 - a116); + a117 = (a032 * a116); + a118 = (a033 * a115); + a117 = (a117 + a118); + a118 = (a034 * a114); + a117 = (a117 + a118); + a118 = (a035 * a113); + a117 = (a117 + a118); + a118 = (a036 * a112); + a117 = (a117 + a118); + a118 = (a037 * a011); + a117 = (a117 + a118); + a117 = (a038 - a117); + a118 = (a039 * a117); + a119 = (a040 * a116); + a118 = (a118 + a119); + a119 = (a041 * a115); + a118 = (a118 + a119); + a119 = (a042 * a114); + a118 = (a118 + a119); + a119 = (a043 * a113); + a118 = (a118 + a119); + a119 = (a044 * a112); + a118 = (a118 + a119); + a119 = (a045 * a011); + a118 = (a118 + a119); + a118 = (a046 - a118); + a119 = (a047 * a118); + a120 = (a048 * a117); + a119 = (a119 + a120); + a120 = (a049 * a116); + a119 = (a119 + a120); + a120 = (a050 * a115); + a119 = (a119 + a120); + a120 = (a051 * a114); + a119 = (a119 + a120); + a120 = (a052 * a113); + a119 = (a119 + a120); + a120 = (a053 * a112); + a119 = (a119 + a120); + a120 = (a054 * a011); + a119 = (a119 + a120); + a119 = (a055 - a119); + a120 = (a056 * a119); + a121 = (a057 * a118); + a120 = (a120 + a121); + a121 = (a058 * a117); + a120 = (a120 + a121); + a121 = (a059 * a116); + a120 = (a120 + a121); + a121 = (a060 * a115); + a120 = (a120 + a121); + a121 = (a061 * a114); + a120 = (a120 + a121); + a121 = (a062 * a113); + a120 = (a120 + a121); + a121 = (a063 * a112); + a120 = (a120 + a121); + a121 = (a064 * a011); + a120 = (a120 + a121); + a120 = (a065 - a120); + a120 = (a120 / a000); + a000 = (-a120); + output_vec[10] = a000; + output_vec[11] = a067; + a067 = (1. / a001); + a066 = (a056 * a066); + a067 = (a067 + a066); + output_vec[12] = a067; + a067 = (a056 * a068); + a066 = (a047 / a001); + a067 = (a067 - a066); + output_vec[13] = a067; + a066 = (a056 * a071); + a070 = (a070 / a001); + a066 = (a066 - a070); + output_vec[14] = a066; + a070 = (a056 * a075); + a074 = (a074 / a001); + a070 = (a070 - a074); + output_vec[15] = a070; + a074 = (a056 * a080); + a079 = (a079 / a001); + a074 = (a074 - a079); + output_vec[16] = a074; + a079 = (a056 * a086); + a085 = (a085 / a001); + a079 = (a079 - a085); + output_vec[17] = a079; + a085 = (a056 * a093); + a092 = (a092 / a001); + a085 = (a085 - a092); + output_vec[18] = a085; + a092 = (a056 * a101); + a100 = (a100 / a001); + a092 = (a092 - a100); + output_vec[19] = a092; + a100 = (a056 * a110); + a109 = (a109 / a001); + a100 = (a100 - a109); + output_vec[20] = a100; + a056 = (a056 * a120); + a119 = (a119 / a001); + a056 = (a056 - a119); + output_vec[21] = a056; + output_vec[22] = a069; + output_vec[23] = a067; + a069 = (1. / a002); + a067 = (a047 * a067); + a068 = (a057 * a068); + a067 = (a067 - a068); + a069 = (a069 - a067); + output_vec[24] = a069; + a069 = (a039 / a002); + a067 = (a047 * a066); + a068 = (a057 * a071); + a067 = (a067 - a068); + a069 = (a069 + a067); + a067 = (-a069); + output_vec[25] = a067; + a073 = (a073 / a002); + a068 = (a047 * a070); + a119 = (a057 * a075); + a068 = (a068 - a119); + a073 = (a073 + a068); + a068 = (-a073); + output_vec[26] = a068; + a078 = (a078 / a002); + a119 = (a047 * a074); + a001 = (a057 * a080); + a119 = (a119 - a001); + a078 = (a078 + a119); + a119 = (-a078); + output_vec[27] = a119; + a084 = (a084 / a002); + a001 = (a047 * a079); + a109 = (a057 * a086); + a001 = (a001 - a109); + a084 = (a084 + a001); + a001 = (-a084); + output_vec[28] = a001; + a091 = (a091 / a002); + a109 = (a047 * a085); + a121 = (a057 * a093); + a109 = (a109 - a121); + a091 = (a091 + a109); + a109 = (-a091); + output_vec[29] = a109; + a099 = (a099 / a002); + a121 = (a047 * a092); + a122 = (a057 * a101); + a121 = (a121 - a122); + a099 = (a099 + a121); + a121 = (-a099); + output_vec[30] = a121; + a108 = (a108 / a002); + a122 = (a047 * a100); + a123 = (a057 * a110); + a122 = (a122 - a123); + a108 = (a108 + a122); + a122 = (-a108); + output_vec[31] = a122; + a118 = (a118 / a002); + a047 = (a047 * a056); + a057 = (a057 * a120); + a047 = (a047 - a057); + a118 = (a118 + a047); + a047 = (-a118); + output_vec[32] = a047; + output_vec[33] = a072; + output_vec[34] = a066; + output_vec[35] = a067; + a067 = (1. / a003); + a066 = (a048 * a066); + a071 = (a058 * a071); + a066 = (a066 - a071); + a069 = (a039 * a069); + a066 = (a066 - a069); + a067 = (a067 - a066); + output_vec[36] = a067; + a067 = (a032 / a003); + a066 = (a048 * a070); + a069 = (a058 * a075); + a066 = (a066 - a069); + a069 = (a039 * a073); + a066 = (a066 - a069); + a067 = (a067 + a066); + a066 = (-a067); + output_vec[37] = a066; + a077 = (a077 / a003); + a069 = (a048 * a074); + a071 = (a058 * a080); + a069 = (a069 - a071); + a071 = (a039 * a078); + a069 = (a069 - a071); + a077 = (a077 + a069); + a069 = (-a077); + output_vec[38] = a069; + a083 = (a083 / a003); + a071 = (a048 * a079); + a072 = (a058 * a086); + a071 = (a071 - a072); + a072 = (a039 * a084); + a071 = (a071 - a072); + a083 = (a083 + a071); + a071 = (-a083); + output_vec[39] = a071; + a090 = (a090 / a003); + a072 = (a048 * a085); + a057 = (a058 * a093); + a072 = (a072 - a057); + a057 = (a039 * a091); + a072 = (a072 - a057); + a090 = (a090 + a072); + a072 = (-a090); + output_vec[40] = a072; + a098 = (a098 / a003); + a057 = (a048 * a092); + a002 = (a058 * a101); + a057 = (a057 - a002); + a002 = (a039 * a099); + a057 = (a057 - a002); + a098 = (a098 + a057); + a057 = (-a098); + output_vec[41] = a057; + a107 = (a107 / a003); + a002 = (a048 * a100); + a123 = (a058 * a110); + a002 = (a002 - a123); + a123 = (a039 * a108); + a002 = (a002 - a123); + a107 = (a107 + a002); + a002 = (-a107); + output_vec[42] = a002; + a117 = (a117 / a003); + a048 = (a048 * a056); + a058 = (a058 * a120); + a048 = (a048 - a058); + a039 = (a039 * a118); + a048 = (a048 - a039); + a117 = (a117 + a048); + a048 = (-a117); + output_vec[43] = a048; + output_vec[44] = a076; + output_vec[45] = a070; + output_vec[46] = a068; + output_vec[47] = a066; + a066 = (1. / a004); + a070 = (a049 * a070); + a075 = (a059 * a075); + a070 = (a070 - a075); + a073 = (a040 * a073); + a070 = (a070 - a073); + a067 = (a032 * a067); + a070 = (a070 - a067); + a066 = (a066 - a070); + output_vec[48] = a066; + a066 = (a026 / a004); + a070 = (a049 * a074); + a067 = (a059 * a080); + a070 = (a070 - a067); + a067 = (a040 * a078); + a070 = (a070 - a067); + a067 = (a032 * a077); + a070 = (a070 - a067); + a066 = (a066 + a070); + a070 = (-a066); + output_vec[49] = a070; + a082 = (a082 / a004); + a067 = (a049 * a079); + a073 = (a059 * a086); + a067 = (a067 - a073); + a073 = (a040 * a084); + a067 = (a067 - a073); + a073 = (a032 * a083); + a067 = (a067 - a073); + a082 = (a082 + a067); + a067 = (-a082); + output_vec[50] = a067; + a089 = (a089 / a004); + a073 = (a049 * a085); + a075 = (a059 * a093); + a073 = (a073 - a075); + a075 = (a040 * a091); + a073 = (a073 - a075); + a075 = (a032 * a090); + a073 = (a073 - a075); + a089 = (a089 + a073); + a073 = (-a089); + output_vec[51] = a073; + a097 = (a097 / a004); + a075 = (a049 * a092); + a068 = (a059 * a101); + a075 = (a075 - a068); + a068 = (a040 * a099); + a075 = (a075 - a068); + a068 = (a032 * a098); + a075 = (a075 - a068); + a097 = (a097 + a075); + a075 = (-a097); + output_vec[52] = a075; + a106 = (a106 / a004); + a068 = (a049 * a100); + a076 = (a059 * a110); + a068 = (a068 - a076); + a076 = (a040 * a108); + a068 = (a068 - a076); + a076 = (a032 * a107); + a068 = (a068 - a076); + a106 = (a106 + a068); + a068 = (-a106); + output_vec[53] = a068; + a116 = (a116 / a004); + a049 = (a049 * a056); + a059 = (a059 * a120); + a049 = (a049 - a059); + a040 = (a040 * a118); + a049 = (a049 - a040); + a032 = (a032 * a117); + a049 = (a049 - a032); + a116 = (a116 + a049); + a049 = (-a116); + output_vec[54] = a049; + output_vec[55] = a081; + output_vec[56] = a074; + output_vec[57] = a119; + output_vec[58] = a069; + output_vec[59] = a070; + a070 = (1. / a005); + a074 = (a050 * a074); + a080 = (a060 * a080); + a074 = (a074 - a080); + a078 = (a041 * a078); + a074 = (a074 - a078); + a077 = (a033 * a077); + a074 = (a074 - a077); + a066 = (a026 * a066); + a074 = (a074 - a066); + a070 = (a070 - a074); + output_vec[60] = a070; + a070 = (a021 / a005); + a074 = (a050 * a079); + a066 = (a060 * a086); + a074 = (a074 - a066); + a066 = (a041 * a084); + a074 = (a074 - a066); + a066 = (a033 * a083); + a074 = (a074 - a066); + a066 = (a026 * a082); + a074 = (a074 - a066); + a070 = (a070 + a074); + a074 = (-a070); + output_vec[61] = a074; + a088 = (a088 / a005); + a066 = (a050 * a085); + a077 = (a060 * a093); + a066 = (a066 - a077); + a077 = (a041 * a091); + a066 = (a066 - a077); + a077 = (a033 * a090); + a066 = (a066 - a077); + a077 = (a026 * a089); + a066 = (a066 - a077); + a088 = (a088 + a066); + a066 = (-a088); + output_vec[62] = a066; + a096 = (a096 / a005); + a077 = (a050 * a092); + a078 = (a060 * a101); + a077 = (a077 - a078); + a078 = (a041 * a099); + a077 = (a077 - a078); + a078 = (a033 * a098); + a077 = (a077 - a078); + a078 = (a026 * a097); + a077 = (a077 - a078); + a096 = (a096 + a077); + a077 = (-a096); + output_vec[63] = a077; + a105 = (a105 / a005); + a078 = (a050 * a100); + a080 = (a060 * a110); + a078 = (a078 - a080); + a080 = (a041 * a108); + a078 = (a078 - a080); + a080 = (a033 * a107); + a078 = (a078 - a080); + a080 = (a026 * a106); + a078 = (a078 - a080); + a105 = (a105 + a078); + a078 = (-a105); + output_vec[64] = a078; + a115 = (a115 / a005); + a050 = (a050 * a056); + a060 = (a060 * a120); + a050 = (a050 - a060); + a041 = (a041 * a118); + a050 = (a050 - a041); + a033 = (a033 * a117); + a050 = (a050 - a033); + a026 = (a026 * a116); + a050 = (a050 - a026); + a115 = (a115 + a050); + a050 = (-a115); + output_vec[65] = a050; + output_vec[66] = a087; + output_vec[67] = a079; + output_vec[68] = a001; + output_vec[69] = a071; + output_vec[70] = a067; + output_vec[71] = a074; + a074 = (1. / a006); + a079 = (a051 * a079); + a086 = (a061 * a086); + a079 = (a079 - a086); + a084 = (a042 * a084); + a079 = (a079 - a084); + a083 = (a034 * a083); + a079 = (a079 - a083); + a082 = (a027 * a082); + a079 = (a079 - a082); + a070 = (a021 * a070); + a079 = (a079 - a070); + a074 = (a074 - a079); + output_vec[72] = a074; + a074 = (a017 / a006); + a079 = (a051 * a085); + a070 = (a061 * a093); + a079 = (a079 - a070); + a070 = (a042 * a091); + a079 = (a079 - a070); + a070 = (a034 * a090); + a079 = (a079 - a070); + a070 = (a027 * a089); + a079 = (a079 - a070); + a070 = (a021 * a088); + a079 = (a079 - a070); + a074 = (a074 + a079); + a079 = (-a074); + output_vec[73] = a079; + a095 = (a095 / a006); + a070 = (a051 * a092); + a082 = (a061 * a101); + a070 = (a070 - a082); + a082 = (a042 * a099); + a070 = (a070 - a082); + a082 = (a034 * a098); + a070 = (a070 - a082); + a082 = (a027 * a097); + a070 = (a070 - a082); + a082 = (a021 * a096); + a070 = (a070 - a082); + a095 = (a095 + a070); + a070 = (-a095); + output_vec[74] = a070; + a104 = (a104 / a006); + a082 = (a051 * a100); + a083 = (a061 * a110); + a082 = (a082 - a083); + a083 = (a042 * a108); + a082 = (a082 - a083); + a083 = (a034 * a107); + a082 = (a082 - a083); + a083 = (a027 * a106); + a082 = (a082 - a083); + a083 = (a021 * a105); + a082 = (a082 - a083); + a104 = (a104 + a082); + a082 = (-a104); + output_vec[75] = a082; + a114 = (a114 / a006); + a051 = (a051 * a056); + a061 = (a061 * a120); + a051 = (a051 - a061); + a042 = (a042 * a118); + a051 = (a051 - a042); + a034 = (a034 * a117); + a051 = (a051 - a034); + a027 = (a027 * a116); + a051 = (a051 - a027); + a021 = (a021 * a115); + a051 = (a051 - a021); + a114 = (a114 + a051); + a051 = (-a114); + output_vec[76] = a051; + output_vec[77] = a094; + output_vec[78] = a085; + output_vec[79] = a109; + output_vec[80] = a072; + output_vec[81] = a073; + output_vec[82] = a066; + output_vec[83] = a079; + a079 = (1. / a007); + a085 = (a052 * a085); + a093 = (a062 * a093); + a085 = (a085 - a093); + a091 = (a043 * a091); + a085 = (a085 - a091); + a090 = (a035 * a090); + a085 = (a085 - a090); + a089 = (a028 * a089); + a085 = (a085 - a089); + a088 = (a022 * a088); + a085 = (a085 - a088); + a074 = (a017 * a074); + a085 = (a085 - a074); + a079 = (a079 - a085); + output_vec[84] = a079; + a079 = (a014 / a007); + a085 = (a052 * a092); + a074 = (a062 * a101); + a085 = (a085 - a074); + a074 = (a043 * a099); + a085 = (a085 - a074); + a074 = (a035 * a098); + a085 = (a085 - a074); + a074 = (a028 * a097); + a085 = (a085 - a074); + a074 = (a022 * a096); + a085 = (a085 - a074); + a074 = (a017 * a095); + a085 = (a085 - a074); + a079 = (a079 + a085); + a085 = (-a079); + output_vec[85] = a085; + a103 = (a103 / a007); + a074 = (a052 * a100); + a088 = (a062 * a110); + a074 = (a074 - a088); + a088 = (a043 * a108); + a074 = (a074 - a088); + a088 = (a035 * a107); + a074 = (a074 - a088); + a088 = (a028 * a106); + a074 = (a074 - a088); + a088 = (a022 * a105); + a074 = (a074 - a088); + a088 = (a017 * a104); + a074 = (a074 - a088); + a103 = (a103 + a074); + a074 = (-a103); + output_vec[86] = a074; + a113 = (a113 / a007); + a052 = (a052 * a056); + a062 = (a062 * a120); + a052 = (a052 - a062); + a043 = (a043 * a118); + a052 = (a052 - a043); + a035 = (a035 * a117); + a052 = (a052 - a035); + a028 = (a028 * a116); + a052 = (a052 - a028); + a022 = (a022 * a115); + a052 = (a052 - a022); + a017 = (a017 * a114); + a052 = (a052 - a017); + a113 = (a113 + a052); + a052 = (-a113); + output_vec[87] = a052; + output_vec[88] = a102; + output_vec[89] = a092; + output_vec[90] = a121; + output_vec[91] = a057; + output_vec[92] = a075; + output_vec[93] = a077; + output_vec[94] = a070; + output_vec[95] = a085; + a085 = (1. / a008); + a092 = (a053 * a092); + a101 = (a063 * a101); + a092 = (a092 - a101); + a099 = (a044 * a099); + a092 = (a092 - a099); + a098 = (a036 * a098); + a092 = (a092 - a098); + a097 = (a029 * a097); + a092 = (a092 - a097); + a096 = (a023 * a096); + a092 = (a092 - a096); + a095 = (a018 * a095); + a092 = (a092 - a095); + a079 = (a014 * a079); + a092 = (a092 - a079); + a085 = (a085 - a092); + output_vec[96] = a085; + a085 = (a012 / a008); + a092 = (a053 * a100); + a079 = (a063 * a110); + a092 = (a092 - a079); + a079 = (a044 * a108); + a092 = (a092 - a079); + a079 = (a036 * a107); + a092 = (a092 - a079); + a079 = (a029 * a106); + a092 = (a092 - a079); + a079 = (a023 * a105); + a092 = (a092 - a079); + a079 = (a018 * a104); + a092 = (a092 - a079); + a079 = (a014 * a103); + a092 = (a092 - a079); + a085 = (a085 + a092); + a092 = (-a085); + output_vec[97] = a092; + a112 = (a112 / a008); + a053 = (a053 * a056); + a063 = (a063 * a120); + a053 = (a053 - a063); + a044 = (a044 * a118); + a053 = (a053 - a044); + a036 = (a036 * a117); + a053 = (a053 - a036); + a029 = (a029 * a116); + a053 = (a053 - a029); + a023 = (a023 * a115); + a053 = (a053 - a023); + a018 = (a018 * a114); + a053 = (a053 - a018); + a014 = (a014 * a113); + a053 = (a053 - a014); + a112 = (a112 + a053); + a053 = (-a112); + output_vec[98] = a053; + output_vec[99] = a111; + output_vec[100] = a100; + output_vec[101] = a122; + output_vec[102] = a002; + output_vec[103] = a068; + output_vec[104] = a078; + output_vec[105] = a082; + output_vec[106] = a074; + output_vec[107] = a092; + a092 = (1. / a009); + a100 = (a054 * a100); + a110 = (a064 * a110); + a100 = (a100 - a110); + a108 = (a045 * a108); + a100 = (a100 - a108); + a107 = (a037 * a107); + a100 = (a100 - a107); + a106 = (a030 * a106); + a100 = (a100 - a106); + a105 = (a024 * a105); + a100 = (a100 - a105); + a104 = (a019 * a104); + a100 = (a100 - a104); + a103 = (a015 * a103); + a100 = (a100 - a103); + a085 = (a012 * a085); + a100 = (a100 - a085); + a092 = (a092 - a100); + output_vec[108] = a092; + a009 = (a011 / a009); + a054 = (a054 * a056); + a064 = (a064 * a120); + a054 = (a054 - a064); + a045 = (a045 * a118); + a054 = (a054 - a045); + a037 = (a037 * a117); + a054 = (a054 - a037); + a030 = (a030 * a116); + a054 = (a054 - a030); + a024 = (a024 * a115); + a054 = (a054 - a024); + a019 = (a019 * a114); + a054 = (a054 - a019); + a015 = (a015 * a113); + a054 = (a054 - a015); + a012 = (a012 * a112); + a054 = (a054 - a012); + a009 = (a009 + a054); + a054 = (-a009); + output_vec[109] = a054; + output_vec[110] = a000; + output_vec[111] = a056; + output_vec[112] = a047; + output_vec[113] = a048; + output_vec[114] = a049; + output_vec[115] = a050; + output_vec[116] = a051; + output_vec[117] = a052; + output_vec[118] = a053; + output_vec[119] = a054; + a010 = (1. / a010); + a055 = (a055 * a056); + a065 = (a065 * a120); + a055 = (a055 - a065); + a046 = (a046 * a118); + a055 = (a055 - a046); + a038 = (a038 * a117); + a055 = (a055 - a038); + a031 = (a031 * a116); + a055 = (a055 - a031); + a025 = (a025 * a115); + a055 = (a055 - a025); + a020 = (a020 * a114); + a055 = (a055 - a020); + a016 = (a016 * a113); + a055 = (a055 - a016); + a013 = (a013 * a112); + a055 = (a055 - a013); + a011 = (a011 * a009); + a055 = (a055 - a011); + a010 = (a010 - a055); + output_vec[120] = a010; + } + }; + } // namespace internal +} // namespace pinocchio + +#endif // ifndef __pinocchio_math_details_matrix_inversion_11x11_hpp__ diff --git a/include/pinocchio/math/details/matrix-inverse-12x12.hpp b/include/pinocchio/math/details/matrix-inverse-12x12.hpp new file mode 100644 index 0000000000..930b505c95 --- /dev/null +++ b/include/pinocchio/math/details/matrix-inverse-12x12.hpp @@ -0,0 +1,2119 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_math_details_matrix_inversion_12x12_hpp__ +#define __pinocchio_math_details_matrix_inversion_12x12_hpp__ + +#include "pinocchio/math/matrix.hpp" + +namespace pinocchio +{ + namespace internal + { + template<> + struct MatrixInversionCodeGeneratedImpl<12> + { + template + static void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse_) + { + typedef typename M1::Scalar Scalar; + + assert(is_symmetric(matrix, math::sqrt(dummy_precision()))); + + const auto & input_vec = matrix.reshaped(); + auto & matrix_inverse = matrix_inverse_.const_cast_derived(); + auto output_vec = matrix_inverse.reshaped(); + + Scalar a000, a001, a002, a003, a004, a005, a006, a007, a008, a009, a010, a011; + Scalar a012, a013, a014, a015, a016, a017, a018, a019, a020, a021, a022, a023; + Scalar a024, a025, a026, a027, a028, a029, a030, a031, a032, a033, a034, a035; + Scalar a036, a037, a038, a039, a040, a041, a042, a043, a044, a045, a046, a047; + Scalar a048, a049, a050, a051, a052, a053, a054, a055, a056, a057, a058, a059; + Scalar a060, a061, a062, a063, a064, a065, a066, a067, a068, a069, a070, a071; + Scalar a072, a073, a074, a075, a076, a077, a078, a079, a080, a081, a082, a083; + Scalar a084, a085, a086, a087, a088, a089, a090, a091, a092, a093, a094, a095; + Scalar a096, a097, a098, a099, a100, a101, a102, a103, a104, a105, a106, a107; + Scalar a108, a109, a110, a111, a112, a113, a114, a115, a116, a117, a118, a119; + Scalar a120, a121, a122, a123, a124, a125, a126, a127, a128, a129, a130, a131; + Scalar a132, a133, a134, a135, a136, a137, a138, a139, a140, a141, a142, a143; + Scalar a144, a145, a146, a147, a148; + a000 = input_vec[0]; + a001 = input_vec[13]; + a002 = input_vec[26]; + a003 = input_vec[39]; + a004 = input_vec[52]; + a005 = input_vec[65]; + a006 = input_vec[78]; + a007 = input_vec[91]; + a008 = input_vec[104]; + a009 = input_vec[117]; + a010 = input_vec[130]; + a011 = input_vec[143]; + a012 = input_vec[142]; + a012 = (a012 / a011); + a013 = math::square(a012); + a013 = (a011 * a013); + a010 = (a010 - a013); + a013 = input_vec[129]; + a014 = input_vec[141]; + a015 = (a014 * a012); + a013 = (a013 - a015); + a013 = (a013 / a010); + a015 = math::square(a013); + a015 = (a010 * a015); + a014 = (a014 / a011); + a016 = math::square(a014); + a016 = (a011 * a016); + a015 = (a015 + a016); + a009 = (a009 - a015); + a015 = input_vec[116]; + a016 = input_vec[128]; + a017 = input_vec[140]; + a018 = (a017 * a012); + a016 = (a016 - a018); + a018 = (a016 * a013); + a019 = (a017 * a014); + a018 = (a018 + a019); + a015 = (a015 - a018); + a015 = (a015 / a009); + a018 = math::square(a015); + a018 = (a009 * a018); + a016 = (a016 / a010); + a019 = math::square(a016); + a019 = (a010 * a019); + a018 = (a018 + a019); + a017 = (a017 / a011); + a019 = math::square(a017); + a019 = (a011 * a019); + a018 = (a018 + a019); + a008 = (a008 - a018); + a018 = input_vec[103]; + a019 = input_vec[115]; + a020 = input_vec[127]; + a021 = input_vec[139]; + a022 = (a021 * a012); + a020 = (a020 - a022); + a022 = (a020 * a013); + a023 = (a021 * a014); + a022 = (a022 + a023); + a019 = (a019 - a022); + a022 = (a019 * a015); + a023 = (a020 * a016); + a022 = (a022 + a023); + a023 = (a021 * a017); + a022 = (a022 + a023); + a018 = (a018 - a022); + a018 = (a018 / a008); + a022 = math::square(a018); + a022 = (a008 * a022); + a019 = (a019 / a009); + a023 = math::square(a019); + a023 = (a009 * a023); + a022 = (a022 + a023); + a020 = (a020 / a010); + a023 = math::square(a020); + a023 = (a010 * a023); + a022 = (a022 + a023); + a021 = (a021 / a011); + a023 = math::square(a021); + a023 = (a011 * a023); + a022 = (a022 + a023); + a007 = (a007 - a022); + a022 = input_vec[90]; + a023 = input_vec[102]; + a024 = input_vec[114]; + a025 = input_vec[126]; + a026 = input_vec[138]; + a027 = (a026 * a012); + a025 = (a025 - a027); + a027 = (a025 * a013); + a028 = (a026 * a014); + a027 = (a027 + a028); + a024 = (a024 - a027); + a027 = (a024 * a015); + a028 = (a025 * a016); + a027 = (a027 + a028); + a028 = (a026 * a017); + a027 = (a027 + a028); + a023 = (a023 - a027); + a027 = (a023 * a018); + a028 = (a024 * a019); + a027 = (a027 + a028); + a028 = (a025 * a020); + a027 = (a027 + a028); + a028 = (a026 * a021); + a027 = (a027 + a028); + a022 = (a022 - a027); + a022 = (a022 / a007); + a027 = math::square(a022); + a027 = (a007 * a027); + a023 = (a023 / a008); + a028 = math::square(a023); + a028 = (a008 * a028); + a027 = (a027 + a028); + a024 = (a024 / a009); + a028 = math::square(a024); + a028 = (a009 * a028); + a027 = (a027 + a028); + a025 = (a025 / a010); + a028 = math::square(a025); + a028 = (a010 * a028); + a027 = (a027 + a028); + a026 = (a026 / a011); + a028 = math::square(a026); + a028 = (a011 * a028); + a027 = (a027 + a028); + a006 = (a006 - a027); + a027 = input_vec[77]; + a028 = input_vec[89]; + a029 = input_vec[101]; + a030 = input_vec[113]; + a031 = input_vec[125]; + a032 = input_vec[137]; + a033 = (a032 * a012); + a031 = (a031 - a033); + a033 = (a031 * a013); + a034 = (a032 * a014); + a033 = (a033 + a034); + a030 = (a030 - a033); + a033 = (a030 * a015); + a034 = (a031 * a016); + a033 = (a033 + a034); + a034 = (a032 * a017); + a033 = (a033 + a034); + a029 = (a029 - a033); + a033 = (a029 * a018); + a034 = (a030 * a019); + a033 = (a033 + a034); + a034 = (a031 * a020); + a033 = (a033 + a034); + a034 = (a032 * a021); + a033 = (a033 + a034); + a028 = (a028 - a033); + a033 = (a028 * a022); + a034 = (a029 * a023); + a033 = (a033 + a034); + a034 = (a030 * a024); + a033 = (a033 + a034); + a034 = (a031 * a025); + a033 = (a033 + a034); + a034 = (a032 * a026); + a033 = (a033 + a034); + a027 = (a027 - a033); + a027 = (a027 / a006); + a033 = math::square(a027); + a033 = (a006 * a033); + a028 = (a028 / a007); + a034 = math::square(a028); + a034 = (a007 * a034); + a033 = (a033 + a034); + a029 = (a029 / a008); + a034 = math::square(a029); + a034 = (a008 * a034); + a033 = (a033 + a034); + a030 = (a030 / a009); + a034 = math::square(a030); + a034 = (a009 * a034); + a033 = (a033 + a034); + a031 = (a031 / a010); + a034 = math::square(a031); + a034 = (a010 * a034); + a033 = (a033 + a034); + a032 = (a032 / a011); + a034 = math::square(a032); + a034 = (a011 * a034); + a033 = (a033 + a034); + a005 = (a005 - a033); + a033 = input_vec[64]; + a034 = input_vec[76]; + a035 = input_vec[88]; + a036 = input_vec[100]; + a037 = input_vec[112]; + a038 = input_vec[124]; + a039 = input_vec[136]; + a040 = (a039 * a012); + a038 = (a038 - a040); + a040 = (a038 * a013); + a041 = (a039 * a014); + a040 = (a040 + a041); + a037 = (a037 - a040); + a040 = (a037 * a015); + a041 = (a038 * a016); + a040 = (a040 + a041); + a041 = (a039 * a017); + a040 = (a040 + a041); + a036 = (a036 - a040); + a040 = (a036 * a018); + a041 = (a037 * a019); + a040 = (a040 + a041); + a041 = (a038 * a020); + a040 = (a040 + a041); + a041 = (a039 * a021); + a040 = (a040 + a041); + a035 = (a035 - a040); + a040 = (a035 * a022); + a041 = (a036 * a023); + a040 = (a040 + a041); + a041 = (a037 * a024); + a040 = (a040 + a041); + a041 = (a038 * a025); + a040 = (a040 + a041); + a041 = (a039 * a026); + a040 = (a040 + a041); + a034 = (a034 - a040); + a040 = (a034 * a027); + a041 = (a035 * a028); + a040 = (a040 + a041); + a041 = (a036 * a029); + a040 = (a040 + a041); + a041 = (a037 * a030); + a040 = (a040 + a041); + a041 = (a038 * a031); + a040 = (a040 + a041); + a041 = (a039 * a032); + a040 = (a040 + a041); + a033 = (a033 - a040); + a033 = (a033 / a005); + a040 = math::square(a033); + a040 = (a005 * a040); + a034 = (a034 / a006); + a041 = math::square(a034); + a041 = (a006 * a041); + a040 = (a040 + a041); + a035 = (a035 / a007); + a041 = math::square(a035); + a041 = (a007 * a041); + a040 = (a040 + a041); + a036 = (a036 / a008); + a041 = math::square(a036); + a041 = (a008 * a041); + a040 = (a040 + a041); + a037 = (a037 / a009); + a041 = math::square(a037); + a041 = (a009 * a041); + a040 = (a040 + a041); + a038 = (a038 / a010); + a041 = math::square(a038); + a041 = (a010 * a041); + a040 = (a040 + a041); + a039 = (a039 / a011); + a041 = math::square(a039); + a041 = (a011 * a041); + a040 = (a040 + a041); + a004 = (a004 - a040); + a040 = input_vec[51]; + a041 = input_vec[63]; + a042 = input_vec[75]; + a043 = input_vec[87]; + a044 = input_vec[99]; + a045 = input_vec[111]; + a046 = input_vec[123]; + a047 = input_vec[135]; + a048 = (a047 * a012); + a046 = (a046 - a048); + a048 = (a046 * a013); + a049 = (a047 * a014); + a048 = (a048 + a049); + a045 = (a045 - a048); + a048 = (a045 * a015); + a049 = (a046 * a016); + a048 = (a048 + a049); + a049 = (a047 * a017); + a048 = (a048 + a049); + a044 = (a044 - a048); + a048 = (a044 * a018); + a049 = (a045 * a019); + a048 = (a048 + a049); + a049 = (a046 * a020); + a048 = (a048 + a049); + a049 = (a047 * a021); + a048 = (a048 + a049); + a043 = (a043 - a048); + a048 = (a043 * a022); + a049 = (a044 * a023); + a048 = (a048 + a049); + a049 = (a045 * a024); + a048 = (a048 + a049); + a049 = (a046 * a025); + a048 = (a048 + a049); + a049 = (a047 * a026); + a048 = (a048 + a049); + a042 = (a042 - a048); + a048 = (a042 * a027); + a049 = (a043 * a028); + a048 = (a048 + a049); + a049 = (a044 * a029); + a048 = (a048 + a049); + a049 = (a045 * a030); + a048 = (a048 + a049); + a049 = (a046 * a031); + a048 = (a048 + a049); + a049 = (a047 * a032); + a048 = (a048 + a049); + a041 = (a041 - a048); + a048 = (a041 * a033); + a049 = (a042 * a034); + a048 = (a048 + a049); + a049 = (a043 * a035); + a048 = (a048 + a049); + a049 = (a044 * a036); + a048 = (a048 + a049); + a049 = (a045 * a037); + a048 = (a048 + a049); + a049 = (a046 * a038); + a048 = (a048 + a049); + a049 = (a047 * a039); + a048 = (a048 + a049); + a040 = (a040 - a048); + a040 = (a040 / a004); + a048 = math::square(a040); + a048 = (a004 * a048); + a041 = (a041 / a005); + a049 = math::square(a041); + a049 = (a005 * a049); + a048 = (a048 + a049); + a042 = (a042 / a006); + a049 = math::square(a042); + a049 = (a006 * a049); + a048 = (a048 + a049); + a043 = (a043 / a007); + a049 = math::square(a043); + a049 = (a007 * a049); + a048 = (a048 + a049); + a044 = (a044 / a008); + a049 = math::square(a044); + a049 = (a008 * a049); + a048 = (a048 + a049); + a045 = (a045 / a009); + a049 = math::square(a045); + a049 = (a009 * a049); + a048 = (a048 + a049); + a046 = (a046 / a010); + a049 = math::square(a046); + a049 = (a010 * a049); + a048 = (a048 + a049); + a047 = (a047 / a011); + a049 = math::square(a047); + a049 = (a011 * a049); + a048 = (a048 + a049); + a003 = (a003 - a048); + a048 = input_vec[38]; + a049 = input_vec[50]; + a050 = input_vec[62]; + a051 = input_vec[74]; + a052 = input_vec[86]; + a053 = input_vec[98]; + a054 = input_vec[110]; + a055 = input_vec[122]; + a056 = input_vec[134]; + a057 = (a056 * a012); + a055 = (a055 - a057); + a057 = (a055 * a013); + a058 = (a056 * a014); + a057 = (a057 + a058); + a054 = (a054 - a057); + a057 = (a054 * a015); + a058 = (a055 * a016); + a057 = (a057 + a058); + a058 = (a056 * a017); + a057 = (a057 + a058); + a053 = (a053 - a057); + a057 = (a053 * a018); + a058 = (a054 * a019); + a057 = (a057 + a058); + a058 = (a055 * a020); + a057 = (a057 + a058); + a058 = (a056 * a021); + a057 = (a057 + a058); + a052 = (a052 - a057); + a057 = (a052 * a022); + a058 = (a053 * a023); + a057 = (a057 + a058); + a058 = (a054 * a024); + a057 = (a057 + a058); + a058 = (a055 * a025); + a057 = (a057 + a058); + a058 = (a056 * a026); + a057 = (a057 + a058); + a051 = (a051 - a057); + a057 = (a051 * a027); + a058 = (a052 * a028); + a057 = (a057 + a058); + a058 = (a053 * a029); + a057 = (a057 + a058); + a058 = (a054 * a030); + a057 = (a057 + a058); + a058 = (a055 * a031); + a057 = (a057 + a058); + a058 = (a056 * a032); + a057 = (a057 + a058); + a050 = (a050 - a057); + a057 = (a050 * a033); + a058 = (a051 * a034); + a057 = (a057 + a058); + a058 = (a052 * a035); + a057 = (a057 + a058); + a058 = (a053 * a036); + a057 = (a057 + a058); + a058 = (a054 * a037); + a057 = (a057 + a058); + a058 = (a055 * a038); + a057 = (a057 + a058); + a058 = (a056 * a039); + a057 = (a057 + a058); + a049 = (a049 - a057); + a057 = (a049 * a040); + a058 = (a050 * a041); + a057 = (a057 + a058); + a058 = (a051 * a042); + a057 = (a057 + a058); + a058 = (a052 * a043); + a057 = (a057 + a058); + a058 = (a053 * a044); + a057 = (a057 + a058); + a058 = (a054 * a045); + a057 = (a057 + a058); + a058 = (a055 * a046); + a057 = (a057 + a058); + a058 = (a056 * a047); + a057 = (a057 + a058); + a048 = (a048 - a057); + a048 = (a048 / a003); + a057 = math::square(a048); + a057 = (a003 * a057); + a049 = (a049 / a004); + a058 = math::square(a049); + a058 = (a004 * a058); + a057 = (a057 + a058); + a050 = (a050 / a005); + a058 = math::square(a050); + a058 = (a005 * a058); + a057 = (a057 + a058); + a051 = (a051 / a006); + a058 = math::square(a051); + a058 = (a006 * a058); + a057 = (a057 + a058); + a052 = (a052 / a007); + a058 = math::square(a052); + a058 = (a007 * a058); + a057 = (a057 + a058); + a053 = (a053 / a008); + a058 = math::square(a053); + a058 = (a008 * a058); + a057 = (a057 + a058); + a054 = (a054 / a009); + a058 = math::square(a054); + a058 = (a009 * a058); + a057 = (a057 + a058); + a055 = (a055 / a010); + a058 = math::square(a055); + a058 = (a010 * a058); + a057 = (a057 + a058); + a056 = (a056 / a011); + a058 = math::square(a056); + a058 = (a011 * a058); + a057 = (a057 + a058); + a002 = (a002 - a057); + a057 = input_vec[25]; + a058 = input_vec[37]; + a059 = input_vec[49]; + a060 = input_vec[61]; + a061 = input_vec[73]; + a062 = input_vec[85]; + a063 = input_vec[97]; + a064 = input_vec[109]; + a065 = input_vec[121]; + a066 = input_vec[133]; + a067 = (a066 * a012); + a065 = (a065 - a067); + a067 = (a065 * a013); + a068 = (a066 * a014); + a067 = (a067 + a068); + a064 = (a064 - a067); + a067 = (a064 * a015); + a068 = (a065 * a016); + a067 = (a067 + a068); + a068 = (a066 * a017); + a067 = (a067 + a068); + a063 = (a063 - a067); + a067 = (a063 * a018); + a068 = (a064 * a019); + a067 = (a067 + a068); + a068 = (a065 * a020); + a067 = (a067 + a068); + a068 = (a066 * a021); + a067 = (a067 + a068); + a062 = (a062 - a067); + a067 = (a062 * a022); + a068 = (a063 * a023); + a067 = (a067 + a068); + a068 = (a064 * a024); + a067 = (a067 + a068); + a068 = (a065 * a025); + a067 = (a067 + a068); + a068 = (a066 * a026); + a067 = (a067 + a068); + a061 = (a061 - a067); + a067 = (a061 * a027); + a068 = (a062 * a028); + a067 = (a067 + a068); + a068 = (a063 * a029); + a067 = (a067 + a068); + a068 = (a064 * a030); + a067 = (a067 + a068); + a068 = (a065 * a031); + a067 = (a067 + a068); + a068 = (a066 * a032); + a067 = (a067 + a068); + a060 = (a060 - a067); + a067 = (a060 * a033); + a068 = (a061 * a034); + a067 = (a067 + a068); + a068 = (a062 * a035); + a067 = (a067 + a068); + a068 = (a063 * a036); + a067 = (a067 + a068); + a068 = (a064 * a037); + a067 = (a067 + a068); + a068 = (a065 * a038); + a067 = (a067 + a068); + a068 = (a066 * a039); + a067 = (a067 + a068); + a059 = (a059 - a067); + a067 = (a059 * a040); + a068 = (a060 * a041); + a067 = (a067 + a068); + a068 = (a061 * a042); + a067 = (a067 + a068); + a068 = (a062 * a043); + a067 = (a067 + a068); + a068 = (a063 * a044); + a067 = (a067 + a068); + a068 = (a064 * a045); + a067 = (a067 + a068); + a068 = (a065 * a046); + a067 = (a067 + a068); + a068 = (a066 * a047); + a067 = (a067 + a068); + a058 = (a058 - a067); + a067 = (a058 * a048); + a068 = (a059 * a049); + a067 = (a067 + a068); + a068 = (a060 * a050); + a067 = (a067 + a068); + a068 = (a061 * a051); + a067 = (a067 + a068); + a068 = (a062 * a052); + a067 = (a067 + a068); + a068 = (a063 * a053); + a067 = (a067 + a068); + a068 = (a064 * a054); + a067 = (a067 + a068); + a068 = (a065 * a055); + a067 = (a067 + a068); + a068 = (a066 * a056); + a067 = (a067 + a068); + a057 = (a057 - a067); + a057 = (a057 / a002); + a067 = math::square(a057); + a067 = (a002 * a067); + a058 = (a058 / a003); + a068 = math::square(a058); + a068 = (a003 * a068); + a067 = (a067 + a068); + a059 = (a059 / a004); + a068 = math::square(a059); + a068 = (a004 * a068); + a067 = (a067 + a068); + a060 = (a060 / a005); + a068 = math::square(a060); + a068 = (a005 * a068); + a067 = (a067 + a068); + a061 = (a061 / a006); + a068 = math::square(a061); + a068 = (a006 * a068); + a067 = (a067 + a068); + a062 = (a062 / a007); + a068 = math::square(a062); + a068 = (a007 * a068); + a067 = (a067 + a068); + a063 = (a063 / a008); + a068 = math::square(a063); + a068 = (a008 * a068); + a067 = (a067 + a068); + a064 = (a064 / a009); + a068 = math::square(a064); + a068 = (a009 * a068); + a067 = (a067 + a068); + a065 = (a065 / a010); + a068 = math::square(a065); + a068 = (a010 * a068); + a067 = (a067 + a068); + a066 = (a066 / a011); + a068 = math::square(a066); + a068 = (a011 * a068); + a067 = (a067 + a068); + a001 = (a001 - a067); + a067 = input_vec[12]; + a068 = input_vec[24]; + a069 = input_vec[36]; + a070 = input_vec[48]; + a071 = input_vec[60]; + a072 = input_vec[72]; + a073 = input_vec[84]; + a074 = input_vec[96]; + a075 = input_vec[108]; + a076 = input_vec[120]; + a077 = input_vec[132]; + a078 = (a077 * a012); + a076 = (a076 - a078); + a078 = (a076 * a013); + a079 = (a077 * a014); + a078 = (a078 + a079); + a075 = (a075 - a078); + a078 = (a075 * a015); + a079 = (a076 * a016); + a078 = (a078 + a079); + a079 = (a077 * a017); + a078 = (a078 + a079); + a074 = (a074 - a078); + a078 = (a074 * a018); + a079 = (a075 * a019); + a078 = (a078 + a079); + a079 = (a076 * a020); + a078 = (a078 + a079); + a079 = (a077 * a021); + a078 = (a078 + a079); + a073 = (a073 - a078); + a078 = (a073 * a022); + a079 = (a074 * a023); + a078 = (a078 + a079); + a079 = (a075 * a024); + a078 = (a078 + a079); + a079 = (a076 * a025); + a078 = (a078 + a079); + a079 = (a077 * a026); + a078 = (a078 + a079); + a072 = (a072 - a078); + a078 = (a072 * a027); + a079 = (a073 * a028); + a078 = (a078 + a079); + a079 = (a074 * a029); + a078 = (a078 + a079); + a079 = (a075 * a030); + a078 = (a078 + a079); + a079 = (a076 * a031); + a078 = (a078 + a079); + a079 = (a077 * a032); + a078 = (a078 + a079); + a071 = (a071 - a078); + a078 = (a071 * a033); + a079 = (a072 * a034); + a078 = (a078 + a079); + a079 = (a073 * a035); + a078 = (a078 + a079); + a079 = (a074 * a036); + a078 = (a078 + a079); + a079 = (a075 * a037); + a078 = (a078 + a079); + a079 = (a076 * a038); + a078 = (a078 + a079); + a079 = (a077 * a039); + a078 = (a078 + a079); + a070 = (a070 - a078); + a078 = (a070 * a040); + a079 = (a071 * a041); + a078 = (a078 + a079); + a079 = (a072 * a042); + a078 = (a078 + a079); + a079 = (a073 * a043); + a078 = (a078 + a079); + a079 = (a074 * a044); + a078 = (a078 + a079); + a079 = (a075 * a045); + a078 = (a078 + a079); + a079 = (a076 * a046); + a078 = (a078 + a079); + a079 = (a077 * a047); + a078 = (a078 + a079); + a069 = (a069 - a078); + a078 = (a069 * a048); + a079 = (a070 * a049); + a078 = (a078 + a079); + a079 = (a071 * a050); + a078 = (a078 + a079); + a079 = (a072 * a051); + a078 = (a078 + a079); + a079 = (a073 * a052); + a078 = (a078 + a079); + a079 = (a074 * a053); + a078 = (a078 + a079); + a079 = (a075 * a054); + a078 = (a078 + a079); + a079 = (a076 * a055); + a078 = (a078 + a079); + a079 = (a077 * a056); + a078 = (a078 + a079); + a068 = (a068 - a078); + a078 = (a068 * a057); + a079 = (a069 * a058); + a078 = (a078 + a079); + a079 = (a070 * a059); + a078 = (a078 + a079); + a079 = (a071 * a060); + a078 = (a078 + a079); + a079 = (a072 * a061); + a078 = (a078 + a079); + a079 = (a073 * a062); + a078 = (a078 + a079); + a079 = (a074 * a063); + a078 = (a078 + a079); + a079 = (a075 * a064); + a078 = (a078 + a079); + a079 = (a076 * a065); + a078 = (a078 + a079); + a079 = (a077 * a066); + a078 = (a078 + a079); + a067 = (a067 - a078); + a067 = (a067 / a001); + a078 = math::square(a067); + a078 = (a001 * a078); + a068 = (a068 / a002); + a079 = math::square(a068); + a079 = (a002 * a079); + a078 = (a078 + a079); + a069 = (a069 / a003); + a079 = math::square(a069); + a079 = (a003 * a079); + a078 = (a078 + a079); + a070 = (a070 / a004); + a079 = math::square(a070); + a079 = (a004 * a079); + a078 = (a078 + a079); + a071 = (a071 / a005); + a079 = math::square(a071); + a079 = (a005 * a079); + a078 = (a078 + a079); + a072 = (a072 / a006); + a079 = math::square(a072); + a079 = (a006 * a079); + a078 = (a078 + a079); + a073 = (a073 / a007); + a079 = math::square(a073); + a079 = (a007 * a079); + a078 = (a078 + a079); + a074 = (a074 / a008); + a079 = math::square(a074); + a079 = (a008 * a079); + a078 = (a078 + a079); + a075 = (a075 / a009); + a079 = math::square(a075); + a079 = (a009 * a079); + a078 = (a078 + a079); + a076 = (a076 / a010); + a079 = math::square(a076); + a079 = (a010 * a079); + a078 = (a078 + a079); + a077 = (a077 / a011); + a079 = math::square(a077); + a079 = (a011 * a079); + a078 = (a078 + a079); + a000 = (a000 - a078); + a078 = (1. / a000); + output_vec[0] = a078; + a078 = (a067 / a000); + a079 = (-a078); + output_vec[1] = a079; + a080 = (a067 * a057); + a080 = (a068 - a080); + a080 = (a080 / a000); + a081 = (-a080); + output_vec[2] = a081; + a082 = (a057 * a048); + a082 = (a058 - a082); + a083 = (a067 * a082); + a084 = (a068 * a048); + a083 = (a083 + a084); + a083 = (a069 - a083); + a083 = (a083 / a000); + a084 = (-a083); + output_vec[3] = a084; + a085 = (a048 * a040); + a085 = (a049 - a085); + a086 = (a057 * a085); + a087 = (a058 * a040); + a086 = (a086 + a087); + a086 = (a059 - a086); + a087 = (a067 * a086); + a088 = (a068 * a085); + a087 = (a087 + a088); + a088 = (a069 * a040); + a087 = (a087 + a088); + a087 = (a070 - a087); + a087 = (a087 / a000); + a088 = (-a087); + output_vec[4] = a088; + a089 = (a040 * a033); + a089 = (a041 - a089); + a090 = (a048 * a089); + a091 = (a049 * a033); + a090 = (a090 + a091); + a090 = (a050 - a090); + a091 = (a057 * a090); + a092 = (a058 * a089); + a091 = (a091 + a092); + a092 = (a059 * a033); + a091 = (a091 + a092); + a091 = (a060 - a091); + a092 = (a067 * a091); + a093 = (a068 * a090); + a092 = (a092 + a093); + a093 = (a069 * a089); + a092 = (a092 + a093); + a093 = (a070 * a033); + a092 = (a092 + a093); + a092 = (a071 - a092); + a092 = (a092 / a000); + a093 = (-a092); + output_vec[5] = a093; + a094 = (a033 * a027); + a094 = (a034 - a094); + a095 = (a040 * a094); + a096 = (a041 * a027); + a095 = (a095 + a096); + a095 = (a042 - a095); + a096 = (a048 * a095); + a097 = (a049 * a094); + a096 = (a096 + a097); + a097 = (a050 * a027); + a096 = (a096 + a097); + a096 = (a051 - a096); + a097 = (a057 * a096); + a098 = (a058 * a095); + a097 = (a097 + a098); + a098 = (a059 * a094); + a097 = (a097 + a098); + a098 = (a060 * a027); + a097 = (a097 + a098); + a097 = (a061 - a097); + a098 = (a067 * a097); + a099 = (a068 * a096); + a098 = (a098 + a099); + a099 = (a069 * a095); + a098 = (a098 + a099); + a099 = (a070 * a094); + a098 = (a098 + a099); + a099 = (a071 * a027); + a098 = (a098 + a099); + a098 = (a072 - a098); + a098 = (a098 / a000); + a099 = (-a098); + output_vec[6] = a099; + a100 = (a027 * a022); + a100 = (a028 - a100); + a101 = (a033 * a100); + a102 = (a034 * a022); + a101 = (a101 + a102); + a101 = (a035 - a101); + a102 = (a040 * a101); + a103 = (a041 * a100); + a102 = (a102 + a103); + a103 = (a042 * a022); + a102 = (a102 + a103); + a102 = (a043 - a102); + a103 = (a048 * a102); + a104 = (a049 * a101); + a103 = (a103 + a104); + a104 = (a050 * a100); + a103 = (a103 + a104); + a104 = (a051 * a022); + a103 = (a103 + a104); + a103 = (a052 - a103); + a104 = (a057 * a103); + a105 = (a058 * a102); + a104 = (a104 + a105); + a105 = (a059 * a101); + a104 = (a104 + a105); + a105 = (a060 * a100); + a104 = (a104 + a105); + a105 = (a061 * a022); + a104 = (a104 + a105); + a104 = (a062 - a104); + a105 = (a067 * a104); + a106 = (a068 * a103); + a105 = (a105 + a106); + a106 = (a069 * a102); + a105 = (a105 + a106); + a106 = (a070 * a101); + a105 = (a105 + a106); + a106 = (a071 * a100); + a105 = (a105 + a106); + a106 = (a072 * a022); + a105 = (a105 + a106); + a105 = (a073 - a105); + a105 = (a105 / a000); + a106 = (-a105); + output_vec[7] = a106; + a107 = (a022 * a018); + a107 = (a023 - a107); + a108 = (a027 * a107); + a109 = (a028 * a018); + a108 = (a108 + a109); + a108 = (a029 - a108); + a109 = (a033 * a108); + a110 = (a034 * a107); + a109 = (a109 + a110); + a110 = (a035 * a018); + a109 = (a109 + a110); + a109 = (a036 - a109); + a110 = (a040 * a109); + a111 = (a041 * a108); + a110 = (a110 + a111); + a111 = (a042 * a107); + a110 = (a110 + a111); + a111 = (a043 * a018); + a110 = (a110 + a111); + a110 = (a044 - a110); + a111 = (a048 * a110); + a112 = (a049 * a109); + a111 = (a111 + a112); + a112 = (a050 * a108); + a111 = (a111 + a112); + a112 = (a051 * a107); + a111 = (a111 + a112); + a112 = (a052 * a018); + a111 = (a111 + a112); + a111 = (a053 - a111); + a112 = (a057 * a111); + a113 = (a058 * a110); + a112 = (a112 + a113); + a113 = (a059 * a109); + a112 = (a112 + a113); + a113 = (a060 * a108); + a112 = (a112 + a113); + a113 = (a061 * a107); + a112 = (a112 + a113); + a113 = (a062 * a018); + a112 = (a112 + a113); + a112 = (a063 - a112); + a113 = (a067 * a112); + a114 = (a068 * a111); + a113 = (a113 + a114); + a114 = (a069 * a110); + a113 = (a113 + a114); + a114 = (a070 * a109); + a113 = (a113 + a114); + a114 = (a071 * a108); + a113 = (a113 + a114); + a114 = (a072 * a107); + a113 = (a113 + a114); + a114 = (a073 * a018); + a113 = (a113 + a114); + a113 = (a074 - a113); + a113 = (a113 / a000); + a114 = (-a113); + output_vec[8] = a114; + a115 = (a018 * a015); + a115 = (a019 - a115); + a116 = (a022 * a115); + a117 = (a023 * a015); + a116 = (a116 + a117); + a116 = (a024 - a116); + a117 = (a027 * a116); + a118 = (a028 * a115); + a117 = (a117 + a118); + a118 = (a029 * a015); + a117 = (a117 + a118); + a117 = (a030 - a117); + a118 = (a033 * a117); + a119 = (a034 * a116); + a118 = (a118 + a119); + a119 = (a035 * a115); + a118 = (a118 + a119); + a119 = (a036 * a015); + a118 = (a118 + a119); + a118 = (a037 - a118); + a119 = (a040 * a118); + a120 = (a041 * a117); + a119 = (a119 + a120); + a120 = (a042 * a116); + a119 = (a119 + a120); + a120 = (a043 * a115); + a119 = (a119 + a120); + a120 = (a044 * a015); + a119 = (a119 + a120); + a119 = (a045 - a119); + a120 = (a048 * a119); + a121 = (a049 * a118); + a120 = (a120 + a121); + a121 = (a050 * a117); + a120 = (a120 + a121); + a121 = (a051 * a116); + a120 = (a120 + a121); + a121 = (a052 * a115); + a120 = (a120 + a121); + a121 = (a053 * a015); + a120 = (a120 + a121); + a120 = (a054 - a120); + a121 = (a057 * a120); + a122 = (a058 * a119); + a121 = (a121 + a122); + a122 = (a059 * a118); + a121 = (a121 + a122); + a122 = (a060 * a117); + a121 = (a121 + a122); + a122 = (a061 * a116); + a121 = (a121 + a122); + a122 = (a062 * a115); + a121 = (a121 + a122); + a122 = (a063 * a015); + a121 = (a121 + a122); + a121 = (a064 - a121); + a122 = (a067 * a121); + a123 = (a068 * a120); + a122 = (a122 + a123); + a123 = (a069 * a119); + a122 = (a122 + a123); + a123 = (a070 * a118); + a122 = (a122 + a123); + a123 = (a071 * a117); + a122 = (a122 + a123); + a123 = (a072 * a116); + a122 = (a122 + a123); + a123 = (a073 * a115); + a122 = (a122 + a123); + a123 = (a074 * a015); + a122 = (a122 + a123); + a122 = (a075 - a122); + a122 = (a122 / a000); + a123 = (-a122); + output_vec[9] = a123; + a124 = (a015 * a013); + a124 = (a016 - a124); + a125 = (a018 * a124); + a126 = (a019 * a013); + a125 = (a125 + a126); + a125 = (a020 - a125); + a126 = (a022 * a125); + a127 = (a023 * a124); + a126 = (a126 + a127); + a127 = (a024 * a013); + a126 = (a126 + a127); + a126 = (a025 - a126); + a127 = (a027 * a126); + a128 = (a028 * a125); + a127 = (a127 + a128); + a128 = (a029 * a124); + a127 = (a127 + a128); + a128 = (a030 * a013); + a127 = (a127 + a128); + a127 = (a031 - a127); + a128 = (a033 * a127); + a129 = (a034 * a126); + a128 = (a128 + a129); + a129 = (a035 * a125); + a128 = (a128 + a129); + a129 = (a036 * a124); + a128 = (a128 + a129); + a129 = (a037 * a013); + a128 = (a128 + a129); + a128 = (a038 - a128); + a129 = (a040 * a128); + a130 = (a041 * a127); + a129 = (a129 + a130); + a130 = (a042 * a126); + a129 = (a129 + a130); + a130 = (a043 * a125); + a129 = (a129 + a130); + a130 = (a044 * a124); + a129 = (a129 + a130); + a130 = (a045 * a013); + a129 = (a129 + a130); + a129 = (a046 - a129); + a130 = (a048 * a129); + a131 = (a049 * a128); + a130 = (a130 + a131); + a131 = (a050 * a127); + a130 = (a130 + a131); + a131 = (a051 * a126); + a130 = (a130 + a131); + a131 = (a052 * a125); + a130 = (a130 + a131); + a131 = (a053 * a124); + a130 = (a130 + a131); + a131 = (a054 * a013); + a130 = (a130 + a131); + a130 = (a055 - a130); + a131 = (a057 * a130); + a132 = (a058 * a129); + a131 = (a131 + a132); + a132 = (a059 * a128); + a131 = (a131 + a132); + a132 = (a060 * a127); + a131 = (a131 + a132); + a132 = (a061 * a126); + a131 = (a131 + a132); + a132 = (a062 * a125); + a131 = (a131 + a132); + a132 = (a063 * a124); + a131 = (a131 + a132); + a132 = (a064 * a013); + a131 = (a131 + a132); + a131 = (a065 - a131); + a132 = (a067 * a131); + a133 = (a068 * a130); + a132 = (a132 + a133); + a133 = (a069 * a129); + a132 = (a132 + a133); + a133 = (a070 * a128); + a132 = (a132 + a133); + a133 = (a071 * a127); + a132 = (a132 + a133); + a133 = (a072 * a126); + a132 = (a132 + a133); + a133 = (a073 * a125); + a132 = (a132 + a133); + a133 = (a074 * a124); + a132 = (a132 + a133); + a133 = (a075 * a013); + a132 = (a132 + a133); + a132 = (a076 - a132); + a132 = (a132 / a000); + a133 = (-a132); + output_vec[10] = a133; + a134 = (a013 * a012); + a134 = (a014 - a134); + a135 = (a015 * a134); + a136 = (a016 * a012); + a135 = (a135 + a136); + a135 = (a017 - a135); + a136 = (a018 * a135); + a137 = (a019 * a134); + a136 = (a136 + a137); + a137 = (a020 * a012); + a136 = (a136 + a137); + a136 = (a021 - a136); + a137 = (a022 * a136); + a138 = (a023 * a135); + a137 = (a137 + a138); + a138 = (a024 * a134); + a137 = (a137 + a138); + a138 = (a025 * a012); + a137 = (a137 + a138); + a137 = (a026 - a137); + a138 = (a027 * a137); + a139 = (a028 * a136); + a138 = (a138 + a139); + a139 = (a029 * a135); + a138 = (a138 + a139); + a139 = (a030 * a134); + a138 = (a138 + a139); + a139 = (a031 * a012); + a138 = (a138 + a139); + a138 = (a032 - a138); + a139 = (a033 * a138); + a140 = (a034 * a137); + a139 = (a139 + a140); + a140 = (a035 * a136); + a139 = (a139 + a140); + a140 = (a036 * a135); + a139 = (a139 + a140); + a140 = (a037 * a134); + a139 = (a139 + a140); + a140 = (a038 * a012); + a139 = (a139 + a140); + a139 = (a039 - a139); + a140 = (a040 * a139); + a141 = (a041 * a138); + a140 = (a140 + a141); + a141 = (a042 * a137); + a140 = (a140 + a141); + a141 = (a043 * a136); + a140 = (a140 + a141); + a141 = (a044 * a135); + a140 = (a140 + a141); + a141 = (a045 * a134); + a140 = (a140 + a141); + a141 = (a046 * a012); + a140 = (a140 + a141); + a140 = (a047 - a140); + a141 = (a048 * a140); + a142 = (a049 * a139); + a141 = (a141 + a142); + a142 = (a050 * a138); + a141 = (a141 + a142); + a142 = (a051 * a137); + a141 = (a141 + a142); + a142 = (a052 * a136); + a141 = (a141 + a142); + a142 = (a053 * a135); + a141 = (a141 + a142); + a142 = (a054 * a134); + a141 = (a141 + a142); + a142 = (a055 * a012); + a141 = (a141 + a142); + a141 = (a056 - a141); + a142 = (a057 * a141); + a143 = (a058 * a140); + a142 = (a142 + a143); + a143 = (a059 * a139); + a142 = (a142 + a143); + a143 = (a060 * a138); + a142 = (a142 + a143); + a143 = (a061 * a137); + a142 = (a142 + a143); + a143 = (a062 * a136); + a142 = (a142 + a143); + a143 = (a063 * a135); + a142 = (a142 + a143); + a143 = (a064 * a134); + a142 = (a142 + a143); + a143 = (a065 * a012); + a142 = (a142 + a143); + a142 = (a066 - a142); + a143 = (a067 * a142); + a144 = (a068 * a141); + a143 = (a143 + a144); + a144 = (a069 * a140); + a143 = (a143 + a144); + a144 = (a070 * a139); + a143 = (a143 + a144); + a144 = (a071 * a138); + a143 = (a143 + a144); + a144 = (a072 * a137); + a143 = (a143 + a144); + a144 = (a073 * a136); + a143 = (a143 + a144); + a144 = (a074 * a135); + a143 = (a143 + a144); + a144 = (a075 * a134); + a143 = (a143 + a144); + a144 = (a076 * a012); + a143 = (a143 + a144); + a143 = (a077 - a143); + a143 = (a143 / a000); + a000 = (-a143); + output_vec[11] = a000; + output_vec[12] = a079; + a079 = (1. / a001); + a078 = (a067 * a078); + a079 = (a079 + a078); + output_vec[13] = a079; + a079 = (a067 * a080); + a078 = (a057 / a001); + a079 = (a079 - a078); + output_vec[14] = a079; + a078 = (a067 * a083); + a082 = (a082 / a001); + a078 = (a078 - a082); + output_vec[15] = a078; + a082 = (a067 * a087); + a086 = (a086 / a001); + a082 = (a082 - a086); + output_vec[16] = a082; + a086 = (a067 * a092); + a091 = (a091 / a001); + a086 = (a086 - a091); + output_vec[17] = a086; + a091 = (a067 * a098); + a097 = (a097 / a001); + a091 = (a091 - a097); + output_vec[18] = a091; + a097 = (a067 * a105); + a104 = (a104 / a001); + a097 = (a097 - a104); + output_vec[19] = a097; + a104 = (a067 * a113); + a112 = (a112 / a001); + a104 = (a104 - a112); + output_vec[20] = a104; + a112 = (a067 * a122); + a121 = (a121 / a001); + a112 = (a112 - a121); + output_vec[21] = a112; + a121 = (a067 * a132); + a131 = (a131 / a001); + a121 = (a121 - a131); + output_vec[22] = a121; + a067 = (a067 * a143); + a142 = (a142 / a001); + a067 = (a067 - a142); + output_vec[23] = a067; + output_vec[24] = a081; + output_vec[25] = a079; + a081 = (1. / a002); + a079 = (a057 * a079); + a080 = (a068 * a080); + a079 = (a079 - a080); + a081 = (a081 - a079); + output_vec[26] = a081; + a081 = (a048 / a002); + a079 = (a057 * a078); + a080 = (a068 * a083); + a079 = (a079 - a080); + a081 = (a081 + a079); + a079 = (-a081); + output_vec[27] = a079; + a085 = (a085 / a002); + a080 = (a057 * a082); + a142 = (a068 * a087); + a080 = (a080 - a142); + a085 = (a085 + a080); + a080 = (-a085); + output_vec[28] = a080; + a090 = (a090 / a002); + a142 = (a057 * a086); + a001 = (a068 * a092); + a142 = (a142 - a001); + a090 = (a090 + a142); + a142 = (-a090); + output_vec[29] = a142; + a096 = (a096 / a002); + a001 = (a057 * a091); + a131 = (a068 * a098); + a001 = (a001 - a131); + a096 = (a096 + a001); + a001 = (-a096); + output_vec[30] = a001; + a103 = (a103 / a002); + a131 = (a057 * a097); + a144 = (a068 * a105); + a131 = (a131 - a144); + a103 = (a103 + a131); + a131 = (-a103); + output_vec[31] = a131; + a111 = (a111 / a002); + a144 = (a057 * a104); + a145 = (a068 * a113); + a144 = (a144 - a145); + a111 = (a111 + a144); + a144 = (-a111); + output_vec[32] = a144; + a120 = (a120 / a002); + a145 = (a057 * a112); + a146 = (a068 * a122); + a145 = (a145 - a146); + a120 = (a120 + a145); + a145 = (-a120); + output_vec[33] = a145; + a130 = (a130 / a002); + a146 = (a057 * a121); + a147 = (a068 * a132); + a146 = (a146 - a147); + a130 = (a130 + a146); + a146 = (-a130); + output_vec[34] = a146; + a141 = (a141 / a002); + a057 = (a057 * a067); + a068 = (a068 * a143); + a057 = (a057 - a068); + a141 = (a141 + a057); + a057 = (-a141); + output_vec[35] = a057; + output_vec[36] = a084; + output_vec[37] = a078; + output_vec[38] = a079; + a079 = (1. / a003); + a078 = (a058 * a078); + a083 = (a069 * a083); + a078 = (a078 - a083); + a081 = (a048 * a081); + a078 = (a078 - a081); + a079 = (a079 - a078); + output_vec[39] = a079; + a079 = (a040 / a003); + a078 = (a058 * a082); + a081 = (a069 * a087); + a078 = (a078 - a081); + a081 = (a048 * a085); + a078 = (a078 - a081); + a079 = (a079 + a078); + a078 = (-a079); + output_vec[40] = a078; + a089 = (a089 / a003); + a081 = (a058 * a086); + a083 = (a069 * a092); + a081 = (a081 - a083); + a083 = (a048 * a090); + a081 = (a081 - a083); + a089 = (a089 + a081); + a081 = (-a089); + output_vec[41] = a081; + a095 = (a095 / a003); + a083 = (a058 * a091); + a084 = (a069 * a098); + a083 = (a083 - a084); + a084 = (a048 * a096); + a083 = (a083 - a084); + a095 = (a095 + a083); + a083 = (-a095); + output_vec[42] = a083; + a102 = (a102 / a003); + a084 = (a058 * a097); + a068 = (a069 * a105); + a084 = (a084 - a068); + a068 = (a048 * a103); + a084 = (a084 - a068); + a102 = (a102 + a084); + a084 = (-a102); + output_vec[43] = a084; + a110 = (a110 / a003); + a068 = (a058 * a104); + a002 = (a069 * a113); + a068 = (a068 - a002); + a002 = (a048 * a111); + a068 = (a068 - a002); + a110 = (a110 + a068); + a068 = (-a110); + output_vec[44] = a068; + a119 = (a119 / a003); + a002 = (a058 * a112); + a147 = (a069 * a122); + a002 = (a002 - a147); + a147 = (a048 * a120); + a002 = (a002 - a147); + a119 = (a119 + a002); + a002 = (-a119); + output_vec[45] = a002; + a129 = (a129 / a003); + a147 = (a058 * a121); + a148 = (a069 * a132); + a147 = (a147 - a148); + a148 = (a048 * a130); + a147 = (a147 - a148); + a129 = (a129 + a147); + a147 = (-a129); + output_vec[46] = a147; + a140 = (a140 / a003); + a058 = (a058 * a067); + a069 = (a069 * a143); + a058 = (a058 - a069); + a048 = (a048 * a141); + a058 = (a058 - a048); + a140 = (a140 + a058); + a058 = (-a140); + output_vec[47] = a058; + output_vec[48] = a088; + output_vec[49] = a082; + output_vec[50] = a080; + output_vec[51] = a078; + a078 = (1. / a004); + a082 = (a059 * a082); + a087 = (a070 * a087); + a082 = (a082 - a087); + a085 = (a049 * a085); + a082 = (a082 - a085); + a079 = (a040 * a079); + a082 = (a082 - a079); + a078 = (a078 - a082); + output_vec[52] = a078; + a078 = (a033 / a004); + a082 = (a059 * a086); + a079 = (a070 * a092); + a082 = (a082 - a079); + a079 = (a049 * a090); + a082 = (a082 - a079); + a079 = (a040 * a089); + a082 = (a082 - a079); + a078 = (a078 + a082); + a082 = (-a078); + output_vec[53] = a082; + a094 = (a094 / a004); + a079 = (a059 * a091); + a085 = (a070 * a098); + a079 = (a079 - a085); + a085 = (a049 * a096); + a079 = (a079 - a085); + a085 = (a040 * a095); + a079 = (a079 - a085); + a094 = (a094 + a079); + a079 = (-a094); + output_vec[54] = a079; + a101 = (a101 / a004); + a085 = (a059 * a097); + a087 = (a070 * a105); + a085 = (a085 - a087); + a087 = (a049 * a103); + a085 = (a085 - a087); + a087 = (a040 * a102); + a085 = (a085 - a087); + a101 = (a101 + a085); + a085 = (-a101); + output_vec[55] = a085; + a109 = (a109 / a004); + a087 = (a059 * a104); + a080 = (a070 * a113); + a087 = (a087 - a080); + a080 = (a049 * a111); + a087 = (a087 - a080); + a080 = (a040 * a110); + a087 = (a087 - a080); + a109 = (a109 + a087); + a087 = (-a109); + output_vec[56] = a087; + a118 = (a118 / a004); + a080 = (a059 * a112); + a088 = (a070 * a122); + a080 = (a080 - a088); + a088 = (a049 * a120); + a080 = (a080 - a088); + a088 = (a040 * a119); + a080 = (a080 - a088); + a118 = (a118 + a080); + a080 = (-a118); + output_vec[57] = a080; + a128 = (a128 / a004); + a088 = (a059 * a121); + a048 = (a070 * a132); + a088 = (a088 - a048); + a048 = (a049 * a130); + a088 = (a088 - a048); + a048 = (a040 * a129); + a088 = (a088 - a048); + a128 = (a128 + a088); + a088 = (-a128); + output_vec[58] = a088; + a139 = (a139 / a004); + a059 = (a059 * a067); + a070 = (a070 * a143); + a059 = (a059 - a070); + a049 = (a049 * a141); + a059 = (a059 - a049); + a040 = (a040 * a140); + a059 = (a059 - a040); + a139 = (a139 + a059); + a059 = (-a139); + output_vec[59] = a059; + output_vec[60] = a093; + output_vec[61] = a086; + output_vec[62] = a142; + output_vec[63] = a081; + output_vec[64] = a082; + a082 = (1. / a005); + a086 = (a060 * a086); + a092 = (a071 * a092); + a086 = (a086 - a092); + a090 = (a050 * a090); + a086 = (a086 - a090); + a089 = (a041 * a089); + a086 = (a086 - a089); + a078 = (a033 * a078); + a086 = (a086 - a078); + a082 = (a082 - a086); + output_vec[65] = a082; + a082 = (a027 / a005); + a086 = (a060 * a091); + a078 = (a071 * a098); + a086 = (a086 - a078); + a078 = (a050 * a096); + a086 = (a086 - a078); + a078 = (a041 * a095); + a086 = (a086 - a078); + a078 = (a033 * a094); + a086 = (a086 - a078); + a082 = (a082 + a086); + a086 = (-a082); + output_vec[66] = a086; + a100 = (a100 / a005); + a078 = (a060 * a097); + a089 = (a071 * a105); + a078 = (a078 - a089); + a089 = (a050 * a103); + a078 = (a078 - a089); + a089 = (a041 * a102); + a078 = (a078 - a089); + a089 = (a033 * a101); + a078 = (a078 - a089); + a100 = (a100 + a078); + a078 = (-a100); + output_vec[67] = a078; + a108 = (a108 / a005); + a089 = (a060 * a104); + a090 = (a071 * a113); + a089 = (a089 - a090); + a090 = (a050 * a111); + a089 = (a089 - a090); + a090 = (a041 * a110); + a089 = (a089 - a090); + a090 = (a033 * a109); + a089 = (a089 - a090); + a108 = (a108 + a089); + a089 = (-a108); + output_vec[68] = a089; + a117 = (a117 / a005); + a090 = (a060 * a112); + a092 = (a071 * a122); + a090 = (a090 - a092); + a092 = (a050 * a120); + a090 = (a090 - a092); + a092 = (a041 * a119); + a090 = (a090 - a092); + a092 = (a033 * a118); + a090 = (a090 - a092); + a117 = (a117 + a090); + a090 = (-a117); + output_vec[69] = a090; + a127 = (a127 / a005); + a092 = (a060 * a121); + a081 = (a071 * a132); + a092 = (a092 - a081); + a081 = (a050 * a130); + a092 = (a092 - a081); + a081 = (a041 * a129); + a092 = (a092 - a081); + a081 = (a033 * a128); + a092 = (a092 - a081); + a127 = (a127 + a092); + a092 = (-a127); + output_vec[70] = a092; + a138 = (a138 / a005); + a060 = (a060 * a067); + a071 = (a071 * a143); + a060 = (a060 - a071); + a050 = (a050 * a141); + a060 = (a060 - a050); + a041 = (a041 * a140); + a060 = (a060 - a041); + a033 = (a033 * a139); + a060 = (a060 - a033); + a138 = (a138 + a060); + a060 = (-a138); + output_vec[71] = a060; + output_vec[72] = a099; + output_vec[73] = a091; + output_vec[74] = a001; + output_vec[75] = a083; + output_vec[76] = a079; + output_vec[77] = a086; + a086 = (1. / a006); + a091 = (a061 * a091); + a098 = (a072 * a098); + a091 = (a091 - a098); + a096 = (a051 * a096); + a091 = (a091 - a096); + a095 = (a042 * a095); + a091 = (a091 - a095); + a094 = (a034 * a094); + a091 = (a091 - a094); + a082 = (a027 * a082); + a091 = (a091 - a082); + a086 = (a086 - a091); + output_vec[78] = a086; + a086 = (a022 / a006); + a091 = (a061 * a097); + a082 = (a072 * a105); + a091 = (a091 - a082); + a082 = (a051 * a103); + a091 = (a091 - a082); + a082 = (a042 * a102); + a091 = (a091 - a082); + a082 = (a034 * a101); + a091 = (a091 - a082); + a082 = (a027 * a100); + a091 = (a091 - a082); + a086 = (a086 + a091); + a091 = (-a086); + output_vec[79] = a091; + a107 = (a107 / a006); + a082 = (a061 * a104); + a094 = (a072 * a113); + a082 = (a082 - a094); + a094 = (a051 * a111); + a082 = (a082 - a094); + a094 = (a042 * a110); + a082 = (a082 - a094); + a094 = (a034 * a109); + a082 = (a082 - a094); + a094 = (a027 * a108); + a082 = (a082 - a094); + a107 = (a107 + a082); + a082 = (-a107); + output_vec[80] = a082; + a116 = (a116 / a006); + a094 = (a061 * a112); + a095 = (a072 * a122); + a094 = (a094 - a095); + a095 = (a051 * a120); + a094 = (a094 - a095); + a095 = (a042 * a119); + a094 = (a094 - a095); + a095 = (a034 * a118); + a094 = (a094 - a095); + a095 = (a027 * a117); + a094 = (a094 - a095); + a116 = (a116 + a094); + a094 = (-a116); + output_vec[81] = a094; + a126 = (a126 / a006); + a095 = (a061 * a121); + a096 = (a072 * a132); + a095 = (a095 - a096); + a096 = (a051 * a130); + a095 = (a095 - a096); + a096 = (a042 * a129); + a095 = (a095 - a096); + a096 = (a034 * a128); + a095 = (a095 - a096); + a096 = (a027 * a127); + a095 = (a095 - a096); + a126 = (a126 + a095); + a095 = (-a126); + output_vec[82] = a095; + a137 = (a137 / a006); + a061 = (a061 * a067); + a072 = (a072 * a143); + a061 = (a061 - a072); + a051 = (a051 * a141); + a061 = (a061 - a051); + a042 = (a042 * a140); + a061 = (a061 - a042); + a034 = (a034 * a139); + a061 = (a061 - a034); + a027 = (a027 * a138); + a061 = (a061 - a027); + a137 = (a137 + a061); + a061 = (-a137); + output_vec[83] = a061; + output_vec[84] = a106; + output_vec[85] = a097; + output_vec[86] = a131; + output_vec[87] = a084; + output_vec[88] = a085; + output_vec[89] = a078; + output_vec[90] = a091; + a091 = (1. / a007); + a097 = (a062 * a097); + a105 = (a073 * a105); + a097 = (a097 - a105); + a103 = (a052 * a103); + a097 = (a097 - a103); + a102 = (a043 * a102); + a097 = (a097 - a102); + a101 = (a035 * a101); + a097 = (a097 - a101); + a100 = (a028 * a100); + a097 = (a097 - a100); + a086 = (a022 * a086); + a097 = (a097 - a086); + a091 = (a091 - a097); + output_vec[91] = a091; + a091 = (a018 / a007); + a097 = (a062 * a104); + a086 = (a073 * a113); + a097 = (a097 - a086); + a086 = (a052 * a111); + a097 = (a097 - a086); + a086 = (a043 * a110); + a097 = (a097 - a086); + a086 = (a035 * a109); + a097 = (a097 - a086); + a086 = (a028 * a108); + a097 = (a097 - a086); + a086 = (a022 * a107); + a097 = (a097 - a086); + a091 = (a091 + a097); + a097 = (-a091); + output_vec[92] = a097; + a115 = (a115 / a007); + a086 = (a062 * a112); + a100 = (a073 * a122); + a086 = (a086 - a100); + a100 = (a052 * a120); + a086 = (a086 - a100); + a100 = (a043 * a119); + a086 = (a086 - a100); + a100 = (a035 * a118); + a086 = (a086 - a100); + a100 = (a028 * a117); + a086 = (a086 - a100); + a100 = (a022 * a116); + a086 = (a086 - a100); + a115 = (a115 + a086); + a086 = (-a115); + output_vec[93] = a086; + a125 = (a125 / a007); + a100 = (a062 * a121); + a101 = (a073 * a132); + a100 = (a100 - a101); + a101 = (a052 * a130); + a100 = (a100 - a101); + a101 = (a043 * a129); + a100 = (a100 - a101); + a101 = (a035 * a128); + a100 = (a100 - a101); + a101 = (a028 * a127); + a100 = (a100 - a101); + a101 = (a022 * a126); + a100 = (a100 - a101); + a125 = (a125 + a100); + a100 = (-a125); + output_vec[94] = a100; + a136 = (a136 / a007); + a062 = (a062 * a067); + a073 = (a073 * a143); + a062 = (a062 - a073); + a052 = (a052 * a141); + a062 = (a062 - a052); + a043 = (a043 * a140); + a062 = (a062 - a043); + a035 = (a035 * a139); + a062 = (a062 - a035); + a028 = (a028 * a138); + a062 = (a062 - a028); + a022 = (a022 * a137); + a062 = (a062 - a022); + a136 = (a136 + a062); + a062 = (-a136); + output_vec[95] = a062; + output_vec[96] = a114; + output_vec[97] = a104; + output_vec[98] = a144; + output_vec[99] = a068; + output_vec[100] = a087; + output_vec[101] = a089; + output_vec[102] = a082; + output_vec[103] = a097; + a097 = (1. / a008); + a104 = (a063 * a104); + a113 = (a074 * a113); + a104 = (a104 - a113); + a111 = (a053 * a111); + a104 = (a104 - a111); + a110 = (a044 * a110); + a104 = (a104 - a110); + a109 = (a036 * a109); + a104 = (a104 - a109); + a108 = (a029 * a108); + a104 = (a104 - a108); + a107 = (a023 * a107); + a104 = (a104 - a107); + a091 = (a018 * a091); + a104 = (a104 - a091); + a097 = (a097 - a104); + output_vec[104] = a097; + a097 = (a015 / a008); + a104 = (a063 * a112); + a091 = (a074 * a122); + a104 = (a104 - a091); + a091 = (a053 * a120); + a104 = (a104 - a091); + a091 = (a044 * a119); + a104 = (a104 - a091); + a091 = (a036 * a118); + a104 = (a104 - a091); + a091 = (a029 * a117); + a104 = (a104 - a091); + a091 = (a023 * a116); + a104 = (a104 - a091); + a091 = (a018 * a115); + a104 = (a104 - a091); + a097 = (a097 + a104); + a104 = (-a097); + output_vec[105] = a104; + a124 = (a124 / a008); + a091 = (a063 * a121); + a107 = (a074 * a132); + a091 = (a091 - a107); + a107 = (a053 * a130); + a091 = (a091 - a107); + a107 = (a044 * a129); + a091 = (a091 - a107); + a107 = (a036 * a128); + a091 = (a091 - a107); + a107 = (a029 * a127); + a091 = (a091 - a107); + a107 = (a023 * a126); + a091 = (a091 - a107); + a107 = (a018 * a125); + a091 = (a091 - a107); + a124 = (a124 + a091); + a091 = (-a124); + output_vec[106] = a091; + a135 = (a135 / a008); + a063 = (a063 * a067); + a074 = (a074 * a143); + a063 = (a063 - a074); + a053 = (a053 * a141); + a063 = (a063 - a053); + a044 = (a044 * a140); + a063 = (a063 - a044); + a036 = (a036 * a139); + a063 = (a063 - a036); + a029 = (a029 * a138); + a063 = (a063 - a029); + a023 = (a023 * a137); + a063 = (a063 - a023); + a018 = (a018 * a136); + a063 = (a063 - a018); + a135 = (a135 + a063); + a063 = (-a135); + output_vec[107] = a063; + output_vec[108] = a123; + output_vec[109] = a112; + output_vec[110] = a145; + output_vec[111] = a002; + output_vec[112] = a080; + output_vec[113] = a090; + output_vec[114] = a094; + output_vec[115] = a086; + output_vec[116] = a104; + a104 = (1. / a009); + a112 = (a064 * a112); + a122 = (a075 * a122); + a112 = (a112 - a122); + a120 = (a054 * a120); + a112 = (a112 - a120); + a119 = (a045 * a119); + a112 = (a112 - a119); + a118 = (a037 * a118); + a112 = (a112 - a118); + a117 = (a030 * a117); + a112 = (a112 - a117); + a116 = (a024 * a116); + a112 = (a112 - a116); + a115 = (a019 * a115); + a112 = (a112 - a115); + a097 = (a015 * a097); + a112 = (a112 - a097); + a104 = (a104 - a112); + output_vec[117] = a104; + a104 = (a013 / a009); + a112 = (a064 * a121); + a097 = (a075 * a132); + a112 = (a112 - a097); + a097 = (a054 * a130); + a112 = (a112 - a097); + a097 = (a045 * a129); + a112 = (a112 - a097); + a097 = (a037 * a128); + a112 = (a112 - a097); + a097 = (a030 * a127); + a112 = (a112 - a097); + a097 = (a024 * a126); + a112 = (a112 - a097); + a097 = (a019 * a125); + a112 = (a112 - a097); + a097 = (a015 * a124); + a112 = (a112 - a097); + a104 = (a104 + a112); + a112 = (-a104); + output_vec[118] = a112; + a134 = (a134 / a009); + a064 = (a064 * a067); + a075 = (a075 * a143); + a064 = (a064 - a075); + a054 = (a054 * a141); + a064 = (a064 - a054); + a045 = (a045 * a140); + a064 = (a064 - a045); + a037 = (a037 * a139); + a064 = (a064 - a037); + a030 = (a030 * a138); + a064 = (a064 - a030); + a024 = (a024 * a137); + a064 = (a064 - a024); + a019 = (a019 * a136); + a064 = (a064 - a019); + a015 = (a015 * a135); + a064 = (a064 - a015); + a134 = (a134 + a064); + a064 = (-a134); + output_vec[119] = a064; + output_vec[120] = a133; + output_vec[121] = a121; + output_vec[122] = a146; + output_vec[123] = a147; + output_vec[124] = a088; + output_vec[125] = a092; + output_vec[126] = a095; + output_vec[127] = a100; + output_vec[128] = a091; + output_vec[129] = a112; + a112 = (1. / a010); + a121 = (a065 * a121); + a132 = (a076 * a132); + a121 = (a121 - a132); + a130 = (a055 * a130); + a121 = (a121 - a130); + a129 = (a046 * a129); + a121 = (a121 - a129); + a128 = (a038 * a128); + a121 = (a121 - a128); + a127 = (a031 * a127); + a121 = (a121 - a127); + a126 = (a025 * a126); + a121 = (a121 - a126); + a125 = (a020 * a125); + a121 = (a121 - a125); + a124 = (a016 * a124); + a121 = (a121 - a124); + a104 = (a013 * a104); + a121 = (a121 - a104); + a112 = (a112 - a121); + output_vec[130] = a112; + a010 = (a012 / a010); + a065 = (a065 * a067); + a076 = (a076 * a143); + a065 = (a065 - a076); + a055 = (a055 * a141); + a065 = (a065 - a055); + a046 = (a046 * a140); + a065 = (a065 - a046); + a038 = (a038 * a139); + a065 = (a065 - a038); + a031 = (a031 * a138); + a065 = (a065 - a031); + a025 = (a025 * a137); + a065 = (a065 - a025); + a020 = (a020 * a136); + a065 = (a065 - a020); + a016 = (a016 * a135); + a065 = (a065 - a016); + a013 = (a013 * a134); + a065 = (a065 - a013); + a010 = (a010 + a065); + a065 = (-a010); + output_vec[131] = a065; + output_vec[132] = a000; + output_vec[133] = a067; + output_vec[134] = a057; + output_vec[135] = a058; + output_vec[136] = a059; + output_vec[137] = a060; + output_vec[138] = a061; + output_vec[139] = a062; + output_vec[140] = a063; + output_vec[141] = a064; + output_vec[142] = a065; + a011 = (1. / a011); + a066 = (a066 * a067); + a077 = (a077 * a143); + a066 = (a066 - a077); + a056 = (a056 * a141); + a066 = (a066 - a056); + a047 = (a047 * a140); + a066 = (a066 - a047); + a039 = (a039 * a139); + a066 = (a066 - a039); + a032 = (a032 * a138); + a066 = (a066 - a032); + a026 = (a026 * a137); + a066 = (a066 - a026); + a021 = (a021 * a136); + a066 = (a066 - a021); + a017 = (a017 * a135); + a066 = (a066 - a017); + a014 = (a014 * a134); + a066 = (a066 - a014); + a012 = (a012 * a010); + a066 = (a066 - a012); + a011 = (a011 - a066); + output_vec[143] = a011; + } + }; + } // namespace internal +} // namespace pinocchio + +#endif // ifndef __pinocchio_math_details_matrix_inversion_12x12_hpp__ diff --git a/include/pinocchio/math/details/matrix-inverse-1x1.hpp b/include/pinocchio/math/details/matrix-inverse-1x1.hpp new file mode 100644 index 0000000000..4d6185cf32 --- /dev/null +++ b/include/pinocchio/math/details/matrix-inverse-1x1.hpp @@ -0,0 +1,38 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_math_details_matrix_inversion_1x1_hpp__ +#define __pinocchio_math_details_matrix_inversion_1x1_hpp__ + +#include "pinocchio/math/matrix.hpp" + +namespace pinocchio +{ + namespace internal + { + template<> + struct MatrixInversionCodeGeneratedImpl<1> + { + template + static void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse_) + { + typedef typename M1::Scalar Scalar; + + assert(is_symmetric(matrix, math::sqrt(dummy_precision()))); + + const auto & input_vec = matrix.reshaped(); + auto & matrix_inverse = matrix_inverse_.const_cast_derived(); + auto output_vec = matrix_inverse.reshaped(); + + Scalar a0; + a0 = input_vec[0]; + a0 = (1. / a0); + output_vec[0] = a0; + } + }; + } // namespace internal +} // namespace pinocchio + +#endif // ifndef __pinocchio_math_details_matrix_inversion_1x1_hpp__ diff --git a/include/pinocchio/math/details/matrix-inverse-2x2.hpp b/include/pinocchio/math/details/matrix-inverse-2x2.hpp new file mode 100644 index 0000000000..3662c75612 --- /dev/null +++ b/include/pinocchio/math/details/matrix-inverse-2x2.hpp @@ -0,0 +1,52 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_math_details_matrix_inversion_2x2_hpp__ +#define __pinocchio_math_details_matrix_inversion_2x2_hpp__ + +#include "pinocchio/math/matrix.hpp" + +namespace pinocchio +{ + namespace internal + { + template<> + struct MatrixInversionCodeGeneratedImpl<2> + { + template + static void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse_) + { + typedef typename M1::Scalar Scalar; + + assert(is_symmetric(matrix, math::sqrt(dummy_precision()))); + + const auto & input_vec = matrix.reshaped(); + auto & matrix_inverse = matrix_inverse_.const_cast_derived(); + auto output_vec = matrix_inverse.reshaped(); + + Scalar a0, a1, a2, a3; + a0 = input_vec[0]; + a1 = input_vec[3]; + a2 = input_vec[2]; + a2 = (a2 / a1); + a3 = math::square(a2); + a3 = (a1 * a3); + a0 = (a0 - a3); + a3 = (1. / a0); + output_vec[0] = a3; + a0 = (a2 * a3); + a3 = (-a0); + output_vec[1] = a3; + output_vec[2] = a3; + a1 = (1. / a1); + a2 = (a2 * a0); + a1 = (a1 + a2); + output_vec[3] = a1; + } + }; + } // namespace internal +} // namespace pinocchio + +#endif // ifndef __pinocchio_math_details_matrix_inversion_2x2_hpp__ diff --git a/include/pinocchio/math/details/matrix-inverse-3x3.hpp b/include/pinocchio/math/details/matrix-inverse-3x3.hpp new file mode 100644 index 0000000000..56a417c1cf --- /dev/null +++ b/include/pinocchio/math/details/matrix-inverse-3x3.hpp @@ -0,0 +1,82 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_math_details_matrix_inversion_3x3_hpp__ +#define __pinocchio_math_details_matrix_inversion_3x3_hpp__ + +#include "pinocchio/math/matrix.hpp" + +namespace pinocchio +{ + namespace internal + { + template<> + struct MatrixInversionCodeGeneratedImpl<3> + { + template + static void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse_) + { + typedef typename M1::Scalar Scalar; + + assert(is_symmetric(matrix, math::sqrt(dummy_precision()))); + + const auto & input_vec = matrix.reshaped(); + auto & matrix_inverse = matrix_inverse_.const_cast_derived(); + auto output_vec = matrix_inverse.reshaped(); + + Scalar a0, a1, a2, a3, a4, a5, a6, a7, a8; + a0 = input_vec[0]; + a1 = input_vec[4]; + a2 = input_vec[8]; + a3 = input_vec[7]; + a3 = (a3 / a2); + a4 = math::square(a3); + a4 = (a2 * a4); + a1 = (a1 - a4); + a4 = input_vec[3]; + a5 = input_vec[6]; + a6 = (a5 * a3); + a4 = (a4 - a6); + a4 = (a4 / a1); + a6 = math::square(a4); + a6 = (a1 * a6); + a5 = (a5 / a2); + a7 = math::square(a5); + a7 = (a2 * a7); + a6 = (a6 + a7); + a0 = (a0 - a6); + a6 = (1. / a0); + output_vec[0] = a6; + a6 = (a4 / a0); + a7 = (-a6); + output_vec[1] = a7; + a8 = (a4 * a3); + a8 = (a5 - a8); + a8 = (a8 / a0); + a0 = (-a8); + output_vec[2] = a0; + output_vec[3] = a7; + a7 = (1. / a1); + a6 = (a4 * a6); + a7 = (a7 + a6); + output_vec[4] = a7; + a4 = (a4 * a8); + a1 = (a3 / a1); + a4 = (a4 - a1); + output_vec[5] = a4; + output_vec[6] = a0; + output_vec[7] = a4; + a2 = (1. / a2); + a3 = (a3 * a4); + a5 = (a5 * a8); + a3 = (a3 - a5); + a2 = (a2 - a3); + output_vec[8] = a2; + } + }; + } // namespace internal +} // namespace pinocchio + +#endif // ifndef __pinocchio_math_details_matrix_inversion_3x3_hpp__ diff --git a/include/pinocchio/math/details/matrix-inverse-4x4.hpp b/include/pinocchio/math/details/matrix-inverse-4x4.hpp new file mode 100644 index 0000000000..ef9190496a --- /dev/null +++ b/include/pinocchio/math/details/matrix-inverse-4x4.hpp @@ -0,0 +1,136 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_math_details_matrix_inversion_4x4_hpp__ +#define __pinocchio_math_details_matrix_inversion_4x4_hpp__ + +#include "pinocchio/math/matrix.hpp" + +namespace pinocchio +{ + namespace internal + { + template<> + struct MatrixInversionCodeGeneratedImpl<4> + { + template + static void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse_) + { + typedef typename M1::Scalar Scalar; + + assert(is_symmetric(matrix, math::sqrt(dummy_precision()))); + + const auto & input_vec = matrix.reshaped(); + auto & matrix_inverse = matrix_inverse_.const_cast_derived(); + auto output_vec = matrix_inverse.reshaped(); + + Scalar a00, a01, a02, a03, a04, a05, a06, a07, a08, a09, a10, a11; + Scalar a12, a13, a14, a15, a16; + a00 = input_vec[0]; + a01 = input_vec[5]; + a02 = input_vec[10]; + a03 = input_vec[15]; + a04 = input_vec[14]; + a04 = (a04 / a03); + a05 = math::square(a04); + a05 = (a03 * a05); + a02 = (a02 - a05); + a05 = input_vec[9]; + a06 = input_vec[13]; + a07 = (a06 * a04); + a05 = (a05 - a07); + a05 = (a05 / a02); + a07 = math::square(a05); + a07 = (a02 * a07); + a06 = (a06 / a03); + a08 = math::square(a06); + a08 = (a03 * a08); + a07 = (a07 + a08); + a01 = (a01 - a07); + a07 = input_vec[4]; + a08 = input_vec[8]; + a09 = input_vec[12]; + a10 = (a09 * a04); + a08 = (a08 - a10); + a10 = (a08 * a05); + a11 = (a09 * a06); + a10 = (a10 + a11); + a07 = (a07 - a10); + a07 = (a07 / a01); + a10 = math::square(a07); + a10 = (a01 * a10); + a08 = (a08 / a02); + a11 = math::square(a08); + a11 = (a02 * a11); + a10 = (a10 + a11); + a09 = (a09 / a03); + a11 = math::square(a09); + a11 = (a03 * a11); + a10 = (a10 + a11); + a00 = (a00 - a10); + a10 = (1. / a00); + output_vec[0] = a10; + a10 = (a07 / a00); + a11 = (-a10); + output_vec[1] = a11; + a12 = (a07 * a05); + a12 = (a08 - a12); + a12 = (a12 / a00); + a13 = (-a12); + output_vec[2] = a13; + a14 = (a05 * a04); + a14 = (a06 - a14); + a15 = (a07 * a14); + a16 = (a08 * a04); + a15 = (a15 + a16); + a15 = (a09 - a15); + a15 = (a15 / a00); + a00 = (-a15); + output_vec[3] = a00; + output_vec[4] = a11; + a11 = (1. / a01); + a10 = (a07 * a10); + a11 = (a11 + a10); + output_vec[5] = a11; + a11 = (a07 * a12); + a10 = (a05 / a01); + a11 = (a11 - a10); + output_vec[6] = a11; + a07 = (a07 * a15); + a14 = (a14 / a01); + a07 = (a07 - a14); + output_vec[7] = a07; + output_vec[8] = a13; + output_vec[9] = a11; + a13 = (1. / a02); + a11 = (a05 * a11); + a12 = (a08 * a12); + a11 = (a11 - a12); + a13 = (a13 - a11); + output_vec[10] = a13; + a02 = (a04 / a02); + a05 = (a05 * a07); + a08 = (a08 * a15); + a05 = (a05 - a08); + a02 = (a02 + a05); + a05 = (-a02); + output_vec[11] = a05; + output_vec[12] = a00; + output_vec[13] = a07; + output_vec[14] = a05; + a03 = (1. / a03); + a06 = (a06 * a07); + a09 = (a09 * a15); + a06 = (a06 - a09); + a04 = (a04 * a02); + a06 = (a06 - a04); + a03 = (a03 - a06); + output_vec[15] = a03; + } + }; + } // namespace internal +} // namespace pinocchio + +#endif // ifndef __pinocchio_math_details_matrix_inversion_4x4_hpp__ diff --git a/include/pinocchio/math/details/matrix-inverse-5x5.hpp b/include/pinocchio/math/details/matrix-inverse-5x5.hpp new file mode 100644 index 0000000000..d6da80ad32 --- /dev/null +++ b/include/pinocchio/math/details/matrix-inverse-5x5.hpp @@ -0,0 +1,219 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_math_details_matrix_inversion_5x5_hpp__ +#define __pinocchio_math_details_matrix_inversion_5x5_hpp__ + +#include "pinocchio/math/matrix.hpp" + +namespace pinocchio +{ + namespace internal + { + template<> + struct MatrixInversionCodeGeneratedImpl<5> + { + template + static void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse_) + { + typedef typename M1::Scalar Scalar; + + assert(is_symmetric(matrix, math::sqrt(dummy_precision()))); + + const auto & input_vec = matrix.reshaped(); + auto & matrix_inverse = matrix_inverse_.const_cast_derived(); + auto output_vec = matrix_inverse.reshaped(); + + Scalar a00, a01, a02, a03, a04, a05, a06, a07, a08, a09, a10, a11; + Scalar a12, a13, a14, a15, a16, a17, a18, a19, a20, a21, a22, a23; + Scalar a24, a25; + a00 = input_vec[0]; + a01 = input_vec[6]; + a02 = input_vec[12]; + a03 = input_vec[18]; + a04 = input_vec[24]; + a05 = input_vec[23]; + a05 = (a05 / a04); + a06 = math::square(a05); + a06 = (a04 * a06); + a03 = (a03 - a06); + a06 = input_vec[17]; + a07 = input_vec[22]; + a08 = (a07 * a05); + a06 = (a06 - a08); + a06 = (a06 / a03); + a08 = math::square(a06); + a08 = (a03 * a08); + a07 = (a07 / a04); + a09 = math::square(a07); + a09 = (a04 * a09); + a08 = (a08 + a09); + a02 = (a02 - a08); + a08 = input_vec[11]; + a09 = input_vec[16]; + a10 = input_vec[21]; + a11 = (a10 * a05); + a09 = (a09 - a11); + a11 = (a09 * a06); + a12 = (a10 * a07); + a11 = (a11 + a12); + a08 = (a08 - a11); + a08 = (a08 / a02); + a11 = math::square(a08); + a11 = (a02 * a11); + a09 = (a09 / a03); + a12 = math::square(a09); + a12 = (a03 * a12); + a11 = (a11 + a12); + a10 = (a10 / a04); + a12 = math::square(a10); + a12 = (a04 * a12); + a11 = (a11 + a12); + a01 = (a01 - a11); + a11 = input_vec[5]; + a12 = input_vec[10]; + a13 = input_vec[15]; + a14 = input_vec[20]; + a15 = (a14 * a05); + a13 = (a13 - a15); + a15 = (a13 * a06); + a16 = (a14 * a07); + a15 = (a15 + a16); + a12 = (a12 - a15); + a15 = (a12 * a08); + a16 = (a13 * a09); + a15 = (a15 + a16); + a16 = (a14 * a10); + a15 = (a15 + a16); + a11 = (a11 - a15); + a11 = (a11 / a01); + a15 = math::square(a11); + a15 = (a01 * a15); + a12 = (a12 / a02); + a16 = math::square(a12); + a16 = (a02 * a16); + a15 = (a15 + a16); + a13 = (a13 / a03); + a16 = math::square(a13); + a16 = (a03 * a16); + a15 = (a15 + a16); + a14 = (a14 / a04); + a16 = math::square(a14); + a16 = (a04 * a16); + a15 = (a15 + a16); + a00 = (a00 - a15); + a15 = (1. / a00); + output_vec[0] = a15; + a15 = (a11 / a00); + a16 = (-a15); + output_vec[1] = a16; + a17 = (a11 * a08); + a17 = (a12 - a17); + a17 = (a17 / a00); + a18 = (-a17); + output_vec[2] = a18; + a19 = (a08 * a06); + a19 = (a09 - a19); + a20 = (a11 * a19); + a21 = (a12 * a06); + a20 = (a20 + a21); + a20 = (a13 - a20); + a20 = (a20 / a00); + a21 = (-a20); + output_vec[3] = a21; + a22 = (a06 * a05); + a22 = (a07 - a22); + a23 = (a08 * a22); + a24 = (a09 * a05); + a23 = (a23 + a24); + a23 = (a10 - a23); + a24 = (a11 * a23); + a25 = (a12 * a22); + a24 = (a24 + a25); + a25 = (a13 * a05); + a24 = (a24 + a25); + a24 = (a14 - a24); + a24 = (a24 / a00); + a00 = (-a24); + output_vec[4] = a00; + output_vec[5] = a16; + a16 = (1. / a01); + a15 = (a11 * a15); + a16 = (a16 + a15); + output_vec[6] = a16; + a16 = (a11 * a17); + a15 = (a08 / a01); + a16 = (a16 - a15); + output_vec[7] = a16; + a15 = (a11 * a20); + a19 = (a19 / a01); + a15 = (a15 - a19); + output_vec[8] = a15; + a11 = (a11 * a24); + a23 = (a23 / a01); + a11 = (a11 - a23); + output_vec[9] = a11; + output_vec[10] = a18; + output_vec[11] = a16; + a18 = (1. / a02); + a16 = (a08 * a16); + a17 = (a12 * a17); + a16 = (a16 - a17); + a18 = (a18 - a16); + output_vec[12] = a18; + a18 = (a06 / a02); + a16 = (a08 * a15); + a17 = (a12 * a20); + a16 = (a16 - a17); + a18 = (a18 + a16); + a16 = (-a18); + output_vec[13] = a16; + a22 = (a22 / a02); + a08 = (a08 * a11); + a12 = (a12 * a24); + a08 = (a08 - a12); + a22 = (a22 + a08); + a08 = (-a22); + output_vec[14] = a08; + output_vec[15] = a21; + output_vec[16] = a15; + output_vec[17] = a16; + a16 = (1. / a03); + a15 = (a09 * a15); + a20 = (a13 * a20); + a15 = (a15 - a20); + a18 = (a06 * a18); + a15 = (a15 - a18); + a16 = (a16 - a15); + output_vec[18] = a16; + a03 = (a05 / a03); + a09 = (a09 * a11); + a13 = (a13 * a24); + a09 = (a09 - a13); + a06 = (a06 * a22); + a09 = (a09 - a06); + a03 = (a03 + a09); + a09 = (-a03); + output_vec[19] = a09; + output_vec[20] = a00; + output_vec[21] = a11; + output_vec[22] = a08; + output_vec[23] = a09; + a04 = (1. / a04); + a10 = (a10 * a11); + a14 = (a14 * a24); + a10 = (a10 - a14); + a07 = (a07 * a22); + a10 = (a10 - a07); + a05 = (a05 * a03); + a10 = (a10 - a05); + a04 = (a04 - a10); + output_vec[24] = a04; + } + }; + } // namespace internal +} // namespace pinocchio + +#endif // ifndef __pinocchio_math_details_matrix_inversion_5x5_hpp__ diff --git a/include/pinocchio/math/details/matrix-inverse-6x6.hpp b/include/pinocchio/math/details/matrix-inverse-6x6.hpp new file mode 100644 index 0000000000..c01aa51248 --- /dev/null +++ b/include/pinocchio/math/details/matrix-inverse-6x6.hpp @@ -0,0 +1,337 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_math_details_matrix_inversion_6x6_hpp__ +#define __pinocchio_math_details_matrix_inversion_6x6_hpp__ + +#include "pinocchio/math/matrix.hpp" + +namespace pinocchio +{ + namespace internal + { + template<> + struct MatrixInversionCodeGeneratedImpl<6> + { + template + static void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse_) + { + typedef typename M1::Scalar Scalar; + + assert(is_symmetric(matrix, math::sqrt(dummy_precision()))); + + const auto & input_vec = matrix.reshaped(); + auto & matrix_inverse = matrix_inverse_.const_cast_derived(); + auto output_vec = matrix_inverse.reshaped(); + + Scalar a00, a01, a02, a03, a04, a05, a06, a07, a08, a09, a10, a11; + Scalar a12, a13, a14, a15, a16, a17, a18, a19, a20, a21, a22, a23; + Scalar a24, a25, a26, a27, a28, a29, a30, a31, a32, a33, a34, a35; + Scalar a36; + a00 = input_vec[0]; + a01 = input_vec[7]; + a02 = input_vec[14]; + a03 = input_vec[21]; + a04 = input_vec[28]; + a05 = input_vec[35]; + a06 = input_vec[34]; + a06 = (a06 / a05); + a07 = math::square(a06); + a07 = (a05 * a07); + a04 = (a04 - a07); + a07 = input_vec[27]; + a08 = input_vec[33]; + a09 = (a08 * a06); + a07 = (a07 - a09); + a07 = (a07 / a04); + a09 = math::square(a07); + a09 = (a04 * a09); + a08 = (a08 / a05); + a10 = math::square(a08); + a10 = (a05 * a10); + a09 = (a09 + a10); + a03 = (a03 - a09); + a09 = input_vec[20]; + a10 = input_vec[26]; + a11 = input_vec[32]; + a12 = (a11 * a06); + a10 = (a10 - a12); + a12 = (a10 * a07); + a13 = (a11 * a08); + a12 = (a12 + a13); + a09 = (a09 - a12); + a09 = (a09 / a03); + a12 = math::square(a09); + a12 = (a03 * a12); + a10 = (a10 / a04); + a13 = math::square(a10); + a13 = (a04 * a13); + a12 = (a12 + a13); + a11 = (a11 / a05); + a13 = math::square(a11); + a13 = (a05 * a13); + a12 = (a12 + a13); + a02 = (a02 - a12); + a12 = input_vec[13]; + a13 = input_vec[19]; + a14 = input_vec[25]; + a15 = input_vec[31]; + a16 = (a15 * a06); + a14 = (a14 - a16); + a16 = (a14 * a07); + a17 = (a15 * a08); + a16 = (a16 + a17); + a13 = (a13 - a16); + a16 = (a13 * a09); + a17 = (a14 * a10); + a16 = (a16 + a17); + a17 = (a15 * a11); + a16 = (a16 + a17); + a12 = (a12 - a16); + a12 = (a12 / a02); + a16 = math::square(a12); + a16 = (a02 * a16); + a13 = (a13 / a03); + a17 = math::square(a13); + a17 = (a03 * a17); + a16 = (a16 + a17); + a14 = (a14 / a04); + a17 = math::square(a14); + a17 = (a04 * a17); + a16 = (a16 + a17); + a15 = (a15 / a05); + a17 = math::square(a15); + a17 = (a05 * a17); + a16 = (a16 + a17); + a01 = (a01 - a16); + a16 = input_vec[6]; + a17 = input_vec[12]; + a18 = input_vec[18]; + a19 = input_vec[24]; + a20 = input_vec[30]; + a21 = (a20 * a06); + a19 = (a19 - a21); + a21 = (a19 * a07); + a22 = (a20 * a08); + a21 = (a21 + a22); + a18 = (a18 - a21); + a21 = (a18 * a09); + a22 = (a19 * a10); + a21 = (a21 + a22); + a22 = (a20 * a11); + a21 = (a21 + a22); + a17 = (a17 - a21); + a21 = (a17 * a12); + a22 = (a18 * a13); + a21 = (a21 + a22); + a22 = (a19 * a14); + a21 = (a21 + a22); + a22 = (a20 * a15); + a21 = (a21 + a22); + a16 = (a16 - a21); + a16 = (a16 / a01); + a21 = math::square(a16); + a21 = (a01 * a21); + a17 = (a17 / a02); + a22 = math::square(a17); + a22 = (a02 * a22); + a21 = (a21 + a22); + a18 = (a18 / a03); + a22 = math::square(a18); + a22 = (a03 * a22); + a21 = (a21 + a22); + a19 = (a19 / a04); + a22 = math::square(a19); + a22 = (a04 * a22); + a21 = (a21 + a22); + a20 = (a20 / a05); + a22 = math::square(a20); + a22 = (a05 * a22); + a21 = (a21 + a22); + a00 = (a00 - a21); + a21 = (1. / a00); + output_vec[0] = a21; + a21 = (a16 / a00); + a22 = (-a21); + output_vec[1] = a22; + a23 = (a16 * a12); + a23 = (a17 - a23); + a23 = (a23 / a00); + a24 = (-a23); + output_vec[2] = a24; + a25 = (a12 * a09); + a25 = (a13 - a25); + a26 = (a16 * a25); + a27 = (a17 * a09); + a26 = (a26 + a27); + a26 = (a18 - a26); + a26 = (a26 / a00); + a27 = (-a26); + output_vec[3] = a27; + a28 = (a09 * a07); + a28 = (a10 - a28); + a29 = (a12 * a28); + a30 = (a13 * a07); + a29 = (a29 + a30); + a29 = (a14 - a29); + a30 = (a16 * a29); + a31 = (a17 * a28); + a30 = (a30 + a31); + a31 = (a18 * a07); + a30 = (a30 + a31); + a30 = (a19 - a30); + a30 = (a30 / a00); + a31 = (-a30); + output_vec[4] = a31; + a32 = (a07 * a06); + a32 = (a08 - a32); + a33 = (a09 * a32); + a34 = (a10 * a06); + a33 = (a33 + a34); + a33 = (a11 - a33); + a34 = (a12 * a33); + a35 = (a13 * a32); + a34 = (a34 + a35); + a35 = (a14 * a06); + a34 = (a34 + a35); + a34 = (a15 - a34); + a35 = (a16 * a34); + a36 = (a17 * a33); + a35 = (a35 + a36); + a36 = (a18 * a32); + a35 = (a35 + a36); + a36 = (a19 * a06); + a35 = (a35 + a36); + a35 = (a20 - a35); + a35 = (a35 / a00); + a00 = (-a35); + output_vec[5] = a00; + output_vec[6] = a22; + a22 = (1. / a01); + a21 = (a16 * a21); + a22 = (a22 + a21); + output_vec[7] = a22; + a22 = (a16 * a23); + a21 = (a12 / a01); + a22 = (a22 - a21); + output_vec[8] = a22; + a21 = (a16 * a26); + a25 = (a25 / a01); + a21 = (a21 - a25); + output_vec[9] = a21; + a25 = (a16 * a30); + a29 = (a29 / a01); + a25 = (a25 - a29); + output_vec[10] = a25; + a16 = (a16 * a35); + a34 = (a34 / a01); + a16 = (a16 - a34); + output_vec[11] = a16; + output_vec[12] = a24; + output_vec[13] = a22; + a24 = (1. / a02); + a22 = (a12 * a22); + a23 = (a17 * a23); + a22 = (a22 - a23); + a24 = (a24 - a22); + output_vec[14] = a24; + a24 = (a09 / a02); + a22 = (a12 * a21); + a23 = (a17 * a26); + a22 = (a22 - a23); + a24 = (a24 + a22); + a22 = (-a24); + output_vec[15] = a22; + a28 = (a28 / a02); + a23 = (a12 * a25); + a34 = (a17 * a30); + a23 = (a23 - a34); + a28 = (a28 + a23); + a23 = (-a28); + output_vec[16] = a23; + a33 = (a33 / a02); + a12 = (a12 * a16); + a17 = (a17 * a35); + a12 = (a12 - a17); + a33 = (a33 + a12); + a12 = (-a33); + output_vec[17] = a12; + output_vec[18] = a27; + output_vec[19] = a21; + output_vec[20] = a22; + a22 = (1. / a03); + a21 = (a13 * a21); + a26 = (a18 * a26); + a21 = (a21 - a26); + a24 = (a09 * a24); + a21 = (a21 - a24); + a22 = (a22 - a21); + output_vec[21] = a22; + a22 = (a07 / a03); + a21 = (a13 * a25); + a24 = (a18 * a30); + a21 = (a21 - a24); + a24 = (a09 * a28); + a21 = (a21 - a24); + a22 = (a22 + a21); + a21 = (-a22); + output_vec[22] = a21; + a32 = (a32 / a03); + a13 = (a13 * a16); + a18 = (a18 * a35); + a13 = (a13 - a18); + a09 = (a09 * a33); + a13 = (a13 - a09); + a32 = (a32 + a13); + a13 = (-a32); + output_vec[23] = a13; + output_vec[24] = a31; + output_vec[25] = a25; + output_vec[26] = a23; + output_vec[27] = a21; + a21 = (1. / a04); + a25 = (a14 * a25); + a30 = (a19 * a30); + a25 = (a25 - a30); + a28 = (a10 * a28); + a25 = (a25 - a28); + a22 = (a07 * a22); + a25 = (a25 - a22); + a21 = (a21 - a25); + output_vec[28] = a21; + a04 = (a06 / a04); + a14 = (a14 * a16); + a19 = (a19 * a35); + a14 = (a14 - a19); + a10 = (a10 * a33); + a14 = (a14 - a10); + a07 = (a07 * a32); + a14 = (a14 - a07); + a04 = (a04 + a14); + a14 = (-a04); + output_vec[29] = a14; + output_vec[30] = a00; + output_vec[31] = a16; + output_vec[32] = a12; + output_vec[33] = a13; + output_vec[34] = a14; + a05 = (1. / a05); + a15 = (a15 * a16); + a20 = (a20 * a35); + a15 = (a15 - a20); + a11 = (a11 * a33); + a15 = (a15 - a11); + a08 = (a08 * a32); + a15 = (a15 - a08); + a06 = (a06 * a04); + a15 = (a15 - a06); + a05 = (a05 - a15); + output_vec[35] = a05; + } + }; + } // namespace internal +} // namespace pinocchio + +#endif // ifndef __pinocchio_math_details_matrix_inversion_6x6_hpp__ diff --git a/include/pinocchio/math/details/matrix-inverse-7x7.hpp b/include/pinocchio/math/details/matrix-inverse-7x7.hpp new file mode 100644 index 0000000000..a1ccd69719 --- /dev/null +++ b/include/pinocchio/math/details/matrix-inverse-7x7.hpp @@ -0,0 +1,496 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_math_details_matrix_inversion_7x7_hpp__ +#define __pinocchio_math_details_matrix_inversion_7x7_hpp__ + +#include "pinocchio/math/matrix.hpp" + +namespace pinocchio +{ + namespace internal + { + template<> + struct MatrixInversionCodeGeneratedImpl<7> + { + template + static void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse_) + { + typedef typename M1::Scalar Scalar; + + assert(is_symmetric(matrix, math::sqrt(dummy_precision()))); + + const auto & input_vec = matrix.reshaped(); + auto & matrix_inverse = matrix_inverse_.const_cast_derived(); + auto output_vec = matrix_inverse.reshaped(); + + Scalar a00, a01, a02, a03, a04, a05, a06, a07, a08, a09, a10, a11; + Scalar a12, a13, a14, a15, a16, a17, a18, a19, a20, a21, a22, a23; + Scalar a24, a25, a26, a27, a28, a29, a30, a31, a32, a33, a34, a35; + Scalar a36, a37, a38, a39, a40, a41, a42, a43, a44, a45, a46, a47; + Scalar a48, a49; + a00 = input_vec[0]; + a01 = input_vec[8]; + a02 = input_vec[16]; + a03 = input_vec[24]; + a04 = input_vec[32]; + a05 = input_vec[40]; + a06 = input_vec[48]; + a07 = input_vec[47]; + a07 = (a07 / a06); + a08 = math::square(a07); + a08 = (a06 * a08); + a05 = (a05 - a08); + a08 = input_vec[39]; + a09 = input_vec[46]; + a10 = (a09 * a07); + a08 = (a08 - a10); + a08 = (a08 / a05); + a10 = math::square(a08); + a10 = (a05 * a10); + a09 = (a09 / a06); + a11 = math::square(a09); + a11 = (a06 * a11); + a10 = (a10 + a11); + a04 = (a04 - a10); + a10 = input_vec[31]; + a11 = input_vec[38]; + a12 = input_vec[45]; + a13 = (a12 * a07); + a11 = (a11 - a13); + a13 = (a11 * a08); + a14 = (a12 * a09); + a13 = (a13 + a14); + a10 = (a10 - a13); + a10 = (a10 / a04); + a13 = math::square(a10); + a13 = (a04 * a13); + a11 = (a11 / a05); + a14 = math::square(a11); + a14 = (a05 * a14); + a13 = (a13 + a14); + a12 = (a12 / a06); + a14 = math::square(a12); + a14 = (a06 * a14); + a13 = (a13 + a14); + a03 = (a03 - a13); + a13 = input_vec[23]; + a14 = input_vec[30]; + a15 = input_vec[37]; + a16 = input_vec[44]; + a17 = (a16 * a07); + a15 = (a15 - a17); + a17 = (a15 * a08); + a18 = (a16 * a09); + a17 = (a17 + a18); + a14 = (a14 - a17); + a17 = (a14 * a10); + a18 = (a15 * a11); + a17 = (a17 + a18); + a18 = (a16 * a12); + a17 = (a17 + a18); + a13 = (a13 - a17); + a13 = (a13 / a03); + a17 = math::square(a13); + a17 = (a03 * a17); + a14 = (a14 / a04); + a18 = math::square(a14); + a18 = (a04 * a18); + a17 = (a17 + a18); + a15 = (a15 / a05); + a18 = math::square(a15); + a18 = (a05 * a18); + a17 = (a17 + a18); + a16 = (a16 / a06); + a18 = math::square(a16); + a18 = (a06 * a18); + a17 = (a17 + a18); + a02 = (a02 - a17); + a17 = input_vec[15]; + a18 = input_vec[22]; + a19 = input_vec[29]; + a20 = input_vec[36]; + a21 = input_vec[43]; + a22 = (a21 * a07); + a20 = (a20 - a22); + a22 = (a20 * a08); + a23 = (a21 * a09); + a22 = (a22 + a23); + a19 = (a19 - a22); + a22 = (a19 * a10); + a23 = (a20 * a11); + a22 = (a22 + a23); + a23 = (a21 * a12); + a22 = (a22 + a23); + a18 = (a18 - a22); + a22 = (a18 * a13); + a23 = (a19 * a14); + a22 = (a22 + a23); + a23 = (a20 * a15); + a22 = (a22 + a23); + a23 = (a21 * a16); + a22 = (a22 + a23); + a17 = (a17 - a22); + a17 = (a17 / a02); + a22 = math::square(a17); + a22 = (a02 * a22); + a18 = (a18 / a03); + a23 = math::square(a18); + a23 = (a03 * a23); + a22 = (a22 + a23); + a19 = (a19 / a04); + a23 = math::square(a19); + a23 = (a04 * a23); + a22 = (a22 + a23); + a20 = (a20 / a05); + a23 = math::square(a20); + a23 = (a05 * a23); + a22 = (a22 + a23); + a21 = (a21 / a06); + a23 = math::square(a21); + a23 = (a06 * a23); + a22 = (a22 + a23); + a01 = (a01 - a22); + a22 = input_vec[7]; + a23 = input_vec[14]; + a24 = input_vec[21]; + a25 = input_vec[28]; + a26 = input_vec[35]; + a27 = input_vec[42]; + a28 = (a27 * a07); + a26 = (a26 - a28); + a28 = (a26 * a08); + a29 = (a27 * a09); + a28 = (a28 + a29); + a25 = (a25 - a28); + a28 = (a25 * a10); + a29 = (a26 * a11); + a28 = (a28 + a29); + a29 = (a27 * a12); + a28 = (a28 + a29); + a24 = (a24 - a28); + a28 = (a24 * a13); + a29 = (a25 * a14); + a28 = (a28 + a29); + a29 = (a26 * a15); + a28 = (a28 + a29); + a29 = (a27 * a16); + a28 = (a28 + a29); + a23 = (a23 - a28); + a28 = (a23 * a17); + a29 = (a24 * a18); + a28 = (a28 + a29); + a29 = (a25 * a19); + a28 = (a28 + a29); + a29 = (a26 * a20); + a28 = (a28 + a29); + a29 = (a27 * a21); + a28 = (a28 + a29); + a22 = (a22 - a28); + a22 = (a22 / a01); + a28 = math::square(a22); + a28 = (a01 * a28); + a23 = (a23 / a02); + a29 = math::square(a23); + a29 = (a02 * a29); + a28 = (a28 + a29); + a24 = (a24 / a03); + a29 = math::square(a24); + a29 = (a03 * a29); + a28 = (a28 + a29); + a25 = (a25 / a04); + a29 = math::square(a25); + a29 = (a04 * a29); + a28 = (a28 + a29); + a26 = (a26 / a05); + a29 = math::square(a26); + a29 = (a05 * a29); + a28 = (a28 + a29); + a27 = (a27 / a06); + a29 = math::square(a27); + a29 = (a06 * a29); + a28 = (a28 + a29); + a00 = (a00 - a28); + a28 = (1. / a00); + output_vec[0] = a28; + a28 = (a22 / a00); + a29 = (-a28); + output_vec[1] = a29; + a30 = (a22 * a17); + a30 = (a23 - a30); + a30 = (a30 / a00); + a31 = (-a30); + output_vec[2] = a31; + a32 = (a17 * a13); + a32 = (a18 - a32); + a33 = (a22 * a32); + a34 = (a23 * a13); + a33 = (a33 + a34); + a33 = (a24 - a33); + a33 = (a33 / a00); + a34 = (-a33); + output_vec[3] = a34; + a35 = (a13 * a10); + a35 = (a14 - a35); + a36 = (a17 * a35); + a37 = (a18 * a10); + a36 = (a36 + a37); + a36 = (a19 - a36); + a37 = (a22 * a36); + a38 = (a23 * a35); + a37 = (a37 + a38); + a38 = (a24 * a10); + a37 = (a37 + a38); + a37 = (a25 - a37); + a37 = (a37 / a00); + a38 = (-a37); + output_vec[4] = a38; + a39 = (a10 * a08); + a39 = (a11 - a39); + a40 = (a13 * a39); + a41 = (a14 * a08); + a40 = (a40 + a41); + a40 = (a15 - a40); + a41 = (a17 * a40); + a42 = (a18 * a39); + a41 = (a41 + a42); + a42 = (a19 * a08); + a41 = (a41 + a42); + a41 = (a20 - a41); + a42 = (a22 * a41); + a43 = (a23 * a40); + a42 = (a42 + a43); + a43 = (a24 * a39); + a42 = (a42 + a43); + a43 = (a25 * a08); + a42 = (a42 + a43); + a42 = (a26 - a42); + a42 = (a42 / a00); + a43 = (-a42); + output_vec[5] = a43; + a44 = (a08 * a07); + a44 = (a09 - a44); + a45 = (a10 * a44); + a46 = (a11 * a07); + a45 = (a45 + a46); + a45 = (a12 - a45); + a46 = (a13 * a45); + a47 = (a14 * a44); + a46 = (a46 + a47); + a47 = (a15 * a07); + a46 = (a46 + a47); + a46 = (a16 - a46); + a47 = (a17 * a46); + a48 = (a18 * a45); + a47 = (a47 + a48); + a48 = (a19 * a44); + a47 = (a47 + a48); + a48 = (a20 * a07); + a47 = (a47 + a48); + a47 = (a21 - a47); + a48 = (a22 * a47); + a49 = (a23 * a46); + a48 = (a48 + a49); + a49 = (a24 * a45); + a48 = (a48 + a49); + a49 = (a25 * a44); + a48 = (a48 + a49); + a49 = (a26 * a07); + a48 = (a48 + a49); + a48 = (a27 - a48); + a48 = (a48 / a00); + a00 = (-a48); + output_vec[6] = a00; + output_vec[7] = a29; + a29 = (1. / a01); + a28 = (a22 * a28); + a29 = (a29 + a28); + output_vec[8] = a29; + a29 = (a22 * a30); + a28 = (a17 / a01); + a29 = (a29 - a28); + output_vec[9] = a29; + a28 = (a22 * a33); + a32 = (a32 / a01); + a28 = (a28 - a32); + output_vec[10] = a28; + a32 = (a22 * a37); + a36 = (a36 / a01); + a32 = (a32 - a36); + output_vec[11] = a32; + a36 = (a22 * a42); + a41 = (a41 / a01); + a36 = (a36 - a41); + output_vec[12] = a36; + a22 = (a22 * a48); + a47 = (a47 / a01); + a22 = (a22 - a47); + output_vec[13] = a22; + output_vec[14] = a31; + output_vec[15] = a29; + a31 = (1. / a02); + a29 = (a17 * a29); + a30 = (a23 * a30); + a29 = (a29 - a30); + a31 = (a31 - a29); + output_vec[16] = a31; + a31 = (a13 / a02); + a29 = (a17 * a28); + a30 = (a23 * a33); + a29 = (a29 - a30); + a31 = (a31 + a29); + a29 = (-a31); + output_vec[17] = a29; + a35 = (a35 / a02); + a30 = (a17 * a32); + a47 = (a23 * a37); + a30 = (a30 - a47); + a35 = (a35 + a30); + a30 = (-a35); + output_vec[18] = a30; + a40 = (a40 / a02); + a47 = (a17 * a36); + a01 = (a23 * a42); + a47 = (a47 - a01); + a40 = (a40 + a47); + a47 = (-a40); + output_vec[19] = a47; + a46 = (a46 / a02); + a17 = (a17 * a22); + a23 = (a23 * a48); + a17 = (a17 - a23); + a46 = (a46 + a17); + a17 = (-a46); + output_vec[20] = a17; + output_vec[21] = a34; + output_vec[22] = a28; + output_vec[23] = a29; + a29 = (1. / a03); + a28 = (a18 * a28); + a33 = (a24 * a33); + a28 = (a28 - a33); + a31 = (a13 * a31); + a28 = (a28 - a31); + a29 = (a29 - a28); + output_vec[24] = a29; + a29 = (a10 / a03); + a28 = (a18 * a32); + a31 = (a24 * a37); + a28 = (a28 - a31); + a31 = (a13 * a35); + a28 = (a28 - a31); + a29 = (a29 + a28); + a28 = (-a29); + output_vec[25] = a28; + a39 = (a39 / a03); + a31 = (a18 * a36); + a33 = (a24 * a42); + a31 = (a31 - a33); + a33 = (a13 * a40); + a31 = (a31 - a33); + a39 = (a39 + a31); + a31 = (-a39); + output_vec[26] = a31; + a45 = (a45 / a03); + a18 = (a18 * a22); + a24 = (a24 * a48); + a18 = (a18 - a24); + a13 = (a13 * a46); + a18 = (a18 - a13); + a45 = (a45 + a18); + a18 = (-a45); + output_vec[27] = a18; + output_vec[28] = a38; + output_vec[29] = a32; + output_vec[30] = a30; + output_vec[31] = a28; + a28 = (1. / a04); + a32 = (a19 * a32); + a37 = (a25 * a37); + a32 = (a32 - a37); + a35 = (a14 * a35); + a32 = (a32 - a35); + a29 = (a10 * a29); + a32 = (a32 - a29); + a28 = (a28 - a32); + output_vec[32] = a28; + a28 = (a08 / a04); + a32 = (a19 * a36); + a29 = (a25 * a42); + a32 = (a32 - a29); + a29 = (a14 * a40); + a32 = (a32 - a29); + a29 = (a10 * a39); + a32 = (a32 - a29); + a28 = (a28 + a32); + a32 = (-a28); + output_vec[33] = a32; + a44 = (a44 / a04); + a19 = (a19 * a22); + a25 = (a25 * a48); + a19 = (a19 - a25); + a14 = (a14 * a46); + a19 = (a19 - a14); + a10 = (a10 * a45); + a19 = (a19 - a10); + a44 = (a44 + a19); + a19 = (-a44); + output_vec[34] = a19; + output_vec[35] = a43; + output_vec[36] = a36; + output_vec[37] = a47; + output_vec[38] = a31; + output_vec[39] = a32; + a32 = (1. / a05); + a36 = (a20 * a36); + a42 = (a26 * a42); + a36 = (a36 - a42); + a40 = (a15 * a40); + a36 = (a36 - a40); + a39 = (a11 * a39); + a36 = (a36 - a39); + a28 = (a08 * a28); + a36 = (a36 - a28); + a32 = (a32 - a36); + output_vec[40] = a32; + a05 = (a07 / a05); + a20 = (a20 * a22); + a26 = (a26 * a48); + a20 = (a20 - a26); + a15 = (a15 * a46); + a20 = (a20 - a15); + a11 = (a11 * a45); + a20 = (a20 - a11); + a08 = (a08 * a44); + a20 = (a20 - a08); + a05 = (a05 + a20); + a20 = (-a05); + output_vec[41] = a20; + output_vec[42] = a00; + output_vec[43] = a22; + output_vec[44] = a17; + output_vec[45] = a18; + output_vec[46] = a19; + output_vec[47] = a20; + a06 = (1. / a06); + a21 = (a21 * a22); + a27 = (a27 * a48); + a21 = (a21 - a27); + a16 = (a16 * a46); + a21 = (a21 - a16); + a12 = (a12 * a45); + a21 = (a21 - a12); + a09 = (a09 * a44); + a21 = (a21 - a09); + a07 = (a07 * a05); + a21 = (a21 - a07); + a06 = (a06 - a21); + output_vec[48] = a06; + } + }; + } // namespace internal +} // namespace pinocchio + +#endif // ifndef __pinocchio_math_details_matrix_inversion_7x7_hpp__ diff --git a/include/pinocchio/math/details/matrix-inverse-8x8.hpp b/include/pinocchio/math/details/matrix-inverse-8x8.hpp new file mode 100644 index 0000000000..f34d4a46ab --- /dev/null +++ b/include/pinocchio/math/details/matrix-inverse-8x8.hpp @@ -0,0 +1,702 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_math_details_matrix_inversion_8x8_hpp__ +#define __pinocchio_math_details_matrix_inversion_8x8_hpp__ + +#include "pinocchio/math/matrix.hpp" + +namespace pinocchio +{ + namespace internal + { + template<> + struct MatrixInversionCodeGeneratedImpl<8> + { + template + static void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse_) + { + typedef typename M1::Scalar Scalar; + + assert(is_symmetric(matrix, math::sqrt(dummy_precision()))); + + const auto & input_vec = matrix.reshaped(); + auto & matrix_inverse = matrix_inverse_.const_cast_derived(); + auto output_vec = matrix_inverse.reshaped(); + + Scalar a00, a01, a02, a03, a04, a05, a06, a07, a08, a09, a10, a11; + Scalar a12, a13, a14, a15, a16, a17, a18, a19, a20, a21, a22, a23; + Scalar a24, a25, a26, a27, a28, a29, a30, a31, a32, a33, a34, a35; + Scalar a36, a37, a38, a39, a40, a41, a42, a43, a44, a45, a46, a47; + Scalar a48, a49, a50, a51, a52, a53, a54, a55, a56, a57, a58, a59; + Scalar a60, a61, a62, a63, a64; + a00 = input_vec[0]; + a01 = input_vec[9]; + a02 = input_vec[18]; + a03 = input_vec[27]; + a04 = input_vec[36]; + a05 = input_vec[45]; + a06 = input_vec[54]; + a07 = input_vec[63]; + a08 = input_vec[62]; + a08 = (a08 / a07); + a09 = math::square(a08); + a09 = (a07 * a09); + a06 = (a06 - a09); + a09 = input_vec[53]; + a10 = input_vec[61]; + a11 = (a10 * a08); + a09 = (a09 - a11); + a09 = (a09 / a06); + a11 = math::square(a09); + a11 = (a06 * a11); + a10 = (a10 / a07); + a12 = math::square(a10); + a12 = (a07 * a12); + a11 = (a11 + a12); + a05 = (a05 - a11); + a11 = input_vec[44]; + a12 = input_vec[52]; + a13 = input_vec[60]; + a14 = (a13 * a08); + a12 = (a12 - a14); + a14 = (a12 * a09); + a15 = (a13 * a10); + a14 = (a14 + a15); + a11 = (a11 - a14); + a11 = (a11 / a05); + a14 = math::square(a11); + a14 = (a05 * a14); + a12 = (a12 / a06); + a15 = math::square(a12); + a15 = (a06 * a15); + a14 = (a14 + a15); + a13 = (a13 / a07); + a15 = math::square(a13); + a15 = (a07 * a15); + a14 = (a14 + a15); + a04 = (a04 - a14); + a14 = input_vec[35]; + a15 = input_vec[43]; + a16 = input_vec[51]; + a17 = input_vec[59]; + a18 = (a17 * a08); + a16 = (a16 - a18); + a18 = (a16 * a09); + a19 = (a17 * a10); + a18 = (a18 + a19); + a15 = (a15 - a18); + a18 = (a15 * a11); + a19 = (a16 * a12); + a18 = (a18 + a19); + a19 = (a17 * a13); + a18 = (a18 + a19); + a14 = (a14 - a18); + a14 = (a14 / a04); + a18 = math::square(a14); + a18 = (a04 * a18); + a15 = (a15 / a05); + a19 = math::square(a15); + a19 = (a05 * a19); + a18 = (a18 + a19); + a16 = (a16 / a06); + a19 = math::square(a16); + a19 = (a06 * a19); + a18 = (a18 + a19); + a17 = (a17 / a07); + a19 = math::square(a17); + a19 = (a07 * a19); + a18 = (a18 + a19); + a03 = (a03 - a18); + a18 = input_vec[26]; + a19 = input_vec[34]; + a20 = input_vec[42]; + a21 = input_vec[50]; + a22 = input_vec[58]; + a23 = (a22 * a08); + a21 = (a21 - a23); + a23 = (a21 * a09); + a24 = (a22 * a10); + a23 = (a23 + a24); + a20 = (a20 - a23); + a23 = (a20 * a11); + a24 = (a21 * a12); + a23 = (a23 + a24); + a24 = (a22 * a13); + a23 = (a23 + a24); + a19 = (a19 - a23); + a23 = (a19 * a14); + a24 = (a20 * a15); + a23 = (a23 + a24); + a24 = (a21 * a16); + a23 = (a23 + a24); + a24 = (a22 * a17); + a23 = (a23 + a24); + a18 = (a18 - a23); + a18 = (a18 / a03); + a23 = math::square(a18); + a23 = (a03 * a23); + a19 = (a19 / a04); + a24 = math::square(a19); + a24 = (a04 * a24); + a23 = (a23 + a24); + a20 = (a20 / a05); + a24 = math::square(a20); + a24 = (a05 * a24); + a23 = (a23 + a24); + a21 = (a21 / a06); + a24 = math::square(a21); + a24 = (a06 * a24); + a23 = (a23 + a24); + a22 = (a22 / a07); + a24 = math::square(a22); + a24 = (a07 * a24); + a23 = (a23 + a24); + a02 = (a02 - a23); + a23 = input_vec[17]; + a24 = input_vec[25]; + a25 = input_vec[33]; + a26 = input_vec[41]; + a27 = input_vec[49]; + a28 = input_vec[57]; + a29 = (a28 * a08); + a27 = (a27 - a29); + a29 = (a27 * a09); + a30 = (a28 * a10); + a29 = (a29 + a30); + a26 = (a26 - a29); + a29 = (a26 * a11); + a30 = (a27 * a12); + a29 = (a29 + a30); + a30 = (a28 * a13); + a29 = (a29 + a30); + a25 = (a25 - a29); + a29 = (a25 * a14); + a30 = (a26 * a15); + a29 = (a29 + a30); + a30 = (a27 * a16); + a29 = (a29 + a30); + a30 = (a28 * a17); + a29 = (a29 + a30); + a24 = (a24 - a29); + a29 = (a24 * a18); + a30 = (a25 * a19); + a29 = (a29 + a30); + a30 = (a26 * a20); + a29 = (a29 + a30); + a30 = (a27 * a21); + a29 = (a29 + a30); + a30 = (a28 * a22); + a29 = (a29 + a30); + a23 = (a23 - a29); + a23 = (a23 / a02); + a29 = math::square(a23); + a29 = (a02 * a29); + a24 = (a24 / a03); + a30 = math::square(a24); + a30 = (a03 * a30); + a29 = (a29 + a30); + a25 = (a25 / a04); + a30 = math::square(a25); + a30 = (a04 * a30); + a29 = (a29 + a30); + a26 = (a26 / a05); + a30 = math::square(a26); + a30 = (a05 * a30); + a29 = (a29 + a30); + a27 = (a27 / a06); + a30 = math::square(a27); + a30 = (a06 * a30); + a29 = (a29 + a30); + a28 = (a28 / a07); + a30 = math::square(a28); + a30 = (a07 * a30); + a29 = (a29 + a30); + a01 = (a01 - a29); + a29 = input_vec[8]; + a30 = input_vec[16]; + a31 = input_vec[24]; + a32 = input_vec[32]; + a33 = input_vec[40]; + a34 = input_vec[48]; + a35 = input_vec[56]; + a36 = (a35 * a08); + a34 = (a34 - a36); + a36 = (a34 * a09); + a37 = (a35 * a10); + a36 = (a36 + a37); + a33 = (a33 - a36); + a36 = (a33 * a11); + a37 = (a34 * a12); + a36 = (a36 + a37); + a37 = (a35 * a13); + a36 = (a36 + a37); + a32 = (a32 - a36); + a36 = (a32 * a14); + a37 = (a33 * a15); + a36 = (a36 + a37); + a37 = (a34 * a16); + a36 = (a36 + a37); + a37 = (a35 * a17); + a36 = (a36 + a37); + a31 = (a31 - a36); + a36 = (a31 * a18); + a37 = (a32 * a19); + a36 = (a36 + a37); + a37 = (a33 * a20); + a36 = (a36 + a37); + a37 = (a34 * a21); + a36 = (a36 + a37); + a37 = (a35 * a22); + a36 = (a36 + a37); + a30 = (a30 - a36); + a36 = (a30 * a23); + a37 = (a31 * a24); + a36 = (a36 + a37); + a37 = (a32 * a25); + a36 = (a36 + a37); + a37 = (a33 * a26); + a36 = (a36 + a37); + a37 = (a34 * a27); + a36 = (a36 + a37); + a37 = (a35 * a28); + a36 = (a36 + a37); + a29 = (a29 - a36); + a29 = (a29 / a01); + a36 = math::square(a29); + a36 = (a01 * a36); + a30 = (a30 / a02); + a37 = math::square(a30); + a37 = (a02 * a37); + a36 = (a36 + a37); + a31 = (a31 / a03); + a37 = math::square(a31); + a37 = (a03 * a37); + a36 = (a36 + a37); + a32 = (a32 / a04); + a37 = math::square(a32); + a37 = (a04 * a37); + a36 = (a36 + a37); + a33 = (a33 / a05); + a37 = math::square(a33); + a37 = (a05 * a37); + a36 = (a36 + a37); + a34 = (a34 / a06); + a37 = math::square(a34); + a37 = (a06 * a37); + a36 = (a36 + a37); + a35 = (a35 / a07); + a37 = math::square(a35); + a37 = (a07 * a37); + a36 = (a36 + a37); + a00 = (a00 - a36); + a36 = (1. / a00); + output_vec[0] = a36; + a36 = (a29 / a00); + a37 = (-a36); + output_vec[1] = a37; + a38 = (a29 * a23); + a38 = (a30 - a38); + a38 = (a38 / a00); + a39 = (-a38); + output_vec[2] = a39; + a40 = (a23 * a18); + a40 = (a24 - a40); + a41 = (a29 * a40); + a42 = (a30 * a18); + a41 = (a41 + a42); + a41 = (a31 - a41); + a41 = (a41 / a00); + a42 = (-a41); + output_vec[3] = a42; + a43 = (a18 * a14); + a43 = (a19 - a43); + a44 = (a23 * a43); + a45 = (a24 * a14); + a44 = (a44 + a45); + a44 = (a25 - a44); + a45 = (a29 * a44); + a46 = (a30 * a43); + a45 = (a45 + a46); + a46 = (a31 * a14); + a45 = (a45 + a46); + a45 = (a32 - a45); + a45 = (a45 / a00); + a46 = (-a45); + output_vec[4] = a46; + a47 = (a14 * a11); + a47 = (a15 - a47); + a48 = (a18 * a47); + a49 = (a19 * a11); + a48 = (a48 + a49); + a48 = (a20 - a48); + a49 = (a23 * a48); + a50 = (a24 * a47); + a49 = (a49 + a50); + a50 = (a25 * a11); + a49 = (a49 + a50); + a49 = (a26 - a49); + a50 = (a29 * a49); + a51 = (a30 * a48); + a50 = (a50 + a51); + a51 = (a31 * a47); + a50 = (a50 + a51); + a51 = (a32 * a11); + a50 = (a50 + a51); + a50 = (a33 - a50); + a50 = (a50 / a00); + a51 = (-a50); + output_vec[5] = a51; + a52 = (a11 * a09); + a52 = (a12 - a52); + a53 = (a14 * a52); + a54 = (a15 * a09); + a53 = (a53 + a54); + a53 = (a16 - a53); + a54 = (a18 * a53); + a55 = (a19 * a52); + a54 = (a54 + a55); + a55 = (a20 * a09); + a54 = (a54 + a55); + a54 = (a21 - a54); + a55 = (a23 * a54); + a56 = (a24 * a53); + a55 = (a55 + a56); + a56 = (a25 * a52); + a55 = (a55 + a56); + a56 = (a26 * a09); + a55 = (a55 + a56); + a55 = (a27 - a55); + a56 = (a29 * a55); + a57 = (a30 * a54); + a56 = (a56 + a57); + a57 = (a31 * a53); + a56 = (a56 + a57); + a57 = (a32 * a52); + a56 = (a56 + a57); + a57 = (a33 * a09); + a56 = (a56 + a57); + a56 = (a34 - a56); + a56 = (a56 / a00); + a57 = (-a56); + output_vec[6] = a57; + a58 = (a09 * a08); + a58 = (a10 - a58); + a59 = (a11 * a58); + a60 = (a12 * a08); + a59 = (a59 + a60); + a59 = (a13 - a59); + a60 = (a14 * a59); + a61 = (a15 * a58); + a60 = (a60 + a61); + a61 = (a16 * a08); + a60 = (a60 + a61); + a60 = (a17 - a60); + a61 = (a18 * a60); + a62 = (a19 * a59); + a61 = (a61 + a62); + a62 = (a20 * a58); + a61 = (a61 + a62); + a62 = (a21 * a08); + a61 = (a61 + a62); + a61 = (a22 - a61); + a62 = (a23 * a61); + a63 = (a24 * a60); + a62 = (a62 + a63); + a63 = (a25 * a59); + a62 = (a62 + a63); + a63 = (a26 * a58); + a62 = (a62 + a63); + a63 = (a27 * a08); + a62 = (a62 + a63); + a62 = (a28 - a62); + a63 = (a29 * a62); + a64 = (a30 * a61); + a63 = (a63 + a64); + a64 = (a31 * a60); + a63 = (a63 + a64); + a64 = (a32 * a59); + a63 = (a63 + a64); + a64 = (a33 * a58); + a63 = (a63 + a64); + a64 = (a34 * a08); + a63 = (a63 + a64); + a63 = (a35 - a63); + a63 = (a63 / a00); + a00 = (-a63); + output_vec[7] = a00; + output_vec[8] = a37; + a37 = (1. / a01); + a36 = (a29 * a36); + a37 = (a37 + a36); + output_vec[9] = a37; + a37 = (a29 * a38); + a36 = (a23 / a01); + a37 = (a37 - a36); + output_vec[10] = a37; + a36 = (a29 * a41); + a40 = (a40 / a01); + a36 = (a36 - a40); + output_vec[11] = a36; + a40 = (a29 * a45); + a44 = (a44 / a01); + a40 = (a40 - a44); + output_vec[12] = a40; + a44 = (a29 * a50); + a49 = (a49 / a01); + a44 = (a44 - a49); + output_vec[13] = a44; + a49 = (a29 * a56); + a55 = (a55 / a01); + a49 = (a49 - a55); + output_vec[14] = a49; + a29 = (a29 * a63); + a62 = (a62 / a01); + a29 = (a29 - a62); + output_vec[15] = a29; + output_vec[16] = a39; + output_vec[17] = a37; + a39 = (1. / a02); + a37 = (a23 * a37); + a38 = (a30 * a38); + a37 = (a37 - a38); + a39 = (a39 - a37); + output_vec[18] = a39; + a39 = (a18 / a02); + a37 = (a23 * a36); + a38 = (a30 * a41); + a37 = (a37 - a38); + a39 = (a39 + a37); + a37 = (-a39); + output_vec[19] = a37; + a43 = (a43 / a02); + a38 = (a23 * a40); + a62 = (a30 * a45); + a38 = (a38 - a62); + a43 = (a43 + a38); + a38 = (-a43); + output_vec[20] = a38; + a48 = (a48 / a02); + a62 = (a23 * a44); + a01 = (a30 * a50); + a62 = (a62 - a01); + a48 = (a48 + a62); + a62 = (-a48); + output_vec[21] = a62; + a54 = (a54 / a02); + a01 = (a23 * a49); + a55 = (a30 * a56); + a01 = (a01 - a55); + a54 = (a54 + a01); + a01 = (-a54); + output_vec[22] = a01; + a61 = (a61 / a02); + a23 = (a23 * a29); + a30 = (a30 * a63); + a23 = (a23 - a30); + a61 = (a61 + a23); + a23 = (-a61); + output_vec[23] = a23; + output_vec[24] = a42; + output_vec[25] = a36; + output_vec[26] = a37; + a37 = (1. / a03); + a36 = (a24 * a36); + a41 = (a31 * a41); + a36 = (a36 - a41); + a39 = (a18 * a39); + a36 = (a36 - a39); + a37 = (a37 - a36); + output_vec[27] = a37; + a37 = (a14 / a03); + a36 = (a24 * a40); + a39 = (a31 * a45); + a36 = (a36 - a39); + a39 = (a18 * a43); + a36 = (a36 - a39); + a37 = (a37 + a36); + a36 = (-a37); + output_vec[28] = a36; + a47 = (a47 / a03); + a39 = (a24 * a44); + a41 = (a31 * a50); + a39 = (a39 - a41); + a41 = (a18 * a48); + a39 = (a39 - a41); + a47 = (a47 + a39); + a39 = (-a47); + output_vec[29] = a39; + a53 = (a53 / a03); + a41 = (a24 * a49); + a42 = (a31 * a56); + a41 = (a41 - a42); + a42 = (a18 * a54); + a41 = (a41 - a42); + a53 = (a53 + a41); + a41 = (-a53); + output_vec[30] = a41; + a60 = (a60 / a03); + a24 = (a24 * a29); + a31 = (a31 * a63); + a24 = (a24 - a31); + a18 = (a18 * a61); + a24 = (a24 - a18); + a60 = (a60 + a24); + a24 = (-a60); + output_vec[31] = a24; + output_vec[32] = a46; + output_vec[33] = a40; + output_vec[34] = a38; + output_vec[35] = a36; + a36 = (1. / a04); + a40 = (a25 * a40); + a45 = (a32 * a45); + a40 = (a40 - a45); + a43 = (a19 * a43); + a40 = (a40 - a43); + a37 = (a14 * a37); + a40 = (a40 - a37); + a36 = (a36 - a40); + output_vec[36] = a36; + a36 = (a11 / a04); + a40 = (a25 * a44); + a37 = (a32 * a50); + a40 = (a40 - a37); + a37 = (a19 * a48); + a40 = (a40 - a37); + a37 = (a14 * a47); + a40 = (a40 - a37); + a36 = (a36 + a40); + a40 = (-a36); + output_vec[37] = a40; + a52 = (a52 / a04); + a37 = (a25 * a49); + a43 = (a32 * a56); + a37 = (a37 - a43); + a43 = (a19 * a54); + a37 = (a37 - a43); + a43 = (a14 * a53); + a37 = (a37 - a43); + a52 = (a52 + a37); + a37 = (-a52); + output_vec[38] = a37; + a59 = (a59 / a04); + a25 = (a25 * a29); + a32 = (a32 * a63); + a25 = (a25 - a32); + a19 = (a19 * a61); + a25 = (a25 - a19); + a14 = (a14 * a60); + a25 = (a25 - a14); + a59 = (a59 + a25); + a25 = (-a59); + output_vec[39] = a25; + output_vec[40] = a51; + output_vec[41] = a44; + output_vec[42] = a62; + output_vec[43] = a39; + output_vec[44] = a40; + a40 = (1. / a05); + a44 = (a26 * a44); + a50 = (a33 * a50); + a44 = (a44 - a50); + a48 = (a20 * a48); + a44 = (a44 - a48); + a47 = (a15 * a47); + a44 = (a44 - a47); + a36 = (a11 * a36); + a44 = (a44 - a36); + a40 = (a40 - a44); + output_vec[45] = a40; + a40 = (a09 / a05); + a44 = (a26 * a49); + a36 = (a33 * a56); + a44 = (a44 - a36); + a36 = (a20 * a54); + a44 = (a44 - a36); + a36 = (a15 * a53); + a44 = (a44 - a36); + a36 = (a11 * a52); + a44 = (a44 - a36); + a40 = (a40 + a44); + a44 = (-a40); + output_vec[46] = a44; + a58 = (a58 / a05); + a26 = (a26 * a29); + a33 = (a33 * a63); + a26 = (a26 - a33); + a20 = (a20 * a61); + a26 = (a26 - a20); + a15 = (a15 * a60); + a26 = (a26 - a15); + a11 = (a11 * a59); + a26 = (a26 - a11); + a58 = (a58 + a26); + a26 = (-a58); + output_vec[47] = a26; + output_vec[48] = a57; + output_vec[49] = a49; + output_vec[50] = a01; + output_vec[51] = a41; + output_vec[52] = a37; + output_vec[53] = a44; + a44 = (1. / a06); + a49 = (a27 * a49); + a56 = (a34 * a56); + a49 = (a49 - a56); + a54 = (a21 * a54); + a49 = (a49 - a54); + a53 = (a16 * a53); + a49 = (a49 - a53); + a52 = (a12 * a52); + a49 = (a49 - a52); + a40 = (a09 * a40); + a49 = (a49 - a40); + a44 = (a44 - a49); + output_vec[54] = a44; + a06 = (a08 / a06); + a27 = (a27 * a29); + a34 = (a34 * a63); + a27 = (a27 - a34); + a21 = (a21 * a61); + a27 = (a27 - a21); + a16 = (a16 * a60); + a27 = (a27 - a16); + a12 = (a12 * a59); + a27 = (a27 - a12); + a09 = (a09 * a58); + a27 = (a27 - a09); + a06 = (a06 + a27); + a27 = (-a06); + output_vec[55] = a27; + output_vec[56] = a00; + output_vec[57] = a29; + output_vec[58] = a23; + output_vec[59] = a24; + output_vec[60] = a25; + output_vec[61] = a26; + output_vec[62] = a27; + a07 = (1. / a07); + a28 = (a28 * a29); + a35 = (a35 * a63); + a28 = (a28 - a35); + a22 = (a22 * a61); + a28 = (a28 - a22); + a17 = (a17 * a60); + a28 = (a28 - a17); + a13 = (a13 * a59); + a28 = (a28 - a13); + a10 = (a10 * a58); + a28 = (a28 - a10); + a08 = (a08 * a06); + a28 = (a28 - a08); + a07 = (a07 - a28); + output_vec[63] = a07; + } + }; + } // namespace internal +} // namespace pinocchio + +#endif // ifndef __pinocchio_math_details_matrix_inversion_8x8_hpp__ diff --git a/include/pinocchio/math/details/matrix-inverse-9x9.hpp b/include/pinocchio/math/details/matrix-inverse-9x9.hpp new file mode 100644 index 0000000000..fcede501d9 --- /dev/null +++ b/include/pinocchio/math/details/matrix-inverse-9x9.hpp @@ -0,0 +1,961 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_math_details_matrix_inversion_9x9_hpp__ +#define __pinocchio_math_details_matrix_inversion_9x9_hpp__ + +#include "pinocchio/math/matrix.hpp" + +namespace pinocchio +{ + namespace internal + { + template<> + struct MatrixInversionCodeGeneratedImpl<9> + { + template + static void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse_) + { + typedef typename M1::Scalar Scalar; + + assert(is_symmetric(matrix, math::sqrt(dummy_precision()))); + + const auto & input_vec = matrix.reshaped(); + auto & matrix_inverse = matrix_inverse_.const_cast_derived(); + auto output_vec = matrix_inverse.reshaped(); + + Scalar a00, a01, a02, a03, a04, a05, a06, a07, a08, a09, a10, a11; + Scalar a12, a13, a14, a15, a16, a17, a18, a19, a20, a21, a22, a23; + Scalar a24, a25, a26, a27, a28, a29, a30, a31, a32, a33, a34, a35; + Scalar a36, a37, a38, a39, a40, a41, a42, a43, a44, a45, a46, a47; + Scalar a48, a49, a50, a51, a52, a53, a54, a55, a56, a57, a58, a59; + Scalar a60, a61, a62, a63, a64, a65, a66, a67, a68, a69, a70, a71; + Scalar a72, a73, a74, a75, a76, a77, a78, a79, a80, a81; + a00 = input_vec[0]; + a01 = input_vec[10]; + a02 = input_vec[20]; + a03 = input_vec[30]; + a04 = input_vec[40]; + a05 = input_vec[50]; + a06 = input_vec[60]; + a07 = input_vec[70]; + a08 = input_vec[80]; + a09 = input_vec[79]; + a09 = (a09 / a08); + a10 = math::square(a09); + a10 = (a08 * a10); + a07 = (a07 - a10); + a10 = input_vec[69]; + a11 = input_vec[78]; + a12 = (a11 * a09); + a10 = (a10 - a12); + a10 = (a10 / a07); + a12 = math::square(a10); + a12 = (a07 * a12); + a11 = (a11 / a08); + a13 = math::square(a11); + a13 = (a08 * a13); + a12 = (a12 + a13); + a06 = (a06 - a12); + a12 = input_vec[59]; + a13 = input_vec[68]; + a14 = input_vec[77]; + a15 = (a14 * a09); + a13 = (a13 - a15); + a15 = (a13 * a10); + a16 = (a14 * a11); + a15 = (a15 + a16); + a12 = (a12 - a15); + a12 = (a12 / a06); + a15 = math::square(a12); + a15 = (a06 * a15); + a13 = (a13 / a07); + a16 = math::square(a13); + a16 = (a07 * a16); + a15 = (a15 + a16); + a14 = (a14 / a08); + a16 = math::square(a14); + a16 = (a08 * a16); + a15 = (a15 + a16); + a05 = (a05 - a15); + a15 = input_vec[49]; + a16 = input_vec[58]; + a17 = input_vec[67]; + a18 = input_vec[76]; + a19 = (a18 * a09); + a17 = (a17 - a19); + a19 = (a17 * a10); + a20 = (a18 * a11); + a19 = (a19 + a20); + a16 = (a16 - a19); + a19 = (a16 * a12); + a20 = (a17 * a13); + a19 = (a19 + a20); + a20 = (a18 * a14); + a19 = (a19 + a20); + a15 = (a15 - a19); + a15 = (a15 / a05); + a19 = math::square(a15); + a19 = (a05 * a19); + a16 = (a16 / a06); + a20 = math::square(a16); + a20 = (a06 * a20); + a19 = (a19 + a20); + a17 = (a17 / a07); + a20 = math::square(a17); + a20 = (a07 * a20); + a19 = (a19 + a20); + a18 = (a18 / a08); + a20 = math::square(a18); + a20 = (a08 * a20); + a19 = (a19 + a20); + a04 = (a04 - a19); + a19 = input_vec[39]; + a20 = input_vec[48]; + a21 = input_vec[57]; + a22 = input_vec[66]; + a23 = input_vec[75]; + a24 = (a23 * a09); + a22 = (a22 - a24); + a24 = (a22 * a10); + a25 = (a23 * a11); + a24 = (a24 + a25); + a21 = (a21 - a24); + a24 = (a21 * a12); + a25 = (a22 * a13); + a24 = (a24 + a25); + a25 = (a23 * a14); + a24 = (a24 + a25); + a20 = (a20 - a24); + a24 = (a20 * a15); + a25 = (a21 * a16); + a24 = (a24 + a25); + a25 = (a22 * a17); + a24 = (a24 + a25); + a25 = (a23 * a18); + a24 = (a24 + a25); + a19 = (a19 - a24); + a19 = (a19 / a04); + a24 = math::square(a19); + a24 = (a04 * a24); + a20 = (a20 / a05); + a25 = math::square(a20); + a25 = (a05 * a25); + a24 = (a24 + a25); + a21 = (a21 / a06); + a25 = math::square(a21); + a25 = (a06 * a25); + a24 = (a24 + a25); + a22 = (a22 / a07); + a25 = math::square(a22); + a25 = (a07 * a25); + a24 = (a24 + a25); + a23 = (a23 / a08); + a25 = math::square(a23); + a25 = (a08 * a25); + a24 = (a24 + a25); + a03 = (a03 - a24); + a24 = input_vec[29]; + a25 = input_vec[38]; + a26 = input_vec[47]; + a27 = input_vec[56]; + a28 = input_vec[65]; + a29 = input_vec[74]; + a30 = (a29 * a09); + a28 = (a28 - a30); + a30 = (a28 * a10); + a31 = (a29 * a11); + a30 = (a30 + a31); + a27 = (a27 - a30); + a30 = (a27 * a12); + a31 = (a28 * a13); + a30 = (a30 + a31); + a31 = (a29 * a14); + a30 = (a30 + a31); + a26 = (a26 - a30); + a30 = (a26 * a15); + a31 = (a27 * a16); + a30 = (a30 + a31); + a31 = (a28 * a17); + a30 = (a30 + a31); + a31 = (a29 * a18); + a30 = (a30 + a31); + a25 = (a25 - a30); + a30 = (a25 * a19); + a31 = (a26 * a20); + a30 = (a30 + a31); + a31 = (a27 * a21); + a30 = (a30 + a31); + a31 = (a28 * a22); + a30 = (a30 + a31); + a31 = (a29 * a23); + a30 = (a30 + a31); + a24 = (a24 - a30); + a24 = (a24 / a03); + a30 = math::square(a24); + a30 = (a03 * a30); + a25 = (a25 / a04); + a31 = math::square(a25); + a31 = (a04 * a31); + a30 = (a30 + a31); + a26 = (a26 / a05); + a31 = math::square(a26); + a31 = (a05 * a31); + a30 = (a30 + a31); + a27 = (a27 / a06); + a31 = math::square(a27); + a31 = (a06 * a31); + a30 = (a30 + a31); + a28 = (a28 / a07); + a31 = math::square(a28); + a31 = (a07 * a31); + a30 = (a30 + a31); + a29 = (a29 / a08); + a31 = math::square(a29); + a31 = (a08 * a31); + a30 = (a30 + a31); + a02 = (a02 - a30); + a30 = input_vec[19]; + a31 = input_vec[28]; + a32 = input_vec[37]; + a33 = input_vec[46]; + a34 = input_vec[55]; + a35 = input_vec[64]; + a36 = input_vec[73]; + a37 = (a36 * a09); + a35 = (a35 - a37); + a37 = (a35 * a10); + a38 = (a36 * a11); + a37 = (a37 + a38); + a34 = (a34 - a37); + a37 = (a34 * a12); + a38 = (a35 * a13); + a37 = (a37 + a38); + a38 = (a36 * a14); + a37 = (a37 + a38); + a33 = (a33 - a37); + a37 = (a33 * a15); + a38 = (a34 * a16); + a37 = (a37 + a38); + a38 = (a35 * a17); + a37 = (a37 + a38); + a38 = (a36 * a18); + a37 = (a37 + a38); + a32 = (a32 - a37); + a37 = (a32 * a19); + a38 = (a33 * a20); + a37 = (a37 + a38); + a38 = (a34 * a21); + a37 = (a37 + a38); + a38 = (a35 * a22); + a37 = (a37 + a38); + a38 = (a36 * a23); + a37 = (a37 + a38); + a31 = (a31 - a37); + a37 = (a31 * a24); + a38 = (a32 * a25); + a37 = (a37 + a38); + a38 = (a33 * a26); + a37 = (a37 + a38); + a38 = (a34 * a27); + a37 = (a37 + a38); + a38 = (a35 * a28); + a37 = (a37 + a38); + a38 = (a36 * a29); + a37 = (a37 + a38); + a30 = (a30 - a37); + a30 = (a30 / a02); + a37 = math::square(a30); + a37 = (a02 * a37); + a31 = (a31 / a03); + a38 = math::square(a31); + a38 = (a03 * a38); + a37 = (a37 + a38); + a32 = (a32 / a04); + a38 = math::square(a32); + a38 = (a04 * a38); + a37 = (a37 + a38); + a33 = (a33 / a05); + a38 = math::square(a33); + a38 = (a05 * a38); + a37 = (a37 + a38); + a34 = (a34 / a06); + a38 = math::square(a34); + a38 = (a06 * a38); + a37 = (a37 + a38); + a35 = (a35 / a07); + a38 = math::square(a35); + a38 = (a07 * a38); + a37 = (a37 + a38); + a36 = (a36 / a08); + a38 = math::square(a36); + a38 = (a08 * a38); + a37 = (a37 + a38); + a01 = (a01 - a37); + a37 = input_vec[9]; + a38 = input_vec[18]; + a39 = input_vec[27]; + a40 = input_vec[36]; + a41 = input_vec[45]; + a42 = input_vec[54]; + a43 = input_vec[63]; + a44 = input_vec[72]; + a45 = (a44 * a09); + a43 = (a43 - a45); + a45 = (a43 * a10); + a46 = (a44 * a11); + a45 = (a45 + a46); + a42 = (a42 - a45); + a45 = (a42 * a12); + a46 = (a43 * a13); + a45 = (a45 + a46); + a46 = (a44 * a14); + a45 = (a45 + a46); + a41 = (a41 - a45); + a45 = (a41 * a15); + a46 = (a42 * a16); + a45 = (a45 + a46); + a46 = (a43 * a17); + a45 = (a45 + a46); + a46 = (a44 * a18); + a45 = (a45 + a46); + a40 = (a40 - a45); + a45 = (a40 * a19); + a46 = (a41 * a20); + a45 = (a45 + a46); + a46 = (a42 * a21); + a45 = (a45 + a46); + a46 = (a43 * a22); + a45 = (a45 + a46); + a46 = (a44 * a23); + a45 = (a45 + a46); + a39 = (a39 - a45); + a45 = (a39 * a24); + a46 = (a40 * a25); + a45 = (a45 + a46); + a46 = (a41 * a26); + a45 = (a45 + a46); + a46 = (a42 * a27); + a45 = (a45 + a46); + a46 = (a43 * a28); + a45 = (a45 + a46); + a46 = (a44 * a29); + a45 = (a45 + a46); + a38 = (a38 - a45); + a45 = (a38 * a30); + a46 = (a39 * a31); + a45 = (a45 + a46); + a46 = (a40 * a32); + a45 = (a45 + a46); + a46 = (a41 * a33); + a45 = (a45 + a46); + a46 = (a42 * a34); + a45 = (a45 + a46); + a46 = (a43 * a35); + a45 = (a45 + a46); + a46 = (a44 * a36); + a45 = (a45 + a46); + a37 = (a37 - a45); + a37 = (a37 / a01); + a45 = math::square(a37); + a45 = (a01 * a45); + a38 = (a38 / a02); + a46 = math::square(a38); + a46 = (a02 * a46); + a45 = (a45 + a46); + a39 = (a39 / a03); + a46 = math::square(a39); + a46 = (a03 * a46); + a45 = (a45 + a46); + a40 = (a40 / a04); + a46 = math::square(a40); + a46 = (a04 * a46); + a45 = (a45 + a46); + a41 = (a41 / a05); + a46 = math::square(a41); + a46 = (a05 * a46); + a45 = (a45 + a46); + a42 = (a42 / a06); + a46 = math::square(a42); + a46 = (a06 * a46); + a45 = (a45 + a46); + a43 = (a43 / a07); + a46 = math::square(a43); + a46 = (a07 * a46); + a45 = (a45 + a46); + a44 = (a44 / a08); + a46 = math::square(a44); + a46 = (a08 * a46); + a45 = (a45 + a46); + a00 = (a00 - a45); + a45 = (1. / a00); + output_vec[0] = a45; + a45 = (a37 / a00); + a46 = (-a45); + output_vec[1] = a46; + a47 = (a37 * a30); + a47 = (a38 - a47); + a47 = (a47 / a00); + a48 = (-a47); + output_vec[2] = a48; + a49 = (a30 * a24); + a49 = (a31 - a49); + a50 = (a37 * a49); + a51 = (a38 * a24); + a50 = (a50 + a51); + a50 = (a39 - a50); + a50 = (a50 / a00); + a51 = (-a50); + output_vec[3] = a51; + a52 = (a24 * a19); + a52 = (a25 - a52); + a53 = (a30 * a52); + a54 = (a31 * a19); + a53 = (a53 + a54); + a53 = (a32 - a53); + a54 = (a37 * a53); + a55 = (a38 * a52); + a54 = (a54 + a55); + a55 = (a39 * a19); + a54 = (a54 + a55); + a54 = (a40 - a54); + a54 = (a54 / a00); + a55 = (-a54); + output_vec[4] = a55; + a56 = (a19 * a15); + a56 = (a20 - a56); + a57 = (a24 * a56); + a58 = (a25 * a15); + a57 = (a57 + a58); + a57 = (a26 - a57); + a58 = (a30 * a57); + a59 = (a31 * a56); + a58 = (a58 + a59); + a59 = (a32 * a15); + a58 = (a58 + a59); + a58 = (a33 - a58); + a59 = (a37 * a58); + a60 = (a38 * a57); + a59 = (a59 + a60); + a60 = (a39 * a56); + a59 = (a59 + a60); + a60 = (a40 * a15); + a59 = (a59 + a60); + a59 = (a41 - a59); + a59 = (a59 / a00); + a60 = (-a59); + output_vec[5] = a60; + a61 = (a15 * a12); + a61 = (a16 - a61); + a62 = (a19 * a61); + a63 = (a20 * a12); + a62 = (a62 + a63); + a62 = (a21 - a62); + a63 = (a24 * a62); + a64 = (a25 * a61); + a63 = (a63 + a64); + a64 = (a26 * a12); + a63 = (a63 + a64); + a63 = (a27 - a63); + a64 = (a30 * a63); + a65 = (a31 * a62); + a64 = (a64 + a65); + a65 = (a32 * a61); + a64 = (a64 + a65); + a65 = (a33 * a12); + a64 = (a64 + a65); + a64 = (a34 - a64); + a65 = (a37 * a64); + a66 = (a38 * a63); + a65 = (a65 + a66); + a66 = (a39 * a62); + a65 = (a65 + a66); + a66 = (a40 * a61); + a65 = (a65 + a66); + a66 = (a41 * a12); + a65 = (a65 + a66); + a65 = (a42 - a65); + a65 = (a65 / a00); + a66 = (-a65); + output_vec[6] = a66; + a67 = (a12 * a10); + a67 = (a13 - a67); + a68 = (a15 * a67); + a69 = (a16 * a10); + a68 = (a68 + a69); + a68 = (a17 - a68); + a69 = (a19 * a68); + a70 = (a20 * a67); + a69 = (a69 + a70); + a70 = (a21 * a10); + a69 = (a69 + a70); + a69 = (a22 - a69); + a70 = (a24 * a69); + a71 = (a25 * a68); + a70 = (a70 + a71); + a71 = (a26 * a67); + a70 = (a70 + a71); + a71 = (a27 * a10); + a70 = (a70 + a71); + a70 = (a28 - a70); + a71 = (a30 * a70); + a72 = (a31 * a69); + a71 = (a71 + a72); + a72 = (a32 * a68); + a71 = (a71 + a72); + a72 = (a33 * a67); + a71 = (a71 + a72); + a72 = (a34 * a10); + a71 = (a71 + a72); + a71 = (a35 - a71); + a72 = (a37 * a71); + a73 = (a38 * a70); + a72 = (a72 + a73); + a73 = (a39 * a69); + a72 = (a72 + a73); + a73 = (a40 * a68); + a72 = (a72 + a73); + a73 = (a41 * a67); + a72 = (a72 + a73); + a73 = (a42 * a10); + a72 = (a72 + a73); + a72 = (a43 - a72); + a72 = (a72 / a00); + a73 = (-a72); + output_vec[7] = a73; + a74 = (a10 * a09); + a74 = (a11 - a74); + a75 = (a12 * a74); + a76 = (a13 * a09); + a75 = (a75 + a76); + a75 = (a14 - a75); + a76 = (a15 * a75); + a77 = (a16 * a74); + a76 = (a76 + a77); + a77 = (a17 * a09); + a76 = (a76 + a77); + a76 = (a18 - a76); + a77 = (a19 * a76); + a78 = (a20 * a75); + a77 = (a77 + a78); + a78 = (a21 * a74); + a77 = (a77 + a78); + a78 = (a22 * a09); + a77 = (a77 + a78); + a77 = (a23 - a77); + a78 = (a24 * a77); + a79 = (a25 * a76); + a78 = (a78 + a79); + a79 = (a26 * a75); + a78 = (a78 + a79); + a79 = (a27 * a74); + a78 = (a78 + a79); + a79 = (a28 * a09); + a78 = (a78 + a79); + a78 = (a29 - a78); + a79 = (a30 * a78); + a80 = (a31 * a77); + a79 = (a79 + a80); + a80 = (a32 * a76); + a79 = (a79 + a80); + a80 = (a33 * a75); + a79 = (a79 + a80); + a80 = (a34 * a74); + a79 = (a79 + a80); + a80 = (a35 * a09); + a79 = (a79 + a80); + a79 = (a36 - a79); + a80 = (a37 * a79); + a81 = (a38 * a78); + a80 = (a80 + a81); + a81 = (a39 * a77); + a80 = (a80 + a81); + a81 = (a40 * a76); + a80 = (a80 + a81); + a81 = (a41 * a75); + a80 = (a80 + a81); + a81 = (a42 * a74); + a80 = (a80 + a81); + a81 = (a43 * a09); + a80 = (a80 + a81); + a80 = (a44 - a80); + a80 = (a80 / a00); + a00 = (-a80); + output_vec[8] = a00; + output_vec[9] = a46; + a46 = (1. / a01); + a45 = (a37 * a45); + a46 = (a46 + a45); + output_vec[10] = a46; + a46 = (a37 * a47); + a45 = (a30 / a01); + a46 = (a46 - a45); + output_vec[11] = a46; + a45 = (a37 * a50); + a49 = (a49 / a01); + a45 = (a45 - a49); + output_vec[12] = a45; + a49 = (a37 * a54); + a53 = (a53 / a01); + a49 = (a49 - a53); + output_vec[13] = a49; + a53 = (a37 * a59); + a58 = (a58 / a01); + a53 = (a53 - a58); + output_vec[14] = a53; + a58 = (a37 * a65); + a64 = (a64 / a01); + a58 = (a58 - a64); + output_vec[15] = a58; + a64 = (a37 * a72); + a71 = (a71 / a01); + a64 = (a64 - a71); + output_vec[16] = a64; + a37 = (a37 * a80); + a79 = (a79 / a01); + a37 = (a37 - a79); + output_vec[17] = a37; + output_vec[18] = a48; + output_vec[19] = a46; + a48 = (1. / a02); + a46 = (a30 * a46); + a47 = (a38 * a47); + a46 = (a46 - a47); + a48 = (a48 - a46); + output_vec[20] = a48; + a48 = (a24 / a02); + a46 = (a30 * a45); + a47 = (a38 * a50); + a46 = (a46 - a47); + a48 = (a48 + a46); + a46 = (-a48); + output_vec[21] = a46; + a52 = (a52 / a02); + a47 = (a30 * a49); + a79 = (a38 * a54); + a47 = (a47 - a79); + a52 = (a52 + a47); + a47 = (-a52); + output_vec[22] = a47; + a57 = (a57 / a02); + a79 = (a30 * a53); + a01 = (a38 * a59); + a79 = (a79 - a01); + a57 = (a57 + a79); + a79 = (-a57); + output_vec[23] = a79; + a63 = (a63 / a02); + a01 = (a30 * a58); + a71 = (a38 * a65); + a01 = (a01 - a71); + a63 = (a63 + a01); + a01 = (-a63); + output_vec[24] = a01; + a70 = (a70 / a02); + a71 = (a30 * a64); + a81 = (a38 * a72); + a71 = (a71 - a81); + a70 = (a70 + a71); + a71 = (-a70); + output_vec[25] = a71; + a78 = (a78 / a02); + a30 = (a30 * a37); + a38 = (a38 * a80); + a30 = (a30 - a38); + a78 = (a78 + a30); + a30 = (-a78); + output_vec[26] = a30; + output_vec[27] = a51; + output_vec[28] = a45; + output_vec[29] = a46; + a46 = (1. / a03); + a45 = (a31 * a45); + a50 = (a39 * a50); + a45 = (a45 - a50); + a48 = (a24 * a48); + a45 = (a45 - a48); + a46 = (a46 - a45); + output_vec[30] = a46; + a46 = (a19 / a03); + a45 = (a31 * a49); + a48 = (a39 * a54); + a45 = (a45 - a48); + a48 = (a24 * a52); + a45 = (a45 - a48); + a46 = (a46 + a45); + a45 = (-a46); + output_vec[31] = a45; + a56 = (a56 / a03); + a48 = (a31 * a53); + a50 = (a39 * a59); + a48 = (a48 - a50); + a50 = (a24 * a57); + a48 = (a48 - a50); + a56 = (a56 + a48); + a48 = (-a56); + output_vec[32] = a48; + a62 = (a62 / a03); + a50 = (a31 * a58); + a51 = (a39 * a65); + a50 = (a50 - a51); + a51 = (a24 * a63); + a50 = (a50 - a51); + a62 = (a62 + a50); + a50 = (-a62); + output_vec[33] = a50; + a69 = (a69 / a03); + a51 = (a31 * a64); + a38 = (a39 * a72); + a51 = (a51 - a38); + a38 = (a24 * a70); + a51 = (a51 - a38); + a69 = (a69 + a51); + a51 = (-a69); + output_vec[34] = a51; + a77 = (a77 / a03); + a31 = (a31 * a37); + a39 = (a39 * a80); + a31 = (a31 - a39); + a24 = (a24 * a78); + a31 = (a31 - a24); + a77 = (a77 + a31); + a31 = (-a77); + output_vec[35] = a31; + output_vec[36] = a55; + output_vec[37] = a49; + output_vec[38] = a47; + output_vec[39] = a45; + a45 = (1. / a04); + a49 = (a32 * a49); + a54 = (a40 * a54); + a49 = (a49 - a54); + a52 = (a25 * a52); + a49 = (a49 - a52); + a46 = (a19 * a46); + a49 = (a49 - a46); + a45 = (a45 - a49); + output_vec[40] = a45; + a45 = (a15 / a04); + a49 = (a32 * a53); + a46 = (a40 * a59); + a49 = (a49 - a46); + a46 = (a25 * a57); + a49 = (a49 - a46); + a46 = (a19 * a56); + a49 = (a49 - a46); + a45 = (a45 + a49); + a49 = (-a45); + output_vec[41] = a49; + a61 = (a61 / a04); + a46 = (a32 * a58); + a52 = (a40 * a65); + a46 = (a46 - a52); + a52 = (a25 * a63); + a46 = (a46 - a52); + a52 = (a19 * a62); + a46 = (a46 - a52); + a61 = (a61 + a46); + a46 = (-a61); + output_vec[42] = a46; + a68 = (a68 / a04); + a52 = (a32 * a64); + a54 = (a40 * a72); + a52 = (a52 - a54); + a54 = (a25 * a70); + a52 = (a52 - a54); + a54 = (a19 * a69); + a52 = (a52 - a54); + a68 = (a68 + a52); + a52 = (-a68); + output_vec[43] = a52; + a76 = (a76 / a04); + a32 = (a32 * a37); + a40 = (a40 * a80); + a32 = (a32 - a40); + a25 = (a25 * a78); + a32 = (a32 - a25); + a19 = (a19 * a77); + a32 = (a32 - a19); + a76 = (a76 + a32); + a32 = (-a76); + output_vec[44] = a32; + output_vec[45] = a60; + output_vec[46] = a53; + output_vec[47] = a79; + output_vec[48] = a48; + output_vec[49] = a49; + a49 = (1. / a05); + a53 = (a33 * a53); + a59 = (a41 * a59); + a53 = (a53 - a59); + a57 = (a26 * a57); + a53 = (a53 - a57); + a56 = (a20 * a56); + a53 = (a53 - a56); + a45 = (a15 * a45); + a53 = (a53 - a45); + a49 = (a49 - a53); + output_vec[50] = a49; + a49 = (a12 / a05); + a53 = (a33 * a58); + a45 = (a41 * a65); + a53 = (a53 - a45); + a45 = (a26 * a63); + a53 = (a53 - a45); + a45 = (a20 * a62); + a53 = (a53 - a45); + a45 = (a15 * a61); + a53 = (a53 - a45); + a49 = (a49 + a53); + a53 = (-a49); + output_vec[51] = a53; + a67 = (a67 / a05); + a45 = (a33 * a64); + a56 = (a41 * a72); + a45 = (a45 - a56); + a56 = (a26 * a70); + a45 = (a45 - a56); + a56 = (a20 * a69); + a45 = (a45 - a56); + a56 = (a15 * a68); + a45 = (a45 - a56); + a67 = (a67 + a45); + a45 = (-a67); + output_vec[52] = a45; + a75 = (a75 / a05); + a33 = (a33 * a37); + a41 = (a41 * a80); + a33 = (a33 - a41); + a26 = (a26 * a78); + a33 = (a33 - a26); + a20 = (a20 * a77); + a33 = (a33 - a20); + a15 = (a15 * a76); + a33 = (a33 - a15); + a75 = (a75 + a33); + a33 = (-a75); + output_vec[53] = a33; + output_vec[54] = a66; + output_vec[55] = a58; + output_vec[56] = a01; + output_vec[57] = a50; + output_vec[58] = a46; + output_vec[59] = a53; + a53 = (1. / a06); + a58 = (a34 * a58); + a65 = (a42 * a65); + a58 = (a58 - a65); + a63 = (a27 * a63); + a58 = (a58 - a63); + a62 = (a21 * a62); + a58 = (a58 - a62); + a61 = (a16 * a61); + a58 = (a58 - a61); + a49 = (a12 * a49); + a58 = (a58 - a49); + a53 = (a53 - a58); + output_vec[60] = a53; + a53 = (a10 / a06); + a58 = (a34 * a64); + a49 = (a42 * a72); + a58 = (a58 - a49); + a49 = (a27 * a70); + a58 = (a58 - a49); + a49 = (a21 * a69); + a58 = (a58 - a49); + a49 = (a16 * a68); + a58 = (a58 - a49); + a49 = (a12 * a67); + a58 = (a58 - a49); + a53 = (a53 + a58); + a58 = (-a53); + output_vec[61] = a58; + a74 = (a74 / a06); + a34 = (a34 * a37); + a42 = (a42 * a80); + a34 = (a34 - a42); + a27 = (a27 * a78); + a34 = (a34 - a27); + a21 = (a21 * a77); + a34 = (a34 - a21); + a16 = (a16 * a76); + a34 = (a34 - a16); + a12 = (a12 * a75); + a34 = (a34 - a12); + a74 = (a74 + a34); + a34 = (-a74); + output_vec[62] = a34; + output_vec[63] = a73; + output_vec[64] = a64; + output_vec[65] = a71; + output_vec[66] = a51; + output_vec[67] = a52; + output_vec[68] = a45; + output_vec[69] = a58; + a58 = (1. / a07); + a64 = (a35 * a64); + a72 = (a43 * a72); + a64 = (a64 - a72); + a70 = (a28 * a70); + a64 = (a64 - a70); + a69 = (a22 * a69); + a64 = (a64 - a69); + a68 = (a17 * a68); + a64 = (a64 - a68); + a67 = (a13 * a67); + a64 = (a64 - a67); + a53 = (a10 * a53); + a64 = (a64 - a53); + a58 = (a58 - a64); + output_vec[70] = a58; + a07 = (a09 / a07); + a35 = (a35 * a37); + a43 = (a43 * a80); + a35 = (a35 - a43); + a28 = (a28 * a78); + a35 = (a35 - a28); + a22 = (a22 * a77); + a35 = (a35 - a22); + a17 = (a17 * a76); + a35 = (a35 - a17); + a13 = (a13 * a75); + a35 = (a35 - a13); + a10 = (a10 * a74); + a35 = (a35 - a10); + a07 = (a07 + a35); + a35 = (-a07); + output_vec[71] = a35; + output_vec[72] = a00; + output_vec[73] = a37; + output_vec[74] = a30; + output_vec[75] = a31; + output_vec[76] = a32; + output_vec[77] = a33; + output_vec[78] = a34; + output_vec[79] = a35; + a08 = (1. / a08); + a36 = (a36 * a37); + a44 = (a44 * a80); + a36 = (a36 - a44); + a29 = (a29 * a78); + a36 = (a36 - a29); + a23 = (a23 * a77); + a36 = (a36 - a23); + a18 = (a18 * a76); + a36 = (a36 - a18); + a14 = (a14 * a75); + a36 = (a36 - a14); + a11 = (a11 * a74); + a36 = (a36 - a11); + a09 = (a09 * a07); + a36 = (a36 - a09); + a08 = (a08 - a36); + output_vec[80] = a08; + } + }; + } // namespace internal +} // namespace pinocchio + +#endif // ifndef __pinocchio_math_details_matrix_inversion_9x9_hpp__ diff --git a/include/pinocchio/math/details/matrix-inverse-tpl.hpp b/include/pinocchio/math/details/matrix-inverse-tpl.hpp new file mode 100644 index 0000000000..5d55fd82cf --- /dev/null +++ b/include/pinocchio/math/details/matrix-inverse-tpl.hpp @@ -0,0 +1,33 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_math_details_matrix_inversion_3x3_hpp__ +#define __pinocchio_math_details_matrix_inversion_3x3_hpp__ + +#include "pinocchio/math/matrix.hpp" + +namespace pinocchio +{ + namespace internal + { + template<> + struct MatrixInversionCodeGeneratedImpl<3> + { + template + static EIGEN_STRONG_INLINE void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse_) + { + typedef typename M1::Scalar Scalar; + + assert(is_symmetric(matrix, math::sqrt(dummy_precision()))); + + const auto & input_vec = matrix.reshaped(); + auto & matrix_inverse = matrix_inverse_.const_cast_derived(); + auto output_vec = matrix_inverse.reshaped(); + } + }; + } // namespace internal +} // namespace pinocchio + +#endif // ifndef __pinocchio_math_details_matrix_inversion_3x3_hpp__ diff --git a/include/pinocchio/math/eigen-helpers.hpp b/include/pinocchio/math/eigen-helpers.hpp new file mode 100644 index 0000000000..b4fd05c5f5 --- /dev/null +++ b/include/pinocchio/math/eigen-helpers.hpp @@ -0,0 +1,28 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_math_eigen_helpers_hpp__ +#define __pinocchio_math_eigen_helpers_hpp__ + +#include "pinocchio/math/fwd.hpp" + +namespace pinocchio +{ + +#define PINOCCHIO_EIGEN_HELPER_FUNC(method) \ + template \ + void method(const Eigen::MatrixBase & mat) \ + { \ + mat.const_cast_derived().method(); \ + } + + PINOCCHIO_EIGEN_HELPER_FUNC(setZero); + PINOCCHIO_EIGEN_HELPER_FUNC(setOnes); + PINOCCHIO_EIGEN_HELPER_FUNC(setIdentity); + +#undef PINOCCHIO_EIGEN_HELPER_FUNC + +} // namespace pinocchio + +#endif // ifndef __pinocchio_math_eigen_helpers_hpp__ diff --git a/include/pinocchio/math/eigenvalues-tridiagonal-matrix.hpp b/include/pinocchio/math/eigenvalues-tridiagonal-matrix.hpp new file mode 100644 index 0000000000..0505e09ead --- /dev/null +++ b/include/pinocchio/math/eigenvalues-tridiagonal-matrix.hpp @@ -0,0 +1,209 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_math_eigenvalues_tridiagonal_matrix_hpp__ +#define __pinocchio_math_eigenvalues_tridiagonal_matrix_hpp__ + +#include "pinocchio/math/fwd.hpp" + +namespace pinocchio +{ + template + struct TridiagonalSymmetricMatrixTpl; + + /// + /// \brief Computes the spectrum[m1:m2] of the input tridiagonal matrix up to precision eps + /// + /// \param[in] tridiagonal_mat a Tridiagonal Symmetric matrix + /// \param[in] m1 the index of the first eigenvalue to compute (lowest) + /// \param[in] m2 the index of the last eigenvalue to compute (largest) + /// \param[in] eps tolerance in the estimate of the eigenvalues + /// + /// \returns The spectrum[m1:m2] of the input tridiagonal matrix + /// + /// \details This functions implements the seminal work of W. BARTH, R. S. MARTIN and J. H. + /// WILKINSON which can be downloaded at + /// https://link.springer.com/content/pdf/10.1007/BF02162154.pdf \remarks This function proceeds + /// to some minimal memory allocation for efficiency \remarks One potential improvement of this + /// implementation of bissec could be fine at + /// https://link.springer.com/content/pdf/10.1007/BF01389644.pdf + /// + template + Eigen::Matrix computeSpectrum( + const TridiagonalSymmetricMatrixTpl & tridiagonal_mat, + const Eigen::DenseIndex m1, + const Eigen::DenseIndex m2, + Scalar eps = 1e-4) + { + typedef Eigen::Matrix ReturnType; + typedef TridiagonalSymmetricMatrixTpl TridiagonalSymmetricMatrix; + typedef typename TridiagonalSymmetricMatrix::CoeffVectorType CoeffVectorType; + + PINOCCHIO_CHECK_INPUT_ARGUMENT(m1 <= m2, "m1 should be lower than m2."); + PINOCCHIO_CHECK_INPUT_ARGUMENT(m1 >= 0, "m1 should be greater than 0."); + PINOCCHIO_CHECK_INPUT_ARGUMENT(m2 >= 0, "m2 should be greater than 0."); + PINOCCHIO_CHECK_INPUT_ARGUMENT( + m2 <= tridiagonal_mat.rows() - 1, + "m2 should be lower than the size of the tridiagonal matrix."); + PINOCCHIO_CHECK_INPUT_ARGUMENT(eps >= Scalar(0), "eps should be greater than 0.") + + const Eigen::DenseIndex n = tridiagonal_mat.rows(); + const Eigen::DenseIndex dm = m2 - m1 + 1; + const Scalar relfeh = 2 * Eigen::NumTraits::epsilon(); + + assert((Scalar(1) + relfeh) > Scalar(1)); + + const auto & alphas = tridiagonal_mat.diagonal(); + const auto & betas_ = tridiagonal_mat.subDiagonal(); + CoeffVectorType betas_abs = CoeffVectorType::Zero(n); + betas_abs.array().tail(n - 1) = betas_.array().abs(); + CoeffVectorType betas_square = betas_abs.array().square(); + + Scalar xmin = alphas[n - 1] - betas_abs[n - 1], xmax = alphas[n - 1] + betas_abs[n - 1]; + + for (Eigen::DenseIndex i = n - 2; i >= 0; --i) + { + const Scalar h = betas_abs[i] + betas_abs[i + 1]; + xmax = math::max(alphas[i] + h, xmax); + xmin = math::min(alphas[i] - h, xmin); + } + + Scalar eps2 = relfeh * ((xmin + xmax > 0) ? xmax : xmin); + eps2 = 0.5 * eps + 7 * eps2; + + // Inner block + Scalar x0 = xmax; + ReturnType spectrum = ReturnType::Zero(n); + auto & x = spectrum; + CoeffVectorType wu = CoeffVectorType::Zero(n); + + x.segment(m1, dm).fill(xmax); + wu.segment(m1, dm).fill(xmin); + + // Eigen::DenseIndex z = 0; + // Loop for the kth eigenvalue + for (Eigen::DenseIndex k = m2; k >= m1; --k) + { + Scalar xu = xmin; + for (Eigen::DenseIndex i = k; i >= m1; --i) + { + if (xu <= wu[i]) + { + xu = wu[i]; + x0 = math::min(x0, x[k]); + while ((x0 - xu) > (2 * relfeh * (math::fabs(xu) + math::fabs(x0)) + eps)) + { + // z++; + Scalar x1 = 0.5 * (xu + x0); + Eigen::DenseIndex a = -1; + Scalar q = 1.; + for (Eigen::DenseIndex j = 0; j < n; ++j) + { + const Scalar dq = q != Scalar(0) ? betas_square[j] / q : betas_abs[j] / relfeh; + q = alphas[j] - x1 - dq; + if (q < Scalar(0)) + a++; + } // end for j + if (a < k) + { + xu = x1; + if (a < m1) + { + wu[m1] = x1; + } + else + { + wu[a + 1] = x1; + x[a] = math::min(x[a], x1); + } + } + else + { + x0 = x1; + } + } // end while + x[k] = 0.5 * (xu + x0); + } + } // end for i + } // end for k + + return spectrum; + } + + /// + /// \brief Computes the full spectrum of the input tridiagonal matrix up to precision eps + /// + /// \param[in] tridiagonal_mat a Tridiagonal Symmetric matrix + /// \param[in] eps tolerance in the estimate of the eigenvalues + /// + /// \details This functions implements the seminal work of W. BARTH, R. S. MARTIN and J. H. + /// WILKINSON which can be downloaded at + /// https://link.springer.com/content/pdf/10.1007/BF02162154.pdf \remarks This function proceeds + /// to some minimal memory allocation for efficiency + /// + template + Eigen::Matrix computeSpectrum( + const TridiagonalSymmetricMatrixTpl & tridiagonal_mat, Scalar eps = 1e-4) + { + return computeSpectrum(tridiagonal_mat, 0, tridiagonal_mat.cols() - 1, eps); + } + + /// + ///  \brief Computes the kth eigenvalue associated with the input tridiagonal matrix up to + /// precision eps + /// + /// \param[in] tridiagonal_mat a Tridiagonal Symmetric matrix + /// \param[in] eigenvalue_index index of the eigenvalue to compute + /// \param[in] eps tolerance in the estimate of the eigenvalues + /// + /// \returns The kth eigenvalue + /// \see computeSpectrum + template + Scalar computeEigenvalue( + const TridiagonalSymmetricMatrixTpl & tridiagonal_mat, + const Eigen::DenseIndex eigenvalue_index, + Scalar eps = 1e-4) + { + return computeSpectrum( + tridiagonal_mat, eigenvalue_index, eigenvalue_index, eps)[eigenvalue_index]; + } + + /// + ///  \brief Computes the lowest eigenvalue associated with the input tridiagonal matrix up to + /// precision eps + /// + /// \param[in] tridiagonal_mat a Tridiagonal Symmetric matrix + /// \param[in] eigenvalue_index index of the eigenvalue to compute + /// \param[in] eps tolerance in the estimate of the eigenvalues + /// + /// \returns The lowest eigenvalue + /// \see computeSpectrum + template + Scalar computeLowestEigenvalue( + const TridiagonalSymmetricMatrixTpl & tridiagonal_mat, Scalar eps = 1e-4) + { + return computeSpectrum(tridiagonal_mat, 0, 0, eps)[0]; + } + + /// + ///  \brief Computes the largest eigenvalue associated with the input tridiagonal matrix up to + /// precision eps + /// + /// \param[in] tridiagonal_mat a Tridiagonal Symmetric matrix + /// \param[in] eigenvalue_index index of the eigenvalue to compute + /// \param[in] eps tolerance in the estimate of the eigenvalues + /// + /// \returns The largest eigenvalue + /// \see computeSpectrum + template + Scalar computeLargestEigenvalue( + const TridiagonalSymmetricMatrixTpl & tridiagonal_mat, Scalar eps = 1e-4) + { + return computeSpectrum( + tridiagonal_mat, tridiagonal_mat.cols() - 1, tridiagonal_mat.cols() - 1, + eps)[tridiagonal_mat.cols() - 1]; + } +} // namespace pinocchio + +#endif // #ifndef __pinocchio_math_eigenvalues_tridiagonal_matrix_hpp__ diff --git a/include/pinocchio/math/eigenvalues.hpp b/include/pinocchio/math/eigenvalues.hpp index 23cbf62e55..2ec007f7fa 100644 --- a/include/pinocchio/math/eigenvalues.hpp +++ b/include/pinocchio/math/eigenvalues.hpp @@ -6,7 +6,7 @@ #define __pinocchio_math_eigenvalues_hpp__ #include "pinocchio/math/fwd.hpp" -#include +#include "pinocchio/math/matrix.hpp" namespace pinocchio { @@ -41,11 +41,11 @@ namespace pinocchio for (it = 0; it < max_it; ++it) { const Scalar eigenvalue_est_prev = eigenvalue_est; - principal_eigen_vector /= eigenvalue_est; + principal_eigen_vector /= principal_eigen_vector.norm(); eigen_vector_prev = principal_eigen_vector; - principal_eigen_vector.noalias() = mat * eigen_vector_prev; + evalTo(mat * eigen_vector_prev, principal_eigen_vector); - eigenvalue_est = principal_eigen_vector.norm(); + eigenvalue_est = eigen_vector_prev.dot(principal_eigen_vector); convergence_criteria = math::fabs(eigenvalue_est_prev - eigenvalue_est); if (check_expression_if_real( @@ -78,12 +78,12 @@ namespace pinocchio for (it = 0; it < max_it; ++it) { const Scalar eigenvalue_est_prev = eigenvalue_est; - lowest_eigen_vector /= eigenvalue_est; + lowest_eigen_vector /= lowest_eigen_vector.norm(); eigen_vector_prev = lowest_eigen_vector; - lowest_eigen_vector.noalias() = mat * eigen_vector_prev; + evalTo(mat * eigen_vector_prev, lowest_eigen_vector); lowest_eigen_vector -= largest_eigen_value * eigen_vector_prev; - eigenvalue_est = lowest_eigen_vector.norm(); + eigenvalue_est = eigen_vector_prev.dot(lowest_eigen_vector); convergence_criteria = math::fabs(eigenvalue_est_prev - eigenvalue_est); if (check_expression_if_real( diff --git a/include/pinocchio/math/fwd.hpp b/include/pinocchio/math/fwd.hpp index 7d972a1575..de3750b31d 100644 --- a/include/pinocchio/math/fwd.hpp +++ b/include/pinocchio/math/fwd.hpp @@ -1,20 +1,25 @@ // -// Copyright (c) 2016-2024 CNRS INRIA +// Copyright (c) 2016-2018 CNRS +// Copyright (c) 2018-2025 INRIA // #ifndef __pinocchio_math_fwd_hpp__ #define __pinocchio_math_fwd_hpp__ #include "pinocchio/fwd.hpp" + #include #include -#include +#include namespace pinocchio { template - struct is_floating_point : boost::is_floating_point + struct EigenMatrixExpression; + + template + struct is_floating_point : ::std::is_floating_point { }; @@ -82,7 +87,21 @@ namespace pinocchio PINOCCHIO_OVERLOAD_MATH_BINARY_OPERATOR(min) PINOCCHIO_OVERLOAD_MATH_BINARY_OPERATOR(max) PINOCCHIO_OVERLOAD_MATH_BINARY_OPERATOR(atan2) + + template + inline T square(const T & value) + { + return value * value; + } } // namespace math + + /// \brief Shortcut for calling ::Eigen::NumTraits::dummy_precision() + template + inline EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR T dummy_precision() + { + return ::Eigen::NumTraits::dummy_precision(); + } + } // namespace pinocchio #endif // #ifndef __pinocchio_math_fwd_hpp__ diff --git a/include/pinocchio/math/gram-schmidt-orthonormalisation.hpp b/include/pinocchio/math/gram-schmidt-orthonormalisation.hpp index 69227a8faa..1829ba4d1f 100644 --- a/include/pinocchio/math/gram-schmidt-orthonormalisation.hpp +++ b/include/pinocchio/math/gram-schmidt-orthonormalisation.hpp @@ -1,39 +1,80 @@ // -// Copyright (c) 2024 INRIA +// Copyright (c) 2024-2025 INRIA // #ifndef __pinocchio_math_gram_schmidt_orthonormalisation_hpp__ #define __pinocchio_math_gram_schmidt_orthonormalisation_hpp__ #include "pinocchio/math/fwd.hpp" -#include namespace pinocchio { - ///  \brief Perform the Gram-Schmidt orthonormalisation on the input/output vector for a given + ///  \brief Perform the Gram-Schmidt orthogonalization on the input/output vector for a given /// input basis /// - ///  \param[in] basis Orthonormal basis - ///  \param[in,out] vec Vector to orthonomarlize wrt the input basis + ///  \param[in] basis Orthonormal basis. + ///  \param[in,out] vec Vector to orthonomarlize wrt the input basis. + ///  \param[in] threshold Only perform the orthonormalization if the scalar product between the + /// current column and the input vector is above the given threshold. /// template - void orthonormalisation( - const Eigen::MatrixBase & basis, const Eigen::MatrixBase & vec_) + void orthogonalization( + const Eigen::MatrixBase & basis, + const Eigen::MatrixBase & vec_, + const typename MatrixType::Scalar & threshold = 0) { typedef typename VectorType::Scalar Scalar; VectorType & vec = vec_.const_cast_derived(); PINOCCHIO_CHECK_ARGUMENT_SIZE(basis.rows(), vec.size()); - assert((basis.transpose() * basis).isIdentity() && "The input basis is not orthonormal."); + // assert((basis.transpose() * basis).isIdentity() && "The input basis is not orthonormal."); for (Eigen::DenseIndex col_id = 0; col_id < basis.cols(); ++col_id) { const auto col = basis.col(col_id); const Scalar alpha = col.dot(vec); - vec -= alpha * col; + if (math::fabs(alpha) >= threshold) // only perform the orthonormalization if the scalar + // product is above a certain threshold + vec -= alpha * col; } + } + + ///  \brief Perform the orthonormalization of the input matrix via the Gram-Schmidt procedure. + /// + ///  \param[in,out] matrix_ Matrix to orthonormalize. + ///  \param[in] threshold Only perform the orthonormalization if the scalar product between the + /// current column and the input vector is above the given threshold. + /// + template + void orthonormalization( + const Eigen::MatrixBase & matrix_, + const typename MatrixType::Scalar & threshold = 0) + { + auto & matrix = matrix_.const_cast_derived(); + + for (Eigen::Index i = 0; i < matrix.cols(); ++i) + { + auto vec = matrix.col(i); + if (i > 0) + orthogonalization(matrix.leftCols(i), vec, threshold); - assert((basis.transpose() * vec).isZero()); + const auto vec_norm = vec.norm(); + vec /= vec_norm; + } + } + + ///  \brief Check whether the input matrix is orthonormal up to a given input precision. + /// + ///  \param[in,out] matrix_ Matrix to orthonormalize. + ///  \param[in] prec Numerical precision of the check (optional). + /// + template + bool isOrthonormal( + const Eigen::MatrixBase & matrix, + const typename MatrixType::Scalar & prec = + Eigen::NumTraits::dummy_precision()) + { + return (matrix.transpose() * matrix).isIdentity(prec); } } // namespace pinocchio diff --git a/include/pinocchio/math/lanczos-decomposition.hpp b/include/pinocchio/math/lanczos-decomposition.hpp index a1cbe25bea..28b47bd510 100644 --- a/include/pinocchio/math/lanczos-decomposition.hpp +++ b/include/pinocchio/math/lanczos-decomposition.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2024 INRIA +// Copyright (c) 2024-2025 INRIA // #ifndef __pinocchio_math_lanczos_decomposition_hpp__ @@ -46,6 +46,22 @@ namespace pinocchio compute(mat); } + /// \brief Constructor for the Lanczos decomposition from given sizes. + /// Compute must be called afterwards. + LanczosDecompositionTpl( + const Eigen::DenseIndex size, const Eigen::DenseIndex decomposition_size) + : m_Qs(size, decomposition_size) + , m_Ts(decomposition_size) + , m_A_times_q(size) + , m_rank(-1) + { + PINOCCHIO_CHECK_INPUT_ARGUMENT( + decomposition_size >= 1, "The size of the decomposition should be greater than one."); + PINOCCHIO_CHECK_INPUT_ARGUMENT( + decomposition_size <= size, + "The size of the decomposition should not be larger than the number of rows."); + } + bool operator==(const LanczosDecompositionTpl & other) const { if (this == &other) @@ -68,16 +84,20 @@ namespace pinocchio { PINOCCHIO_CHECK_INPUT_ARGUMENT(A.rows() == A.cols(), "The input matrix is not square."); PINOCCHIO_CHECK_INPUT_ARGUMENT( - A.rows() == m_Qs.rows(), "The input matrix is of correct size."); + A.rows() == m_Qs.rows(), "The input matrix is not of correct size."); + const Eigen::DenseIndex num_cols = A.cols(); const Eigen::DenseIndex decomposition_size = m_Ts.cols(); auto & alphas = m_Ts.diagonal(); auto & betas = m_Ts.subDiagonal(); - m_Qs.col(0).fill(Scalar(1) / math::sqrt(Scalar(m_Qs.rows()))); + const Scalar prec = 10 * Eigen::NumTraits::epsilon(); + + m_Qs.setIdentity(); + m_Ts.setZero(); - Eigen::DenseIndex k; - for (k = 0; k < decomposition_size; ++k) + m_rank = 1; + for (Eigen::DenseIndex k = 0; k < decomposition_size; ++k) { const auto q = m_Qs.col(k); m_A_times_q.noalias() = A * q; @@ -89,26 +109,57 @@ namespace pinocchio m_A_times_q -= alphas[k] * q; if (k > 0) { - m_A_times_q -= betas[k - 1] * m_Qs.col(k - 1); + const auto q_previous = m_Qs.col(k - 1); + m_A_times_q -= betas[k - 1] * q_previous; } // Perform Gram-Schmidt orthogonalization procedure. if (k > 0) - orthonormalisation(m_Qs.leftCols(k), m_A_times_q); + orthogonalization(m_Qs.leftCols(k + 1), m_A_times_q); + assert(m_Qs.leftCols(k + 1).cols() == k + 1); // Compute beta betas[k] = m_A_times_q.norm(); - if (betas[k] <= 1e2 * Eigen::NumTraits::epsilon()) + if (betas[k] <= prec) { - break; + // Pick a new arbitrary vector + bool found_new_base_vector = false; + PINOCCHIO_ONLY_USED_FOR_DEBUG(found_new_base_vector); + + Scalar q_next_norm = -1; //= q_next.norm(); + + for (Eigen::DenseIndex j = 0; j < num_cols; ++j) + { + const Eigen::DenseIndex base_col_id = (k + 1 + j) % num_cols; + if (base_col_id == 0) + continue; // The first column of Qs is the first unit vector. + + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(decltype(q_next)) VectorPlain; + q_next = VectorPlain::Unit(num_cols, base_col_id); + orthogonalization(m_Qs.leftCols(k + 1), q_next); + q_next_norm = q_next.norm(); + if (q_next_norm > prec) + { + found_new_base_vector = true; + break; + } + } + + assert(found_new_base_vector && "Issue with picking a new arbitrary vector."); + + q_next /= q_next_norm; + betas[k] = 0.; + m_rank++; } else { q_next.noalias() = m_A_times_q / betas[k]; + m_rank++; } } } - m_rank = math::max(Eigen::DenseIndex(1), k); + + m_Qs.rightCols(decomposition_size - m_rank).setZero(); } /// @@ -129,7 +180,7 @@ namespace pinocchio PlainMatrix residual = A * m_Qs; residual -= (m_Qs * m_Ts).eval(); - const auto & q = m_Qs.col(last_col_id); + const auto q = m_Qs.col(last_col_id); auto & tmp_vec = m_A_times_q; // use m_A_times_q as a temporary vector tmp_vec.noalias() = A * q; @@ -164,10 +215,16 @@ namespace pinocchio return m_Qs; } - /// \brief Returns the rank of the decomposition - Eigen::DenseIndex rank() const + /// \brief Returns the external size of the Lanczos decomposition. + Eigen::DenseIndex size() const + { + return m_Qs.rows(); + } + + /// \brief Returns the inerternal size of the Lanczos decomposition. + Eigen::DenseIndex decompositionSize() const { - return m_rank; + return m_Ts.rows(); } protected: diff --git a/include/pinocchio/math/matrix-block.hpp b/include/pinocchio/math/matrix-block.hpp index cba4065fb5..cd047183f1 100644 --- a/include/pinocchio/math/matrix-block.hpp +++ b/include/pinocchio/math/matrix-block.hpp @@ -1,11 +1,11 @@ // -// Copyright (c) 2019 INRIA +// Copyright (c) 2019-2024 INRIA // #ifndef __pinocchio_math_matrix_block_hpp__ #define __pinocchio_math_matrix_block_hpp__ -#include +#include "pinocchio/fwd.hpp" namespace pinocchio { @@ -234,6 +234,78 @@ namespace pinocchio return mat.block(row_id, col_id, row_size_block, col_size_block); } }; + + template + struct DoubleSizeDepType + { + template + struct BlockReturn + { + typedef Eigen::Block Type; + typedef const Eigen::Block ConstType; + }; + + template + static typename BlockReturn::ConstType block( + const Eigen::MatrixBase & mat, + typename Eigen::DenseBase::Index row_id, + typename Eigen::DenseBase::Index col_id, + typename Eigen::DenseBase::Index row_size_block = NQ, + typename Eigen::DenseBase::Index col_size_block = NV) + { + PINOCCHIO_UNUSED_VARIABLE(row_size_block); + PINOCCHIO_UNUSED_VARIABLE(col_size_block); + return mat.template block(row_id, col_id); + } + + template + static typename BlockReturn::Type block( + Eigen::MatrixBase & mat, + typename Eigen::DenseBase::Index row_id, + typename Eigen::DenseBase::Index col_id, + typename Eigen::DenseBase::Index row_size_block = NQ, + typename Eigen::DenseBase::Index col_size_block = NV) + { + PINOCCHIO_UNUSED_VARIABLE(row_size_block); + PINOCCHIO_UNUSED_VARIABLE(col_size_block); + return mat.template block(row_id, col_id); + } + }; + + template<> + struct DoubleSizeDepType + { + template + struct BlockReturn + { + typedef Eigen::Block Type; + typedef const Eigen::Block ConstType; + }; + + template + static typename BlockReturn::ConstType block( + const Eigen::MatrixBase & mat, + typename Eigen::DenseBase::Index row_id, + typename Eigen::DenseBase::Index col_id, + typename Eigen::DenseBase::Index row_size_block, + typename Eigen::DenseBase::Index col_size_block) + { + return mat.block(row_id, col_id, row_size_block, col_size_block); + } + + template + static typename BlockReturn::Type block( + Eigen::MatrixBase & mat, + typename Eigen::DenseBase::Index row_id, + typename Eigen::DenseBase::Index col_id, + typename Eigen::DenseBase::Index row_size_block, + typename Eigen::DenseBase::Index col_size_block) + { + return mat.block(row_id, col_id, row_size_block, col_size_block); + } + }; + // Could be specialized for only one of the two dynamics, but this usecase does not exist yet + } // namespace pinocchio #endif // ifndef __pinocchio_math_matrix_block_hpp__ diff --git a/include/pinocchio/math/matrix-inverse-code-generated.hpp b/include/pinocchio/math/matrix-inverse-code-generated.hpp new file mode 100644 index 0000000000..60186fed38 --- /dev/null +++ b/include/pinocchio/math/matrix-inverse-code-generated.hpp @@ -0,0 +1,50 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_math_matrix_inverse_code_generated_hpp__ +#define __pinocchio_math_matrix_inverse_code_generated_hpp__ + +#include "pinocchio/math/matrix.hpp" + +namespace pinocchio +{ + namespace internal + { + template + struct MatrixInversionCodeGeneratedImpl + { + template + static EIGEN_STRONG_INLINE void run( + const Eigen::MatrixBase & /*matrix*/, const Eigen::MatrixBase & /*matrix_inverse*/) + { + // static_assert(false, "Not implemented."); + assert(false && "Not implemented."); + } + }; + } // namespace internal + + template + EIGEN_STRONG_INLINE void matrix_inversion_code_generated( + const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse) + { + typedef internal::MatrixInversionCodeGeneratedImpl + Runner; + Runner::run(matrix, matrix_inverse.const_cast_derived()); + } +} // namespace pinocchio + +#include "pinocchio/math/details/matrix-inverse-1x1.hpp" +#include "pinocchio/math/details/matrix-inverse-2x2.hpp" +#include "pinocchio/math/details/matrix-inverse-3x3.hpp" +#include "pinocchio/math/details/matrix-inverse-4x4.hpp" +#include "pinocchio/math/details/matrix-inverse-5x5.hpp" +#include "pinocchio/math/details/matrix-inverse-6x6.hpp" +#include "pinocchio/math/details/matrix-inverse-7x7.hpp" +#include "pinocchio/math/details/matrix-inverse-8x8.hpp" +#include "pinocchio/math/details/matrix-inverse-9x9.hpp" +#include "pinocchio/math/details/matrix-inverse-10x10.hpp" +#include "pinocchio/math/details/matrix-inverse-11x11.hpp" +#include "pinocchio/math/details/matrix-inverse-12x12.hpp" + +#endif // ifndef __pinocchio_math_matrix_inverse_code_generated_hpp__ diff --git a/include/pinocchio/math/matrix-inverse.hpp b/include/pinocchio/math/matrix-inverse.hpp new file mode 100644 index 0000000000..1c08288de4 --- /dev/null +++ b/include/pinocchio/math/matrix-inverse.hpp @@ -0,0 +1,150 @@ +// +// Copyright (c) 2019-2025 INRIA +// + +#ifndef __pinocchio_math_matrix_inverse_hpp__ +#define __pinocchio_math_matrix_inverse_hpp__ + +#include "pinocchio/math/matrix.hpp" +#include "pinocchio/math/matrix-inverse-code-generated.hpp" + +namespace pinocchio +{ + namespace internal + { + template + struct MatrixInversionEigenDefaultImpl + { + template + static EIGEN_STRONG_INLINE void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse) + { + matrix_inverse.const_cast_derived().noalias() = + matrix.template block(0, 0).inverse(); + } + }; + + template<> + struct MatrixInversionEigenDefaultImpl<::Eigen::Dynamic> + { + template + static EIGEN_STRONG_INLINE void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse) + { + matrix_inverse.const_cast_derived().noalias() = matrix.inverse(); + } + }; + + template + struct MatrixInversionImpl; + +#define SET_MATRIX_INVERSION_FOR(size, Impl) \ + template<> \ + struct MatrixInversionImpl : Impl \ + { \ + }; + + // For size lower than 4, we can use the spezialized inverse of Eigen + SET_MATRIX_INVERSION_FOR(1, MatrixInversionEigenDefaultImpl<1>) + SET_MATRIX_INVERSION_FOR(2, MatrixInversionEigenDefaultImpl<2>) + SET_MATRIX_INVERSION_FOR(3, MatrixInversionEigenDefaultImpl<3>) + SET_MATRIX_INVERSION_FOR(4, MatrixInversionEigenDefaultImpl<4>) + + // For size in [5,12], we can use code generated impl + SET_MATRIX_INVERSION_FOR(5, MatrixInversionCodeGeneratedImpl<5>) + SET_MATRIX_INVERSION_FOR(6, MatrixInversionCodeGeneratedImpl<6>) + SET_MATRIX_INVERSION_FOR(7, MatrixInversionCodeGeneratedImpl<7>) + SET_MATRIX_INVERSION_FOR(8, MatrixInversionCodeGeneratedImpl<8>) + SET_MATRIX_INVERSION_FOR(9, MatrixInversionCodeGeneratedImpl<9>) + SET_MATRIX_INVERSION_FOR(10, MatrixInversionCodeGeneratedImpl<10>) + SET_MATRIX_INVERSION_FOR(11, MatrixInversionCodeGeneratedImpl<11>) + SET_MATRIX_INVERSION_FOR(12, MatrixInversionCodeGeneratedImpl<12>) + +#undef SET_MATRIX_INVERSION_FOR + + struct MatrixInversionDynamicMatrixImpl + { + template + static EIGEN_STRONG_INLINE void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse) + { + PINOCCHIO_MAYBE_UNUSED typedef typename M1::RealScalar RealScalar; + assert(is_symmetric(matrix, math::sqrt(dummy_precision()))); + +#define CASE_RUN_SPECIFIC_MATRIX_INVERSE_FOR_SIZE(size) \ +case size: \ + MatrixInversionImpl::run(matrix.derived(), matrix_inverse.const_cast_derived()); \ + break; + + switch (matrix.rows()) + { + CASE_RUN_SPECIFIC_MATRIX_INVERSE_FOR_SIZE(1) + CASE_RUN_SPECIFIC_MATRIX_INVERSE_FOR_SIZE(2) + CASE_RUN_SPECIFIC_MATRIX_INVERSE_FOR_SIZE(3) + CASE_RUN_SPECIFIC_MATRIX_INVERSE_FOR_SIZE(4) + CASE_RUN_SPECIFIC_MATRIX_INVERSE_FOR_SIZE(5) + CASE_RUN_SPECIFIC_MATRIX_INVERSE_FOR_SIZE(6) + CASE_RUN_SPECIFIC_MATRIX_INVERSE_FOR_SIZE(7) + CASE_RUN_SPECIFIC_MATRIX_INVERSE_FOR_SIZE(8) + CASE_RUN_SPECIFIC_MATRIX_INVERSE_FOR_SIZE(9) + CASE_RUN_SPECIFIC_MATRIX_INVERSE_FOR_SIZE(10) + CASE_RUN_SPECIFIC_MATRIX_INVERSE_FOR_SIZE(11) + CASE_RUN_SPECIFIC_MATRIX_INVERSE_FOR_SIZE(12) + default: + generic(matrix.derived(), matrix_inverse.const_cast_derived()); + break; + } + +#undef CASE_RUN_SPECIFIC_MATRIX_INVERSE_FOR_SIZE + } + + template + static EIGEN_STRONG_INLINE void + generic(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse) + { + auto & matrix_inverse_ = matrix_inverse.const_cast_derived(); + + matrix_inverse_.setIdentity(); +#ifdef PINOCCHIO_MAC_ARM64 + matrix.ldlt().solveInPlace(matrix_inverse_); +#else + matrix.llt().solveInPlace(matrix_inverse_); +#endif + } + }; + + template + struct MatrixInversionImpl : MatrixInversionDynamicMatrixImpl + { + }; + + template< + typename InputMatrix, + bool is_floating_point = pinocchio::is_floating_point::value> + struct MatrixInversion + : MatrixInversionImpl + { + }; + + template + struct MatrixInversion + { + template + static EIGEN_STRONG_INLINE void + run(const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse) + { + inverse(matrix, matrix_inverse.const_cast_derived()); + } + }; + + } // namespace internal + + template + EIGEN_STRONG_INLINE void matrix_inversion( + const Eigen::MatrixBase & matrix, const Eigen::MatrixBase & matrix_inverse) + { + internal::MatrixInversion::run(matrix, matrix_inverse.const_cast_derived()); + } +} // namespace pinocchio + +#endif // ifndef __pinocchio_math_matrix_inverse_hpp__ diff --git a/include/pinocchio/math/matrix.hpp b/include/pinocchio/math/matrix.hpp index f98cce99d7..845a76110c 100644 --- a/include/pinocchio/math/matrix.hpp +++ b/include/pinocchio/math/matrix.hpp @@ -1,5 +1,6 @@ // -// Copyright (c) 2016-2020 CNRS INRIA +// Copyright (c) 2018-2025 INRIA +// Copyright (c) 2016-2018 CNRS // #ifndef __pinocchio_math_matrix_hpp__ @@ -10,7 +11,6 @@ #include "pinocchio/utils/static-if.hpp" #include -#include namespace pinocchio { @@ -21,6 +21,20 @@ namespace pinocchio return !((m.derived().array() == m.derived().array()).all()); } + template + bool isApproxOrZero( + const Eigen::MatrixBase & mat1, + const Eigen::MatrixBase & mat2, + const typename Matrix1::RealScalar & prec = + Eigen::NumTraits::dummy_precision()) + { + const bool mat1_is_zero = mat1.isZero(prec); + const bool mat2_is_zero = mat2.isZero(prec); + + const bool mat1_is_approx_mat2 = mat1.isApprox(mat2, prec); + return mat1_is_approx_mat2 || (mat1_is_zero && mat2_is_zero); + } + namespace internal { template< @@ -277,6 +291,181 @@ namespace pinocchio m_in, dest_); } + namespace internal + { + template< + typename MatrixLike, + bool value = is_floating_point::value> + struct isSymmetricAlgo + { + typedef typename MatrixLike::Scalar Scalar; + typedef typename MatrixLike::RealScalar RealScalar; + + static bool run( + const Eigen::MatrixBase & mat, + const RealScalar & prec = Eigen::NumTraits::dummy_precision()) + { + if (mat.rows() != mat.cols()) + return false; + return (mat - mat.transpose()).isZero(prec); + } + }; + + template + struct isSymmetricAlgo + { + typedef typename MatrixLike::Scalar Scalar; + typedef typename MatrixLike::RealScalar RealScalar; + + static bool run( + const Eigen::MatrixBase & /*mat*/, + const RealScalar & prec = Eigen::NumTraits::dummy_precision()) + { + PINOCCHIO_UNUSED_VARIABLE(prec); + return true; + } + }; + } // namespace internal + + /// + /// \brief Check whether the input matrix is symmetric within the given precision. + /// + /// \param[in] mat Input matrix + /// \param[in] prec Required precision + /// + /// \returns true if mat is symmetric within the precision prec. + /// + template + inline bool isSymmetric( + const Eigen::MatrixBase & mat, + const typename MatrixLike::RealScalar & prec = + Eigen::NumTraits::dummy_precision()) + { + return internal::isSymmetricAlgo::run(mat, prec); + } + + namespace internal + { + template + struct evalToImpl + { + static void run(const XprType & xpr, DestType & dest) + { + xpr.evalTo(dest); + } + }; + + template + struct evalToImpl, DenseDerived, void> + { + typedef Eigen::MatrixBase DestType; + typedef Eigen::Product XprType; + static void run(const XprType & xpr, DestType & dest) + { + dest.noalias() = xpr; + } + }; + + } // namespace internal + + template + inline void evalTo(const XprType & xpr, DestType & dest) + { + internal::evalToImpl::run(xpr, dest); + } + + template + Eigen::Ref make_ref(const Eigen::PlainObjectBase & mat) + { + typedef Eigen::Ref ReturnType; + return ReturnType(mat.const_cast_derived()); + } + + /// \brief Helper to make the matrix symmetric + /// + /// \param[in,out] mat Input matrix to symmetrize. + /// \param[in] mode Part of the matrix to symmetrize : Eigen::Upper or Eigen::Lower + template + void make_symmetric(const Eigen::MatrixBase & mat, const int mode = Eigen::Upper) + { + PINOCCHIO_CHECK_INPUT_ARGUMENT(mode == Eigen::Upper || mode == Eigen::Lower); + + if (mode == Eigen::Upper) + { + mat.const_cast_derived().template triangularView() = + mat.transpose().template triangularView(); + } + else if (mode == Eigen::Lower) + { + mat.const_cast_derived().template triangularView() = + mat.transpose().template triangularView(); + } + } + + /// + /// \brief Helper to check whether the input matrix is square. + /// + /// \param[in] mat Input matrix to check whether it is square. + /// + template + EIGEN_STRONG_INLINE bool is_square(const Eigen::MatrixBase & mat) + { + return mat.rows() == mat.cols(); + } + + /// + /// \brief Helper to check whether the input matrix is symmetric. + /// + /// \param[in] mat Input matrix to check symmetry. + /// \param[in] prec Numerical precision of the check (optional). + /// + template + bool is_symmetric( + const Eigen::MatrixBase & mat, + const typename Matrix::Scalar & prec = + Eigen::NumTraits::dummy_precision()) + { + if (!is_square(mat)) + return false; + + return mat.reshaped().isApprox(mat.transpose().reshaped(), prec); + } + + /// \brief Enforce the symmetry of the input matrix + template + void enforceSymmetry(const Eigen::MatrixBase & mat_) + { + PINOCCHIO_CHECK_SQUARE_MATRIX(mat_); + + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix) PlainMatrix; + typedef typename Matrix::Scalar Scalar; + typedef Eigen::Map MapMatrix; + + auto & mat = mat_.const_cast_derived(); + MapMatrix tmp = MapMatrix(PINOCCHIO_EIGEN_MAP_ALLOCA(Scalar, mat.rows(), mat.rows())); + + tmp = 0.5 * (mat + mat.transpose()); + mat = tmp; + + assert(mat == mat.transpose()); + } + + template + typename PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix) make_copy(const Eigen::MatrixBase & mat) + { + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix) ReturnType; + return ReturnType(mat); + } + + template + struct is_eigen_ref : std::false_type + { + }; + + template + struct is_eigen_ref> : std::true_type + { + }; } // namespace pinocchio #endif // #ifndef __pinocchio_math_matrix_hpp__ diff --git a/include/pinocchio/math/multiprecision.hpp b/include/pinocchio/math/multiprecision.hpp index 19b3f30603..200f6a4cf1 100644 --- a/include/pinocchio/math/multiprecision.hpp +++ b/include/pinocchio/math/multiprecision.hpp @@ -9,7 +9,6 @@ #include #include -#include namespace pinocchio { @@ -86,32 +85,32 @@ namespace Eigen : true, RequireInitialization = 1 }; - static Real epsilon() + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline Real epsilon() { return std::numeric_limits::epsilon(); } - static Real dummy_precision() + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline Real dummy_precision() { return 1000 * epsilon(); } - static Real highest() + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline Real highest() { return (std::numeric_limits::max)(); } - static Real lowest() + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline Real lowest() { return (std::numeric_limits::min)(); } - static int digits10_imp(const boost::mpl::true_ &) + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline int digits10_imp(const std::true_type &) { return std::numeric_limits::digits10; } template - static int digits10_imp(const boost::mpl::bool_ &) + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline int digits10_imp(const boost::mpl::bool_ &) { return static_cast(Real::default_precision()); } - static int digits10() + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline int digits10() { return digits10_imp( boost::mpl::bool_< @@ -120,13 +119,13 @@ namespace Eigen : false>()); } - constexpr static inline int digits() + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline inline int digits() { return internal::default_digits_impl::run(); } #if EIGEN_VERSION_AT_LEAST(3, 4, 90) - constexpr static inline int max_digits10() + EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR static inline inline int max_digits10() { return internal::default_max_digits10_impl::run(); } diff --git a/include/pinocchio/math/quaternion.hpp b/include/pinocchio/math/quaternion.hpp index a2f22908db..43833c4702 100644 --- a/include/pinocchio/math/quaternion.hpp +++ b/include/pinocchio/math/quaternion.hpp @@ -16,7 +16,6 @@ #include "pinocchio/utils/static-if.hpp" #include -#include namespace pinocchio { @@ -130,10 +129,10 @@ namespace pinocchio Scalar s3, c3; SINCOS(Scalar(2) * PI_value * u3, &s3, &c3); - q.w() = mult1 * s2; - q.x() = mult1 * c2; - q.y() = mult2 * s3; - q.z() = mult2 * c3; + PINOCCHIO_EIGEN_CONST_CAST(Derived, q).w() = mult1 * s2; + PINOCCHIO_EIGEN_CONST_CAST(Derived, q).x() = mult1 * c2; + PINOCCHIO_EIGEN_CONST_CAST(Derived, q).y() = mult2 * s3; + PINOCCHIO_EIGEN_CONST_CAST(Derived, q).z() = mult2 * c3; } namespace internal @@ -305,6 +304,35 @@ namespace pinocchio scale0 * quat0.coeffs() + scale1 * quat1.coeffs(); } + /// + ///  \brief Computes the tangentmap for a unit quaternion. + /// + /// \param[in] quat A unit quaternion representing the input rotation. + /// \param[out] TM The resulting Jacobian of the log operator. + /// + template + inline void tangentMap( + const Eigen::QuaternionBase & quat, + const Eigen::MatrixBase & TM) + { + Matrix43Like & TMm(PINOCCHIO_EIGEN_CONST_CAST(Matrix43Like, TM)); + typedef typename QuaternionLike::Scalar Scalar; + + TMm(0, 0) = Scalar(.5) * quat.w(); + TMm(1, 0) = Scalar(.5) * quat.z(); + TMm(2, 0) = Scalar(-.5) * quat.y(); + TMm(3, 0) = Scalar(-.5) * quat.x(); + + TMm(0, 1) = Scalar(-.5) * quat.z(); + TMm(1, 1) = Scalar(.5) * quat.w(); + TMm(2, 1) = Scalar(.5) * quat.x(); + TMm(3, 1) = Scalar(-.5) * quat.y(); + + TMm(0, 2) = Scalar(.5) * quat.y(); + TMm(1, 2) = Scalar(-.5) * quat.x(); + TMm(2, 2) = Scalar(.5) * quat.w(); + TMm(3, 2) = Scalar(-.5) * quat.z(); + } } // namespace quaternion } // namespace pinocchio diff --git a/include/pinocchio/math/rotation.hpp b/include/pinocchio/math/rotation.hpp index 144433ee10..858efd4d6f 100644 --- a/include/pinocchio/math/rotation.hpp +++ b/include/pinocchio/math/rotation.hpp @@ -9,8 +9,6 @@ #include "pinocchio/math/matrix.hpp" #include "pinocchio/math/sincos.hpp" -#include -#include #include namespace pinocchio diff --git a/include/pinocchio/math/rpy.hxx b/include/pinocchio/math/rpy.hxx index 7b7b76261f..9b54dd90f8 100644 --- a/include/pinocchio/math/rpy.hxx +++ b/include/pinocchio/math/rpy.hxx @@ -5,8 +5,6 @@ #ifndef __pinocchio_math_rpy_hxx__ #define __pinocchio_math_rpy_hxx__ -#include - #include "pinocchio/math/sincos.hpp" namespace pinocchio diff --git a/include/pinocchio/math/sincos.hpp b/include/pinocchio/math/sincos.hpp index ed32fec83b..b6b7140403 100644 --- a/include/pinocchio/math/sincos.hpp +++ b/include/pinocchio/math/sincos.hpp @@ -7,6 +7,7 @@ #define __pinocchio_math_sincos_hpp__ #include +#include "pinocchio/math/fwd.hpp" namespace pinocchio { diff --git a/include/pinocchio/math/triangular-matrix.hpp b/include/pinocchio/math/triangular-matrix.hpp index c79adfac75..99745b01e5 100644 --- a/include/pinocchio/math/triangular-matrix.hpp +++ b/include/pinocchio/math/triangular-matrix.hpp @@ -5,9 +5,7 @@ #ifndef __pinocchio_math_triangular_matrix_hpp__ #define __pinocchio_math_triangular_matrix_hpp__ -#include "pinocchio/macros.hpp" - -#include +#include "pinocchio/math/fwd.hpp" namespace pinocchio { diff --git a/include/pinocchio/math/tridiagonal-matrix.hpp b/include/pinocchio/math/tridiagonal-matrix.hpp index d7005e5e46..edbcb058f6 100644 --- a/include/pinocchio/math/tridiagonal-matrix.hpp +++ b/include/pinocchio/math/tridiagonal-matrix.hpp @@ -5,8 +5,8 @@ #ifndef __pinocchio_math_tridiagonal_matrix_hpp__ #define __pinocchio_math_tridiagonal_matrix_hpp__ -#include "pinocchio/fwd.hpp" -#include +#include "pinocchio/math/fwd.hpp" +#include "pinocchio/math/eigenvalues-tridiagonal-matrix.hpp" namespace pinocchio { @@ -62,6 +62,46 @@ namespace pinocchio MatrixDerived>> : public traits { }; + + template + struct traits>> + : traits> + { + }; + + template + struct EigenMatrixExpression> + : public Eigen::ReturnByValue< + EigenMatrixExpression>> + { + typedef TridiagonalSymmetricMatrixTpl TridiagonalSymmetricMatrix; + + EigenMatrixExpression(const TridiagonalSymmetricMatrix & self) + : self(self) + { + } + + template + inline void evalTo(ResultType & result) const + { + result.setZero(); + result.template diagonal<1>() = self.subDiagonal().conjugate(); + result.diagonal() = self.diagonal(); + result.template diagonal<-1>() = self.subDiagonal(); + } + + EIGEN_CONSTEXPR Eigen::Index rows() const PINOCCHIO_NOEXCEPT + { + return self.rows(); + } + EIGEN_CONSTEXPR Eigen::Index cols() const PINOCCHIO_NOEXCEPT + { + return self.cols(); + } + + protected: + const TridiagonalSymmetricMatrix & self; + }; } // namespace pinocchio namespace Eigen @@ -82,6 +122,20 @@ namespace Eigen }; }; + template + struct traits< + pinocchio::EigenMatrixExpression>> + : public traits>::PlainMatrixType> + { + typedef pinocchio::traits> Base; + typedef typename Base::PlainMatrixType ReturnType; + enum + { + Flags = 0 + }; + }; + template struct traits struct TridiagonalSymmetricMatrixTpl - : public Eigen::ReturnByValue> { + EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef TridiagonalSymmetricMatrixTpl Self; typedef _Scalar Scalar; @@ -260,27 +314,24 @@ namespace pinocchio subDiagonal().setZero(); } - EIGEN_CONSTEXPR Eigen::Index rows() const EIGEN_NOEXCEPT + EIGEN_CONSTEXPR Eigen::Index rows() const PINOCCHIO_NOEXCEPT { return m_size; } - EIGEN_CONSTEXPR Eigen::Index cols() const EIGEN_NOEXCEPT + EIGEN_CONSTEXPR Eigen::Index cols() const PINOCCHIO_NOEXCEPT { return m_size; } PlainMatrixType matrix() const { - return PlainMatrixType(*this); + return PlainMatrixType(eigen()); } - template - inline void evalTo(ResultType & result) const + EigenMatrixExpression eigen() const { - result.setZero(); - result.template diagonal<1>() = subDiagonal().conjugate(); - result.diagonal() = diagonal(); - result.template diagonal<-1>() = subDiagonal(); + typedef EigenMatrixExpression ReturnType; + return ReturnType(*this); } template @@ -306,9 +357,39 @@ namespace pinocchio return this->applyOnTheRight(mat.derived()); } + /// + /// \brief Computes the full spectrum of the input tridiagonal matrix up to precision eps + /// + /// \param[in] eps tolerance in the estimate of the eigenvalues + /// + /// \returns The spectrum of the input tridiagonal matrix + /// + CoeffVectorType computeSpectrum(const Scalar eps = 1e-8) const + { + return ::pinocchio::computeSpectrum(*this, eps); + } + + /// + /// \brief Computes the kth eigenvalue associated with the input tridiagonal matrix up to + /// precision eps + /// + /// \param[in] eigenvalue_index index of the eigenvalue to compute + /// \param[in] eps tolerance in the estimate of the eigenvalues/// + /// + /// \returns The kth eigenvalue + /// + Scalar + computeEigenvalue(const Eigen::DenseIndex eigenvalue_index, const Scalar eps = 1e-8) const + { + return ::pinocchio::computeEigenvalue(*this, eigenvalue_index, eps); + } + protected: + /// \brief Size of the tridiagonal matrix Eigen::DenseIndex m_size; + /// \brief Main diagonal of the tridiagonal matrix CoeffVectorType m_diagonal; + /// \brief Subdiagonal of the tridiagonal matrix CoeffVectorType m_sub_diagonal; }; @@ -358,11 +439,11 @@ namespace pinocchio m_lhs.subDiagonal().asDiagonal() * m_rhs.topRows(reduced_size); } - EIGEN_CONSTEXPR Eigen::Index rows() const EIGEN_NOEXCEPT + EIGEN_CONSTEXPR Eigen::Index rows() const PINOCCHIO_NOEXCEPT { return m_lhs.rows(); } - EIGEN_CONSTEXPR Eigen::Index cols() const EIGEN_NOEXCEPT + EIGEN_CONSTEXPR Eigen::Index cols() const PINOCCHIO_NOEXCEPT { return m_rhs.cols(); } @@ -407,11 +488,11 @@ namespace pinocchio m_lhs.rightCols(reduced_size) * m_rhs.subDiagonal().asDiagonal(); } - EIGEN_CONSTEXPR Eigen::Index rows() const EIGEN_NOEXCEPT + EIGEN_CONSTEXPR Eigen::Index rows() const PINOCCHIO_NOEXCEPT { return m_lhs.rows(); } - EIGEN_CONSTEXPR Eigen::Index cols() const EIGEN_NOEXCEPT + EIGEN_CONSTEXPR Eigen::Index cols() const PINOCCHIO_NOEXCEPT { return m_rhs.cols(); } @@ -496,11 +577,11 @@ namespace pinocchio } } - EIGEN_CONSTEXPR Eigen::Index rows() const EIGEN_NOEXCEPT + EIGEN_CONSTEXPR Eigen::Index rows() const PINOCCHIO_NOEXCEPT { return m_size; } - EIGEN_CONSTEXPR Eigen::Index cols() const EIGEN_NOEXCEPT + EIGEN_CONSTEXPR Eigen::Index cols() const PINOCCHIO_NOEXCEPT { return m_size; } @@ -576,11 +657,11 @@ namespace pinocchio } } - EIGEN_CONSTEXPR Eigen::Index rows() const EIGEN_NOEXCEPT + EIGEN_CONSTEXPR Eigen::Index rows() const PINOCCHIO_NOEXCEPT { return m_lhs.rows(); } - EIGEN_CONSTEXPR Eigen::Index cols() const EIGEN_NOEXCEPT + EIGEN_CONSTEXPR Eigen::Index cols() const PINOCCHIO_NOEXCEPT { return m_rhs.cols(); } diff --git a/include/pinocchio/multibody/data.hpp b/include/pinocchio/multibody/data.hpp index a06ebf622f..810c89812c 100644 --- a/include/pinocchio/multibody/data.hpp +++ b/include/pinocchio/multibody/data.hpp @@ -1,30 +1,28 @@ // -// Copyright (c) 2015-2024 CNRS INRIA +// Copyright (c) 2015-2025 CNRS INRIA // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France. // #ifndef __pinocchio_multibody_data_hpp__ #define __pinocchio_multibody_data_hpp__ -#include "pinocchio/spatial/fwd.hpp" #include "pinocchio/math/tensor.hpp" #include "pinocchio/spatial/se3.hpp" #include "pinocchio/spatial/force.hpp" #include "pinocchio/spatial/motion.hpp" #include "pinocchio/spatial/inertia.hpp" -#include "pinocchio/multibody/fwd.hpp" + +#include "pinocchio/common/data-entity.hpp" + #include "pinocchio/multibody/joint/joint-generic.hpp" + #include "pinocchio/container/aligned-vector.hpp" +#include "pinocchio/container/double-entry-container.hpp" #include "pinocchio/algorithm/contact-cholesky.hpp" #include "pinocchio/serialization/serializable.hpp" -#include -#include -#include - -#include #include namespace pinocchio @@ -34,24 +32,30 @@ namespace pinocchio struct traits> { typedef _Scalar Scalar; + enum + { + Options = _Options + }; + typedef ModelTpl Model; + typedef JointCollectionTpl JointCollection; }; template class JointCollectionTpl> struct DataTpl : serialization::Serializable> , NumericalBase> + , DataEntity> { EIGEN_MAKE_ALIGNED_OPERATOR_NEW - typedef _Scalar Scalar; + typedef typename traits::Scalar Scalar; enum { - Options = _Options + Options = traits::Options }; - typedef JointCollectionTpl JointCollection; - - typedef ModelTpl Model; + typedef typename traits::JointCollection JointCollection; + typedef typename traits::Model Model; typedef SE3Tpl SE3; typedef MotionTpl Motion; @@ -77,7 +81,7 @@ namespace pinocchio typedef Eigen::Matrix Vector3; typedef Eigen::Matrix Vector6; - typedef Eigen::Matrix Vector6c; + typedef Vector6 Vector6c; typedef Eigen::Matrix Vector6r; /// \brief Dense vectorized version of a joint configuration vector. @@ -111,9 +115,25 @@ namespace pinocchio PINOCCHIO_COMPILER_DIAGNOSTIC_POP /// \brief Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in - /// model, encapsulated in JointDataAccessor. + /// model JointDataVector joints; + /// \brief Vector of pinocchio::JointData associated to the pinocchio::JointModel stored in + /// model augmented by constraints + JointDataVector joints_augmented; + + /// \brief Input configuration vector + ConfigVectorType q_in; + + /// \brief Input velocity vector + TangentVectorType v_in; + + /// \brief Input acceleration vector + TangentVectorType a_in; + + /// \brief Input torque vector + TangentVectorType tau_in; + /// \brief Vector of joint accelerations expressed in the local frame of the joint. PINOCCHIO_ALIGNED_STD_VECTOR(Motion) a; @@ -264,10 +284,10 @@ namespace pinocchio /// frame PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) oYaba; // TODO: change with dense symmetric matrix6 - /// \brief Articulated Body Inertia matrix with contact apparent inertia, of a given the subtree - /// and expressed in the WORLD coordinate frame + /// \brief Articulated Body Inertia matrix with constraint augmented inertia, expressed in the + /// WORLD coordinate frame PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) - oYaba_contact; // TODO: change with dense symmetric matrix6 + oYaba_augmented; // TODO: change with dense symmetric matrix6 /// \brief Acceleration propagator PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6) oL; // TODO: change with dense symmetric matrix6 @@ -312,9 +332,6 @@ namespace pinocchio /// \brief Spatial forces set, used in CRBA and CCRBA PINOCCHIO_ALIGNED_STD_VECTOR(Matrix6x) Fcrb; - /// \brief Index of the last child (for CRBA) - std::vector lastChild; - /// \brief Dimension of the subtree motion space (for CRBA) std::vector nvSubtree; @@ -591,6 +608,24 @@ namespace pinocchio PINOCCHIO_ALIGNED_STD_VECTOR(size_t) accumulation_joints; PINOCCHIO_ALIGNED_STD_VECTOR(std::vector) constraints_on_joint; + typedef std::vector JointIndexVector; + + /// \brief Bookkeeping neighbouring vertices during CL-CABA or proxBBO + std::vector neighbour_links; + + typedef std::pair JointIndexPair; + + /// \brief Stores the cross-coupling between links in CL-CABA + container::DoubleEntryContainer> + joint_cross_coupling; + + /// \brief Stores the elimination ordering of CL-CABA + std::vector elimination_order; + + /// \brief Joint apparent inertia vector (related to model.armarture, joint-wise constraints, + /// etc.) + VectorXs joint_apparent_inertia; + /// /// \brief Default constructor of pinocchio::Data from a pinocchio::Model. /// @@ -606,7 +641,7 @@ namespace pinocchio } private: - void computeLastChild(const Model & model); + void computeNvSubtree(const Model & model); void computeParents_fromRow(const Model & model); void computeSupports_fromRow(const Model & model); }; diff --git a/include/pinocchio/multibody/data.hxx b/include/pinocchio/multibody/data.hxx index 71c00bc280..2c6d39a991 100644 --- a/include/pinocchio/multibody/data.hxx +++ b/include/pinocchio/multibody/data.hxx @@ -1,5 +1,6 @@ // -// Copyright (c) 2015-2024 CNRS INRIA +// Copyright (c) 2015-2018 CNRS +// Copyright (c) 2018-2025 INRIA // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France. // @@ -10,6 +11,7 @@ #include "pinocchio/multibody/model.hpp" #include "pinocchio/utils/string-generator.hpp" #include "pinocchio/multibody/liegroup/liegroup-algo.hpp" +#include "pinocchio/algorithm/joint-configuration.hpp" /// @cond DEV @@ -18,7 +20,10 @@ namespace pinocchio template class JointCollectionTpl> DataTpl::DataTpl(const Model & model) - : joints(0) + : q_in(neutral(model)) + , v_in(VectorXs::Zero(model.nv)) + , a_in(VectorXs::Zero(model.nv)) + , tau_in(VectorXs::Zero(model.nv)) , a((std::size_t)model.njoints, Motion::Zero()) , oa((std::size_t)model.njoints, Motion::Zero()) , oa_drift((std::size_t)model.njoints, Motion::Zero()) @@ -59,6 +64,7 @@ namespace pinocchio , ddq(VectorXs::Zero(model.nv)) , Yaba((std::size_t)model.njoints, Inertia::Matrix6::Zero()) , oYaba((std::size_t)model.njoints, Inertia::Matrix6::Zero()) + , oYaba_augmented((std::size_t)model.njoints, Inertia::Matrix6::Zero()) , oL((std::size_t)model.njoints, Inertia::Matrix6::Zero()) , oK((std::size_t)model.njoints, Inertia::Matrix6::Zero()) , u(VectorXs::Zero(model.nv)) @@ -68,7 +74,6 @@ namespace pinocchio , dhg(Force::Zero()) , Ig(Inertia::Zero()) , Fcrb((std::size_t)model.njoints, Matrix6x::Zero(6, model.nv)) - , lastChild((std::size_t)model.njoints, -1) , nvSubtree((std::size_t)model.njoints, -1) , start_idx_v_fromRow((std::size_t)model.nvExtended, -1) , end_idx_v_fromRow((std::size_t)model.nvExtended, -1) @@ -162,22 +167,26 @@ namespace pinocchio , constraints_supported_dim((std::size_t)model.njoints, 0) , constraints_supported((std::size_t)model.njoints) , constraints_on_joint((std::size_t)model.njoints) + , neighbour_links((std::size_t)model.njoints) + , joint_cross_coupling(model.njoints, model.njoints) + , joint_apparent_inertia(VectorXs::Zero(model.nv)) { typedef typename Model::JointIndex JointIndex; /* Create data structure associated to the joints */ - for (JointIndex i = 0; i < (JointIndex)(model.njoints); ++i) - joints.push_back(CreateJointData::run(model.joints[i])); + joints.reserve(JointIndex(model.njoints)); + for (JointIndex i = 0; i < JointIndex(model.njoints); ++i) + { + typedef CreateJointData Constructor; + joints.push_back(Constructor::run(model.joints[i])); + } + joints_augmented = joints; /* Init for CRBA */ M.setZero(); Minv.setZero(); - for (JointIndex i = 0; i < (JointIndex)(model.njoints); ++i) - { - Fcrb[i].resize(6, model.nv); - } - computeLastChild(model); + computeNvSubtree(model); /* Init for Cholesky */ computeParents_fromRow(model); @@ -194,34 +203,27 @@ namespace pinocchio } template class JointCollectionTpl> - inline void DataTpl::computeLastChild(const Model & model) + inline void DataTpl::computeNvSubtree(const Model & model) { - typedef typename Model::Index Index; - - std::fill(lastChild.begin(), lastChild.end(), -1); - for (int i = model.njoints - 1; i >= 0; --i) + for (JointIndex joint_id = 0; joint_id < JointIndex(model.njoints); ++joint_id) { - if (lastChild[(Index)i] == -1) - lastChild[(Index)i] = i; - const Index & parent = model.parents[(Index)i]; - - lastChild[parent] = std::max(lastChild[(Index)i], lastChild[parent]); - // Build a "correct" representation of mimic nvSubtree by using nvExtended, which will cover // its children nv, and allow for a simple check if (boost::get>( - &model.joints[size_t(i)])) - nvSubtree[(Index)i] = 0; + &model.joints[joint_id])) + nvSubtree[joint_id] = 0; else { int nv_; + const JointIndex last_child = + model.subtrees[joint_id].size() > 0 ? model.subtrees[joint_id].back() : JointIndex(0); if (boost::get>( - &model.joints[(Index)lastChild[(Index)i]])) - nv_ = model.joints[(Index)lastChild[(Index)i]].nvExtended(); + &model.joints[last_child])) + nv_ = model.joints[last_child].nvExtended(); else - nv_ = model.joints[(Index)lastChild[(Index)i]].nv(); - nvSubtree[(Index)i] = - model.joints[(Index)lastChild[(Index)i]].idx_v() + nv_ - model.joints[(Index)i].idx_v(); + nv_ = model.joints[last_child].nv(); + nvSubtree[joint_id] = + model.joints[last_child].idx_v() + nv_ - model.joints[joint_id].idx_v(); } } // fill mimic data @@ -348,7 +350,9 @@ namespace pinocchio const DataTpl & data2) { bool value = - data1.joints == data2.joints && data1.a == data2.a && data1.oa == data2.oa + data1.joints == data2.joints && data1.joints_augmented == data2.joints_augmented + && data1.q_in == data2.q_in && data1.v_in == data2.v_in && data1.a_in == data2.a_in + && data1.tau_in == data2.tau_in && data1.a == data2.a && data1.oa == data2.oa && data1.oa_drift == data2.oa_drift && data1.oa_augmented == data2.oa_augmented && data1.a_gf == data2.a_gf && data1.oa_gf == data2.oa_gf && data1.v == data2.v && data1.ov == data2.ov && data1.f == data2.f && data1.of == data2.of @@ -362,11 +366,10 @@ namespace pinocchio && data1.vxI == data2.vxI && data1.Ivx == data2.Ivx && data1.oinertias == data2.oinertias && data1.oYcrb == data2.oYcrb && data1.doYcrb == data2.doYcrb && data1.ddq == data2.ddq && data1.Yaba == data2.Yaba && data1.oYaba == data2.oYaba - && data1.oYaba_contact == data2.oYaba_contact && data1.oL == data2.oL && data1.oK == data2.oK - && data1.u == data2.u && data1.Ag == data2.Ag && data1.dAg == data2.dAg - && data1.hg == data2.hg && data1.dhg == data2.dhg && data1.Ig == data2.Ig - && data1.Fcrb == data2.Fcrb && data1.lastChild == data2.lastChild - && data1.nvSubtree == data2.nvSubtree + && data1.oYaba_augmented == data2.oYaba_augmented && data1.oL == data2.oL + && data1.oK == data2.oK && data1.u == data2.u && data1.Ag == data2.Ag + && data1.dAg == data2.dAg && data1.hg == data2.hg && data1.dhg == data2.dhg + && data1.Ig == data2.Ig && data1.Fcrb == data2.Fcrb && data1.nvSubtree == data2.nvSubtree && data1.start_idx_v_fromRow == data2.start_idx_v_fromRow && data1.end_idx_v_fromRow == data2.end_idx_v_fromRow && data1.U == data2.U && data1.D == data2.D && data1.Dinv == data2.Dinv @@ -398,7 +401,18 @@ namespace pinocchio && data1.bodyRegressor == data2.bodyRegressor && data1.jointTorqueRegressor == data2.jointTorqueRegressor // && data1.contact_chol == data2.contact_chol - && data1.primal_dual_contact_solution == data2.primal_dual_contact_solution; + && data1.primal_dual_contact_solution == data2.primal_dual_contact_solution + && data1.extended_motion_propagator == data2.extended_motion_propagator + && data1.extended_motion_propagator2 == data2.extended_motion_propagator2 + && data1.spatial_inv_inertia == data2.spatial_inv_inertia + && data1.accumulation_descendant == data2.accumulation_descendant + && data1.accumulation_ancestor == data2.accumulation_ancestor + && data1.constraints_supported_dim == data2.constraints_supported_dim + && data1.constraints_supported == data2.constraints_supported + && data1.constraints_on_joint == data2.constraints_on_joint + && data1.neighbour_links == data2.neighbour_links + && data1.joint_cross_coupling == data2.joint_cross_coupling + && data1.joint_apparent_inertia == data2.joint_apparent_inertia; // operator== for Eigen::Tensor provides an Expression which might be not evaluated as a boolean value &= Tensor((data1.kinematic_hessians == data2.kinematic_hessians).all())(0) @@ -418,6 +432,13 @@ namespace pinocchio return !(data1 == data2); } + template class JointCollectionTpl> + typename ModelTpl::Data + ModelTpl::createData() const + { + return Data(*this); + } + } // namespace pinocchio /// @endcond diff --git a/include/pinocchio/multibody/fcl.hpp b/include/pinocchio/multibody/fcl.hpp index e9e0daa741..bf0347a7e3 100644 --- a/include/pinocchio/multibody/fcl.hpp +++ b/include/pinocchio/multibody/fcl.hpp @@ -38,6 +38,7 @@ namespace std #include #include + #include #include #include #include "pinocchio/collision/fcl-pinocchio-conversions.hpp" diff --git a/include/pinocchio/multibody/force-set.hpp b/include/pinocchio/multibody/force-set.hpp index 018999c502..df465be4fe 100644 --- a/include/pinocchio/multibody/force-set.hpp +++ b/include/pinocchio/multibody/force-set.hpp @@ -6,7 +6,6 @@ #define __pinocchio_spatial_force_set_hpp__ #include "pinocchio/spatial/fwd.hpp" -#include namespace pinocchio { diff --git a/include/pinocchio/multibody/fwd.hpp b/include/pinocchio/multibody/fwd.hpp index 2429d46d37..7a0f823017 100644 --- a/include/pinocchio/multibody/fwd.hpp +++ b/include/pinocchio/multibody/fwd.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2017-2020 CNRS INRIA +// Copyright (c) 2017-2024 CNRS INRIA // #ifndef __pinocchio_multibody_fwd_hpp__ @@ -53,6 +53,15 @@ namespace pinocchio ///< projected in the basis of the world frame. }; + template + struct ReferenceFrameTag + { + }; + + using WorldFrameTag = ReferenceFrameTag; + using LocalFrameTag = ReferenceFrameTag; + using LocalWorldAlignedFrameTag = ReferenceFrameTag; + /// /// \brief List of Kinematics Level supported by Pinocchio. /// diff --git a/include/pinocchio/multibody/geometry-object.hpp b/include/pinocchio/multibody/geometry-object.hpp index 004fe6ee90..2994a2ef05 100644 --- a/include/pinocchio/multibody/geometry-object.hpp +++ b/include/pinocchio/multibody/geometry-object.hpp @@ -72,6 +72,63 @@ namespace pinocchio typedef boost::variant GeometryMaterial; + /// Type of physics material. + /// When two objects collide, the physics material of the two objects is notably used + /// to compute the coefficient of friction of the collision pair. + enum PhysicsMaterialType + { + ICE, + METAL, + CONCRETE, + PLASTIC, + WOOD, + PHYSICS_MATERIAL_COUNT + }; + + struct FrictionCoefficientMatrix + { + typedef Eigen::Matrix Matrix; + typedef Eigen::Index Index; + + Matrix friction_coefficient_matrix; + + FrictionCoefficientMatrix(); + + double getFrictionFromMaterialPair(PhysicsMaterialType type1, PhysicsMaterialType type2) const + { + return friction_coefficient_matrix(type1, type2); + } + }; + + inline FrictionCoefficientMatrix & getFrictionCoefficientMatrix() + { + static FrictionCoefficientMatrix table; + return table; + } + + /// Physics material associated to a geometry. + struct PhysicsMaterial + { + PhysicsMaterialType materialType; + double compliance; + double elasticity; + + // Default constructor + explicit PhysicsMaterial( + PhysicsMaterialType materialType = PLASTIC, double compliance = 0.0, double elasticity = 0.) + : materialType(materialType) + , compliance(compliance) + , elasticity(elasticity) + { + } + + bool operator==(const PhysicsMaterial & other) const + { + return materialType == other.materialType && compliance == other.compliance + && elasticity == other.elasticity; + } + }; + struct GeometryObject; // fwd template<> @@ -133,6 +190,9 @@ namespace pinocchio /// other geometry bool disableCollision; + /// \brief The physics property of the object. + PhysicsMaterial physicsMaterial; + /// /// \brief Full constructor. /// @@ -159,7 +219,8 @@ namespace pinocchio const bool overrideMaterial = false, const Eigen::Vector4d & meshColor = Eigen::Vector4d(0, 0, 0, 1), const std::string & meshTexturePath = "", - const GeometryMaterial & meshMaterial = GeometryNoMaterial()) + const GeometryMaterial & meshMaterial = GeometryNoMaterial(), + const PhysicsMaterial & physicsMaterial = PhysicsMaterial()) : Base(name, parent_joint, parent_frame, placement) , geometry(collision_geometry) , meshPath(meshPath) @@ -169,18 +230,18 @@ namespace pinocchio , meshMaterial(meshMaterial) , meshTexturePath(meshTexturePath) , disableCollision(false) + , physicsMaterial(physicsMaterial) { } /// - /// \brief Reduced constructor. - /// \remarks Compared to the other constructor, this one assumes that there is no parentFrame - /// associated to the geometry. + /// \brief Full constructor. /// /// \param[in] name Name of the geometry object. + /// \param[in] parent_frame Index of the parent frame. /// \param[in] parent_joint Index of the parent joint (that supports the geometry). - /// \param[in] placement Placement of the geometry with respect to the joint frame. /// \param[in] collision_geometry The FCL collision geometry object. + /// \param[in] placement Placement of the geometry with respect to the joint frame. /// \param[in] meshPath Path of the mesh (may be needed extarnally to load the mesh inside a /// viewer for instance) [if applicable]. \param[in] meshScale Scale of the mesh [if /// applicable]. \param[in] overrideMaterial If true, this option allows to overrite the @@ -188,18 +249,22 @@ namespace pinocchio /// meshTexturePath Path to the file containing the texture information [if applicable]. /// \param[in] meshMaterial Material of the mesh [if applicable]. /// - GeometryObject( + /// \deprecated This constructor is now deprecated, and its argument order has been changed. + /// + PINOCCHIO_DEPRECATED GeometryObject( const std::string & name, + const FrameIndex parent_frame, const JointIndex parent_joint, - const SE3 & placement, const CollisionGeometryPtr & collision_geometry, + const SE3 & placement, const std::string & meshPath = "", const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(), const bool overrideMaterial = false, const Eigen::Vector4d & meshColor = Eigen::Vector4d(0, 0, 0, 1), const std::string & meshTexturePath = "", - const GeometryMaterial & meshMaterial = GeometryNoMaterial()) - : Base(name, parent_joint, std::numeric_limits::max(), placement) + const GeometryMaterial & meshMaterial = GeometryNoMaterial(), + const PhysicsMaterial & physicsMaterial = PhysicsMaterial()) + : Base(name, parent_joint, parent_frame, placement) , geometry(collision_geometry) , meshPath(meshPath) , meshScale(meshScale) @@ -208,17 +273,19 @@ namespace pinocchio , meshMaterial(meshMaterial) , meshTexturePath(meshTexturePath) , disableCollision(false) + , physicsMaterial(physicsMaterial) { } /// - /// \brief Full constructor. + /// \brief Reduced constructor. + /// \remarks Compared to the other constructor, this one assumes that there is no parentFrame + /// associated to the geometry. /// /// \param[in] name Name of the geometry object. - /// \param[in] parent_frame Index of the parent frame. /// \param[in] parent_joint Index of the parent joint (that supports the geometry). - /// \param[in] collision_geometry The FCL collision geometry object. /// \param[in] placement Placement of the geometry with respect to the joint frame. + /// \param[in] collision_geometry The FCL collision geometry object. /// \param[in] meshPath Path of the mesh (may be needed extarnally to load the mesh inside a /// viewer for instance) [if applicable]. \param[in] meshScale Scale of the mesh [if /// applicable]. \param[in] overrideMaterial If true, this option allows to overrite the @@ -226,21 +293,19 @@ namespace pinocchio /// meshTexturePath Path to the file containing the texture information [if applicable]. /// \param[in] meshMaterial Material of the mesh [if applicable]. /// - /// \deprecated This constructor is now deprecated, and its argument order has been changed. - /// - PINOCCHIO_DEPRECATED GeometryObject( + GeometryObject( const std::string & name, - const FrameIndex parent_frame, const JointIndex parent_joint, - const CollisionGeometryPtr & collision_geometry, const SE3 & placement, + const CollisionGeometryPtr & collision_geometry, const std::string & meshPath = "", const Eigen::Vector3d & meshScale = Eigen::Vector3d::Ones(), const bool overrideMaterial = false, const Eigen::Vector4d & meshColor = Eigen::Vector4d(0, 0, 0, 1), const std::string & meshTexturePath = "", - const GeometryMaterial & meshMaterial = GeometryNoMaterial()) - : Base(name, parent_joint, parent_frame, placement) + const GeometryMaterial & meshMaterial = GeometryNoMaterial(), + const PhysicsMaterial & physicsMaterial = PhysicsMaterial()) + : Base(name, parent_joint, std::numeric_limits::max(), placement) , geometry(collision_geometry) , meshPath(meshPath) , meshScale(meshScale) @@ -249,6 +314,7 @@ namespace pinocchio , meshMaterial(meshMaterial) , meshTexturePath(meshTexturePath) , disableCollision(false) + , physicsMaterial(physicsMaterial) { } @@ -280,7 +346,8 @@ namespace pinocchio const bool overrideMaterial = false, const Eigen::Vector4d & meshColor = Eigen::Vector4d(0, 0, 0, 1), const std::string & meshTexturePath = "", - const GeometryMaterial & meshMaterial = GeometryNoMaterial()) + const GeometryMaterial & meshMaterial = GeometryNoMaterial(), + const PhysicsMaterial & physicsMaterial = PhysicsMaterial()) : Base(name, parent_joint, std::numeric_limits::max(), placement) , geometry(collision_geometry) , meshPath(meshPath) @@ -290,11 +357,36 @@ namespace pinocchio , meshMaterial(meshMaterial) , meshTexturePath(meshTexturePath) , disableCollision(false) + , physicsMaterial(physicsMaterial) { } - GeometryObject(const GeometryObject & other) = default; - GeometryObject & operator=(const GeometryObject & other) = default; + GeometryObject(const GeometryObject & other) + : Base(other) + { + *this = other; + } + + GeometryObject & operator=(const GeometryObject & other) + { + if (&other == this) + return *this; + + name = other.name; + parentFrame = other.parentFrame; + parentJoint = other.parentJoint; + geometry = other.geometry; + placement = other.placement; + meshPath = other.meshPath; + meshScale = other.meshScale; + overrideMaterial = other.overrideMaterial; + meshColor = other.meshColor; + meshMaterial = other.meshMaterial; + meshTexturePath = other.meshTexturePath; + disableCollision = other.disableCollision; + physicsMaterial = other.physicsMaterial; + return *this; + } /// /// \brief Perform a deep copy of this. It will create a copy of the underlying FCL geometry. @@ -321,6 +413,7 @@ namespace pinocchio && overrideMaterial == other.overrideMaterial && meshColor == other.meshColor && meshMaterial == other.meshMaterial && meshTexturePath == other.meshTexturePath && disableCollision == other.disableCollision + && physicsMaterial == other.physicsMaterial && compare_shared_ptr(geometry, other.geometry); } @@ -429,6 +522,58 @@ namespace pinocchio const GeometryObject * go2_ptr; }; + struct ComputeContactPatch : ::hpp::fcl::ComputeContactPatch + { + typedef ::hpp::fcl::ComputeContactPatch Base; + + ComputeContactPatch(const GeometryObject & go1, const GeometryObject & go2) + : Base(go1.geometry.get(), go2.geometry.get()) + , go1_ptr(&go1) + , go2_ptr(&go2) + { + } + + virtual ~ComputeContactPatch() {}; + + void run( + const fcl::Transform3f & tf1, + const fcl::Transform3f & tf2, + const fcl::CollisionResult & collision_result, + const fcl::ContactPatchRequest & request, + fcl::ContactPatchResult & result) const override + { + typedef ::hpp::fcl::CollisionGeometry const * Pointer; + const_cast(Base::o1) = go1_ptr->geometry.get(); + const_cast(Base::o2) = go2_ptr->geometry.get(); + return Base::run(tf1, tf2, collision_result, request, result); + } + + bool operator==(const ComputeContactPatch & other) const + { + return Base::operator==(other) && go1_ptr == other.go1_ptr + && go2_ptr == other.go2_ptr; // Maybe, it would be better to just check *go2_ptr == + // *other.go2_ptr + } + + bool operator!=(const ComputeContactPatch & other) const + { + return !(*this == other); + } + + const GeometryObject & getGeometryObject1() const + { + return *go1_ptr; + } + const GeometryObject & getGeometryObject2() const + { + return *go2_ptr; + } + + protected: + const GeometryObject * go1_ptr; + const GeometryObject * go2_ptr; + }; + struct ComputeDistance : ::hpp::fcl::ComputeDistance { typedef ::hpp::fcl::ComputeDistance Base; diff --git a/include/pinocchio/multibody/geometry-object.hxx b/include/pinocchio/multibody/geometry-object.hxx index bda4c38fee..cc5e7e3a45 100644 --- a/include/pinocchio/multibody/geometry-object.hxx +++ b/include/pinocchio/multibody/geometry-object.hxx @@ -30,6 +30,46 @@ namespace pinocchio return os; } + inline FrictionCoefficientMatrix::FrictionCoefficientMatrix() + { + // Initialize the matrix with zeros, in case we forget to set some coefficients. + for (Index i = 0; i < friction_coefficient_matrix.rows(); ++i) + { + for (Index j = 0; j < friction_coefficient_matrix.cols(); ++j) + { + friction_coefficient_matrix.coeffRef(i, j) = 0.0; + } + } + + // Sources: https://en.wikipedia.org/wiki/Friction + // https://www.engineeringtoolbox.com/friction-coefficients-d_778.html + // These are really rough estimates, and should be replaced by more accurate values if + // available. + friction_coefficient_matrix.coeffRef(METAL, METAL) = 0.75; + friction_coefficient_matrix.coeffRef(METAL, WOOD) = 0.5; + friction_coefficient_matrix.coeffRef(METAL, PLASTIC) = 0.2; + friction_coefficient_matrix.coeffRef(METAL, ICE) = 0.03; + friction_coefficient_matrix.coeffRef(METAL, CONCRETE) = 0.85; + + friction_coefficient_matrix.coeffRef(WOOD, WOOD) = 0.4; + friction_coefficient_matrix.coeffRef(WOOD, PLASTIC) = 0.3; + friction_coefficient_matrix.coeffRef(WOOD, ICE) = 0.03; + friction_coefficient_matrix.coeffRef(WOOD, CONCRETE) = 0.65; + + friction_coefficient_matrix.coeffRef(PLASTIC, PLASTIC) = 0.2; + friction_coefficient_matrix.coeffRef(PLASTIC, ICE) = 0.02; + friction_coefficient_matrix.coeffRef(PLASTIC, CONCRETE) = 0.55; + + friction_coefficient_matrix.coeffRef(ICE, ICE) = 0.01; + friction_coefficient_matrix.coeffRef(ICE, CONCRETE) = 0.25; + + friction_coefficient_matrix.coeffRef(CONCRETE, CONCRETE) = 1.0; + + // Symmetrize the matrix + friction_coefficient_matrix.triangularView() = + friction_coefficient_matrix.transpose(); + } + } // namespace pinocchio #endif // ifndef __pinocchio_multibody_geometry_object_hxx__ diff --git a/include/pinocchio/multibody/geometry.hpp b/include/pinocchio/multibody/geometry.hpp index f2a0ecdd1e..8329f14d6a 100644 --- a/include/pinocchio/multibody/geometry.hpp +++ b/include/pinocchio/multibody/geometry.hpp @@ -257,6 +257,7 @@ namespace pinocchio #ifdef PINOCCHIO_WITH_HPP_FCL typedef ::pinocchio::ComputeCollision ComputeCollision; + typedef ::pinocchio::ComputeContactPatch ComputeContactPatch; typedef ::pinocchio::ComputeDistance ComputeDistance; #endif @@ -296,6 +297,17 @@ namespace pinocchio /// std::vector collisionResults; + /// + /// \brief Defines what information should be computed by contact patch test. + /// There is one request per pair of geometries. + std::vector contactPatchRequests; + + /// + /// \brief Vector gathering the result of the contact patch computation for all the collision + /// pairs. + /// + std::vector contactPatchResults; + /// /// \brief Radius of the bodies, i.e. distance of the further point of the geometry model /// attached to the body from the joint center. @@ -313,6 +325,9 @@ namespace pinocchio ///  \brief Functor associated to the computation of collisions. PINOCCHIO_ALIGNED_STD_VECTOR(ComputeCollision) collision_functors; + ///  \brief Functor associated to the computation of contact patches. + PINOCCHIO_ALIGNED_STD_VECTOR(ComputeContactPatch) contact_patch_functors; + ///  \brief Functor associated to the computation of distances. PINOCCHIO_ALIGNED_STD_VECTOR(ComputeDistance) distance_functors; @@ -464,7 +479,9 @@ namespace pinocchio && distanceRequests == other.distanceRequests && distanceResults == other.distanceResults && collisionRequests == other.collisionRequests - && collisionResults == other.collisionResults && radius == other.radius + && collisionResults == other.collisionResults + && contactPatchRequests == other.contactPatchRequests + && contactPatchResults == other.contactPatchResults && radius == other.radius && collisionPairIndex == other.collisionPairIndex #endif && innerObjects == other.innerObjects && outerObjects == other.outerObjects; diff --git a/include/pinocchio/multibody/geometry.hxx b/include/pinocchio/multibody/geometry.hxx index e3b551e4c4..d91af06b97 100644 --- a/include/pinocchio/multibody/geometry.hxx +++ b/include/pinocchio/multibody/geometry.hxx @@ -88,6 +88,8 @@ namespace pinocchio , collisionRequests( geom_model.collisionPairs.size(), hpp::fcl::CollisionRequest(::hpp::fcl::NO_REQUEST, 1)) , collisionResults(geom_model.collisionPairs.size()) + , contactPatchRequests(geom_model.collisionPairs.size()) // use default constructor + , contactPatchResults(geom_model.collisionPairs.size()) // use default constructor , radius() , collisionPairIndex(0) #endif // PINOCCHIO_WITH_HPP_FCL @@ -106,6 +108,7 @@ namespace pinocchio } #endif collision_functors.reserve(geom_model.collisionPairs.size()); + contact_patch_functors.reserve(geom_model.collisionPairs.size()); distance_functors.reserve(geom_model.collisionPairs.size()); for (size_t cp_index = 0; cp_index < geom_model.collisionPairs.size(); ++cp_index) @@ -115,6 +118,7 @@ namespace pinocchio const GeometryObject & obj_2 = geom_model.geometryObjects[cp.second]; collision_functors.push_back(ComputeCollision(obj_1, obj_2)); + contact_patch_functors.push_back(ComputeContactPatch(obj_1, obj_2)); distance_functors.push_back(ComputeDistance(obj_1, obj_2)); } #endif @@ -129,9 +133,12 @@ namespace pinocchio , distanceResults(other.distanceResults) , collisionRequests(other.collisionRequests) , collisionResults(other.collisionResults) + , contactPatchRequests(other.contactPatchRequests) + , contactPatchResults(other.contactPatchResults) , radius(other.radius) , collisionPairIndex(other.collisionPairIndex) , collision_functors(other.collision_functors) + , contact_patch_functors(other.contact_patch_functors) , distance_functors(other.distance_functors) #endif // PINOCCHIO_WITH_HPP_FCL , innerObjects(other.innerObjects) @@ -150,9 +157,12 @@ namespace pinocchio distanceResults = other.distanceResults; collisionRequests = other.collisionRequests; collisionResults = other.collisionResults; + contactPatchRequests = other.contactPatchRequests; + contactPatchResults = other.contactPatchResults; radius = other.radius; collisionPairIndex = other.collisionPairIndex; collision_functors = other.collision_functors; + contact_patch_functors = other.contact_patch_functors; distance_functors = other.distance_functors; #endif // PINOCCHIO_WITH_HPP_FCL innerObjects = other.innerObjects; @@ -210,8 +220,8 @@ namespace pinocchio break; } } - PINOCCHIO_THROW( - it != geometryObjects.end(), std::invalid_argument, + PINOCCHIO_THROW_IF( + (it == geometryObjects.end()), std::invalid_argument, (std::string("Object ") + name + std::string(" does not belong to model")).c_str()); // Remove all collision pairs that contain i as first or second index, for (CollisionPairVector::iterator itCol = collisionPairs.begin(); @@ -306,8 +316,8 @@ namespace pinocchio inline void GeometryModel::addCollisionPair(const CollisionPair & pair) { PINOCCHIO_CHECK_INPUT_ARGUMENT( - pair.first < ngeoms, "The input pair.first is larger than the number of geometries " - "contained in the GeometryModel"); + pair.first < ngeoms, "The input pair.first is larger than the number of geometries contained " + "in the GeometryModel"); PINOCCHIO_CHECK_INPUT_ARGUMENT( pair.second < ngeoms, "The input pair.second is larger than the number of geometries " "contained in the GeometryModel"); @@ -369,8 +379,8 @@ namespace pinocchio inline void GeometryModel::removeCollisionPair(const CollisionPair & pair) { PINOCCHIO_CHECK_INPUT_ARGUMENT( - pair.first < ngeoms, "The input pair.first is larger than the number of geometries " - "contained in the GeometryModel"); + pair.first < ngeoms, "The input pair.first is larger than the number of geometries contained " + "in the GeometryModel"); PINOCCHIO_CHECK_INPUT_ARGUMENT( pair.second < ngeoms, "The input pair.second is larger than the number of geometries " "contained in the GeometryModel"); @@ -422,8 +432,8 @@ namespace pinocchio { PINOCCHIO_CHECK_INPUT_ARGUMENT( pair_id < activeCollisionPairs.size(), - "The input argument pair_id is larger than the number of " - "collision pairs contained in activeCollisionPairs."); + "The input argument pair_id is larger than the number of collision pairs contained in " + "activeCollisionPairs."); activeCollisionPairs[pair_id] = true; } @@ -498,6 +508,9 @@ namespace pinocchio PINOCCHIO_CHECK_ARGUMENT_SIZE( geom_model.collisionPairs.size(), collisionRequests.size(), "Current geometry data and the input geometry model are not consistent."); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + geom_model.collisionPairs.size(), contactPatchRequests.size(), + "Current geometry data and the input geometry model are not consistent."); for (size_t k = 0; k < geom_model.collisionPairs.size(); ++k) { @@ -526,8 +539,8 @@ namespace pinocchio { PINOCCHIO_CHECK_INPUT_ARGUMENT( pair_id < activeCollisionPairs.size(), - "The input argument pair_id is larger than the number of " - "collision pairs contained in activeCollisionPairs."); + "The input argument pair_id is larger than the number of collision pairs contained in " + "activeCollisionPairs."); activeCollisionPairs[pair_id] = false; } diff --git a/include/pinocchio/multibody/joint-motion-subspace-base.hpp b/include/pinocchio/multibody/joint-motion-subspace-base.hpp index ea9880cb20..b69e355db8 100644 --- a/include/pinocchio/multibody/joint-motion-subspace-base.hpp +++ b/include/pinocchio/multibody/joint-motion-subspace-base.hpp @@ -45,14 +45,14 @@ namespace pinocchio template struct ConstraintForceOp { - typedef ReturnTypeNotDefined ReturnType; + typedef UndefinedReturnType ReturnType; }; /// \brief Return type of the Constraint::Transpose * ForceSet operation template struct ConstraintForceSetOp { - typedef ReturnTypeNotDefined ReturnType; + typedef UndefinedReturnType ReturnType; }; template diff --git a/include/pinocchio/multibody/joint/joint-basic-visitors.hxx b/include/pinocchio/multibody/joint/joint-basic-visitors.hxx index 23a4c40757..d675ef9fa7 100644 --- a/include/pinocchio/multibody/joint/joint-basic-visitors.hxx +++ b/include/pinocchio/multibody/joint/joint-basic-visitors.hxx @@ -1,10 +1,12 @@ // -// Copyright (c) 2016-2020 CNRS INRIA +// Copyright (c) 2016-2024 CNRS INRIA // #ifndef __pinocchio_multibody_joint_basic_visitors_hxx__ #define __pinocchio_multibody_joint_basic_visitors_hxx__ +#include + #include "pinocchio/multibody/joint/joint-basic-visitors.hpp" #include "pinocchio/multibody/visitor.hpp" @@ -41,6 +43,48 @@ namespace pinocchio return CreateJointData::run(jmodel); } + /** + * @brief JointCheckTypeVisitor fusion visitor + */ + template + struct JointCheckTypeVisitor + : fusion::JointUnaryVisitorBase, bool> + { + typedef fusion::NoArg ArgsType; + + template + static bool algo(const pinocchio::JointModelBase &) + { + typedef typename boost::mpl::contains::type result; + return result::value; + } + + template class JointCollectionTpl> + static bool + algo(const ::pinocchio::JointModelCompositeTpl & jmodel) + { + for (const auto & jmodel_internal : jmodel.joints) + { + if (!JointCheckTypeVisitor::run(jmodel_internal)) + return false; + } + + return true; + } + }; + + template< + typename JointModelSequence, + typename Scalar, + int Options, + template class JointCollectionTpl> + inline bool check_joint_type_within_sequence( + const JointModelTpl & jmodel) + { + typedef JointCheckTypeVisitor Algo; + return Algo::run(jmodel); + } + /** * @brief JointCalcZeroOrderVisitor fusion visitor */ diff --git a/include/pinocchio/multibody/joint/joint-collection.hpp b/include/pinocchio/multibody/joint/joint-collection.hpp index 540d8fb3fb..d51b0772b1 100644 --- a/include/pinocchio/multibody/joint/joint-collection.hpp +++ b/include/pinocchio/multibody/joint/joint-collection.hpp @@ -1,5 +1,6 @@ // -// Copyright (c) 2018-2019 CNRS INRIA +// Copyright (c) 2018 CNRS +// Copyright (c) 2018-2025 INRIA // #ifndef __pinocchio_multibody_joint_collection_hpp__ diff --git a/include/pinocchio/multibody/joint/joint-common-operations.hpp b/include/pinocchio/multibody/joint/joint-common-operations.hpp index 8030e507f6..d2b4e8dab8 100644 --- a/include/pinocchio/multibody/joint/joint-common-operations.hpp +++ b/include/pinocchio/multibody/joint/joint-common-operations.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2019 INRIA +// Copyright (c) 2019-2025 INRIA // #ifndef __pinocchio_multibody_joint_joint_common_operations_hpp__ @@ -7,43 +7,10 @@ #include "pinocchio/macros.hpp" #include "pinocchio/math/matrix.hpp" -#include "pinocchio/math/fwd.hpp" - -#include -#include +#include "pinocchio/math/matrix-inverse.hpp" namespace pinocchio { - namespace internal - { - /// - /// \brief Operation called in JointModelBase::calc_aba - /// - template::value> - struct PerformStYSInversion - { - template - static EIGEN_STRONG_INLINE void - run(const Eigen::MatrixBase & StYS, const Eigen::MatrixBase & Dinv) - { - M2 & Dinv_ = PINOCCHIO_EIGEN_CONST_CAST(M2, Dinv); - Dinv_.setIdentity(); - StYS.llt().solveInPlace(Dinv_); - } - }; - - template - struct PerformStYSInversion - { - template - static EIGEN_STRONG_INLINE void - run(const Eigen::MatrixBase & StYS, const Eigen::MatrixBase & Dinv) - { - M2 & Dinv_ = PINOCCHIO_EIGEN_CONST_CAST(M2, Dinv); - inverse(StYS, Dinv_); - } - }; - } // namespace internal /// /// \brief Linear affine transformation of the configuration vector. @@ -59,7 +26,7 @@ namespace pinocchio const Eigen::MatrixBase & qOut) { assert(qIn.size() == qOut.size()); - PINOCCHIO_EIGEN_CONST_CAST(ConfigVectorOut, qOut).noalias() = + qOut.const_cast_derived().noalias() = scaling * qIn + ConfigVectorOut::Constant(qOut.size(), offset); } }; @@ -82,7 +49,7 @@ namespace pinocchio const typename ConfigVectorIn::Scalar & theta = math::atan2(sa, ca); const typename ConfigVectorIn::Scalar & theta_transform = scaling * theta + offset; - ConfigVectorOut & dest_ = PINOCCHIO_EIGEN_CONST_CAST(ConfigVectorOut, qOut); + auto & dest_ = qOut.const_cast_derived(); SINCOS(theta_transform, &dest_.coeffRef(1), &dest_.coeffRef(0)); } }; diff --git a/include/pinocchio/multibody/joint/joint-composite.hpp b/include/pinocchio/multibody/joint/joint-composite.hpp index e36ec56b18..d680d57f32 100644 --- a/include/pinocchio/multibody/joint/joint-composite.hpp +++ b/include/pinocchio/multibody/joint/joint-composite.hpp @@ -48,7 +48,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; - typedef boost::mpl::false_ is_mimicable_t; + typedef std::false_type is_mimicable_t; PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE }; @@ -361,13 +361,17 @@ namespace pinocchio data.StU.noalias() = data.S.matrix().transpose() * data.U; data.StU.diagonal() += armature; - internal::PerformStYSInversion::run(data.StU, data.Dinv); + matrix_inversion(data.StU, data.Dinv); data.UDinv.noalias() = data.U * data.Dinv; if (update_I) - PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose(); + I.const_cast_derived().noalias() -= data.UDinv * data.U.transpose(); } + // Declaration of overload : must be define after Lie group and joint visitors + template + typename LieGroupMap::template operation::type lieGroup_impl() const; + int nv_impl() const { return m_nv; diff --git a/include/pinocchio/multibody/joint/joint-free-flyer.hpp b/include/pinocchio/multibody/joint/joint-free-flyer.hpp index 0de0c5ed53..baa379fefe 100644 --- a/include/pinocchio/multibody/joint/joint-free-flyer.hpp +++ b/include/pinocchio/multibody/joint/joint-free-flyer.hpp @@ -191,7 +191,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; - typedef boost::mpl::false_ is_mimicable_t; + typedef std::false_type is_mimicable_t; PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE }; @@ -384,11 +384,11 @@ namespace pinocchio data.StU = I; data.StU.diagonal() += armature; - internal::PerformStYSInversion::run(data.StU, data.Dinv); + matrix_inversion(data.StU, data.Dinv); data.UDinv.noalias() = I * data.Dinv; if (update_I) - PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose(); + I.const_cast_derived().noalias() -= data.UDinv * data.U.transpose(); } static std::string classname() diff --git a/include/pinocchio/multibody/joint/joint-generic.hpp b/include/pinocchio/multibody/joint/joint-generic.hpp index 975f614544..5bc435d35d 100644 --- a/include/pinocchio/multibody/joint/joint-generic.hpp +++ b/include/pinocchio/multibody/joint/joint-generic.hpp @@ -71,7 +71,7 @@ namespace pinocchio typedef TangentVector_t TangentVectorTypeConstRef; typedef TangentVector_t TangentVectorTypeRef; - typedef boost::mpl::false_ is_mimicable_t; + typedef std::false_type is_mimicable_t; }; template class JointCollectionTpl> @@ -289,6 +289,16 @@ namespace pinocchio { } + template class OtherJointCollectionTpl> + JointModelTpl(const JointModelTpl & other) + { + *this = other; + } + + template class OtherJointCollectionTpl> + JointModelTpl & + operator=(const JointModelTpl & other); + const std::vector hasConfigurationLimit() const { return ::pinocchio::hasConfigurationLimit(*this); @@ -371,6 +381,10 @@ namespace pinocchio calc_first_order(*this, data, q.derived(), v.derived()); } + // Declaration of overload : must be define after Lie group and joint visitors + template + typename LieGroupMap::template operation::type lieGroup_impl() const; + template void calc_aba( JointDataDerived & data, @@ -378,8 +392,7 @@ namespace pinocchio const Eigen::MatrixBase & I, const bool update_I) const { - ::pinocchio::calc_aba( - *this, data, armature.derived(), PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I), update_I); + ::pinocchio::calc_aba(*this, data, armature.derived(), I.const_cast_derived(), update_I); } /* Acces to dedicated segment in robot config space. */ @@ -518,4 +531,6 @@ namespace pinocchio } // namespace pinocchio +#include "pinocchio/multibody/joint/joint-generic.hxx" + #endif // ifndef __pinocchio_multibody_joint_generic_hpp__ diff --git a/include/pinocchio/multibody/joint/joint-generic.hxx b/include/pinocchio/multibody/joint/joint-generic.hxx new file mode 100644 index 0000000000..2d38c5a27f --- /dev/null +++ b/include/pinocchio/multibody/joint/joint-generic.hxx @@ -0,0 +1,93 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_multibody_joint_generic_hxx__ +#define __pinocchio_multibody_joint_generic_hxx__ + +namespace pinocchio +{ + + namespace details + { + template + struct IsContainedInJointCollection + { + typedef typename JointCollection::JointModelVariant ModelVariant; + static constexpr bool value = + boost::mpl::contains(); + }; + + template + struct CopyJointToJointCollection + { + template class JointCollectionTpl> + void operator()( + const JointModelBase & joint_in, + JointModelTpl &) + { + std::stringstream ss; + ss << joint_in.classname(); + ss << " not contained in new joint collection.\n"; + PINOCCHIO_THROW(std::invalid_argument, ss.str()); + } + }; + + template + struct CopyJointToJointCollection + { + template class JointCollectionTpl> + void operator()( + const JointModelBase & joint_in, + JointModelTpl & joint_out) + { + joint_out = joint_in; + } + }; + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + template class OtherJointCollectionTpl> + struct CopyJointFromOtherJointCollection + : fusion::JointUnaryVisitorBase> + { + typedef JointCollectionTpl JointCollection; + typedef OtherJointCollectionTpl OtherJointCollection; + typedef boost::fusion::vector &> ArgsType; + + template + static void algo( + const JointModelDerived & joint_in, + JointModelTpl & joint_out) + { + CopyJointToJointCollection< + IsContainedInJointCollection::value, + JointModelDerived>{}(joint_in, joint_out); + } + }; + + } // namespace details + + template class JointCollectionTpl> + template class OtherJointCollectionTpl> + JointModelTpl & + JointModelTpl::operator=( + const JointModelTpl & other) + { + typedef details::CopyJointFromOtherJointCollection< + Scalar, Options, JointCollectionTpl, OtherJointCollectionTpl> + Algo; + typename Algo::ArgsType args(*this); + Algo::run(other, args); + return *this; + } + +} // namespace pinocchio + +#endif // __pinocchio_multibody_joint_generic_hxx__ diff --git a/include/pinocchio/multibody/joint/joint-helical-unaligned.hpp b/include/pinocchio/multibody/joint/joint-helical-unaligned.hpp index 2c1194a425..cca59d016e 100644 --- a/include/pinocchio/multibody/joint/joint-helical-unaligned.hpp +++ b/include/pinocchio/multibody/joint/joint-helical-unaligned.hpp @@ -547,7 +547,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; - typedef boost::mpl::true_ is_mimicable_t; + typedef std::true_type is_mimicable_t; PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE }; @@ -744,7 +744,7 @@ namespace pinocchio data.Dinv[0] = Scalar(1) / data.StU[0]; data.UDinv.noalias() = data.U * data.Dinv; if (update_I) - PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose(); + I.const_cast_derived().noalias() -= data.UDinv * data.U.transpose(); } static std::string classname() diff --git a/include/pinocchio/multibody/joint/joint-helical.hpp b/include/pinocchio/multibody/joint/joint-helical.hpp index a41ea7a386..49e81ec1b4 100644 --- a/include/pinocchio/multibody/joint/joint-helical.hpp +++ b/include/pinocchio/multibody/joint/joint-helical.hpp @@ -126,7 +126,7 @@ namespace pinocchio template typename SE3GroupAction::ReturnType - se3action(const SE3Tpl & m) const + se3Action(const SE3Tpl & m) const { typedef typename SE3GroupAction::ReturnType ReturnType; ReturnType res; @@ -146,8 +146,8 @@ namespace pinocchio } case 2: { res.rotation().col(0).noalias() = m_cos * m.rotation().col(0) + m_sin * m.rotation().col(1); - res.rotation().col(1).noalias() = res.rotation().col(2).cross(res.rotation().col(0)); res.rotation().col(2) = m.rotation().col(2); + res.rotation().col(1).noalias() = res.rotation().col(2).cross(res.rotation().col(0)); break; } default: { @@ -155,8 +155,8 @@ namespace pinocchio break; } } - res.translation() = m.translation(); - res.translation()[axis] += m_displacement; + res.translation().noalias() = m.translation() + m.rotation().col(axis) * m_displacement; + assert(res.isApprox(m * plain())); return res; } @@ -758,7 +758,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; - typedef boost::mpl::true_ is_mimicable_t; + typedef std::true_type is_mimicable_t; PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE }; @@ -917,7 +917,7 @@ namespace pinocchio data.UDinv.noalias() = data.U * data.Dinv; if (update_I) - PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose(); + I.const_cast_derived().noalias() -= data.UDinv * data.U.transpose(); } static std::string classname() diff --git a/include/pinocchio/multibody/joint/joint-mimic.hpp b/include/pinocchio/multibody/joint/joint-mimic.hpp index 9ea0727e2f..ae961cdeb8 100644 --- a/include/pinocchio/multibody/joint/joint-mimic.hpp +++ b/include/pinocchio/multibody/joint/joint-mimic.hpp @@ -348,7 +348,7 @@ namespace pinocchio typedef const TangentVector_t TangentVectorTypeConstRef; typedef TangentVector_t & TangentVectorTypeRef; - typedef boost::mpl::false_ is_mimicable_t; + typedef std::false_type is_mimicable_t; }; template class JointCollectionTpl> @@ -644,8 +644,8 @@ namespace pinocchio */ void setIndexes_impl(JointIndex id, int /*q*/, int /*v*/, int vExtended) { - PINOCCHIO_THROW( - (id > m_jmodel_mimicking.id()), std::invalid_argument, + PINOCCHIO_THROW_IF( + !(id > m_jmodel_mimicking.id()), std::invalid_argument, "Mimic joint index is lower than its directing joint. Should never happen"); Base::i_id = id; // Base::i_q = q; @@ -873,6 +873,59 @@ namespace pinocchio Mat.derived(), Base::i_v, Base::i_v, m_nvExtended, m_nvExtended); } + /* Acces to dedicated Q releated rows or columns.*/ + // Const access + template + typename SizeDepType::template ColsReturn::ConstType + jointQCols_impl(const Eigen::MatrixBase & A) const + { + return SizeDepType::middleCols(A.derived(), Base::i_q, m_nqExtended); + } + + // Non-const access + template + typename SizeDepType::template ColsReturn::Type + jointQCols_impl(Eigen::MatrixBase & A) const + { + return SizeDepType::middleCols(A.derived(), Base::i_q, m_nqExtended); + } + + // Const access + template + typename SizeDepType::template RowsReturn::ConstType + jointQRows_impl(const Eigen::MatrixBase & A) const + { + return SizeDepType::middleRows(A.derived(), Base::i_q, m_nqExtended); + } + + // Non-const access + template + typename SizeDepType::template RowsReturn::Type + jointQRows_impl(Eigen::MatrixBase & A) const + { + return SizeDepType::middleRows(A.derived(), Base::i_q, m_nqExtended); + } + + /// \brief Returns a block of dimension m_nqExtendedxm_nvExtended located at position + /// idx_q_a,idx_v_a in the matrix Mat + // Const access + template + typename DoubleSizeDepType::template BlockReturn::ConstType + jointQVBlock_impl(const Eigen::MatrixBase & Mat, int idx_q_a, int idx_v_a) const + { + return DoubleSizeDepType::block( + Mat.derived(), idx_q_a, idx_v_a, m_nqExtended, m_nvExtended); + } + + // Non-const access + template + typename DoubleSizeDepType::template BlockReturn::Type + jointQVBlock_impl(Eigen::MatrixBase & Mat, int idx_q_a, int idx_v_a) const + { + return DoubleSizeDepType::block( + Mat.derived(), idx_q_a, idx_v_a, m_nqExtended, m_nvExtended); + } + void disp(std::ostream & os) const { Base::disp(os); diff --git a/include/pinocchio/multibody/joint/joint-model-base.hpp b/include/pinocchio/multibody/joint/joint-model-base.hpp index 93e423dbea..2985f875b1 100644 --- a/include/pinocchio/multibody/joint/joint-model-base.hpp +++ b/include/pinocchio/multibody/joint/joint-model-base.hpp @@ -137,8 +137,21 @@ namespace pinocchio const Eigen::MatrixBase & I, const bool update_I = false) const { - derived().calc_aba( - data, armature.derived(), PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I), update_I); + derived().calc_aba(data, armature.derived(), I.const_cast_derived(), update_I); + } + + template + typename LieGroupMap::template operation::type lieGroup() const + { + return derived().template lieGroup_impl(); + } + + // Default implementation, default construction of the type mapped by the LieGroupMap + template + typename LieGroupMap::template operation::type lieGroup_impl() const + { + typedef typename LieGroupMap::template operation::type lgo; + return lgo(); } int nv() const @@ -586,6 +599,99 @@ namespace pinocchio Mat.derived(), idx_vExtended(), idx_vExtended(), nvExtended(), nvExtended()); } + /* Acces to dedicated Q releated rows or columns.*/ + // Const access + template + typename SizeDepType::template ColsReturn::ConstType + jointQCols(const Eigen::MatrixBase & A) const + { + return derived().jointQCols_impl(A.derived()); + } + + template + typename SizeDepType::template ColsReturn::ConstType + jointQCols_impl(const Eigen::MatrixBase & A) const + { + return SizeDepType::middleCols(A.derived(), idx_q(), nq()); + } + + // Non-const access + template + typename SizeDepType::template ColsReturn::Type + jointQCols(Eigen::MatrixBase & A) const + { + return derived().jointQCols_impl(A.derived()); + } + + template + typename SizeDepType::template ColsReturn::Type + jointQCols_impl(Eigen::MatrixBase & A) const + { + return SizeDepType::middleCols(A.derived(), idx_q(), nq()); + } + + // Const access + template + typename SizeDepType::template RowsReturn::ConstType + jointQRows(const Eigen::MatrixBase & A) const + { + return derived().jointQRows_impl(A.derived()); + } + + template + typename SizeDepType::template RowsReturn::ConstType + jointQRows_impl(const Eigen::MatrixBase & A) const + { + return SizeDepType::middleRows(A.derived(), idx_q(), nq()); + } + + // Non-const access + template + typename SizeDepType::template RowsReturn::Type + jointQRows(Eigen::MatrixBase & A) const + { + return derived().jointQRows_impl(A.derived()); + } + + template + typename SizeDepType::template RowsReturn::Type + jointQRows_impl(Eigen::MatrixBase & A) const + { + return SizeDepType::middleRows(A.derived(), idx_q(), nq()); + } + + /// \brief Returns a block of dimension nq()xnv() located at position idx_q_a,idx_v_a in the + /// matrix Mat + // Const access + template + typename DoubleSizeDepType::template BlockReturn::ConstType + jointQVBlock(const Eigen::MatrixBase & Mat, int idx_q_a, int idx_v_a) const + { + return derived().jointQVBlock_impl(Mat.derived(), idx_q_a, idx_v_a); + } + + template + typename DoubleSizeDepType::template BlockReturn::ConstType + jointQVBlock_impl(const Eigen::MatrixBase & Mat, int idx_q_a, int idx_v_a) const + { + return DoubleSizeDepType::block(Mat.derived(), idx_q_a, idx_v_a, nq(), nv()); + } + + // Non-const access + template + typename DoubleSizeDepType::template BlockReturn::Type + jointQVBlock(Eigen::MatrixBase & Mat, int idx_q_a, int idx_v_a) const + { + return derived().jointQVBlock_impl(Mat.derived(), idx_q_a, idx_v_a); + } + + template + typename DoubleSizeDepType::template BlockReturn::Type + jointQVBlock_impl(Eigen::MatrixBase & Mat, int idx_q_a, int idx_v_a) const + { + return DoubleSizeDepType::block(Mat.derived(), idx_q_a, idx_v_a, nq(), nv()); + } + protected: /// Default constructor: protected. /// diff --git a/include/pinocchio/multibody/joint/joint-planar.hpp b/include/pinocchio/multibody/joint/joint-planar.hpp index 5164f608f2..707f9a5361 100644 --- a/include/pinocchio/multibody/joint/joint-planar.hpp +++ b/include/pinocchio/multibody/joint/joint-planar.hpp @@ -494,7 +494,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; - typedef boost::mpl::false_ is_mimicable_t; + typedef std::false_type is_mimicable_t; PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE }; @@ -653,12 +653,12 @@ namespace pinocchio data.StU.template rightCols<1>() = data.U.template bottomRows<1>(); data.StU.diagonal() += armature; - internal::PerformStYSInversion::run(data.StU, data.Dinv); + matrix_inversion(data.StU, data.Dinv); data.UDinv.noalias() = data.U * data.Dinv; if (update_I) - PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose(); + I.const_cast_derived().noalias() -= data.UDinv * data.U.transpose(); } static std::string classname() diff --git a/include/pinocchio/multibody/joint/joint-prismatic-unaligned.hpp b/include/pinocchio/multibody/joint/joint-prismatic-unaligned.hpp index 9296725619..bc6416e2da 100644 --- a/include/pinocchio/multibody/joint/joint-prismatic-unaligned.hpp +++ b/include/pinocchio/multibody/joint/joint-prismatic-unaligned.hpp @@ -501,7 +501,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; - typedef boost::mpl::true_ is_mimicable_t; + typedef std::true_type is_mimicable_t; PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE }; @@ -680,7 +680,7 @@ namespace pinocchio data.UDinv.noalias() = data.U * data.Dinv; if (update_I) - PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose(); + I.const_cast_derived().noalias() -= data.UDinv * data.U.transpose(); } static std::string classname() diff --git a/include/pinocchio/multibody/joint/joint-prismatic.hpp b/include/pinocchio/multibody/joint/joint-prismatic.hpp index 1bca694ce7..c3b9232755 100644 --- a/include/pinocchio/multibody/joint/joint-prismatic.hpp +++ b/include/pinocchio/multibody/joint/joint-prismatic.hpp @@ -261,12 +261,13 @@ namespace pinocchio template typename SE3GroupAction::ReturnType - se3action(const SE3Tpl & m) const + se3Action(const SE3Tpl & m) const { typedef typename SE3GroupAction::ReturnType ReturnType; ReturnType res(m); - res.translation()[axis] += m_displacement; + res.translation().noalias() += m.rotation().col(axis) * m_displacement; + assert(res.isApprox(m * plain())); return res; } @@ -593,7 +594,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; - typedef boost::mpl::true_ is_mimicable_t; + typedef std::true_type is_mimicable_t; PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE }; @@ -736,7 +737,7 @@ namespace pinocchio data.UDinv.noalias() = data.U * data.Dinv[0]; if (update_I) - PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose(); + I.const_cast_derived().noalias() -= data.UDinv * data.U.transpose(); } static std::string classname() diff --git a/include/pinocchio/multibody/joint/joint-revolute-unaligned.hpp b/include/pinocchio/multibody/joint/joint-revolute-unaligned.hpp index fc203cad09..3f56c75e8e 100644 --- a/include/pinocchio/multibody/joint/joint-revolute-unaligned.hpp +++ b/include/pinocchio/multibody/joint/joint-revolute-unaligned.hpp @@ -526,7 +526,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; - typedef boost::mpl::true_ is_mimicable_t; + typedef std::true_type is_mimicable_t; PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE }; @@ -704,7 +704,7 @@ namespace pinocchio data.UDinv.noalias() = data.U * data.Dinv; if (update_I) - PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose(); + I.const_cast_derived().noalias() -= data.UDinv * data.U.transpose(); } static std::string classname() diff --git a/include/pinocchio/multibody/joint/joint-revolute-unbounded-unaligned.hpp b/include/pinocchio/multibody/joint/joint-revolute-unbounded-unaligned.hpp index 7cf88098b1..7c14a6570c 100644 --- a/include/pinocchio/multibody/joint/joint-revolute-unbounded-unaligned.hpp +++ b/include/pinocchio/multibody/joint/joint-revolute-unbounded-unaligned.hpp @@ -49,7 +49,7 @@ namespace pinocchio typedef Eigen::Matrix D_t; typedef Eigen::Matrix UD_t; - typedef boost::mpl::true_ is_mimicable_t; + typedef std::true_type is_mimicable_t; PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE }; @@ -232,7 +232,7 @@ namespace pinocchio data.UDinv.noalias() = data.U * data.Dinv; if (update_I) - PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose(); + I.const_cast_derived().noalias() -= data.UDinv * data.U.transpose(); } static std::string classname() diff --git a/include/pinocchio/multibody/joint/joint-revolute-unbounded.hpp b/include/pinocchio/multibody/joint/joint-revolute-unbounded.hpp index 90ae6d7d8a..1c098e5cd4 100644 --- a/include/pinocchio/multibody/joint/joint-revolute-unbounded.hpp +++ b/include/pinocchio/multibody/joint/joint-revolute-unbounded.hpp @@ -46,7 +46,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; - typedef boost::mpl::true_ is_mimicable_t; + typedef std::true_type is_mimicable_t; PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE }; @@ -194,7 +194,7 @@ namespace pinocchio data.UDinv.noalias() = data.U * data.Dinv[0]; if (update_I) - PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose(); + I.const_cast_derived().noalias() -= data.UDinv * data.U.transpose(); } static std::string classname() diff --git a/include/pinocchio/multibody/joint/joint-revolute.hpp b/include/pinocchio/multibody/joint/joint-revolute.hpp index bbff93fdbe..0a7453d4f9 100644 --- a/include/pinocchio/multibody/joint/joint-revolute.hpp +++ b/include/pinocchio/multibody/joint/joint-revolute.hpp @@ -80,9 +80,17 @@ namespace pinocchio typedef Matrix3 AngularType; typedef Matrix3 AngularRef; typedef Matrix3 ConstAngularRef; +#if EIGEN_VERSION_AT_LEAST(3, 4, 90) + typedef typename Vector3::ZeroReturnType LinearType; + typedef const typename Vector3::ZeroReturnType ConstLinearType; + typedef typename Vector3::ZeroReturnType LinearRef; + typedef const typename Vector3::ZeroReturnType ConstLinearRef; +#else typedef typename Vector3::ConstantReturnType LinearType; + typedef const typename Vector3::ConstantReturnType ConstLinearType; typedef typename Vector3::ConstantReturnType LinearRef; typedef const typename Vector3::ConstantReturnType ConstLinearRef; +#endif typedef typename traits::ActionMatrixType ActionMatrixType; typedef typename traits::HomogeneousMatrixType HomogeneousMatrixType; }; // traits TransformRevoluteTpl @@ -98,6 +106,7 @@ namespace pinocchio { EIGEN_MAKE_ALIGNED_OPERATOR_NEW PINOCCHIO_SE3_TYPEDEF_TPL(TransformRevoluteTpl); + typedef typename traits::ConstLinearType ConstLinearType; TransformRevoluteTpl() { @@ -122,7 +131,7 @@ namespace pinocchio template typename SE3GroupAction::ReturnType - se3action(const SE3Tpl & m) const + se3Action(const SE3Tpl & m) const { typedef typename SE3GroupAction::ReturnType ReturnType; ReturnType res; @@ -142,8 +151,8 @@ namespace pinocchio } case 2: { res.rotation().col(0).noalias() = m_cos * m.rotation().col(0) + m_sin * m.rotation().col(1); - res.rotation().col(1).noalias() = res.rotation().col(2).cross(res.rotation().col(0)); res.rotation().col(2) = m.rotation().col(2); + res.rotation().col(1).noalias() = res.rotation().col(2).cross(res.rotation().col(0)); break; } default: { @@ -152,6 +161,7 @@ namespace pinocchio } } res.translation() = m.translation(); + assert(res.isApprox(m * plain())); return res; } @@ -180,9 +190,9 @@ namespace pinocchio m_cos = cos; } - LinearType translation() const + ConstLinearType translation() const { - return LinearType::PlainObject::Zero(3); + return ConstLinearType::PlainObject::Zero(3); } AngularType rotation() const { @@ -682,7 +692,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; - typedef boost::mpl::true_ is_mimicable_t; + typedef std::true_type is_mimicable_t; PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE }; @@ -832,7 +842,7 @@ namespace pinocchio data.UDinv.noalias() = data.U * data.Dinv[0]; if (update_I) - PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose(); + I.const_cast_derived().noalias() -= data.UDinv * data.U.transpose(); } static std::string classname() diff --git a/include/pinocchio/multibody/joint/joint-spherical-ZYX.hpp b/include/pinocchio/multibody/joint/joint-spherical-ZYX.hpp index 14eed470ec..87bcde5bb6 100644 --- a/include/pinocchio/multibody/joint/joint-spherical-ZYX.hpp +++ b/include/pinocchio/multibody/joint/joint-spherical-ZYX.hpp @@ -302,7 +302,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; - typedef boost::mpl::false_ is_mimicable_t; + typedef std::false_type is_mimicable_t; PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE }; @@ -481,12 +481,12 @@ namespace pinocchio data.S.angularSubspace().transpose() * data.U.template middleRows<3>(Motion::ANGULAR); data.StU.diagonal() += armature; - internal::PerformStYSInversion::run(data.StU, data.Dinv); + matrix_inversion(data.StU, data.Dinv); data.UDinv.noalias() = data.U * data.Dinv; if (update_I) - PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose(); + I.const_cast_derived().noalias() -= data.UDinv * data.U.transpose(); } static std::string classname() diff --git a/include/pinocchio/multibody/joint/joint-spherical.hpp b/include/pinocchio/multibody/joint/joint-spherical.hpp index e970644a2a..9c4a18c637 100644 --- a/include/pinocchio/multibody/joint/joint-spherical.hpp +++ b/include/pinocchio/multibody/joint/joint-spherical.hpp @@ -405,7 +405,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; - typedef boost::mpl::false_ is_mimicable_t; + typedef std::false_type is_mimicable_t; PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE }; @@ -582,11 +582,11 @@ namespace pinocchio data.StU = data.U.template middleRows<3>(Inertia::ANGULAR); data.StU.diagonal() += armature; - internal::PerformStYSInversion::run(data.StU, data.Dinv); + matrix_inversion(data.StU, data.Dinv); data.UDinv.noalias() = data.U * data.Dinv; if (update_I) - PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose(); + I.const_cast_derived().noalias() -= data.UDinv * data.U.transpose(); } static std::string classname() diff --git a/include/pinocchio/multibody/joint/joint-translation.hpp b/include/pinocchio/multibody/joint/joint-translation.hpp index 5520c5a0ab..880de86900 100644 --- a/include/pinocchio/multibody/joint/joint-translation.hpp +++ b/include/pinocchio/multibody/joint/joint-translation.hpp @@ -257,12 +257,13 @@ namespace pinocchio template typename SE3GroupAction::ReturnType - se3action(const SE3Tpl & m) const + se3Action(const SE3Tpl & m) const { typedef typename SE3GroupAction::ReturnType ReturnType; ReturnType res(m); - res.translation() += translation(); + res.translation().noalias() += m.rotation() * translation(); + assert(res.isApprox(m * plain())); return res; } @@ -502,7 +503,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; - typedef boost::mpl::false_ is_mimicable_t; + typedef std::false_type is_mimicable_t; PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE }; // traits JointTranslationTpl @@ -638,12 +639,12 @@ namespace pinocchio data.StU = data.U.template middleRows<3>(Inertia::LINEAR); data.StU.diagonal() += armature; - internal::PerformStYSInversion::run(data.StU, data.Dinv); + matrix_inversion(data.StU, data.Dinv); data.UDinv.noalias() = data.U * data.Dinv; if (update_I) - PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose(); + I.const_cast_derived().noalias() -= data.UDinv * data.U.transpose(); } static std::string classname() diff --git a/include/pinocchio/multibody/joint/joint-universal.hpp b/include/pinocchio/multibody/joint/joint-universal.hpp index 75b7cbb485..0eb7b571bf 100644 --- a/include/pinocchio/multibody/joint/joint-universal.hpp +++ b/include/pinocchio/multibody/joint/joint-universal.hpp @@ -336,7 +336,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; - typedef boost::mpl::false_ is_mimicable_t; + typedef std::false_type is_mimicable_t; PINOCCHIO_JOINT_DATA_BASE_ACCESSOR_DEFAULT_RETURN_TYPE }; @@ -581,12 +581,12 @@ namespace pinocchio data.StU.noalias() = data.S.angularSubspace().transpose() * data.U.template middleRows<3>(Motion::ANGULAR); data.StU.diagonal() += armature; - internal::PerformStYSInversion::run(data.StU, data.Dinv); + matrix_inversion(data.StU, data.Dinv); data.UDinv.noalias() = data.U * data.Dinv; if (update_I) - PINOCCHIO_EIGEN_CONST_CAST(Matrix6Like, I).noalias() -= data.UDinv * data.U.transpose(); + I.const_cast_derived().noalias() -= data.UDinv * data.U.transpose(); } static std::string classname() diff --git a/include/pinocchio/multibody/liegroup/cartesian-product-variant.hpp b/include/pinocchio/multibody/liegroup/cartesian-product-variant.hpp index e5b3e3fd6a..9577d59bc2 100644 --- a/include/pinocchio/multibody/liegroup/cartesian-product-variant.hpp +++ b/include/pinocchio/multibody/liegroup/cartesian-product-variant.hpp @@ -258,6 +258,26 @@ namespace pinocchio const Eigen::MatrixBase & v, const Eigen::MatrixBase & J) const; + template + void tangentMap_impl( + const Eigen::MatrixBase & q, + Eigen::MatrixBase & TM, + const AssignmentOperatorType op) const; + + template + void tangentMapProduct_impl( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) const; + + template + void tangentMapTransposeProduct_impl( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) const; + template Scalar squaredDistance_impl( const Eigen::MatrixBase & q0, const Eigen::MatrixBase & q1) const; diff --git a/include/pinocchio/multibody/liegroup/cartesian-product-variant.hxx b/include/pinocchio/multibody/liegroup/cartesian-product-variant.hxx index 5d1d959563..f3601273ce 100644 --- a/include/pinocchio/multibody/liegroup/cartesian-product-variant.hxx +++ b/include/pinocchio/multibody/liegroup/cartesian-product-variant.hxx @@ -23,6 +23,7 @@ namespace pinocchio m_nv += lg_nv; if (liegroups.size() > 1) + // Was not empty before the append m_name += " x "; m_name += ::pinocchio::name(lg); @@ -231,6 +232,69 @@ namespace pinocchio } } + template class LieGroupCollectionTpl> + template + void + CartesianProductOperationVariantTpl<_Scalar, _Options, LieGroupCollectionTpl>::tangentMap_impl( + const Eigen::MatrixBase & q, + Eigen::MatrixBase & TM, + const AssignmentOperatorType op) const + { + if (op == SETTO) + TM.setZero(); + Index id_q = 0, id_v = 0; + for (size_t k = 0; k < liegroups.size(); ++k) + { + const Index & nq = lg_nqs[k]; + const Index & nv = lg_nvs[k]; + ::pinocchio::tangentMap(liegroups[k], q.segment(id_q, nq), TM.block(id_q, id_v, nq, nv), op); + id_q += nq; + id_v += nv; + } + } + + template class LieGroupCollectionTpl> + template + void CartesianProductOperationVariantTpl<_Scalar, _Options, LieGroupCollectionTpl>:: + tangentMapProduct_impl( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) const + { + Index id_q = 0, id_v = 0; + for (size_t k = 0; k < liegroups.size(); ++k) + { + const Index & nq = lg_nqs[k]; + const Index & nv = lg_nvs[k]; + ::pinocchio::tangentMapProduct( + liegroups[k], q.segment(id_q, nq), Min.middleRows(id_v, nv), Mout.middleRows(id_q, nq), op); + id_q += nq; + id_v += nv; + } + } + + template class LieGroupCollectionTpl> + template + void CartesianProductOperationVariantTpl<_Scalar, _Options, LieGroupCollectionTpl>:: + tangentMapTransposeProduct_impl( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) const + { + Index id_q = 0, id_v = 0; + for (size_t k = 0; k < liegroups.size(); ++k) + { + const Index & nq = lg_nqs[k]; + const Index & nv = lg_nvs[k]; + ::pinocchio::tangentMapTransposeProduct( + liegroups[k], q.segment(id_q, nq), Min.middleRows(id_q, nq), Mout.middleRows(id_v, nv), op); + id_q += nq; + id_v += nv; + } + } + template class LieGroupCollectionTpl> template void CartesianProductOperationVariantTpl<_Scalar, _Options, LieGroupCollectionTpl>:: @@ -483,7 +547,8 @@ namespace pinocchio if (other.liegroups.size() > 0) { - if (liegroups.size()) + if (liegroups.size() > other.liegroups.size()) + // Was not empty before concat m_name += " x "; m_name += other.m_name; } diff --git a/include/pinocchio/multibody/liegroup/cartesian-product.hpp b/include/pinocchio/multibody/liegroup/cartesian-product.hpp index f81b16499a..a42e106265 100644 --- a/include/pinocchio/multibody/liegroup/cartesian-product.hpp +++ b/include/pinocchio/multibody/liegroup/cartesian-product.hpp @@ -189,6 +189,57 @@ namespace pinocchio } } + template + void tangentMap_impl( + const Eigen::MatrixBase & q, + Eigen::MatrixBase & TM, + const AssignmentOperatorType op) const + { + switch (op) + { + case SETTO: + TM12(TM).setZero(); + TM21(TM).setZero(); + // fallthrough + case ADDTO: + case RMTO: + lg1.tangentMap(Q1(q), TM11(TM), op); + lg2.tangentMap(Q2(q), TM22(TM), op); + break; + default: + assert(false && "Wrong Op requesed value"); + break; + } + } + + template + void tangentMapProduct_impl( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) const + { + lg1.tangentMapProduct( + Q1(q), Min.template topRows(), Mout.template topRows(), op); + lg2.tangentMapProduct( + Q2(q), Min.template bottomRows(), Mout.template bottomRows(), + op); + } + + template + void tangentMapTransposeProduct_impl( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) const + { + lg1.tangentMapTransposeProduct( + Q1(q), Min.template topRows(), Mout.template topRows(), op); + lg2.tangentMapTransposeProduct( + Q2(q), Min.template bottomRows(), Mout.template bottomRows(), + op); + } + template void dIntegrateTransport_dq_impl( const Eigen::MatrixBase & q, @@ -387,6 +438,32 @@ namespace pinocchio return PINOCCHIO_EIGEN_CONST_CAST(Jac, J) .template bottomRightCorner(lg2.nv(), lg2.nv()); } + + template + Eigen::Block TM11(const Eigen::MatrixBase & TM) const + { + return PINOCCHIO_EIGEN_CONST_CAST(TM_t, TM) + .template topLeftCorner(lg1.nq(), lg1.nv()); + } + template + Eigen::Block TM12(const Eigen::MatrixBase & TM) const + { + return PINOCCHIO_EIGEN_CONST_CAST(TM_t, TM) + .template topRightCorner(lg1.nq(), lg2.nv()); + } + template + Eigen::Block TM21(const Eigen::MatrixBase & TM) const + { + return PINOCCHIO_EIGEN_CONST_CAST(TM_t, TM) + .template bottomLeftCorner(lg2.nq(), lg1.nv()); + } + template + Eigen::Block TM22(const Eigen::MatrixBase & TM) const + { + return PINOCCHIO_EIGEN_CONST_CAST(TM_t, TM) + .template bottomRightCorner(lg2.nq(), lg2.nv()); + } + #undef REMOVE_IF_EIGEN_TOO_LOW }; // struct CartesianProductOperation diff --git a/include/pinocchio/multibody/liegroup/liegroup-algo.hxx b/include/pinocchio/multibody/liegroup/liegroup-algo.hxx index 374d5aaea7..2560b687fe 100644 --- a/include/pinocchio/multibody/liegroup/liegroup-algo.hxx +++ b/include/pinocchio/multibody/liegroup/liegroup-algo.hxx @@ -7,13 +7,14 @@ #include "pinocchio/multibody/visitor.hpp" #include "pinocchio/multibody/joint/joint-composite.hpp" +#include "pinocchio/multibody/joint/joint-mimic.hpp" namespace pinocchio { namespace details { - template + template struct Dispatch { template< @@ -25,7 +26,7 @@ namespace pinocchio run(const JointModelCompositeTpl & jmodel, ArgsType args) { for (size_t i = 0; i < jmodel.joints.size(); ++i) - Algo::run(jmodel.joints[i], args); + Visitor::run(jmodel.joints[i], args); } }; @@ -42,61 +43,161 @@ namespace pinocchio PINOCCHIO_DETAILS_WRITE_ARGS_4(JM), typename boost::fusion::result_of::at_c::type a4 #define PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_1(Algo) \ - template \ - struct Algo> \ + template< \ + typename Visitor, typename _Scalar, int _Options, \ + template class JointCollection> \ + struct Algo> \ { \ typedef typename Visitor::ArgsType ArgsType; \ - static void run(PINOCCHIO_DETAILS_WRITE_ARGS_1(JointModelCompositeTpl)) \ + typedef JointModelCompositeTpl<_Scalar, _Options, JointCollection> JointModelComposite; \ + static void run(PINOCCHIO_DETAILS_WRITE_ARGS_1(JointModelComposite)) \ { \ ::pinocchio::details::Dispatch::run(jmodel.derived(), ArgsType(a0)); \ } \ } #define PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_2(Algo) \ - template \ - struct Algo> \ + template< \ + typename Visitor, typename _Scalar, int _Options, \ + template class JointCollection> \ + struct Algo> \ { \ typedef typename Visitor::ArgsType ArgsType; \ - static void run(PINOCCHIO_DETAILS_WRITE_ARGS_2(JointModelCompositeTpl)) \ + typedef JointModelCompositeTpl<_Scalar, _Options, JointCollection> JointModelComposite; \ + static void run(PINOCCHIO_DETAILS_WRITE_ARGS_2(JointModelComposite)) \ { \ ::pinocchio::details::Dispatch::run(jmodel.derived(), ArgsType(a0, a1)); \ } \ } #define PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_3(Algo) \ - template \ - struct Algo> \ + template< \ + typename Visitor, typename _Scalar, int _Options, \ + template class JointCollection> \ + struct Algo> \ { \ typedef typename Visitor::ArgsType ArgsType; \ - static void run(PINOCCHIO_DETAILS_WRITE_ARGS_3(JointModelCompositeTpl)) \ + typedef JointModelCompositeTpl<_Scalar, _Options, JointCollection> JointModelComposite; \ + static void run(PINOCCHIO_DETAILS_WRITE_ARGS_3(JointModelComposite)) \ { \ ::pinocchio::details::Dispatch::run(jmodel.derived(), ArgsType(a0, a1, a2)); \ } \ } #define PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_4(Algo) \ - template \ - struct Algo> \ + template< \ + typename Visitor, typename _Scalar, int _Options, \ + template class JointCollection> \ + struct Algo> \ { \ typedef typename Visitor::ArgsType ArgsType; \ - static void run(PINOCCHIO_DETAILS_WRITE_ARGS_4(JointModelCompositeTpl)) \ + typedef JointModelCompositeTpl<_Scalar, _Options, JointCollection> JointModelComposite; \ + static void run(PINOCCHIO_DETAILS_WRITE_ARGS_4(JointModelComposite)) \ { \ ::pinocchio::details::Dispatch::run(jmodel.derived(), ArgsType(a0, a1, a2, a3)); \ } \ } #define PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_5(Algo) \ - template \ - struct Algo> \ + template< \ + typename Visitor, typename _Scalar, int _Options, \ + template class JointCollection> \ + struct Algo> \ { \ typedef typename Visitor::ArgsType ArgsType; \ - static void run(PINOCCHIO_DETAILS_WRITE_ARGS_5(JointModelCompositeTpl)) \ + typedef JointModelCompositeTpl<_Scalar, _Options, JointCollection> JointModelComposite; \ + static void run(PINOCCHIO_DETAILS_WRITE_ARGS_5(JointModelComposite)) \ { \ ::pinocchio::details::Dispatch::run( \ jmodel.derived(), ArgsType(a0, a1, a2, a3, a4)); \ } \ } +#define PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_1(Algo) \ + template< \ + typename Visitor, typename _Scalar, int _Options, \ + template class JointCollection> \ + struct Algo> \ + { \ + typedef typename Visitor::ArgsType ArgsType; \ + typedef JointModelMimicTpl<_Scalar, _Options, JointCollection> JointModelMimic; \ + static void run(PINOCCHIO_DETAILS_WRITE_ARGS_1(JointModelMimic)) \ + { \ + PINOCCHIO_UNUSED_VARIABLE(jmodel); \ + PINOCCHIO_UNUSED_VARIABLE(a0); \ + } \ + } + +#define PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_2(Algo) \ + template< \ + typename Visitor, typename _Scalar, int _Options, \ + template class JointCollection> \ + struct Algo> \ + { \ + typedef typename Visitor::ArgsType ArgsType; \ + typedef JointModelMimicTpl<_Scalar, _Options, JointCollection> JointModelMimic; \ + static void run(PINOCCHIO_DETAILS_WRITE_ARGS_2(JointModelMimic)) \ + { \ + PINOCCHIO_UNUSED_VARIABLE(jmodel); \ + PINOCCHIO_UNUSED_VARIABLE(a0); \ + PINOCCHIO_UNUSED_VARIABLE(a1); \ + } \ + } + +#define PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_3(Algo) \ + template< \ + typename Visitor, typename _Scalar, int _Options, \ + template class JointCollection> \ + struct Algo> \ + { \ + typedef typename Visitor::ArgsType ArgsType; \ + typedef JointModelMimicTpl<_Scalar, _Options, JointCollection> JointModelMimic; \ + static void run(PINOCCHIO_DETAILS_WRITE_ARGS_3(JointModelMimic)) \ + { \ + PINOCCHIO_UNUSED_VARIABLE(jmodel); \ + PINOCCHIO_UNUSED_VARIABLE(a0); \ + PINOCCHIO_UNUSED_VARIABLE(a1); \ + PINOCCHIO_UNUSED_VARIABLE(a2); \ + } \ + } + +#define PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_4(Algo) \ + template< \ + typename Visitor, typename _Scalar, int _Options, \ + template class JointCollection> \ + struct Algo> \ + { \ + typedef typename Visitor::ArgsType ArgsType; \ + typedef JointModelMimicTpl<_Scalar, _Options, JointCollection> JointModelMimic; \ + static void run(PINOCCHIO_DETAILS_WRITE_ARGS_4(JointModelMimic)) \ + { \ + PINOCCHIO_UNUSED_VARIABLE(jmodel); \ + PINOCCHIO_UNUSED_VARIABLE(a0); \ + PINOCCHIO_UNUSED_VARIABLE(a1); \ + PINOCCHIO_UNUSED_VARIABLE(a2); \ + PINOCCHIO_UNUSED_VARIABLE(a3); \ + } \ + } + +#define PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_5(Algo) \ + template< \ + typename Visitor, typename _Scalar, int _Options, \ + template class JointCollection> \ + struct Algo> \ + { \ + typedef typename Visitor::ArgsType ArgsType; \ + typedef JointModelMimicTpl<_Scalar, _Options, JointCollection> JointModelMimic; \ + static void run(PINOCCHIO_DETAILS_WRITE_ARGS_5(JointModelMimic)) \ + { \ + PINOCCHIO_UNUSED_VARIABLE(jmodel); \ + PINOCCHIO_UNUSED_VARIABLE(a0); \ + PINOCCHIO_UNUSED_VARIABLE(a1); \ + PINOCCHIO_UNUSED_VARIABLE(a2); \ + PINOCCHIO_UNUSED_VARIABLE(a3); \ + PINOCCHIO_UNUSED_VARIABLE(a4); \ + } \ + } + #define PINOCCHIO_DETAILS_VISITOR_METHOD_ALGO_1(Algo, Visitor) \ typedef LieGroup_t LieGroupMap; \ template \ @@ -203,6 +304,7 @@ namespace pinocchio }; PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_3(IntegrateStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_3(IntegrateStepAlgo); template struct dIntegrateStepAlgo; @@ -249,6 +351,176 @@ namespace pinocchio }; PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_5(dIntegrateStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_5(dIntegrateStepAlgo); + + template + struct TangentMapStepAlgo; + + template + struct TangentMapStep + : public fusion::JointUnaryVisitorBase< + TangentMapStep> + { + typedef boost::fusion:: + vector + ArgsType; + + PINOCCHIO_DETAILS_VISITOR_METHOD_ALGO_3(TangentMapStepAlgo, TangentMapStep) + }; + + template + struct TangentMapStepAlgo + { + template + static void run( + const JointModelBase & jmodel, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & TM, + const AssignmentOperatorType & op) + { + typedef typename Visitor::LieGroupMap LieGroupMap; + + typename LieGroupMap::template operation::type lgo; + lgo.tangentMap( + jmodel.jointConfigSelector(q.derived()), + jmodel.jointQVBlock( + PINOCCHIO_EIGEN_CONST_CAST(TangentMapMatrixType, TM), jmodel.idx_q(), jmodel.idx_v()), + op); + } + }; + + PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_3(TangentMapStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_3(TangentMapStepAlgo); + + template + struct CompactSetTangentMapStepAlgo; + + template + struct CompactSetTangentMapStep + : public fusion::JointUnaryVisitorBase< + CompactSetTangentMapStep> + { + typedef boost::fusion::vector + ArgsType; + + PINOCCHIO_DETAILS_VISITOR_METHOD_ALGO_3(CompactSetTangentMapStepAlgo, CompactSetTangentMapStep) + }; + + template + struct CompactSetTangentMapStepAlgo + { + template + static void run( + const JointModelBase & jmodel, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & TMc, + int & idx) + { + typedef typename Visitor::LieGroupMap LieGroupMap; + assert(jmodel.nv() <= TMc.cols()); + typename LieGroupMap::template operation::type lgo; + lgo.tangentMap( + jmodel.jointConfigSelector(q.derived()), + jmodel.jointQVBlock( + PINOCCHIO_EIGEN_CONST_CAST(CompactSetTangentMapMatrixType, TMc), idx, 0), + SETTO); + idx += jmodel.nq(); + } + }; + + PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_3(CompactSetTangentMapStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_3(CompactSetTangentMapStepAlgo); + + template + struct TangentMapProductStepAlgo; + + template< + typename LieGroup_t, + typename ConfigVectorIn, + typename MatrixInType, + typename MatrixOutType> + struct TangentMapProductStep + : public fusion::JointUnaryVisitorBase< + TangentMapProductStep> + { + typedef boost::fusion::vector< + const ConfigVectorIn &, + const MatrixInType &, + MatrixOutType &, + const AssignmentOperatorType &> + ArgsType; + + PINOCCHIO_DETAILS_VISITOR_METHOD_ALGO_4(TangentMapProductStepAlgo, TangentMapProductStep) + }; + + template + struct TangentMapProductStepAlgo + { + template + static void run( + const JointModelBase & jmodel, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & mat_in, + const Eigen::MatrixBase & mat_out, + const AssignmentOperatorType & op) + { + typedef typename Visitor::LieGroupMap LieGroupMap; + + typename LieGroupMap::template operation::type lgo; + lgo.tangentMapProduct( + jmodel.jointConfigSelector(q.derived()), jmodel.jointRows(mat_in.derived()), + jmodel.jointQRows(PINOCCHIO_EIGEN_CONST_CAST(MatrixOutType, mat_out)), op); + } + }; + + PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_4(TangentMapProductStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_4(TangentMapProductStepAlgo); + + template + struct TangentMapTransposeProductStepAlgo; + + template< + typename LieGroup_t, + typename ConfigVectorIn, + typename MatrixInType, + typename MatrixOutType> + struct TangentMapTransposeProductStep + : public fusion::JointUnaryVisitorBase< + TangentMapTransposeProductStep> + { + typedef boost::fusion::vector< + const ConfigVectorIn &, + const MatrixInType &, + MatrixOutType &, + const AssignmentOperatorType &> + ArgsType; + + PINOCCHIO_DETAILS_VISITOR_METHOD_ALGO_4( + TangentMapTransposeProductStepAlgo, TangentMapTransposeProductStep) + }; + + template + struct TangentMapTransposeProductStepAlgo + { + template + static void run( + const JointModelBase & jmodel, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & mat_in, + const Eigen::MatrixBase & mat_out, + const AssignmentOperatorType & op) + { + typedef typename Visitor::LieGroupMap LieGroupMap; + + typename LieGroupMap::template operation::type lgo; + lgo.tangentMapTransposeProduct( + jmodel.jointConfigSelector(q.derived()), jmodel.jointQRows(mat_in.derived()), + jmodel.jointRows(PINOCCHIO_EIGEN_CONST_CAST(MatrixOutType, mat_out)), op); + } + }; + + PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_4(TangentMapTransposeProductStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_4(TangentMapTransposeProductStepAlgo); template struct dIntegrateTransportStepAlgo; @@ -305,6 +577,7 @@ namespace pinocchio }; PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_5(dIntegrateTransportStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_5(dIntegrateTransportStepAlgo); template struct dIntegrateTransportInPlaceStepAlgo; @@ -353,6 +626,7 @@ namespace pinocchio }; PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_4(dIntegrateTransportInPlaceStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_4(dIntegrateTransportInPlaceStepAlgo); template struct dDifferenceStepAlgo; @@ -397,6 +671,7 @@ namespace pinocchio }; PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_4(dDifferenceStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_4(dDifferenceStepAlgo); template struct InterpolateStepAlgo; @@ -443,6 +718,7 @@ namespace pinocchio }; PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_4(InterpolateStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_4(InterpolateStepAlgo); template struct DifferenceStepAlgo; @@ -483,6 +759,7 @@ namespace pinocchio }; PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_3(DifferenceStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_3(DifferenceStepAlgo); template struct SquaredDistanceStepAlgo; @@ -526,6 +803,7 @@ namespace pinocchio }; PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_4(SquaredDistanceStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_4(SquaredDistanceStepAlgo); template struct SquaredDistanceSumStepAlgo; @@ -559,6 +837,7 @@ namespace pinocchio }; PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_3(SquaredDistanceSumStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_3(SquaredDistanceSumStepAlgo); template struct RandomConfigurationStepAlgo; @@ -600,6 +879,7 @@ namespace pinocchio }; PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_3(RandomConfigurationStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_3(RandomConfigurationStepAlgo); template struct NormalizeStepAlgo; @@ -628,6 +908,7 @@ namespace pinocchio }; PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_1(NormalizeStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_1(NormalizeStepAlgo); template struct IsNormalizedStepAlgo; @@ -659,6 +940,7 @@ namespace pinocchio }; PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_3(IsNormalizedStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_3(IsNormalizedStepAlgo); template struct IsSameConfigurationStepAlgo; @@ -695,6 +977,7 @@ namespace pinocchio }; PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_4(IsSameConfigurationStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_4(IsSameConfigurationStepAlgo); template struct NeutralStepAlgo; @@ -725,6 +1008,7 @@ namespace pinocchio }; PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_1(NeutralStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_1(NeutralStepAlgo); template struct IntegrateCoeffWiseJacobianStepAlgo; @@ -762,6 +1046,67 @@ namespace pinocchio }; PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_2(IntegrateCoeffWiseJacobianStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_2(IntegrateCoeffWiseJacobianStepAlgo); + + template + struct LieGroupInstanceStepAlgo; + + template + struct LieGroupInstanceStep + : public fusion::JointUnaryVisitorBase> + { + typedef typename LieGroup_t::template operationProduct::type LgType; + + typedef boost::fusion::vector ArgsType; + + PINOCCHIO_DETAILS_VISITOR_METHOD_ALGO_1(LieGroupInstanceStepAlgo, LieGroupInstanceStep) + }; + + template + struct LieGroupInstanceStepAlgo + { + typedef typename Visitor::LgType LgType; + + static void run(const JointModelBase & jmodel, LgType & res_lgo) + { + typedef typename Visitor::LieGroupMap LieGroupMap; + res_lgo *= jmodel.template lieGroup(); + } + }; + + PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_1(LieGroupInstanceStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_1(LieGroupInstanceStepAlgo); + + template + struct IndexvInfoStepAlgo; + + struct IndexvInfoStep : public fusion::JointUnaryVisitorBase + { + typedef boost::blank LieGroup_t; + typedef boost::fusion::vector &, std::vector &> ArgsType; + + PINOCCHIO_DETAILS_VISITOR_METHOD_ALGO_2(IndexvInfoStepAlgo, IndexvInfoStep) + }; + + template + struct IndexvInfoStepAlgo + { + static void run( + const JointModelBase & jmodel, std::vector & nvs, std::vector & idx_vs) + { + int idx_v = jmodel.idx_v(); + int nv = jmodel.nv(); + + for (size_t i = 0; i < static_cast(jmodel.nq()); ++i) + { + nvs.push_back(nv); + idx_vs.push_back(idx_v); + } + } + }; + + PINOCCHIO_DETAILS_DISPATCH_JOINT_COMPOSITE_2(IndexvInfoStepAlgo); + PINOCCHIO_DETAILS_CANCEL_JOINT_MIMIC_2(IndexvInfoStepAlgo); } // namespace pinocchio diff --git a/include/pinocchio/multibody/liegroup/liegroup-base.hpp b/include/pinocchio/multibody/liegroup/liegroup-base.hpp index 1a5411d1b2..2bec5b9270 100644 --- a/include/pinocchio/multibody/liegroup/liegroup-base.hpp +++ b/include/pinocchio/multibody/liegroup/liegroup-base.hpp @@ -25,7 +25,8 @@ namespace pinocchio }; \ typedef TYPENAME Base::ConfigVector_t ConfigVector_t; \ typedef TYPENAME Base::TangentVector_t TangentVector_t; \ - typedef TYPENAME Base::JacobianMatrix_t JacobianMatrix_t + typedef TYPENAME Base::JacobianMatrix_t JacobianMatrix_t; \ + typedef TYPENAME Base::TangentMapMatrix_t TangentMapMatrix_t #define PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE(Derived) \ PINOCCHIO_LIE_GROUP_PUBLIC_INTERFACE_GENERIC(Derived, PINOCCHIO_MACRO_EMPTY_ARG) @@ -49,6 +50,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; typedef Eigen::Matrix JacobianMatrix_t; + typedef Eigen::Matrix TangentMapMatrix_t; /// \name API with return value as argument /// \{ @@ -546,6 +548,41 @@ namespace pinocchio const Eigen::MatrixBase & Jout, const AssignmentOperatorType op = SETTO) const; + /** + * @brief Computes the left Tangent Mapping from the Lie algebra of the group to the + * parametric space tangent space TqQ. + * + * @details The tangent mapping corresponds to the eucliean Jacobian of \f$ (\mathbf{q} + * \oplus \mathbf{v}\f$ with respect to \f$ \mathbf{q}\f$ in \f$ 0\f$. In other words for any + * vector $v$ in the Lie algebra we have \f$ TM(\mathbf{q}) v = lim_{\delta t \rightarrow 0} + * \frac{\mathbf{q} \oplus (v\delta t) - \mathbf{q}}{\delta t}\f$ + * + * @param[in] q configuration vector. + * @param[in] op assignment operator (SETTO, ADDTO or RMTO). + * @param[out] TM the tangentmapping matrix + */ + template + void tangentMap( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & TM, + const AssignmentOperatorType op = SETTO) const; + + // Mout op TM * Min, it is the jacobian vector product + template + void tangentMapProduct( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + const Eigen::MatrixBase & Mout, + const AssignmentOperatorType op = SETTO) const; + + // Mout op TM^T * Min, it is the jacobian transpose vector product + template + void tangentMapTransposeProduct( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + const Eigen::MatrixBase & Mout, + const AssignmentOperatorType op = SETTO) const; + /** * @brief Squared distance between two joint configurations. * @@ -648,6 +685,20 @@ namespace pinocchio bool dDifferenceOnTheLeft, const AssignmentOperatorType op) const; + template + void tangentMapProduct_impl( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) const; + + template + void tangentMapTransposeProduct_impl( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) const; + template void interpolate_impl( const Eigen::MatrixBase & q0, diff --git a/include/pinocchio/multibody/liegroup/liegroup-base.hxx b/include/pinocchio/multibody/liegroup/liegroup-base.hxx index d096d01cb1..4f15a48aab 100644 --- a/include/pinocchio/multibody/liegroup/liegroup-base.hxx +++ b/include/pinocchio/multibody/liegroup/liegroup-base.hxx @@ -282,6 +282,50 @@ namespace pinocchio q.derived(), v.derived(), PINOCCHIO_EIGEN_CONST_CAST(Jacobian_t, J)); } + template + template + void LieGroupBase::tangentMap( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & TM, + const AssignmentOperatorType op) const + { + EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Config_t, ConfigVector_t); + EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(TangentMap_t, TangentMapMatrix_t); + derived().tangentMap_impl(q.derived(), PINOCCHIO_EIGEN_CONST_CAST(TangentMap_t, TM), op); + } + + template + template + void LieGroupBase::tangentMapProduct( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + const Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) const + { + EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Config_t, ConfigVector_t); + PINOCCHIO_CHECK_ARGUMENT_SIZE(Min.rows(), nv()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(Mout.rows(), nq()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(Min.cols(), Mout.cols()); + derived().tangentMapProduct_impl( + q.derived(), Min.derived(), PINOCCHIO_EIGEN_CONST_CAST(MatrixOut_t, Mout), op); + } + + template + template + void LieGroupBase::tangentMapTransposeProduct( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + const Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) const + { + EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Config_t, ConfigVector_t); + PINOCCHIO_CHECK_ARGUMENT_SIZE(Min.rows(), nq()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(Mout.rows(), nv()); + PINOCCHIO_CHECK_ARGUMENT_SIZE(Min.cols(), Mout.cols()); + derived().tangentMapTransposeProduct_impl( + q.derived(), Min.derived(), PINOCCHIO_EIGEN_CONST_CAST(MatrixOut_t, Mout), op); + } + /** * @brief Interpolation between two joint's configurations * @@ -624,6 +668,64 @@ namespace pinocchio } } + template + template + void LieGroupBase::tangentMapProduct_impl( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) const + { + Index nv_(nv()), nq_(nq()); + PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH + PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED + // When tangent map map is sparse, this must be overwritten + TangentMapMatrix_t TM(nq_, nv_); + tangentMap(q, TM); + PINOCCHIO_COMPILER_DIAGNOSTIC_POP + switch (op) + { + case SETTO: + Mout = TM * Min; + return; + case ADDTO: + Mout += TM * Min; + return; + case RMTO: + Mout -= TM * Min; + return; + } + } + + template + template + void LieGroupBase::tangentMapTransposeProduct_impl( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) const + { + Index nv_(nv()), nq_(nq()); + PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH + PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED + // When tangent map map is sparse, this must be overwritten + TangentMapMatrix_t TM(nq_, nv_); + tangentMap(q, TM); + PINOCCHIO_COMPILER_DIAGNOSTIC_POP + switch (op) + { + case SETTO: + Mout = TM.transpose() * Min; + return; + case ADDTO: + Mout += TM.transpose() * Min; + return; + case RMTO: + Mout -= TM.transpose() * Min; + return; + } + } + template template void LieGroupBase::interpolate_impl( diff --git a/include/pinocchio/multibody/liegroup/liegroup-joint.hpp b/include/pinocchio/multibody/liegroup/liegroup-joint.hpp new file mode 100644 index 0000000000..ee94ef7706 --- /dev/null +++ b/include/pinocchio/multibody/liegroup/liegroup-joint.hpp @@ -0,0 +1,78 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_multibody_liegroup_liegroup_joint_hpp__ +#define __pinocchio_multibody_liegroup_liegroup_joint_hpp__ + +#include "pinocchio/multibody/visitor.hpp" +#include "pinocchio/multibody/joint/joint-generic.hpp" +#include "pinocchio/multibody/liegroup/liegroup-algo.hpp" +#include "pinocchio/multibody/liegroup/liegroup-generic.hpp" + +namespace pinocchio +{ + // Overload the composite using the dispatch of the Lie group algo + template class JointCollectionTpl> + template + typename LieGroup_t::template operation< + JointModelCompositeTpl<_Scalar, _Options, JointCollectionTpl>>::type + JointModelCompositeTpl<_Scalar, _Options, JointCollectionTpl>::lieGroup_impl() const + { + typedef LieGroupInstanceStep Algo; + typedef typename Algo::LgType LgType; + typedef typename Algo::ArgsType ArgsType; + + LgType res; + Algo::run(*this, ArgsType(res)); + return res; + } + + // Write a Lie group for the generic overload + template + struct JointModelLieGroupVisitor + : boost::static_visitor::type> + { + typedef typename LieGroup_t::template operationProduct<_Scalar, _Options>::type LgType; + + // Default behavior, instantiate the atomic type in the agregation type + template + LgType operator()(const JointModelBase & jmodel) const + { + return LgType(jmodel.template lieGroup()); + } + + // Composite and Mimic are already agregated lie group type + template class JointCollectionTpl> + LgType + operator()(const JointModelCompositeTpl & jmodel) const + { + return jmodel.template lieGroup(); + } + + template class JointCollectionTpl> + LgType operator()(const JointModelMimicTpl & jmodel) const + { + return jmodel.template lieGroup(); + } + + template class JointCollectionTpl> + static LgType run(const JointModelTpl & jmodel) + { + return boost::apply_visitor(JointModelLieGroupVisitor(), jmodel); + } + }; + + // Overload the generic with a simple visiting + template class JointCollectionTpl> + template + typename LieGroup_t::template operation< + JointModelTpl<_Scalar, _Options, JointCollectionTpl>>::type + JointModelTpl<_Scalar, _Options, JointCollectionTpl>::lieGroup_impl() const + { + typedef JointModelLieGroupVisitor Algo; + return Algo::run(*this); + } +} // namespace pinocchio + +#endif // #ifndef __pinocchio_multibody_liegroup_liegroup_joint_hpp__ diff --git a/include/pinocchio/multibody/liegroup/liegroup-variant-visitors.hpp b/include/pinocchio/multibody/liegroup/liegroup-variant-visitors.hpp index c91fa90ee5..801b0fb5c0 100644 --- a/include/pinocchio/multibody/liegroup/liegroup-variant-visitors.hpp +++ b/include/pinocchio/multibody/liegroup/liegroup-variant-visitors.hpp @@ -207,6 +207,29 @@ namespace pinocchio const Eigen::MatrixBase & Jout, const ArgumentPosition arg); + template + void tangentMap( + const LieGroupGenericTpl & lg, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & TM, + const AssignmentOperatorType op); + + template + void tangentMapProduct( + const LieGroupGenericTpl & lg, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + const Eigen::MatrixBase & Mout, + const AssignmentOperatorType op); + + template + void tangentMapTransposeProduct( + const LieGroupGenericTpl & lg, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + const Eigen::MatrixBase & Mout, + const AssignmentOperatorType op); + template< typename LieGroupCollection, class Config_t, diff --git a/include/pinocchio/multibody/liegroup/liegroup-variant-visitors.hxx b/include/pinocchio/multibody/liegroup/liegroup-variant-visitors.hxx index a027c67084..9398d87202 100644 --- a/include/pinocchio/multibody/liegroup/liegroup-variant-visitors.hxx +++ b/include/pinocchio/multibody/liegroup/liegroup-variant-visitors.hxx @@ -799,6 +799,85 @@ namespace pinocchio Operation::run(lg, typename Operation::ArgsType(q, v, J, arg)); } + template + struct LieGroupTangentMapVisitor + : visitor::LieGroupVisitorBase> + { + typedef boost::fusion::vector< + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const AssignmentOperatorType> + ArgsType; + + LieGroupTangentMapVisitor(ArgsType & args) + : args(args) + { + } + ArgsType & args; + + template + static void algo( + const LieGroupBase & lg, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & TM, + const AssignmentOperatorType op) + { + lg.tangentMap(q, TM, op); + } + }; + + template + void tangentMap( + const LieGroupGenericTpl & lg, + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & TM, + const AssignmentOperatorType op) + { + typedef LieGroupTangentMapVisitor Operation; + Operation::run(lg, typename Operation::ArgsType(q, TM, op)); + } + +#define PINOCCHIO_LG_TM_PROD_VISITOR(Name, _method) \ + template \ + struct LieGroup##Name##Visitor \ + : visitor::LieGroupVisitorBase> \ + { \ + typedef boost::fusion::vector< \ + const Eigen::MatrixBase &, \ + const Eigen::MatrixBase &, \ + const Eigen::MatrixBase &, \ + const AssignmentOperatorType> \ + ArgsType; \ + LieGroup##Name##Visitor(ArgsType & args) \ + : args(args) \ + { \ + } \ + ArgsType & args; \ + template \ + static void algo( \ + const LieGroupBase & lg, \ + const Eigen::MatrixBase & q, \ + const Eigen::MatrixBase & Min, \ + const Eigen::MatrixBase & Mout, \ + const AssignmentOperatorType op) \ + { \ + lg._method(q, Min, Mout, op); \ + } \ + }; \ + template \ + void _method( \ + const LieGroupGenericTpl & lg, const Eigen::MatrixBase & q, \ + const Eigen::MatrixBase & Min, const Eigen::MatrixBase & Mout, \ + const AssignmentOperatorType op) \ + { \ + typedef LieGroup##Name##Visitor Operation; \ + Operation::run(lg, typename Operation::ArgsType(q, Min, Mout, op)); \ + } + + PINOCCHIO_LG_TM_PROD_VISITOR(TangentMapProduct, tangentMapProduct) + PINOCCHIO_LG_TM_PROD_VISITOR(CoTangentMapProduct, tangentMapTransposeProduct) +#undef PINOCCHIO_LG_TM_PROD_VISITOR + } // namespace pinocchio #undef PINOCCHIO_LG_CHECK_VECTOR_SIZE diff --git a/include/pinocchio/multibody/liegroup/liegroup.hpp b/include/pinocchio/multibody/liegroup/liegroup.hpp index b2291ab88e..ad2ae98ab7 100644 --- a/include/pinocchio/multibody/liegroup/liegroup.hpp +++ b/include/pinocchio/multibody/liegroup/liegroup.hpp @@ -7,15 +7,22 @@ #include "pinocchio/multibody/liegroup/vector-space.hpp" #include "pinocchio/multibody/liegroup/cartesian-product.hpp" +#include "pinocchio/multibody/liegroup/cartesian-product-variant.hpp" #include "pinocchio/multibody/liegroup/special-orthogonal.hpp" #include "pinocchio/multibody/liegroup/special-euclidean.hpp" +#include "pinocchio/multibody/liegroup/liegroup-collection.hpp" #include "pinocchio/multibody/joint/fwd.hpp" namespace pinocchio { + + // A LieGroup map map each joint to a LieGroup and give the type to + // make cartesian product between those groups struct LieGroupMap { + + // Default LieGroup operation is euclidean template struct operation { @@ -25,19 +32,44 @@ namespace pinocchio JointModel::Options> type; }; + + template + struct operationProduct + { + typedef CartesianProductOperationVariantTpl + type; + // LieGroupCollectionDefaultTpl is implicitely chosen by the LieGroupMap + // inside the aggregation type + }; }; + // Alias for shorctut in unittest template struct LieGroup { typedef typename LieGroupMap::operation::type type; }; + // The type for generic, composite and mimic is directly the variant type + template class JointCollectionTpl> + struct LieGroupMap::operation> + { + typedef typename LieGroupMap::operationProduct::type type; + }; + template class JointCollectionTpl> struct LieGroupMap::operation> { + typedef typename LieGroupMap::operationProduct::type type; + }; + + template class JointCollectionTpl> + struct LieGroupMap::operation> + { + typedef typename LieGroupMap::operationProduct::type type; }; + // Atomic joint that are not euclidean template struct LieGroupMap::operation> { diff --git a/include/pinocchio/multibody/liegroup/special-euclidean.hpp b/include/pinocchio/multibody/liegroup/special-euclidean.hpp index b780588412..5855400e41 100644 --- a/include/pinocchio/multibody/liegroup/special-euclidean.hpp +++ b/include/pinocchio/multibody/liegroup/special-euclidean.hpp @@ -246,10 +246,10 @@ namespace pinocchio } template - void dDifference_impl( + static void dDifference_impl( const Eigen::MatrixBase & q0, const Eigen::MatrixBase & q1, - const Eigen::MatrixBase & J) const + const Eigen::MatrixBase & J) { PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED @@ -380,6 +380,119 @@ namespace pinocchio } } + template + static void tangentMap_impl( + const Eigen::MatrixBase & q, + Eigen::MatrixBase & TM, + const AssignmentOperatorType op) + { + switch (op) + { + case SETTO: + TM.template topRightCorner<2, 1>().setZero(); + TM.template bottomLeftCorner<2, 2>().setZero(); + // Linear + TM(0, 0) = q[2]; + TM(1, 0) = q[3]; + TM(0, 1) = -q[3]; + TM(1, 1) = q[2]; + // Angular + TM(2, 2) = -q[3]; + TM(3, 2) = q[2]; + break; + case ADDTO: + TM(0, 0) += q[2]; + TM(1, 0) += q[3]; + TM(0, 1) -= q[3]; + TM(1, 1) += q[2]; + // Angular + TM(2, 2) -= q[3]; + TM(3, 2) += q[2]; + break; + case RMTO: + TM(0, 0) -= q[2]; + TM(1, 0) -= q[3]; + TM(0, 1) += q[3]; + TM(1, 1) -= q[2]; + // Angular + TM(2, 2) += q[3]; + TM(3, 2) -= q[2]; + default: + assert(false && "Wrong Op requesed value"); + break; + } + } + + template + static void tangentMapProduct_impl( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) + { + typedef typename MatrixIn_t::Scalar Scalar; + enum + { + Options = PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixIn_t)::Options + }; + + Eigen::Matrix R; + R << q[2], -q[3], q[3], q[2]; + + switch (op) + { + case SETTO: + Mout.template topRows<2>() = R * Min.template topRows<2>(); + Mout.template bottomRows<2>() = R.template rightCols<1>() * Min.template bottomRows<1>(); + break; + case ADDTO: + Mout.template topRows<2>() += R * Min.template topRows<2>(); + Mout.template bottomRows<2>() += R.template rightCols<1>() * Min.template bottomRows<1>(); + break; + case RMTO: + Mout.template topRows<2>() -= R * Min.template topRows<2>(); + Mout.template bottomRows<2>() -= R.template rightCols<1>() * Min.template bottomRows<1>(); + default: + assert(false && "Wrong Op requesed value"); + break; + } + } + + template + static void tangentMapTransposeProduct_impl( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) + { + typedef typename MatrixIn_t::Scalar Scalar; + enum + { + Options = PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixIn_t)::Options + }; + + Eigen::Matrix RT; + RT << q[2], q[3], -q[3], q[2]; + + switch (op) + { + case SETTO: + Mout.template topRows<2>() = RT * Min.template topRows<2>(); + Mout.template bottomRows<1>() = RT.template bottomRows<1>() * Min.template bottomRows<2>(); + break; + case ADDTO: + Mout.template topRows<2>() += RT * Min.template topRows<2>(); + Mout.template bottomRows<1>() += RT.template bottomRows<1>() * Min.template bottomRows<2>(); + break; + case RMTO: + Mout.template topRows<2>() -= RT * Min.template topRows<2>(); + Mout.template bottomRows<1>() -= RT.template bottomRows<1>() * Min.template bottomRows<2>(); + default: + assert(false && "Wrong Op requesed value"); + break; + } + } + template static void dIntegrateTransport_dq_impl( const Eigen::MatrixBase & /*q*/, @@ -793,6 +906,115 @@ namespace pinocchio } } + template + static void tangentMap_impl( + const Eigen::MatrixBase & q, + Eigen::MatrixBase & TM, + const AssignmentOperatorType op) + { + typedef typename TangentMap_t::Scalar Scalar; + enum + { + Options = PINOCCHIO_EIGEN_PLAIN_TYPE(TangentMap_t)::Options + }; + + ConstQuaternionMap_t quat(q.derived().template tail<4>().data()); + Eigen::Matrix TMq; + quaternion::tangentMap(quat, TMq); + + switch (op) + { + case SETTO: + TM.template topRightCorner<3, 3>().setZero(); + TM.template bottomLeftCorner<4, 3>().setZero(); + TM.template topLeftCorner<3, 3>() = quat.matrix(); + TM.template bottomRightCorner<4, 3>() = TMq; + break; + case ADDTO: + TM.template topLeftCorner<3, 3>() += quat.matrix(); + TM.template bottomRightCorner<4, 3>() += TMq; + break; + case RMTO: + TM.template topLeftCorner<3, 3>() -= quat.matrix(); + TM.template bottomRightCorner<4, 3>() -= TMq; + default: + assert(false && "Wrong Op requesed value"); + break; + } + } + + template + static void tangentMapProduct_impl( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) + { + typedef typename MatrixOut_t::Scalar Scalar; + enum + { + Options = PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixOut_t)::Options + }; + + ConstQuaternionMap_t quat(q.derived().template tail<4>().data()); + Eigen::Matrix TMq; + quaternion::tangentMap(quat, TMq); + + switch (op) + { + case SETTO: + Mout.template topRows<3>() = quat.matrix() * Min.template topRows<3>(); + Mout.template bottomRows<4>() = TMq * Min.template bottomRows<3>(); + break; + case ADDTO: + Mout.template topRows<3>() += quat.matrix() * Min.template topRows<3>(); + Mout.template bottomRows<4>() += TMq * Min.template bottomRows<3>(); + break; + case RMTO: + Mout.template topRows<3>() -= quat.matrix() * Min.template topRows<3>(); + Mout.template bottomRows<4>() -= TMq * Min.template bottomRows<3>(); + default: + assert(false && "Wrong Op requesed value"); + break; + } + } + + template + static void tangentMapTransposeProduct_impl( + const Eigen::MatrixBase & q, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) + { + typedef typename MatrixOut_t::Scalar Scalar; + enum + { + Options = PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixOut_t)::Options + }; + + ConstQuaternionMap_t quat(q.derived().template tail<4>().data()); + Eigen::Matrix TMq; + quaternion::tangentMap(quat, TMq); + + switch (op) + { + case SETTO: + Mout.template topRows<3>() = quat.matrix().transpose() * Min.template topRows<3>(); + Mout.template bottomRows<3>() = TMq.transpose() * Min.template bottomRows<4>(); + break; + case ADDTO: + Mout.template topRows<3>() += quat.matrix().transpose() * Min.template topRows<3>(); + Mout.template bottomRows<3>() += TMq.transpose() * Min.template bottomRows<4>(); + break; + case RMTO: + Mout.template topRows<3>() -= quat.matrix().transpose() * Min.template topRows<3>(); + Mout.template bottomRows<3>() -= TMq.transpose() * Min.template bottomRows<4>(); + default: + assert(false && "Wrong Op requesed value"); + break; + } + } + template static void dIntegrateTransport_dq_impl( const Eigen::MatrixBase & /*q*/, @@ -874,18 +1096,6 @@ namespace pinocchio Jtmp6.template bottomRightCorner<3, 3>() * Jout.template bottomRows<3>(); } - template - static Scalar squaredDistance_impl( - const Eigen::MatrixBase & q0, const Eigen::MatrixBase & q1) - { - PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH - PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED - TangentVector_t t; - difference_impl(q0, q1, t); - PINOCCHIO_COMPILER_DIAGNOSTIC_POP - return t.squaredNorm(); - } - template static void normalize_impl(const Eigen::MatrixBase & qout) { diff --git a/include/pinocchio/multibody/liegroup/special-orthogonal.hpp b/include/pinocchio/multibody/liegroup/special-orthogonal.hpp index 61439ec22d..5ffd2f7f40 100644 --- a/include/pinocchio/multibody/liegroup/special-orthogonal.hpp +++ b/include/pinocchio/multibody/liegroup/special-orthogonal.hpp @@ -243,6 +243,34 @@ namespace pinocchio } } + template + static void tangentMap_impl( + const Eigen::MatrixBase & q, + Eigen::MatrixBase & TM, + const AssignmentOperatorType op) + { + switch (op) + { + case SETTO: + TM(0, 0) = -q[1]; + TM(1, 0) = q[0]; + break; + case ADDTO: + TM(0, 0) -= q[1]; + TM(1, 0) += q[0]; + break; + case RMTO: + TM(0, 0) += q[1]; + TM(1, 0) -= q[0]; + break; + default: + assert(false && "Wrong Op requesed value"); + break; + } + } + // We use default tangentMapProduct_impl and tangentMapTransposeProduct_impl + // because TM is a dense matrix for SO(2) + template static void dIntegrateTransport_dq_impl( const Eigen::MatrixBase & /*q*/, @@ -566,6 +594,34 @@ PINOCCHIO_COMPILER_DIAGNOSTIC_POP } } + template + static void tangentMap_impl( + const Eigen::MatrixBase & q, + Eigen::MatrixBase & TM, + const AssignmentOperatorType op) + { + ConstQuaternionMap_t quat(q.derived().data()); + TangentMapMatrix_t _TM; + quaternion::tangentMap(quat, _TM); + switch (op) + { + case SETTO: + TM = _TM; + break; + case ADDTO: + TM += _TM; + break; + case RMTO: + TM -= _TM; + break; + default: + assert(false && "Wrong Op requesed value"); + break; + } + } + // We use default tangentMapProduct_impl and tangentMapTransposeProduct_impl + // because TM is a dense matrix for SO(3) + template static void dIntegrateTransport_dq_impl( const Eigen::MatrixBase & /*q*/, @@ -644,18 +700,6 @@ PINOCCHIO_COMPILER_DIAGNOSTIC_POP assert(quaternion::isNormalized(quat_res)); } - template - static Scalar squaredDistance_impl( - const Eigen::MatrixBase & q0, const Eigen::MatrixBase & q1) - { - PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH - PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED - TangentVector_t t; - difference_impl(q0, q1, t); - PINOCCHIO_COMPILER_DIAGNOSTIC_POP - return t.squaredNorm(); - } - template static void normalize_impl(const Eigen::MatrixBase & qout) { diff --git a/include/pinocchio/multibody/liegroup/vector-space.hpp b/include/pinocchio/multibody/liegroup/vector-space.hpp index 27f152d2b1..07374afa17 100644 --- a/include/pinocchio/multibody/liegroup/vector-space.hpp +++ b/include/pinocchio/multibody/liegroup/vector-space.hpp @@ -271,6 +271,77 @@ namespace pinocchio // static context::Scalar squaredDistance_impl(const Eigen::MatrixBase & q0, // const Eigen::MatrixBase & q1) + template + static void tangentMap_impl( + const Eigen::MatrixBase & /*q*/, + Eigen::MatrixBase & TM, + const AssignmentOperatorType op) + { + switch (op) + { + case SETTO: + TM.setIdentity(); + break; + case ADDTO: + TM.diagonal().array() += Scalar(1); + break; + case RMTO: + TM.diagonal().array() -= Scalar(1); + break; + default: + assert(false && "Wrong Op requesed value"); + break; + } + } + + template + static void tangentMapProduct_impl( + const Eigen::MatrixBase & /*q*/, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) + { + switch (op) + { + case SETTO: + Mout = Min; + break; + case ADDTO: + Mout += Min; + break; + case RMTO: + Mout -= Min; + break; + default: + assert(false && "Wrong Op requesed value"); + break; + } + } + + template + static void tangentMapTransposeProduct_impl( + const Eigen::MatrixBase & /*q*/, + const Eigen::MatrixBase & Min, + Eigen::MatrixBase & Mout, + const AssignmentOperatorType op) + { + switch (op) + { + case SETTO: + Mout = Min; + break; + case ADDTO: + Mout += Min; + break; + case RMTO: + Mout -= Min; + break; + default: + assert(false && "Wrong Op requesed value"); + break; + } + } + template static void normalize_impl(const Eigen::MatrixBase & /*qout*/) { diff --git a/include/pinocchio/multibody/model.hpp b/include/pinocchio/multibody/model.hpp index be955b3de4..fdf9e52192 100644 --- a/include/pinocchio/multibody/model.hpp +++ b/include/pinocchio/multibody/model.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2015-2020 CNRS INRIA +// Copyright (c) 2015-2024 CNRS INRIA // Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France. // @@ -12,6 +12,8 @@ #include "pinocchio/spatial/motion.hpp" #include "pinocchio/spatial/inertia.hpp" +#include "pinocchio/common/model-entity.hpp" + #include "pinocchio/multibody/fwd.hpp" #include "pinocchio/multibody/frame.hpp" #include "pinocchio/multibody/joint/joint-generic.hpp" @@ -39,23 +41,30 @@ namespace pinocchio struct traits> { typedef _Scalar Scalar; + enum + { + Options = _Options + }; + typedef DataTpl Data; + typedef JointCollectionTpl JointCollection; }; template class JointCollectionTpl> struct ModelTpl : serialization::Serializable> , NumericalBase> + , ModelEntity> { EIGEN_MAKE_ALIGNED_OPERATOR_NEW - typedef _Scalar Scalar; + typedef typename traits::Scalar Scalar; enum { - Options = _Options + Options = traits::Options }; - typedef JointCollectionTpl JointCollection; - typedef DataTpl Data; + typedef typename traits::JointCollection JointCollection; + typedef typename traits::Data Data; typedef SE3Tpl SE3; typedef MotionTpl Motion; @@ -78,6 +87,7 @@ namespace pinocchio typedef PINOCCHIO_ALIGNED_STD_VECTOR(Frame) FrameVector; typedef Eigen::Matrix VectorXs; + typedef Eigen::Matrix MatrixXs; typedef Eigen::Matrix Vector3; typedef PINOCCHIO_ALIGNED_STD_VECTOR(Inertia) InertiaVector; @@ -172,16 +182,37 @@ namespace pinocchio TangentVectorType rotorGearRatio; /// \brief Vector of joint friction parameters - TangentVectorType friction; + /// Deprecated in favor of lowerDryFrictionLimit and upperDryFrictionLimit + PINOCCHIO_DEPRECATED TangentVectorType & friction; + + /// \brief Vector of joint friction parameters + TangentVectorType lowerDryFrictionLimit; + + /// \brief Vector of joint friction parameters + TangentVectorType upperDryFrictionLimit; /// \brief Vector of joint damping parameters TangentVectorType damping; + /// \brief Vector of minimal joint torques + TangentVectorType lowerEffortLimit; + /// \brief Vector of maximal joint torques - TangentVectorType effortLimit; + TangentVectorType upperEffortLimit; + + /// \brief Vector of maximal joint torques + /// Deprecated in favor of lowerEffortLimit and upperEffortLimit + PINOCCHIO_DEPRECATED TangentVectorType & effortLimit; + + /// \brief Vector of minimal joint velocities + TangentVectorType lowerVelocityLimit; + + /// \brief Vector of maximal joint velocities + TangentVectorType upperVelocityLimit; /// \brief Vector of maximal joint velocities - TangentVectorType velocityLimit; + /// Deprecated in favor of lowerVelocityLimit and upperVelocityLimit + PINOCCHIO_DEPRECATED TangentVectorType & velocityLimit; /// \brief Lower joint configuration limit ConfigVectorType lowerPositionLimit; @@ -189,6 +220,9 @@ namespace pinocchio /// \brief Upper joint configuration limit ConfigVectorType upperPositionLimit; + /// \brief Joint configuration limit margin + ConfigVectorType positionLimitMargin; + /// \brief Vector of operational frames registered on the model. FrameVector frames; @@ -239,6 +273,9 @@ namespace pinocchio , parents(1, 0) , children(1) , names(1) + , friction(upperDryFrictionLimit) + , effortLimit(upperEffortLimit) + , velocityLimit(upperVelocityLimit) , supports(1, IndexVector(1, 0)) , mimic_joint_supports(1, IndexVector(1, 0)) , subtrees(1) @@ -258,10 +295,40 @@ namespace pinocchio /// template explicit ModelTpl(const ModelTpl & other) + : friction(upperDryFrictionLimit) + , effortLimit(upperEffortLimit) + , velocityLimit(upperVelocityLimit) { *this = other.template cast(); } + /// + /// \brief Copy constructor from another collection + /// + /// \param[in] other model to copy to *this + /// + template class OtherJointCollectionTpl> + ModelTpl(const ModelTpl & other) + : friction(upperDryFrictionLimit) + , effortLimit(upperEffortLimit) + , velocityLimit(upperVelocityLimit) + { + *this = other; + } + + /// + /// \brief Copy constructor. + /// + /// \param[in] other model to copy to *this + /// + ModelTpl(const ModelTpl & other) + : friction(upperDryFrictionLimit) + , effortLimit(upperEffortLimit) + , velocityLimit(upperVelocityLimit) + { + *this = other; + } + /// \returns A new copy of *this with the Scalar type casted to NewScalar. template typename CastType::type cast() const; @@ -273,6 +340,23 @@ namespace pinocchio /// bool operator==(const ModelTpl & other) const; + /// + /// \brief Assignment operator from another collection. + /// + /// + template class OtherJointCollectionTpl> + ModelTpl & operator=(const ModelTpl & other); + + /// + /// \brief Assignment operator. + /// + /// + ModelTpl & operator=(const ModelTpl & other) + { + (*this).template operator= (other); + return *this; + } + /// /// \returns true if *this is NOT equal to other. /// @@ -309,6 +393,7 @@ namespace pinocchio /// /// \copydoc ModelTpl::addJoint(const JointIndex,const JointModel &,const SE3 &,const /// std::string &) + /// Deprecated in favor of the constructor using min and max effort/velocity /// /// \param[in] max_effort Maximal joint torque. /// \param[in] max_velocity Maximal joint velocity. @@ -325,6 +410,103 @@ namespace pinocchio const VectorXs & min_config, const VectorXs & max_config); + /// + /// \copydoc ModelTpl::addJoint(const JointIndex,const JointModel &,const SE3 &,const + /// std::string &) + /// Deprecated in favor of the constructor using min and max effort/velocity + /// + /// \param[in] max_effort Maximal joint torque. + /// \param[in] max_velocity Maximal joint velocity. + /// \param[in] min_config Lower joint configuration. + /// \param[in] max_config Upper joint configuration. + /// \param[in] config_limit_margin Joint configuration limit margin. + /// + JointIndex addJoint( + const JointIndex parent, + const JointModel & joint_model, + const SE3 & joint_placement, + const std::string & joint_name, + const VectorXs & max_effort, + const VectorXs & max_velocity, + const VectorXs & min_config, + const VectorXs & max_config, + const VectorXs & config_limit_margin); + + /// + /// \copydoc ModelTpl::addJoint(const JointIndex,const JointModel &,const SE3 &,const + /// std::string &,const VectorXs &,const VectorXs &,const VectorXs &,const VectorXs &) + /// Deprecated in favor of the constructor using min and max effort/velocity + /// + /// \param[in] min_effort Minimal joint torque. + /// \param[in] min_velocity Minimal joint velocity. + /// \param[in] min_friction Minimal joint friction parameters. + /// \param[in] max_friction Maximal joint friction parameters. + /// \param[in] damping Joint damping parameters. + /// + JointIndex addJoint( + const JointIndex parent, + const JointModel & joint_model, + const SE3 & joint_placement, + const std::string & joint_name, + const VectorXs & min_effort, + const VectorXs & max_effort, + const VectorXs & min_velocity, + const VectorXs & max_velocity, + const VectorXs & min_config, + const VectorXs & max_config, + const VectorXs & min_friction, + const VectorXs & max_friction, + const VectorXs & damping); + + /// + /// \copydoc ModelTpl::addJoint(const JointIndex,const JointModel &,const SE3 &,const + /// std::string &,const VectorXs &,const VectorXs &,const VectorXs &,const VectorXs &) + /// Deprecated in favor of the constructor using min and max effort/velocity + /// + /// \param[in] config_limit_margin Joint configuration limit margin. + /// \param[in] min_effort Minimal joint torque. + /// \param[in] min_velocity Minimal joint velocity. + /// \param[in] min_friction Minimal joint friction parameters. + /// \param[in] max_friction Maximal joint friction parameters. + /// \param[in] damping Joint damping parameters. + /// + JointIndex addJoint( + const JointIndex parent, + const JointModel & joint_model, + const SE3 & joint_placement, + const std::string & joint_name, + const VectorXs & min_effort, + const VectorXs & max_effort, + const VectorXs & min_velocity, + const VectorXs & max_velocity, + const VectorXs & min_config, + const VectorXs & max_config, + const VectorXs & config_limit_margin, + const VectorXs & min_friction, + const VectorXs & max_friction, + const VectorXs & damping); + + /// + /// \copydoc ModelTpl::addJoint(const JointIndex,const JointModel &,const SE3 &,const + /// std::string &,const VectorXs &,const VectorXs &,const VectorXs &,const VectorXs &) + /// + /// \param[in] config_limit_margin Joint configuration limit margin. + /// \param[in] friction Joint friction parameters. + /// \param[in] damping Joint damping parameters. + /// + JointIndex addJoint( + const JointIndex parent, + const JointModel & joint_model, + const SE3 & joint_placement, + const std::string & joint_name, + const VectorXs & max_effort, + const VectorXs & max_velocity, + const VectorXs & min_config, + const VectorXs & max_config, + const VectorXs & config_limit_margin, + const VectorXs & friction, + const VectorXs & damping); + /// /// \copydoc ModelTpl::addJoint(const JointIndex,const JointModel &,const SE3 &,const /// std::string &,const VectorXs &,const VectorXs &,const VectorXs &,const VectorXs &) @@ -353,7 +535,7 @@ namespace pinocchio /// /// \return The index of the new frame /// - FrameIndex addJointFrame(const JointIndex & joint_index, int previous_frame_index = -1); + FrameIndex addJointFrame(const JointIndex joint_index, int previous_frame_index = -1); /// /// \brief Append a body to a given joint of the kinematic tree. @@ -485,7 +667,7 @@ namespace pinocchio /// \return true if the Model is valid, false otherwise. /// template - bool check(const AlgorithmCheckerBase & checker = AlgorithmCheckerBase()) const + bool check(const AlgorithmCheckerBase & checker) const { return checker.checkModel(*this); } @@ -495,14 +677,14 @@ namespace pinocchio /// /// \return Returns list of boolean of size model.nq. /// - std::vector hasConfigurationLimit(); + std::vector hasConfigurationLimit() const; /// /// \brief Check if joints have configuration limits /// /// \return Returns list of boolean of size model.nq. /// - std::vector hasConfigurationLimitInTangent(); + std::vector hasConfigurationLimitInTangent() const; /// Run check(fusion::list) with DEFAULT_CHECKERS as argument. bool check() const; @@ -516,6 +698,15 @@ namespace pinocchio /// bool check(const Data & data) const; + /// + /// \brief Create a Data structure associated with the current model + /// + Data createData() const; + + /// Returns a vector of the children joints of the kinematic tree. + /// \remark: a child joint is a node without any child joint. + std::vector getChildJoints() const; + protected: /// /// \brief Add the joint_id to its parent subtrees. diff --git a/include/pinocchio/multibody/model.hxx b/include/pinocchio/multibody/model.hxx index 2b941ee288..93cdd5d11d 100644 --- a/include/pinocchio/multibody/model.hxx +++ b/include/pinocchio/multibody/model.hxx @@ -63,11 +63,40 @@ namespace pinocchio const JointModel & joint_model, const SE3 & joint_placement, const std::string & joint_name, + const VectorXs & min_effort, const VectorXs & max_effort, + const VectorXs & min_velocity, const VectorXs & max_velocity, const VectorXs & min_config, const VectorXs & max_config, - const VectorXs & joint_friction, + const VectorXs & min_joint_friction, + const VectorXs & max_joint_friction, + const VectorXs & joint_damping) + { + const VectorXs config_limit_margin = + VectorXs::Constant(joint_model.nq(), static_cast(0)); + return addJoint( + parent, joint_model, joint_placement, joint_name, min_effort, max_effort, min_velocity, + max_velocity, min_config, max_config, config_limit_margin, min_joint_friction, + max_joint_friction, joint_damping); + } + + template class JointCollectionTpl> + typename ModelTpl::JointIndex + ModelTpl::addJoint( + const JointIndex parent, + const JointModel & joint_model, + const SE3 & joint_placement, + const std::string & joint_name, + const VectorXs & min_effort, + const VectorXs & max_effort, + const VectorXs & min_velocity, + const VectorXs & max_velocity, + const VectorXs & min_config, + const VectorXs & max_config, + const VectorXs & config_limit_margin, + const VectorXs & min_joint_friction, + const VectorXs & max_joint_friction, const VectorXs & joint_damping) { assert( @@ -76,11 +105,31 @@ namespace pinocchio assert((joint_model.nq() >= 0) && (joint_model.nv() >= 0) && (joint_model.nvExtended() >= 0)); assert(joint_model.nq() >= joint_model.nv()); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + min_effort.size(), joint_model.nv(), "The joint minimal effort vector is not of right size"); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + min_joint_friction.size(), joint_model.nv(), + "The joint minimal dry friction vector is not of right size"); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + min_velocity.size(), joint_model.nv(), + "The joint minimal velocity vector is not of right size"); PINOCCHIO_CHECK_ARGUMENT_SIZE( max_effort.size(), joint_model.nv(), "The joint maximum effort vector is not of right size"); + PINOCCHIO_CHECK_ARGUMENT_SIZE( + max_joint_friction.size(), joint_model.nv(), + "The joint maximum dry friction vector is not of right size"); PINOCCHIO_CHECK_ARGUMENT_SIZE( max_velocity.size(), joint_model.nv(), "The joint maximum velocity vector is not of right size"); + PINOCCHIO_CHECK_INPUT_ARGUMENT( + (min_effort.array() <= max_effort.array()).all(), + "Some components of min_effort are greater than max_effort"); + PINOCCHIO_CHECK_INPUT_ARGUMENT( + (min_joint_friction.array() <= max_joint_friction.array()).all(), + "Some components of min_dry_friction are greater than max_dry_friction"); + PINOCCHIO_CHECK_INPUT_ARGUMENT( + (min_velocity.array() <= max_velocity.array()).all(), + "Some components of min_velocity are greater than max_velocity"); PINOCCHIO_CHECK_ARGUMENT_SIZE( min_config.size(), joint_model.nq(), "The joint lower configuration bound is not of right size"); @@ -88,7 +137,8 @@ namespace pinocchio max_config.size(), joint_model.nq(), "The joint upper configuration bound is not of right size"); PINOCCHIO_CHECK_ARGUMENT_SIZE( - joint_friction.size(), joint_model.nv(), "The joint friction vector is not of right size"); + config_limit_margin.size(), joint_model.nq(), + "The joint config limit margin is not of right size"); PINOCCHIO_CHECK_ARGUMENT_SIZE( joint_damping.size(), joint_model.nv(), "The joint damping vector is not of right size"); PINOCCHIO_CHECK_INPUT_ARGUMENT( @@ -128,25 +178,36 @@ namespace pinocchio nvExtendeds.push_back(joint_nvExtended); idx_vExtendeds.push_back(joint_idx_vExtended); - effortLimit.conservativeResize(nv); - jmodel.jointVelocitySelector(effortLimit) = max_effort; - velocityLimit.conservativeResize(nv); - jmodel.jointVelocitySelector(velocityLimit) = max_velocity; - lowerPositionLimit.conservativeResize(nq); - jmodel.jointConfigSelector(lowerPositionLimit) = min_config; - upperPositionLimit.conservativeResize(nq); - jmodel.jointConfigSelector(upperPositionLimit) = max_config; - - armature.conservativeResize(nv); - jmodel.jointVelocitySelector(armature).setZero(); - rotorInertia.conservativeResize(nv); - jmodel.jointVelocitySelector(rotorInertia).setZero(); - rotorGearRatio.conservativeResize(nv); - jmodel.jointVelocitySelector(rotorGearRatio).setOnes(); - friction.conservativeResize(nv); - jmodel.jointVelocitySelector(friction) = joint_friction; - damping.conservativeResize(nv); - jmodel.jointVelocitySelector(damping) = joint_damping; + if (joint_nq > 0 && joint_nv > 0) + { + upperEffortLimit.conservativeResize(nv); + jmodel.jointVelocitySelector(upperEffortLimit) = max_effort; + lowerEffortLimit.conservativeResize(nv); + jmodel.jointVelocitySelector(lowerEffortLimit) = min_effort; + upperVelocityLimit.conservativeResize(nv); + jmodel.jointVelocitySelector(upperVelocityLimit) = max_velocity; + lowerVelocityLimit.conservativeResize(nv); + jmodel.jointVelocitySelector(lowerVelocityLimit) = max_velocity; + lowerPositionLimit.conservativeResize(nq); + jmodel.jointConfigSelector(lowerPositionLimit) = min_config; + upperPositionLimit.conservativeResize(nq); + jmodel.jointConfigSelector(upperPositionLimit) = max_config; + positionLimitMargin.conservativeResize(nq); + jmodel.jointConfigSelector(positionLimitMargin) = config_limit_margin; + + armature.conservativeResize(nv); + jmodel.jointVelocitySelector(armature).setZero(); + rotorInertia.conservativeResize(nv); + jmodel.jointVelocitySelector(rotorInertia).setZero(); + rotorGearRatio.conservativeResize(nv); + jmodel.jointVelocitySelector(rotorGearRatio).setOnes(); + upperDryFrictionLimit.conservativeResize(nv); + jmodel.jointVelocitySelector(upperDryFrictionLimit) = max_joint_friction; + lowerDryFrictionLimit.conservativeResize(nv); + jmodel.jointVelocitySelector(lowerDryFrictionLimit) = min_joint_friction; + damping.conservativeResize(nv); + jmodel.jointVelocitySelector(damping) = joint_damping; + } // Init and add joint index to its parent subtrees. subtrees.push_back(IndexVector(1)); @@ -158,7 +219,9 @@ namespace pinocchio supports[joint_id].push_back(joint_id); mimic_joint_supports.push_back(mimic_joint_supports[parent]); - if (auto jmodel_ = boost::get>(&jmodel)) + if ( + const auto & jmodel_ = + boost::get>(&jmodel)) { mimicking_joints.push_back(jmodel.id()); mimicked_joints.push_back(jmodel_->jmodel().id()); @@ -167,6 +230,49 @@ namespace pinocchio return joint_id; } + template class JointCollectionTpl> + typename ModelTpl::JointIndex + ModelTpl::addJoint( + const JointIndex parent, + const JointModel & joint_model, + const SE3 & joint_placement, + const std::string & joint_name, + const VectorXs & max_effort, + const VectorXs & max_velocity, + const VectorXs & min_config, + const VectorXs & max_config, + const VectorXs & config_limit_margin, + const VectorXs & friction, + const VectorXs & damping) + { + + return addJoint( + parent, joint_model, joint_placement, joint_name, -max_effort, max_effort, -max_velocity, + max_velocity, min_config, max_config, config_limit_margin, -friction, friction, damping); + } + + template class JointCollectionTpl> + typename ModelTpl::JointIndex + ModelTpl::addJoint( + const JointIndex parent, + const JointModel & joint_model, + const SE3 & joint_placement, + const std::string & joint_name, + const VectorXs & max_effort, + const VectorXs & max_velocity, + const VectorXs & min_config, + const VectorXs & max_config, + const VectorXs & friction, + const VectorXs & damping) + { + const VectorXs config_limit_margin = + VectorXs::Constant(joint_model.nq(), static_cast(0)); + + return addJoint( + parent, joint_model, joint_placement, joint_name, -max_effort, max_effort, -max_velocity, + max_velocity, min_config, max_config, config_limit_margin, -friction, friction, damping); + } + template class JointCollectionTpl> typename ModelTpl::JointIndex ModelTpl::addJoint( @@ -179,12 +285,35 @@ namespace pinocchio const VectorXs & min_config, const VectorXs & max_config) { + const VectorXs config_limit_margin = + VectorXs::Constant(joint_model.nq(), static_cast(0)); const VectorXs friction = VectorXs::Constant(joint_model.nv(), static_cast(0)); const VectorXs damping = VectorXs::Constant(joint_model.nv(), static_cast(0)); return addJoint( parent, joint_model, joint_placement, joint_name, max_effort, max_velocity, min_config, - max_config, friction, damping); + max_config, config_limit_margin, friction, damping); + } + + template class JointCollectionTpl> + typename ModelTpl::JointIndex + ModelTpl::addJoint( + const JointIndex parent, + const JointModel & joint_model, + const SE3 & joint_placement, + const std::string & joint_name, + const VectorXs & max_effort, + const VectorXs & max_velocity, + const VectorXs & min_config, + const VectorXs & max_config, + const VectorXs & config_limit_margin) + { + const VectorXs friction = VectorXs::Constant(joint_model.nv(), static_cast(0)); + const VectorXs damping = VectorXs::Constant(joint_model.nv(), static_cast(0)); + + return addJoint( + parent, joint_model, joint_placement, joint_name, max_effort, max_velocity, min_config, + max_config, config_limit_margin, friction, damping); } template class JointCollectionTpl> @@ -203,15 +332,17 @@ namespace pinocchio VectorXs::Constant(joint_model.nq(), -std::numeric_limits::max()); const VectorXs max_config = VectorXs::Constant(joint_model.nq(), std::numeric_limits::max()); + const VectorXs config_limit_margin = + VectorXs::Constant(joint_model.nq(), static_cast(0)); return addJoint( parent, joint_model, joint_placement, joint_name, max_effort, max_velocity, min_config, - max_config); + max_config, config_limit_margin); } template class JointCollectionTpl> FrameIndex ModelTpl::addJointFrame( - const JointIndex & joint_index, int previous_frame_index) + const JointIndex joint_index, int previous_frame_index) { PINOCCHIO_CHECK_INPUT_ARGUMENT( joint_index < joints.size(), @@ -239,6 +370,7 @@ namespace pinocchio typedef ModelTpl ReturnType; ReturnType res; + res.nq = nq; res.nv = nv; res.nvExtended = nvExtended; @@ -264,14 +396,18 @@ namespace pinocchio res.nvExtendeds = nvExtendeds; // Eigen Vectors res.armature = armature.template cast(); - res.friction = friction.template cast(); res.damping = damping.template cast(); res.rotorInertia = rotorInertia.template cast(); res.rotorGearRatio = rotorGearRatio.template cast(); - res.effortLimit = effortLimit.template cast(); - res.velocityLimit = velocityLimit.template cast(); + res.upperEffortLimit = upperEffortLimit.template cast(); + res.lowerEffortLimit = lowerEffortLimit.template cast(); + res.upperDryFrictionLimit = upperDryFrictionLimit.template cast(); + res.lowerDryFrictionLimit = lowerDryFrictionLimit.template cast(); + res.lowerVelocityLimit = lowerVelocityLimit.template cast(); + res.upperVelocityLimit = upperVelocityLimit.template cast(); res.lowerPositionLimit = lowerPositionLimit.template cast(); res.upperPositionLimit = upperPositionLimit.template cast(); + res.positionLimitMargin = positionLimitMargin.template cast(); typename ConfigVectorMap::const_iterator it; for (it = referenceConfigurations.begin(); it != referenceConfigurations.end(); it++) @@ -302,13 +438,68 @@ namespace pinocchio return res; } + template class JointCollectionTpl> + template class OtherJointCollectionTpl> + ModelTpl & + ModelTpl::operator=( + const ModelTpl & other) + { + this->nq = other.nq; + this->nv = other.nv; + this->nvExtended = other.nvExtended; + this->njoints = other.njoints; + this->nbodies = other.nbodies; + this->nframes = other.nframes; + this->inertias = other.inertias; + this->jointPlacements = other.jointPlacements; + this->joints.clear(); + this->joints.reserve(other.joints.size()); + for (const auto & other_joint : other.joints) + { + this->joints.push_back(other_joint); + } + this->idx_qs = other.idx_qs; + this->nqs = other.nqs; + this->idx_vs = other.idx_vs; + this->nvs = other.nvs; + this->idx_vExtendeds = other.idx_vExtendeds; + this->nvExtendeds = other.nvExtendeds; + this->parents = other.parents; + this->children = other.children; + this->names = other.names; + this->referenceConfigurations = other.referenceConfigurations; + this->armature = other.armature; + this->rotorInertia = other.rotorInertia; + this->rotorGearRatio = other.rotorGearRatio; + this->lowerDryFrictionLimit = other.lowerDryFrictionLimit; + this->upperDryFrictionLimit = other.upperDryFrictionLimit; + this->damping = other.damping; + this->lowerEffortLimit = other.lowerEffortLimit; + this->upperEffortLimit = other.upperEffortLimit; + this->lowerVelocityLimit = other.lowerVelocityLimit; + this->upperVelocityLimit = other.upperVelocityLimit; + this->lowerPositionLimit = other.lowerPositionLimit; + this->upperPositionLimit = other.upperPositionLimit; + this->positionLimitMargin = other.positionLimitMargin; + this->frames = other.frames; + this->supports = other.supports; + this->subtrees = other.subtrees; + this->mimic_joint_supports = other.mimic_joint_supports; + this->mimicking_joints = other.mimicking_joints; + this->mimicked_joints = other.mimicked_joints; + this->gravity = other.gravity; + this->name = other.name; + return *this; + } + template class JointCollectionTpl> bool ModelTpl::operator==(const ModelTpl & other) const { bool res = other.nq == nq && other.nv == nv && other.nvExtended == nvExtended && other.njoints == njoints && other.nbodies == nbodies && other.nframes == nframes && other.parents == parents && other.children == children && other.names == names - && other.subtrees == subtrees && other.mimicking_joints == mimicking_joints + && other.subtrees == subtrees && other.mimic_joint_supports == mimic_joint_supports + && other.mimicking_joints == mimicking_joints && other.mimicked_joints == mimicked_joints && other.gravity == gravity && other.name == name; @@ -335,12 +526,6 @@ namespace pinocchio if (!res) return res; - if (other.friction.size() != friction.size()) - return false; - res &= other.friction == friction; - if (!res) - return res; - if (other.damping.size() != damping.size()) return false; res &= other.damping == damping; @@ -359,15 +544,39 @@ namespace pinocchio if (!res) return res; - if (other.effortLimit.size() != effortLimit.size()) + if (other.lowerEffortLimit.size() != lowerEffortLimit.size()) + return false; + res &= other.lowerEffortLimit == lowerEffortLimit; + if (!res) + return res; + + if (other.upperEffortLimit.size() != upperEffortLimit.size()) + return false; + res &= other.upperEffortLimit == upperEffortLimit; + if (!res) + return res; + + if (other.lowerDryFrictionLimit.size() != lowerDryFrictionLimit.size()) + return false; + res &= other.lowerDryFrictionLimit == lowerDryFrictionLimit; + if (!res) + return res; + + if (other.upperDryFrictionLimit.size() != upperDryFrictionLimit.size()) return false; - res &= other.effortLimit == effortLimit; + res &= other.upperDryFrictionLimit == upperDryFrictionLimit; if (!res) return res; - if (other.velocityLimit.size() != velocityLimit.size()) + if (other.lowerVelocityLimit.size() != lowerVelocityLimit.size()) return false; - res &= other.velocityLimit == velocityLimit; + res &= other.lowerVelocityLimit == lowerVelocityLimit; + if (!res) + return res; + + if (other.upperVelocityLimit.size() != upperVelocityLimit.size()) + return false; + res &= other.upperVelocityLimit == upperVelocityLimit; if (!res) return res; @@ -380,6 +589,11 @@ namespace pinocchio if (other.upperPositionLimit.size() != upperPositionLimit.size()) return false; res &= other.upperPositionLimit == upperPositionLimit; + + if (other.positionLimitMargin.size() != positionLimitMargin.size()) + return false; + res &= other.positionLimitMargin == positionLimitMargin; + if (!res) return res; @@ -523,7 +737,7 @@ namespace pinocchio } template class JointCollectionTpl> - std::vector ModelTpl::hasConfigurationLimit() + std::vector ModelTpl::hasConfigurationLimit() const { std::vector vec; for (Index i = 1; i < (Index)(njoints); ++i) @@ -535,7 +749,8 @@ namespace pinocchio } template class JointCollectionTpl> - std::vector ModelTpl::hasConfigurationLimitInTangent() + std::vector + ModelTpl::hasConfigurationLimitInTangent() const { std::vector vec; for (Index i = 1; i < (Index)(njoints); ++i) @@ -546,6 +761,18 @@ namespace pinocchio return vec; } + template class JointCollectionTpl> + std::vector ModelTpl::getChildJoints() const + { + std::vector res; + for (JointIndex joint_id = 1; joint_id < JointIndex(njoints); ++joint_id) + { + if (this->children[joint_id].empty()) + res.push_back(joint_id); + } + return res; + } + } // namespace pinocchio /// @endcond diff --git a/include/pinocchio/multibody/model.txx b/include/pinocchio/multibody/model.txx index b6e3814694..08f333a31b 100644 --- a/include/pinocchio/multibody/model.txx +++ b/include/pinocchio/multibody/model.txx @@ -1,5 +1,5 @@ // -// Copyright (c) 2022 INRIA +// Copyright (c) 2022-2024 INRIA // #ifndef __pinocchio_multibody_model_txx__ @@ -43,7 +43,7 @@ namespace pinocchio extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI FrameIndex ModelTpl::addJointFrame( - const JointIndex &, int); + const JointIndex, int); extern template PINOCCHIO_EXPLICIT_INSTANTIATION_DECLARATION_DLLAPI void ModelTpl::appendBodyToJoint( diff --git a/include/pinocchio/multibody/sample-models.hxx b/include/pinocchio/multibody/sample-models.hxx index 4fac645a23..faf752c33e 100644 --- a/include/pinocchio/multibody/sample-models.hxx +++ b/include/pinocchio/multibody/sample-models.hxx @@ -134,8 +134,10 @@ namespace pinocchio model.lowerPositionLimit.segment(idx_q, nq).fill(qmin); model.upperPositionLimit.segment(idx_q, nq).fill(qmax); - model.velocityLimit.segment(idx_v, nq).fill(vmax); - model.effortLimit.segment(idx_v, nq).fill(taumax); + model.lowerVelocityLimit.segment(idx_v, nq).fill(vmax); + model.upperVelocityLimit.segment(idx_v, nq).fill(vmax); + model.lowerEffortLimit.segment(idx_v, nq).fill(taumax); + model.upperEffortLimit.segment(idx_v, nq).fill(taumax); } #ifdef PINOCCHIO_WITH_HPP_FCL diff --git a/include/pinocchio/multibody/visitor/joint-unary-visitor.hpp b/include/pinocchio/multibody/visitor/joint-unary-visitor.hpp index 6ed3fd8dd2..a636ef765c 100644 --- a/include/pinocchio/multibody/visitor/joint-unary-visitor.hpp +++ b/include/pinocchio/multibody/visitor/joint-unary-visitor.hpp @@ -1,10 +1,11 @@ // -// Copyright (c) 2015-2023 CNRS INRIA +// Copyright (c) 2015-2024 CNRS INRIA // #ifndef __pinocchio_multibody_visitor_joint_unary_visitor_hpp__ #define __pinocchio_multibody_visitor_joint_unary_visitor_hpp__ +#include #include #include @@ -16,6 +17,22 @@ namespace pinocchio namespace fusion { + namespace helper + { + /// \brief Add constness to T2 if T1 is const + template + struct add_const_if_const + { + typedef T2 type; + }; + + template + struct add_const_if_const + { + typedef const T2 type; + }; + } // namespace helper + /// /// \brief Base structure for \b Unary visitation of a JointModel. /// This structure provides runners to call the right visitor according to the number of @@ -35,8 +52,27 @@ namespace pinocchio JointDataTpl & jdata, ArgsTmp args) { - InternalVisitorModelAndData, ArgsTmp> - visitor(jdata, args); + typedef JointModelTpl JointModel; + typedef JointDataTpl JointData; + + InternalVisitorModelAndData visitor(jdata, args); + return boost::apply_visitor(visitor, jmodel); + } + + template< + typename Scalar, + int Options, + template class JointCollectionTpl, + typename ArgsTmp> + static ReturnType run( + const JointModelTpl & jmodel, + const JointDataTpl & jdata, + ArgsTmp args) + { + typedef JointModelTpl JointModel; + typedef JointDataTpl JointData; + + InternalVisitorModelAndData visitor(jdata, args); return boost::apply_visitor(visitor, jmodel); } @@ -45,8 +81,22 @@ namespace pinocchio const JointModelTpl & jmodel, JointDataTpl & jdata) { - InternalVisitorModelAndData, NoArg> - visitor(jdata); + typedef JointModelTpl JointModel; + typedef JointDataTpl JointData; + + InternalVisitorModelAndData visitor(jdata); + return boost::apply_visitor(visitor, jmodel); + } + + template class JointCollectionTpl> + static ReturnType run( + const JointModelTpl & jmodel, + const JointDataTpl & jdata) + { + typedef JointModelTpl JointModel; + typedef JointDataTpl JointData; + + InternalVisitorModelAndData visitor(jdata); return boost::apply_visitor(visitor, jmodel); } @@ -56,7 +106,24 @@ namespace pinocchio typename JointModelBase::JointDataDerived & jdata, ArgsTmp args) { - InternalVisitorModelAndData visitor(jdata, args); + typedef JointModelBase JointModel; + typedef typename JointModel::JointDataDerived JointData; + + InternalVisitorModelAndData visitor(jdata, args); + return visitor(jmodel.derived()); + } + + template + static ReturnType run( + const JointModelBase & jmodel, + const typename JointModelBase::JointDataDerived & jdata, + ArgsTmp args) + { + typedef JointModelBase JointModel; + typedef typename JointModel::JointDataDerived JointData; + + InternalVisitorModelAndData visitor( + jdata, args); return visitor(jmodel.derived()); } @@ -65,7 +132,22 @@ namespace pinocchio const JointModelBase & jmodel, typename JointModelBase::JointDataDerived & jdata) { - InternalVisitorModelAndData visitor(jdata); + typedef JointModelBase JointModel; + typedef typename JointModel::JointDataDerived JointData; + + InternalVisitorModelAndData visitor(jdata); + return visitor(jmodel.derived()); + } + + template + static ReturnType run( + const JointModelBase & jmodel, + const typename JointModelBase::JointDataDerived & jdata) + { + typedef JointModelBase JointModel; + typedef typename JointModel::JointDataDerived JointData; + + InternalVisitorModelAndData visitor(jdata); return visitor(jmodel.derived()); } @@ -136,11 +218,9 @@ namespace pinocchio } private: - template + template struct InternalVisitorModelAndData : public boost::static_visitor { - typedef typename JointModel::JointDataDerived JointData; - InternalVisitorModelAndData(JointData & jdata, ArgType args) : jdata(jdata) , args(args) @@ -150,13 +230,13 @@ namespace pinocchio template ReturnType operator()(const JointModelBase & jmodel) const { + typedef typename helper::add_const_if_const< + JointData, typename JointModelBase::JointDataDerived>::type + JointDataDerived; return bf::invoke( &JointVisitorDerived::template algo, bf::append( - boost::ref(jmodel.derived()), - boost::ref( - boost::get::JointDataDerived>(jdata)), - args)); + boost::ref(jmodel.derived()), boost::ref(boost::get(jdata)), args)); } ReturnType operator()(const JointModelVoid) @@ -168,12 +248,10 @@ namespace pinocchio ArgType args; }; - template - struct InternalVisitorModelAndData + template + struct InternalVisitorModelAndData : public boost::static_visitor { - typedef typename JointModel::JointDataDerived JointData; - InternalVisitorModelAndData(JointData & jdata) : jdata(jdata) { @@ -182,12 +260,13 @@ namespace pinocchio template ReturnType operator()(const JointModelBase & jmodel) const { + typedef typename helper::add_const_if_const< + JointData, typename JointModelBase::JointDataDerived>::type + JointDataDerived; return bf::invoke( &JointVisitorDerived::template algo, bf::make_vector( - boost::ref(jmodel.derived()), - boost::ref( - boost::get::JointDataDerived>(jdata)))); + boost::ref(jmodel.derived()), boost::ref(boost::get(jdata)))); } JointData & jdata; diff --git a/include/pinocchio/parsers/fwd.hpp b/include/pinocchio/parsers/fwd.hpp new file mode 100644 index 0000000000..7f5040bb53 --- /dev/null +++ b/include/pinocchio/parsers/fwd.hpp @@ -0,0 +1,27 @@ +// +// Copyright (c) 2024 INRIA +// + +#ifndef __pinocchio_parsers_fwd_hpp__ +#define __pinocchio_parsers_fwd_hpp__ + +#include "pinocchio/multibody/model.hpp" +#include "pinocchio/multibody/geometry.hpp" +#include "pinocchio/algorithm/constraints/point-bilateral-constraint.hpp" + +namespace pinocchio +{ + namespace parsers + { + + // Parsers will work on an object of type ::pinocchio::parsers::Model, which is a + // specialization of the ModelTpl template of Pinocchio. + // Once constructed, this model can then be cast to another scalar or to another joint + // collection. + typedef ::pinocchio::ModelTpl Model; + typedef Model::JointModel JointModel; + + } // namespace parsers +} // namespace pinocchio + +#endif // __pinocchio_parsers_fwd_hpp__ diff --git a/include/pinocchio/parsers/mjcf.hpp b/include/pinocchio/parsers/mjcf.hpp index 73f26684b3..3552be3ec6 100644 --- a/include/pinocchio/parsers/mjcf.hpp +++ b/include/pinocchio/parsers/mjcf.hpp @@ -5,10 +5,7 @@ #ifndef __pinocchio_parsers_mjcf_hpp__ #define __pinocchio_parsers_mjcf_hpp__ -#include "pinocchio/multibody/model.hpp" #include "pinocchio/parsers/urdf.hpp" -#include "pinocchio/multibody/model.hpp" -#include "pinocchio/multibody/geometry.hpp" #include "pinocchio/algorithm/contact-info.hpp" namespace pinocchio @@ -44,21 +41,6 @@ namespace pinocchio ModelTpl & model, const bool verbose = false); - // TODO: update description, buildModel with contact model - template class JointCollectionTpl> - ModelTpl & buildModel( - const std::string & filename, - ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, - const bool verbose = false); - - template class JointCollectionTpl> - ModelTpl & buildModelFromXML( - const std::string & xmlStream, - ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, - const bool verbose = false); - /// /// \brief Build the model from a MJCF file with a particular joint as root of the model tree /// inside the model given as reference argument. @@ -111,70 +93,63 @@ namespace pinocchio const bool verbose = false); /// - /// \brief Build the model from a MJCF file with a particular joint as root of the model tree - /// inside the model given as reference argument. + /// \brief Build the constraint models from a MJCF string. The associated model should be built + /// beforehand by calling buildModel. /// - /// \param[in] filename The MJCF complete file path. - /// \param[in] rootJoint The joint at the root of the model tree. + /// \param[in] xmlStream The MJCF string. + /// \param[in] model The assocaited model /// \param[in] verbose Print parsing info. - /// \param[out] model Reference model where to put the parsed information. - /// \return Return the reference on argument model for convenience. + /// \param[out] bilateral_constraint_models Reference constraint models where to put the parsed + /// \param[out] weld_constraint_models Reference constraint models where to put the parsed + /// information for weld constraints. /// template class JointCollectionTpl> - ModelTpl & buildModel( - const std::string & filename, - const typename ModelTpl::JointModel & rootJoint, - ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, - const bool verbose = false); - - template class JointCollectionTpl> - ModelTpl & buildModelFromXML( + void buildConstraintModelsFromXML( const std::string & xmlStream, - const typename ModelTpl::JointModel & rootJoint, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, - const bool verbose); + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + & bilateral_constraint_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) & weld_constraint_models, + const bool verbose = false); /// - /// \brief Build the model from a MJCF file with a particular joint as root of the model tree - /// inside the model given as reference argument. + /// \brief Build the constraint models from a MJCF string. The associated model should be built + /// beforehand by calling buildModel. /// - /// \param[in] filename The MJCF complete file path. - /// \param[in] rootJoint The joint at the root of the model tree. - /// \param[in] rootJointName Name of the rootJoint. + /// \param[in] xmlStream The MJCF string. + /// \param[in] model The assocaited model /// \param[in] verbose Print parsing info. - /// \param[out] model Reference model where to put the parsed information. - /// \return Return the reference on argument model for convenience. + /// \param[out] bilateral_constraint_models Reference constraint models where to put the parsed + /// information for bilateral constraints. + /// \return Return the reference on argument billateral constraint models for convenience. /// template class JointCollectionTpl> - ModelTpl & buildModel( - const std::string & filename, - const typename ModelTpl::JointModel & rootJoint, - const std::string & rootJointName, - ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, - const bool verbose = false); + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + & buildConstraintModelsFromXML( + const std::string & xmlStream, + ModelTpl & model, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + & bilateral_constraint_models, + const bool verbose = false); /// - /// \brief Build the model from an XML stream with a particular joint as root of the model tree - /// inside the model given as reference argument. + /// \brief Build the constraint models from a MJCF string. The associated model should be built + /// beforehand by calling buildModel. /// - /// \param[in] xmlStream xml stream containing MJCF model - /// \param[in] rootJoint The joint at the root of the model tree. - /// \param[in] rootJointName Name of the rootJoint. + /// \param[in] xmlStream The MJCF string. + /// \param[in] model The assocaited model /// \param[in] verbose Print parsing info. - /// \param[out] model Reference model where to put the parsed information. - /// \return Return the reference on argument model for convenience. + /// \param[out] weld_constraint_models Reference constraint models where to put the parsed + /// information for weld constraints. + /// \return Return the reference on argument weld constraint models for convenience. /// template class JointCollectionTpl> - ModelTpl & buildModelFromXML( - const std::string & xmlStream, - const typename ModelTpl::JointModel & rootJoint, - const std::string & rootJointName, - ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, - const bool verbose = false); + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) + & buildConstraintModelsFromXML( + const std::string & xmlStream, + ModelTpl & model, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) & weld_constraint_models, + const bool verbose = false); /** * @brief Build The GeometryModel from a Mjcf file diff --git a/include/pinocchio/parsers/mjcf/geometry.hxx b/include/pinocchio/parsers/mjcf/geometry.hxx index 879bf0043c..a1eac1b340 100644 --- a/include/pinocchio/parsers/mjcf/geometry.hxx +++ b/include/pinocchio/parsers/mjcf/geometry.hxx @@ -20,7 +20,9 @@ namespace pinocchio GeometryModel & geomModel, ::hpp::fcl::MeshLoaderPtr meshLoader) { - ::pinocchio::urdf::details::UrdfVisitor visitor(model); + typedef ::pinocchio::parsers::Model Model; + Model urdf_model = model; + ::pinocchio::mjcf::details::MjcfVisitor visitor(urdf_model); typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; diff --git a/include/pinocchio/parsers/mjcf/mjcf-graph.hpp b/include/pinocchio/parsers/mjcf/mjcf-graph.hpp index 4960a24a68..9b0d524b1e 100644 --- a/include/pinocchio/parsers/mjcf/mjcf-graph.hpp +++ b/include/pinocchio/parsers/mjcf/mjcf-graph.hpp @@ -9,6 +9,11 @@ #include "pinocchio/multibody/model.hpp" #include "pinocchio/multibody/joint/joints.hpp" #include "pinocchio/algorithm/contact-info.hpp" +#include "pinocchio/algorithm/constraints/point-bilateral-constraint.hpp" +#include "pinocchio/algorithm/constraints/weld-constraint.hpp" +#include "pinocchio/multibody/liegroup/liegroup.hpp" +#include "pinocchio/multibody/liegroup/liegroup-joint.hpp" + #include #include #include @@ -34,6 +39,69 @@ namespace pinocchio struct MjcfGeom; struct MjcfSite; + using JointType = ::pinocchio::urdf::details::JointType; + + class PINOCCHIO_PARSERS_DLLAPI MjcfVisitor : public ::pinocchio::urdf::details::UrdfVisitor + { + public: + typedef ::pinocchio::urdf::details::UrdfVisitor Base; + typedef Base::Model Model; + typedef Base::JointModel JointModel; + + MjcfVisitor(Model & model) + : Base(model) + { + } + + void addRootJoint( + const Inertia & Y, + const std::string & body_name, + Eigen::VectorXd & reference_config, + Eigen::VectorXd & qpos0, + const boost::optional root_joint, + const boost::optional root_joint_name) + { + Base::addRootJoint(Y, body_name, root_joint, root_joint_name); + + if (root_joint.has_value()) + { + Eigen::VectorXd qroot(root_joint->template lieGroup().neutral()); + + // update the reference_config with the size of the root joint + reference_config.conservativeResize(reference_config.size() + qroot.size()); + reference_config.tail(qroot.size()) = qroot; + + // convert qroot to mujoco's convention for quaternions + int qpos0_size = static_cast(qpos0.size()); + qpos0.conservativeResize(qpos0_size + qroot.size()); + qpos0.tail(qroot.size()) = qroot; + if (root_joint->shortname() == "JointModelFreeFlyer") + { + qpos0.tail(4) << qroot(6), qroot(3), qroot(4), qroot(5); + } + else if (root_joint->shortname() == "JointModelSpherical") + { + qpos0.tail(4) << qroot(3), qroot(0), qroot(1), qroot(2); + } + else if (root_joint->shortname() == "JointModelComposite") + { + JointModel root_joint_copy = root_joint.get(); + root_joint_copy.setIndexes(0, 0, 0); + for (const auto & joint_ : + boost::get(root_joint_copy.toVariant()).joints) + { + if (joint_.shortname() == "JointModelSpherical") + { + int idx_q_ = joint_.idx_q(); + qpos0.segment(qpos0_size + idx_q_, 4) << qroot(idx_q_ + 3), qroot(idx_q_ + 0), + qroot(idx_q_ + 1), qroot(idx_q_ + 2); + } + } + } + } + } + }; + /// @brief Informations that are stocked in the XML tag compile. /// struct PINOCCHIO_PARSERS_DLLAPI MjcfCompiler @@ -115,41 +183,53 @@ namespace pinocchio /// @brief All joint limits struct PINOCCHIO_PARSERS_DLLAPI RangeJoint { + // Min effort + Eigen::VectorXd minEffort; // Max effort Eigen::VectorXd maxEffort; + // Min velocity + Eigen::VectorXd minVel; // Max velocity Eigen::VectorXd maxVel; // Max position Eigen::VectorXd maxConfig; // Min position Eigen::VectorXd minConfig; + // Position margin + Eigen::VectorXd configLimitMargin; // Join Stiffness Eigen::VectorXd springStiffness; // joint position or angle in which the joint spring (if any) achieves equilibrium Eigen::VectorXd springReference; - // friction applied in this joint - Eigen::VectorXd friction; + // Min friction applied in this joint + Eigen::VectorXd minDryFriction; + // Max friction applied in this joint + Eigen::VectorXd maxDryFriction; // Damping applied by this joint. Eigen::VectorXd damping; // Armature inertia created by this joint Eigen::VectorXd armature; // Dry friction. - double frictionLoss = 0.; + // double frictionLoss = 0.; RangeJoint() = default; explicit RangeJoint(double v) { const double infty = std::numeric_limits::infinity(); + minVel = Eigen::VectorXd::Constant(1, -infty); maxVel = Eigen::VectorXd::Constant(1, infty); + minEffort = Eigen::VectorXd::Constant(1, -infty); maxEffort = Eigen::VectorXd::Constant(1, infty); minConfig = Eigen::VectorXd::Constant(1, -infty); maxConfig = Eigen::VectorXd::Constant(1, infty); + configLimitMargin = Eigen::VectorXd::Constant(1, 0); springStiffness = Eigen::VectorXd::Constant(1, v); springReference = Eigen::VectorXd::Constant(1, v); - friction = Eigen::VectorXd::Constant(1, 0.); + minDryFriction = Eigen::VectorXd::Constant(1, 0.); + maxDryFriction = Eigen::VectorXd::Constant(1, 0.); damping = Eigen::VectorXd::Constant(1, 0.); armature = Eigen::VectorXd::Constant(1, 0.); } @@ -363,18 +443,22 @@ namespace pinocchio // Name of the second body participating in the constraint (optional, default: world) std::string body2; + // Name of the first site participating in the constraint + std::string site1; + // Name of the second site participating in the constraint (optional, default: world) + std::string site2; + // Coordinates of the 3D anchor point where the two bodies are connected. // Specified relative to the local coordinate frame of the first body. Eigen::Vector3d anchor = Eigen::Vector3d::Zero(); - // TODO: implement when weld is introduced - // This attribute specifies the relative pose (3D position followed by 4D quaternion - // orientation) of body2 relative to body1. If the quaternion part (i.e., last 4 components - // of the vector) are all zeros, as in the default setting, this attribute is ignored and - // the relative pose is the one corresponding to the model reference pose in qpos0. The - // unusual default is because all equality constraint types share the same default for their - // numeric parameters. - // Eigen::VectorXd relativePose = Eigen::VectorXd::Zero(7); + // Relative pose of the weld position where the two bodies are welded. + // Specified relative to the local coordinate frame of the first body. + SE3 relpose = SE3::Identity(); + + // The default value of relpose is not a valid position and trigger. + // a special event where relative pose is calculated in qref + bool use_qref_relpose = true; }; /// @brief The graph which contains all information taken from the mjcf file @@ -408,12 +492,37 @@ namespace pinocchio // Map of equality constraints EqualityMap_t mapOfEqualities; - // reference configuration + // @brief Reference configuration that allows pinocchio's FK to match mujoco's FK. + // When doing a FK in mujoco, there are two differences with pinocchio's FK: + // 1) In mujoco, a freeflyer's placement w.r.t its parent is never taken into consideration. + // Only the freeflyer's component of the configuration vector are used for the FK. + // For all other joints, the joints' components AND their placement w.r.t their parents + // are taken into consideration. + // In pinocchio, the placements w.r.t parents are always taken into consideration. + // 2) In mujoco, for hinge and slide joints, a reference can be used to offset the "zero" of + // these joints. + // + // If we were to simply parse an MJCF file to construct a pinocchio model, we would find + // that FK(mujoco, q) = FK(pinocchio, q - qref). + // However, to make it easier to switch between mujoco and pinocchio, it's handy to use the + // same q in both frameworks. Therefore, after parsing the model, we update the placement of + // each pinocchio joint such that FK(mujoco, q) = FK(pinocchio, q). + // Therefore, the `referenceConfig` vector is used to perform this update. Eigen::VectorXd referenceConfig; + /// @brief Default configuration obtained when parsing an MJCF file. + /// This configuration is not a keyframe and is only obtained by parsing the succession of + /// ... inside + /// It is handy to store this default configuration as it is typically used to define + /// equality constraints in a MJCF file. + Eigen::VectorXd qpos0; + // property tree where xml file is stored ptree pt; + // World body, mainly used to store geoms that are outside the body hierarchy + MjcfBody worldBody; + // Ordered list of bodies VectorOfStrings bodiesList; @@ -421,17 +530,16 @@ namespace pinocchio std::string modelName; std::string modelPath; - // Urdf Visitor to add joint and body - typedef pinocchio::urdf::details:: - UrdfVisitor - UrdfVisitor; - UrdfVisitor & urdfVisitor; + // Mjcf Visitor to add joint and body + MjcfVisitor & mjcfVisitor; + typedef MjcfVisitor::Model Model; + typedef MjcfVisitor::JointModel JointModel; /// @brief graph constructor - /// @param urdfVisitor - MjcfGraph(UrdfVisitor & urdfVisitor, const std::string & modelPath) + /// @param mjcfVisitor + MjcfGraph(MjcfVisitor & mjcfVisitor, const std::string & modelPath) : modelPath(modelPath) - , urdfVisitor(urdfVisitor) + , mjcfVisitor(mjcfVisitor) { } @@ -450,6 +558,11 @@ namespace pinocchio /// @param el ptree element. Root of the default void parseDefault(ptree & el, const ptree & parent, const std::string & parentTag); + /// @brief Inspect the worlbody tag to retrieve potential geoms that are not attached + /// to any bodies. + /// @param el root of the tree + void parseWorldBodyGeoms(const ptree & el); + /// @brief Go through the main body of the mjcf file "worldbody" to get all the info ready /// to create the model. /// @param el root of the tree @@ -516,8 +629,22 @@ namespace pinocchio /// @param nameOfBody Name of the body to add void fillModel(const std::string & nameOfBody); + /// @brief Use the reference configuration that was parsed to update the joint placements so + /// that pinocchio and mujoco forward kinematics match given the same configuration vector. + /// See @ref referenceConfig for more information. + void updateJointPlacementsFromReferenceConfig(); + /// @brief Fill the pinocchio model with all the infos from the graph - void parseRootTree(); + /// @param rootJoint optional root joint to add to the base of the model. The root joint + /// will be ignored if the model doesn't have a fixed base. + /// @param rootJointName name of the optional root joint. + /// @note If a root joint provided and the graph has a fixed base, this root joint will be + /// added at the base of the model. + /// If the graph doesn't have a fixed base (the first body has one or more child joints), + /// this root joint will be ignored. + void parseRootTree( + const boost::optional rootJoint = boost::none, + const boost::optional rootJointName = boost::none); /// @brief Fill reference configuration for a body and all it's associated dof /// @param currentBody body to check @@ -530,10 +657,13 @@ namespace pinocchio /// @brief Parse the equality constraints and add them to the model /// @param model Model to add the constraints to - /// @param contact_models Vector of contact models to add the constraints to + /// @param bilateral_constraint_models Vector of contact models to add the constraints to + /// @param weld_constraint_models Vector of contact models to add the constraints to void parseContactInformation( const Model & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models); + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + & bilateral_constraint_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) & weld_constraint_models); /// @brief Fill geometry model with all the info taken from the mjcf model file /// @param type Type of geometry to parse (COLLISION or VISUAL) diff --git a/include/pinocchio/parsers/mjcf/model.hxx b/include/pinocchio/parsers/mjcf/model.hxx index 6338de07c5..67962848d5 100644 --- a/include/pinocchio/parsers/mjcf/model.hxx +++ b/include/pinocchio/parsers/mjcf/model.hxx @@ -29,28 +29,10 @@ namespace pinocchio ModelTpl & model, const bool verbose) { - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; - return buildModelFromXML(xmlStream, model, contact_models, verbose); - } - - template class JointCollectionTpl> - ModelTpl & buildModel( - const std::string & filename, - ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, - const bool verbose) - { - return buildModelFromXML(filename, model, contact_models, verbose); - } + typedef ::pinocchio::parsers::Model Model; - template class JointCollectionTpl> - ModelTpl & buildModelFromXML( - const std::string & xmlStream, - ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, - const bool verbose) - { - ::pinocchio::urdf::details::UrdfVisitor visitor(model); + Model mjcf_model = model; + ::pinocchio::mjcf::details::MjcfVisitor visitor(mjcf_model); typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; @@ -62,53 +44,66 @@ namespace pinocchio // Use the Mjcf graph to create the model graph.parseRootTree(); - graph.parseContactInformation(model, contact_models); + model = visitor.model; return model; } template class JointCollectionTpl> - ModelTpl & buildModel( - const std::string & filename, - const typename ModelTpl::JointModel & rootJoint, - ModelTpl & model, - const bool verbose) - { - return buildModelFromXML(filename, rootJoint, model, verbose); - } - - template class JointCollectionTpl> - ModelTpl & buildModelFromXML( + void buildConstraintModelsFromXML( const std::string & xmlStream, - const typename ModelTpl::JointModel & rootJoint, ModelTpl & model, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + & bilateral_constraint_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) & weld_constraint_models, const bool verbose) { - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; - return buildModelFromXML(xmlStream, rootJoint, "root_joint", model, contact_models, verbose); + typedef ::pinocchio::parsers::Model Model; + Model mjcf_model = model; + + ::pinocchio::mjcf::details::MjcfVisitor visitor(mjcf_model); + + typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; + MjcfGraph graph(visitor, xmlStream); + + if (verbose) + visitor.log = &std::cout; + + graph.parseGraphFromXML(xmlStream); + + // Use the Mjcf graph to create the model + graph.parseContactInformation( + mjcf_model, bilateral_constraint_models, weld_constraint_models); } template class JointCollectionTpl> - ModelTpl & buildModel( - const std::string & filename, - const typename ModelTpl::JointModel & rootJoint, - const std::string & rootJointName, - ModelTpl & model, - const bool verbose) + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + & buildConstraintModelsFromXML( + const std::string & xmlStream, + ModelTpl & model, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + & bilateral_constraint_models, + const bool verbose) { - return buildModelFromXML(filename, rootJoint, rootJointName, model, verbose); + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) weld_constraint_models; + buildConstraintModelsFromXML( + xmlStream, model, bilateral_constraint_models, weld_constraint_models, verbose); + return bilateral_constraint_models; } template class JointCollectionTpl> - ModelTpl & buildModelFromXML( - const std::string & xmlStream, - const typename ModelTpl::JointModel & rootJoint, - const std::string & rootJointName, - ModelTpl & model, - const bool verbose) + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) + & buildConstraintModelsFromXML( + const std::string & xmlStream, + ModelTpl & model, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) & weld_constraint_models, + const bool verbose) { - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; - return buildModelFromXML(xmlStream, rootJoint, rootJointName, model, contact_models, verbose); + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + bilateral_constraint_models; + buildConstraintModelsFromXML( + xmlStream, model, bilateral_constraint_models, weld_constraint_models, verbose); + return weld_constraint_models; } template class JointCollectionTpl> @@ -116,10 +111,9 @@ namespace pinocchio const std::string & filename, const typename ModelTpl::JointModel & rootJoint, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, const bool verbose) { - return buildModelFromXML(filename, rootJoint, model, contact_models, verbose); + return buildModelFromXML(filename, rootJoint, model, verbose); } template class JointCollectionTpl> @@ -127,10 +121,9 @@ namespace pinocchio const std::string & xmlStream, const typename ModelTpl::JointModel & rootJoint, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, const bool verbose) { - return buildModelFromXML(xmlStream, rootJoint, "root_joint", model, contact_models, verbose); + return buildModelFromXML(xmlStream, rootJoint, "root_joint", model, verbose); } template class JointCollectionTpl> @@ -139,10 +132,9 @@ namespace pinocchio const typename ModelTpl::JointModel & rootJoint, const std::string & rootJointName, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, const bool verbose) { - return buildModelFromXML(filename, rootJoint, rootJointName, model, contact_models, verbose); + return buildModelFromXML(filename, rootJoint, rootJointName, model, verbose); } template class JointCollectionTpl> @@ -151,15 +143,18 @@ namespace pinocchio const typename ModelTpl::JointModel & rootJoint, const std::string & rootJointName, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, const bool verbose) { + typedef ::pinocchio::parsers::Model Model; + typedef ::pinocchio::parsers::JointModel JointModel; if (rootJointName.empty()) throw std::invalid_argument( "rootJoint was given without a name. Please fill the argument rootJointName"); - ::pinocchio::urdf::details::UrdfVisitorWithRootJoint - visitor(model, rootJoint, rootJointName); + Model mjcf_model = model; + JointModel root_joint = rootJoint; + + ::pinocchio::mjcf::details::MjcfVisitor visitor(mjcf_model); typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; @@ -170,9 +165,11 @@ namespace pinocchio graph.parseGraphFromXML(xmlStream); // Use the Mjcf graph to create the model - graph.parseRootTree(); - graph.parseContactInformation(model, contact_models); + boost::optional root_joint_opt(root_joint); + boost::optional root_joint_name_opt(rootJointName); + graph.parseRootTree(root_joint_opt, root_joint_name_opt); + model = visitor.model; return model; } diff --git a/include/pinocchio/parsers/sample-models.hpp b/include/pinocchio/parsers/sample-models.hpp index 79b9a5c0ba..c116d0c8e4 100644 --- a/include/pinocchio/parsers/sample-models.hpp +++ b/include/pinocchio/parsers/sample-models.hpp @@ -8,7 +8,7 @@ #include "pinocchio/macros.hpp" // clang-format off -PINOCCHIO_PRAGMA_DEPRECATED_HEADER(pinocchio/parsers/sample-models.hpp, pinocchio/multibody/sample-models.hpp) +PINOCCHIO_DEPRECATED_MOVED_HEADER(pinocchio/parsers/sample-models.hpp, pinocchio/multibody/sample-models.hpp) // clang-format on #include "pinocchio/multibody/sample-models.hpp" diff --git a/include/pinocchio/parsers/sdf.hpp b/include/pinocchio/parsers/sdf.hpp index 975b482392..d1d5585931 100644 --- a/include/pinocchio/parsers/sdf.hpp +++ b/include/pinocchio/parsers/sdf.hpp @@ -6,9 +6,8 @@ #define __pinocchio_parsers_sdf_hpp__ #include "pinocchio/parsers/urdf.hpp" -#include "pinocchio/multibody/model.hpp" -#include "pinocchio/multibody/geometry.hpp" #include "pinocchio/algorithm/contact-info.hpp" +#include "pinocchio/algorithm/constraints/point-bilateral-constraint.hpp" namespace pinocchio { @@ -76,7 +75,7 @@ namespace pinocchio template class JointCollectionTpl> GeometryModel & buildGeom( const ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) & constraint_models, const std::string & filename, const GeometryType type, GeometryModel & geomModel, @@ -84,7 +83,7 @@ namespace pinocchio ::hpp::fcl::MeshLoaderPtr meshLoader = ::hpp::fcl::MeshLoaderPtr()) { const std::vector dirs(1, packagePath); - return buildGeom(model, contact_models, filename, type, geomModel, dirs, meshLoader); + return buildGeom(model, constraint_models, filename, type, geomModel, dirs, meshLoader); }; /** @@ -145,7 +144,7 @@ namespace pinocchio const typename ModelTpl::JointModel & rootJoint, const std::string & rootJointName, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) & constraint_models, const std::string & rootLinkName = "", const std::vector & parentGuidance = {}, const bool verbose = false); @@ -168,7 +167,7 @@ namespace pinocchio const std::string & xmlStream, const typename ModelTpl::JointModel & rootJoint, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) & constraint_models, const std::string & rootLinkName = "", const std::vector & parentGuidance = {}, const bool verbose = false); @@ -193,7 +192,7 @@ namespace pinocchio const typename ModelTpl::JointModel & rootJoint, const std::string & rootJointName, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) & constraint_models, const std::string & rootLinkName = "", const std::vector & parentGuidance = {}, const bool verbose = false); @@ -216,7 +215,7 @@ namespace pinocchio const std::string & filename, const typename ModelTpl::JointModel & rootJoint, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) & constraint_models, const std::string & rootLinkName = "", const std::vector & parentGuidance = {}, const bool verbose = false); @@ -233,7 +232,7 @@ namespace pinocchio ModelTpl & buildModelFromXML( const std::string & xmlStream, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) & constraint_models, const std::string & rootLinkName = "", const std::vector & parentGuidance = {}, const bool verbose = false); @@ -250,7 +249,7 @@ namespace pinocchio ModelTpl & buildModel( const std::string & filename, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) & constraint_models, const std::string & rootLinkName = "", const std::vector & parentGuidance = {}, const bool verbose = false); diff --git a/include/pinocchio/parsers/sdf/geometry.hxx b/include/pinocchio/parsers/sdf/geometry.hxx index 3c5d05015d..e32892ddf6 100644 --- a/include/pinocchio/parsers/sdf/geometry.hxx +++ b/include/pinocchio/parsers/sdf/geometry.hxx @@ -56,7 +56,7 @@ namespace pinocchio template class JointCollectionTpl> GeometryModel & buildGeom( - const ModelTpl & const_model, + const ModelTpl & model, const std::string & filename, const GeometryType type, GeometryModel & geomModel, @@ -64,9 +64,10 @@ namespace pinocchio const std::vector & package_dirs, ::hpp::fcl::MeshLoaderPtr meshLoader) { - Model & model = - const_cast(const_model); // TODO: buildGeom should not need to parse model again. - ::pinocchio::urdf::details::UrdfVisitor visitor(model); + typedef ::pinocchio::parsers::Model Model; + Model urdf_model = model; + // TODO: buildGeom should not need to parse model again. + ::pinocchio::urdf::details::UrdfVisitor visitor(urdf_model); ::pinocchio::sdf::details::SdfGraph graph(visitor); // Create maps from the SDF Graph diff --git a/include/pinocchio/parsers/sdf/model.hxx b/include/pinocchio/parsers/sdf/model.hxx index c4690856ba..1623b4ae20 100644 --- a/include/pinocchio/parsers/sdf/model.hxx +++ b/include/pinocchio/parsers/sdf/model.hxx @@ -7,10 +7,11 @@ #include "pinocchio/math/matrix.hpp" #include "pinocchio/parsers/config.hpp" -#include "pinocchio/parsers/sdf.hpp" +// #include "pinocchio/parsers/sdf.hpp" #include "pinocchio/parsers/urdf.hpp" #include "pinocchio/multibody/model.hpp" #include "pinocchio/algorithm/contact-info.hpp" +#include "pinocchio/parsers/urdf/model.hxx" #include #include @@ -139,9 +140,7 @@ namespace pinocchio ChildPoseMap childPoseMap; std::string modelName; - typedef pinocchio::urdf::details:: - UrdfVisitor - UrdfVisitor; + typedef pinocchio::urdf::details::UrdfVisitor UrdfVisitor; UrdfVisitor & urdfVisitor; PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ContactDetails) contact_details; @@ -338,6 +337,7 @@ namespace pinocchio typedef UrdfVisitor::SE3 SE3; typedef UrdfVisitor::Vector Vector; typedef UrdfVisitor::Vector3 Vector3; + typedef urdf::details::JointType JointType; const std::string & jointName = jointElement->template Get("name"); urdfVisitor << jointName << " being parsed." << '\n'; @@ -412,44 +412,7 @@ namespace pinocchio const JointIndex parentJointId = urdfVisitor.getParentId(parentName); const std::string & parentJointName = urdfVisitor.getJointName(parentJointId); - SE3 cMj(SE3::Identity()), pMjp(SE3::Identity()), oMc(SE3::Identity()), - pMj(SE3::Identity()); - - // Find pose of parent link w.r.t. parent joint. - if (parentJointName != urdfVisitor.root_joint_name && parentJointName != "universe") - { - const ::sdf::ElementPtr parentJointElement = mapOfJoints.find(parentJointName)->second; - - const ::sdf::ElementPtr parentJointPoseElem = parentJointElement->GetElement("pose"); - - const ignition::math::Pose3d parentJointPoseElem_ig = - parentJointElement->template Get("pose"); - - const std::string relativeFrame = - parentJointPoseElem->template Get("relative_to"); - const std::string parentJointParentName = - parentJointElement->GetElement("parent")->Get(); - - if (!relativeFrame.compare(parentJointParentName)) - { // If they are equal - - // Pose is relative to Parent joint's parent. Search in parent link instead. - const std::string & parentLinkRelativeFrame = - parentLinkPoseElem->template Get("relative_to"); - - // If the pMjp is not found, throw - PINOCCHIO_THROW( - !parentLinkRelativeFrame.compare(parentJointName), std::logic_error, - parentName + " pose is not defined w.r.t. parent joint"); - - pMjp = parentLinkPlacement.inverse(); - } - else - { // If the relative_to is not the parent - // The joint pose is defined w.r.t to the child, as per the SDF standard < 1.7 - pMjp = ::pinocchio::sdf::details::convertFromPose3d(parentJointPoseElem_ig); - } - } + SE3 cMj(SE3::Identity()), oMc(SE3::Identity()), pMj(SE3::Identity()); // Find Pose of current joint w.r.t. child link, e.t. cMj; const std::string & curJointRelativeFrame = @@ -476,13 +439,10 @@ namespace pinocchio pMj = parentLinkPlacement.inverse() * childLinkPlacement * cMj; } - // const SE3 jointPlacement = pMjp.inverse() * pMj; - urdfVisitor << "Joint " << jointName << " connects parent " << parentName << " link" << " with parent joint " << parentJointName << " to child " << childNameOrig - << " link" - << " with joint type " << jointElement->template Get("type") - << '\n'; + << " link" << " with joint type " + << jointElement->template Get("type") << '\n'; const Scalar infty = std::numeric_limits::infinity(); FrameIndex parentFrameId = urdfVisitor.getBodyId(parentName); Vector max_effort(Vector::Constant(1, infty)), max_velocity(Vector::Constant(1, infty)), @@ -569,14 +529,14 @@ namespace pinocchio urdfVisitor << "joint REVOLUTE with axis" << axis.transpose() << '\n'; urdfVisitor.addJointAndBody( - UrdfVisitor::REVOLUTE, axis, parentFrameId, pMj, jointName, Y, cMj.inverse(), + JointType::REVOLUTE, axis, parentFrameId, pMj, jointName, Y, cMj.inverse(), childName, max_effort, max_velocity, min_config, max_config, friction, damping); } else if (jointElement->template Get("type") == "gearbox") { urdfVisitor << "joint GEARBOX with axis" << '\n'; urdfVisitor.addJointAndBody( - UrdfVisitor::REVOLUTE, axis, parentFrameId, pMj, jointName, Y, cMj.inverse(), + JointType::REVOLUTE, axis, parentFrameId, pMj, jointName, Y, cMj.inverse(), childName, max_effort, max_velocity, min_config, max_config, friction, damping); } else if (jointElement->template Get("type") == "prismatic") @@ -589,7 +549,7 @@ namespace pinocchio urdfVisitor << "joint prismatic with axis" << '\n'; urdfVisitor.addJointAndBody( - UrdfVisitor::PRISMATIC, axis, parentFrameId, pMj, jointName, Y, cMj.inverse(), + JointType::PRISMATIC, axis, parentFrameId, pMj, jointName, Y, cMj.inverse(), childName, max_effort, max_velocity, min_config, max_config, friction, damping); } else if (jointElement->template Get("type") == "fixed") @@ -610,7 +570,7 @@ namespace pinocchio urdfVisitor << "joint BALL" << '\n'; urdfVisitor.addJointAndBody( - UrdfVisitor::SPHERICAL, axis, parentFrameId, pMj, jointName, Y, cMj.inverse(), + JointType::SPHERICAL, axis, parentFrameId, pMj, jointName, Y, cMj.inverse(), childName, max_effort, max_velocity, min_config, max_config, friction, damping); } else @@ -665,13 +625,17 @@ namespace pinocchio } }; // Struct sdfGraph - PINOCCHIO_PARSERS_DLLAPI void - parseRootTree(SdfGraph & graph, const std::string & rootLinkName); + PINOCCHIO_PARSERS_DLLAPI void parseRootTree( + SdfGraph & graph, + const std::string & rootLinkName, + const boost::optional rootJoint = boost::none, + const boost::optional rootJointName = boost::none); PINOCCHIO_PARSERS_DLLAPI void parseContactInformation( const SdfGraph & graph, - const urdf::details::UrdfVisitorBase & visitor, + const urdf::details::UrdfVisitor & visitor, const Model & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models); + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + & constraint_models); /** * @brief Find the parent of all elements, the root link, and return it. @@ -689,17 +653,20 @@ namespace pinocchio const typename ModelTpl::JointModel & rootJoint, const std::string & rootJointName, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) & constraint_models, const std::string & rootLinkName, const std::vector & parentGuidance, const bool verbose) { + typedef ::pinocchio::parsers::Model Model; + typedef ::pinocchio::parsers::JointModel JointModel; if (rootJointName.empty()) throw std::invalid_argument( "rootJoint was given without a name. Please fill the argument rootJointName"); - ::pinocchio::urdf::details::UrdfVisitorWithRootJoint - visitor(model, rootJoint, rootJointName); + Model sdf_model = model; + JointModel root_joint = rootJoint; + ::pinocchio::urdf::details::UrdfVisitor visitor(sdf_model); typedef ::pinocchio::sdf::details::SdfGraph SdfGraph; @@ -718,9 +685,12 @@ namespace pinocchio } // Use the SDF graph to create the model - details::parseRootTree(graph, rootLinkName); - details::parseContactInformation(graph, visitor, model, contact_models); + boost::optional root_joint_opt(root_joint); + boost::optional root_joint_name_opt(rootJointName); + details::parseRootTree(graph, rootLinkName, root_joint_opt, root_joint_name_opt); + details::parseContactInformation(graph, visitor, sdf_model, constraint_models); + model = visitor.model; return model; } @@ -729,13 +699,13 @@ namespace pinocchio const std::string & xmlStream, const typename ModelTpl::JointModel & rootJoint, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) & constraint_models, const std::string & rootLinkName, const std::vector & parentGuidance, const bool verbose) { return buildModelFromXML( - xmlStream, rootJoint, "root_joint", model, contact_models, rootLinkName, parentGuidance, + xmlStream, rootJoint, "root_joint", model, constraint_models, rootLinkName, parentGuidance, verbose); } @@ -745,17 +715,21 @@ namespace pinocchio const typename ModelTpl::JointModel & rootJoint, const std::string & rootJointName, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) & constraint_models, const std::string & rootLinkName, const std::vector & parentGuidance, const bool verbose) { + typedef ::pinocchio::parsers::Model Model; + typedef ::pinocchio::parsers::JointModel JointModel; if (rootJointName.empty()) throw std::invalid_argument( "rootJoint was given without a name. Please fill the argument rootJointName"); - ::pinocchio::urdf::details::UrdfVisitorWithRootJoint - visitor(model, rootJoint, rootJointName); + Model sdf_model = model; + JointModel root_joint = rootJoint; + + ::pinocchio::urdf::details::UrdfVisitor visitor(sdf_model); typedef ::pinocchio::sdf::details::SdfGraph SdfGraph; @@ -774,9 +748,12 @@ namespace pinocchio } // Use the SDF graph to create the model - details::parseRootTree(graph, rootLinkName); - details::parseContactInformation(graph, visitor, model, contact_models); + boost::optional root_joint_opt(root_joint); + boost::optional root_joint_name_opt(rootJointName); + details::parseRootTree(graph, rootLinkName, root_joint_opt, root_joint_name_opt); + details::parseContactInformation(graph, visitor, sdf_model, constraint_models); + model = visitor.model; return model; } @@ -785,13 +762,13 @@ namespace pinocchio const std::string & filename, const typename ModelTpl::JointModel & rootJoint, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) & constraint_models, const std::string & rootLinkName, const std::vector & parentGuidance, const bool verbose) { return buildModel( - filename, rootJoint, "root_joint", model, contact_models, rootLinkName, parentGuidance, + filename, rootJoint, "root_joint", model, constraint_models, rootLinkName, parentGuidance, verbose); } @@ -799,14 +776,16 @@ namespace pinocchio ModelTpl & buildModelFromXML( const std::string & xmlStream, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) & constraint_models, const std::string & rootLinkName, const std::vector & parentGuidance, const bool verbose) { + typedef ::pinocchio::parsers::Model Model; typedef ::pinocchio::sdf::details::SdfGraph SdfGraph; - ::pinocchio::urdf::details::UrdfVisitor visitor(model); + Model sdf_model = model; + ::pinocchio::urdf::details::UrdfVisitor visitor(sdf_model); SdfGraph graph(visitor); graph.setParentGuidance(parentGuidance); @@ -824,8 +803,9 @@ namespace pinocchio // Use the SDF graph to create the model details::parseRootTree(graph, rootLinkName); - details::parseContactInformation(graph, visitor, model, contact_models); + details::parseContactInformation(graph, visitor, sdf_model, constraint_models); + model = visitor.model; return model; } @@ -833,14 +813,16 @@ namespace pinocchio ModelTpl & buildModel( const std::string & filename, ModelTpl & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) & constraint_models, const std::string & rootLinkName, const std::vector & parentGuidance, const bool verbose) { + typedef ::pinocchio::parsers::Model Model; typedef ::pinocchio::sdf::details::SdfGraph SdfGraph; - ::pinocchio::urdf::details::UrdfVisitor visitor(model); + Model sdf_model = model; + ::pinocchio::urdf::details::UrdfVisitor visitor(sdf_model); SdfGraph graph(visitor); graph.setParentGuidance(parentGuidance); @@ -858,8 +840,9 @@ namespace pinocchio // Use the SDF graph to create the model details::parseRootTree(graph, rootLinkName); - details::parseContactInformation(graph, visitor, model, contact_models); + details::parseContactInformation(graph, visitor, sdf_model, constraint_models); + model = visitor.model; return model; } } // namespace sdf diff --git a/include/pinocchio/parsers/srdf.hpp b/include/pinocchio/parsers/srdf.hpp index 97de521e9d..947bcfec16 100644 --- a/include/pinocchio/parsers/srdf.hpp +++ b/include/pinocchio/parsers/srdf.hpp @@ -5,8 +5,7 @@ #ifndef __pinocchio_parser_srdf_hpp__ #define __pinocchio_parser_srdf_hpp__ -#include "pinocchio/multibody/model.hpp" -#include "pinocchio/multibody/geometry.hpp" +#include "pinocchio/parsers/fwd.hpp" namespace pinocchio { diff --git a/include/pinocchio/parsers/urdf.hpp b/include/pinocchio/parsers/urdf.hpp index 91c9223523..8a8ecc4f96 100644 --- a/include/pinocchio/parsers/urdf.hpp +++ b/include/pinocchio/parsers/urdf.hpp @@ -6,6 +6,7 @@ #ifndef __pinocchio_parsers_urdf_hpp__ #define __pinocchio_parsers_urdf_hpp__ +#include "pinocchio/parsers/fwd.hpp" #include "pinocchio/multibody/model.hpp" #include "pinocchio/multibody/geometry.hpp" #include "pinocchio/parsers/meshloader-fwd.hpp" diff --git a/include/pinocchio/parsers/urdf/model.hxx b/include/pinocchio/parsers/urdf/model.hxx index b68667eb20..5044c18568 100644 --- a/include/pinocchio/parsers/urdf/model.hxx +++ b/include/pinocchio/parsers/urdf/model.hxx @@ -10,9 +10,11 @@ #include "pinocchio/parsers/config.hpp" #include "pinocchio/parsers/urdf.hpp" #include "pinocchio/multibody/model.hpp" +#include "pinocchio/algorithm/joint-configuration.hpp" #include #include +#include #include #include #include @@ -26,117 +28,20 @@ namespace pinocchio { typedef double urdf_scalar_type; - template - struct MimicInfo; - - template - class UrdfVisitorBaseTpl + enum JointType { - public: - enum JointType - { - REVOLUTE, - CONTINUOUS, - PRISMATIC, - FLOATING, - PLANAR, - SPHERICAL, - MIMIC - }; - - typedef enum ::pinocchio::FrameType FrameType; - typedef _Scalar Scalar; - typedef SE3Tpl SE3; - typedef InertiaTpl Inertia; - - typedef Eigen::Matrix Vector3; - typedef Eigen::Matrix Vector; - typedef Eigen::Ref VectorRef; - typedef Eigen::Ref VectorConstRef; - typedef MimicInfo MimicInfo_; - - virtual void setName(const std::string & name) = 0; - - virtual void addRootJoint(const Inertia & Y, const std::string & body_name) = 0; - - virtual void addJointAndBody( - JointType type, - const Vector3 & axis, - const FrameIndex & parentFrameId, - const SE3 & placement, - const std::string & joint_name, - const Inertia & Y, - const std::string & body_name, - const VectorConstRef & max_effort, - const VectorConstRef & max_velocity, - const VectorConstRef & min_config, - const VectorConstRef & max_config, - const VectorConstRef & friction, - const VectorConstRef & damping, - const boost::optional & mimic_info = boost::none) = 0; - - virtual void addJointAndBody( - JointType type, - const Vector3 & axis, - const FrameIndex & parentFrameId, - const SE3 & placement, - const std::string & joint_name, - const Inertia & Y, - const SE3 & frame_placement, - const std::string & body_name, - const VectorConstRef & max_effort, - const VectorConstRef & max_velocity, - const VectorConstRef & min_config, - const VectorConstRef & max_config, - const VectorConstRef & friction, - const VectorConstRef & damping, - const boost::optional & mimic_info = boost::none) = 0; - - virtual void addFixedJointAndBody( - const FrameIndex & parentFrameId, - const SE3 & joint_placement, - const std::string & joint_name, - const Inertia & Y, - const std::string & body_name) = 0; - - virtual void appendBodyToJoint( - const FrameIndex fid, - const Inertia & Y, - const SE3 & placement, - const std::string & body_name) = 0; - - virtual FrameIndex getBodyId(const std::string & frame_name) const = 0; - - virtual JointIndex getJointId(const std::string & joint_name) const = 0; - - virtual const std::string & getJointName(const JointIndex jointId) const = 0; - - virtual Frame getBodyFrame(const std::string & frame_name) const = 0; - - virtual JointIndex getParentId(const std::string & frame_name) const = 0; - - virtual bool existFrame(const std::string & frame_name, const FrameType type) const = 0; - - UrdfVisitorBaseTpl() - : log(NULL) - { - } - - template - UrdfVisitorBaseTpl & operator<<(const T & t) - { - if (log != NULL) - *log << t; - return *this; - } - - std::ostream * log; + REVOLUTE, + CONTINUOUS, + PRISMATIC, + FLOATING, + PLANAR, + SPHERICAL, + MIMIC }; - template struct MimicInfo { - typedef _Scalar Scalar; + typedef urdf_scalar_type Scalar; typedef Eigen::Matrix Vector3; std::string mimicked_name; @@ -145,17 +50,16 @@ namespace pinocchio Vector3 axis; // Use the JointType from UrdfVisitorBaseTpl - typedef typename UrdfVisitorBaseTpl<_Scalar, Options>::JointType JointType; JointType jointType; MimicInfo() = default; MimicInfo( - std::string _mimicked_name, - Scalar _multiplier, - Scalar _offset, - Vector3 _axis, - JointType _jointType) + const std::string & _mimicked_name, + const Scalar _multiplier, + const Scalar _offset, + const Vector3 & _axis, + const JointType _jointType) : mimicked_name(_mimicked_name) , multiplier(_multiplier) , offset(_offset) @@ -165,36 +69,40 @@ namespace pinocchio } }; - template class JointCollectionTpl> - class UrdfVisitor : public UrdfVisitorBaseTpl + class UrdfVisitor { public: - typedef UrdfVisitorBaseTpl Base; - typedef typename Base::JointType JointType; - typedef typename Base::Vector3 Vector3; - typedef typename Base::VectorConstRef VectorConstRef; - typedef typename Base::SE3 SE3; - typedef typename Base::Inertia Inertia; - - typedef ModelTpl Model; + typedef UrdfVisitor Self; + + typedef urdf_scalar_type Scalar; + typedef SE3Tpl SE3; + typedef InertiaTpl Inertia; + + typedef Eigen::Matrix Vector3; + typedef Eigen::Matrix Vector; + typedef Eigen::Ref VectorRef; + typedef Eigen::Ref VectorConstRef; + + typedef ::pinocchio::parsers::Model Model; typedef typename Model::JointCollection JointCollection; typedef typename Model::JointModel JointModel; typedef typename Model::Frame Frame; - typedef MimicInfo MimicInfo_; - Model & model; - std::string root_joint_name; + std::ostream * log; UrdfVisitor(Model & model) : model(model) + , log(nullptr) { } - UrdfVisitor(Model & model, const std::string & rjn) - : model(model) - , root_joint_name(rjn) + template + UrdfVisitor & operator<<(const T & t) { + if (log != nullptr) + *log << t; + return *this; } void setName(const std::string & name) @@ -202,12 +110,39 @@ namespace pinocchio model.name = name; } - virtual void addRootJoint(const Inertia & Y, const std::string & body_name) + void addRootJoint( + const Inertia & Y, + const std::string & body_name, + const boost::optional root_joint, + const boost::optional root_joint_name) { const Frame & parent_frame = model.frames[0]; + if (root_joint.has_value()) + { + PINOCCHIO_THROW_IF( + !root_joint_name.has_value(), std::invalid_argument, + "if root_joint is provided, root_joint_name must be also be provided."); + PINOCCHIO_THROW_IF( + model.existJointName(root_joint_name.get()), std::invalid_argument, + "root_joint already exists as a joint in the kinematic tree."); + + const Frame & frame = model.frames[0]; + + JointIndex idx = model.addJoint( + frame.parentJoint, root_joint.get(), SE3::Identity(), root_joint_name.get() + // TODO ,max_effort,max_velocity,min_config,max_config + ); + + FrameIndex jointFrameId = model.addJointFrame(idx, 0); + appendBodyToJoint(jointFrameId, Y, SE3::Identity(), body_name); + return; + } + // If a root joint has not been provided, we simply add a frame that represents + // the body (which inertia and name are given as input to this method) model.addFrame( Frame(body_name, parent_frame.parentJoint, 0, parent_frame.placement, BODY, Y)); + return; } void addJointAndBody( @@ -224,7 +159,7 @@ namespace pinocchio const VectorConstRef & max_config, const VectorConstRef & friction, const VectorConstRef & damping, - const boost::optional & mimic_info = boost::none) + const boost::optional & mimic_info = boost::none) { addJointAndBody( type, axis, parentFrameId, placement, joint_name, Y, SE3::Identity(), body_name, @@ -246,73 +181,135 @@ namespace pinocchio const VectorConstRef & max_config, const VectorConstRef & friction, const VectorConstRef & damping, - const boost::optional & mimic_info = boost::none) + const boost::optional & mimic_info = boost::none) + { + addJointAndBody( + type, axis, parentFrameId, placement, joint_name, Y, frame_placement, body_name, + -max_effort, max_effort, -max_velocity, max_velocity, min_config, max_config, -friction, + friction, damping, mimic_info); + } + void addJointAndBody( + JointType type, + const Vector3 & axis, + const FrameIndex & parentFrameId, + const SE3 & placement, + const std::string & joint_name, + const Inertia & Y, + const SE3 & frame_placement, + const std::string & body_name, + const VectorConstRef & min_effort, + const VectorConstRef & max_effort, + const VectorConstRef & min_velocity, + const VectorConstRef & max_velocity, + const VectorConstRef & min_config, + const VectorConstRef & max_config, + const VectorConstRef & min_dry_friction, + const VectorConstRef & max_dry_friction, + const VectorConstRef & damping, + const boost::optional & mimic_info = boost::none) + { + const Vector config_limit_margin = + Vector::Constant(max_config.size(), static_cast(0)); + addJointAndBody( + type, axis, parentFrameId, placement, joint_name, Y, frame_placement, body_name, + min_effort, max_effort, min_velocity, max_velocity, min_config, max_config, + config_limit_margin, min_dry_friction, max_dry_friction, damping, mimic_info); + } + + void addJointAndBody( + JointType type, + const Vector3 & axis, + const FrameIndex & parentFrameId, + const SE3 & placement, + const std::string & joint_name, + const Inertia & Y, + const SE3 & frame_placement, + const std::string & body_name, + const VectorConstRef & min_effort, + const VectorConstRef & max_effort, + const VectorConstRef & min_velocity, + const VectorConstRef & max_velocity, + const VectorConstRef & min_config, + const VectorConstRef & max_config, + const VectorConstRef & config_limit_margin, + const VectorConstRef & min_dry_friction, + const VectorConstRef & max_dry_friction, + const VectorConstRef & damping, + const boost::optional & mimic_info = boost::none) { JointIndex joint_id; const Frame & frame = model.frames[parentFrameId]; switch (type) { - case Base::FLOATING: + case JointType::FLOATING: joint_id = model.addJoint( frame.parentJoint, typename JointCollection::JointModelFreeFlyer(), - frame.placement * placement, joint_name, max_effort, max_velocity, min_config, - max_config, friction, damping); + frame.placement * placement, joint_name, min_effort, max_effort, min_velocity, + max_velocity, min_config, max_config, config_limit_margin, min_dry_friction, + max_dry_friction, damping); break; - case Base::REVOLUTE: + case JointType::REVOLUTE: joint_id = addJoint< typename JointCollection::JointModelRX, typename JointCollection::JointModelRY, typename JointCollection::JointModelRZ, typename JointCollection::JointModelRevoluteUnaligned>( - axis, frame, placement, joint_name, max_effort, max_velocity, min_config, max_config, - friction, damping); + axis, frame, placement, joint_name, min_effort, max_effort, min_velocity, + max_velocity, min_config, max_config, config_limit_margin, min_dry_friction, + max_dry_friction, damping); break; - case Base::CONTINUOUS: + case CONTINUOUS: joint_id = addJoint< typename JointCollection::JointModelRUBX, typename JointCollection::JointModelRUBY, typename JointCollection::JointModelRUBZ, typename JointCollection::JointModelRevoluteUnboundedUnaligned>( - axis, frame, placement, joint_name, max_effort, max_velocity, min_config, max_config, - friction, damping); + axis, frame, placement, joint_name, min_effort, max_effort, min_velocity, + max_velocity, min_config, max_config, config_limit_margin, min_dry_friction, + max_dry_friction, damping); break; - case Base::PRISMATIC: + case PRISMATIC: joint_id = addJoint< typename JointCollection::JointModelPX, typename JointCollection::JointModelPY, typename JointCollection::JointModelPZ, typename JointCollection::JointModelPrismaticUnaligned>( - axis, frame, placement, joint_name, max_effort, max_velocity, min_config, max_config, - friction, damping); + axis, frame, placement, joint_name, min_effort, max_effort, min_velocity, + max_velocity, min_config, max_config, config_limit_margin, min_dry_friction, + max_dry_friction, damping); break; - case Base::PLANAR: + case JointType::PLANAR: joint_id = model.addJoint( frame.parentJoint, typename JointCollection::JointModelPlanar(), - frame.placement * placement, joint_name, max_effort, max_velocity, min_config, - max_config, friction, damping); + frame.placement * placement, joint_name, min_effort, max_effort, min_velocity, + max_velocity, min_config, max_config, config_limit_margin, min_dry_friction, + max_dry_friction, damping); break; - case Base::SPHERICAL: + case JointType::SPHERICAL: joint_id = model.addJoint( frame.parentJoint, typename JointCollection::JointModelSpherical(), - frame.placement * placement, joint_name, max_effort, max_velocity, min_config, - max_config, friction, damping); + frame.placement * placement, joint_name, min_effort, max_effort, min_velocity, + max_velocity, min_config, max_config, config_limit_margin, min_dry_friction, + max_dry_friction, damping); break; - case Base::MIMIC: + case MIMIC: if (mimic_info) switch (mimic_info->jointType) { - case Base::REVOLUTE: + case JointType::REVOLUTE: joint_id = addMimicJoint< typename JointCollection::JointModelRX, typename JointCollection::JointModelRY, typename JointCollection::JointModelRZ, typename JointCollection::JointModelRevoluteUnaligned>( - frame, placement, joint_name, max_effort, max_velocity, min_config, max_config, - friction, damping, *mimic_info); + frame, placement, joint_name, min_effort, max_effort, min_velocity, max_velocity, + min_config, max_config, config_limit_margin, min_dry_friction, max_dry_friction, + damping, *mimic_info); break; - case Base::PRISMATIC: + case JointType::PRISMATIC: joint_id = addMimicJoint< typename JointCollection::JointModelPX, typename JointCollection::JointModelPY, typename JointCollection::JointModelPZ, typename JointCollection::JointModelPrismaticUnaligned>( - frame, placement, joint_name, max_effort, max_velocity, min_config, max_config, - friction, damping, *mimic_info); + frame, placement, joint_name, min_effort, max_effort, min_velocity, max_velocity, + min_config, max_config, config_limit_margin, min_dry_friction, max_dry_friction, + damping, *mimic_info); break; default: PINOCCHIO_CHECK_INPUT_ARGUMENT( @@ -446,32 +443,82 @@ namespace pinocchio const VectorConstRef & max_config, const VectorConstRef & friction, const VectorConstRef & damping) + { + return addJoint( + axis, frame, placement, joint_name, -max_effort, max_effort, -max_velocity, + max_velocity, min_config, max_config, -friction, friction, damping); + } + + template + JointIndex addJoint( + const Vector3 & axis, + const Frame & frame, + const SE3 & placement, + const std::string & joint_name, + const VectorConstRef & min_effort, + const VectorConstRef & max_effort, + const VectorConstRef & min_velocity, + const VectorConstRef & max_velocity, + const VectorConstRef & min_config, + const VectorConstRef & max_config, + const VectorConstRef & min_dry_friction, + const VectorConstRef & max_dry_friction, + const VectorConstRef & damping) + { + const Vector config_limit_margin = + Vector::Constant(max_config.size(), static_cast(0)); + return addJoint( + axis, frame, placement, joint_name, min_effort, max_effort, min_velocity, max_velocity, + min_config, max_config, config_limit_margin, min_dry_friction, max_dry_friction, + damping); + } + + template + JointIndex addJoint( + const Vector3 & axis, + const Frame & frame, + const SE3 & placement, + const std::string & joint_name, + const VectorConstRef & min_effort, + const VectorConstRef & max_effort, + const VectorConstRef & min_velocity, + const VectorConstRef & max_velocity, + const VectorConstRef & min_config, + const VectorConstRef & max_config, + const VectorConstRef & config_limit_margin, + const VectorConstRef & min_dry_friction, + const VectorConstRef & max_dry_friction, + const VectorConstRef & damping) { CartesianAxis axisType = extractCartesianAxis(axis); switch (axisType) { case AXIS_X: return model.addJoint( - frame.parentJoint, TypeX(), frame.placement * placement, joint_name, max_effort, - max_velocity, min_config, max_config, friction, damping); + frame.parentJoint, TypeX(), frame.placement * placement, joint_name, min_effort, + max_effort, min_velocity, max_velocity, min_config, max_config, config_limit_margin, + min_dry_friction, max_dry_friction, damping); break; case AXIS_Y: return model.addJoint( - frame.parentJoint, TypeY(), frame.placement * placement, joint_name, max_effort, - max_velocity, min_config, max_config, friction, damping); + frame.parentJoint, TypeY(), frame.placement * placement, joint_name, min_effort, + max_effort, min_velocity, max_velocity, min_config, max_config, config_limit_margin, + min_dry_friction, max_dry_friction, damping); break; case AXIS_Z: return model.addJoint( - frame.parentJoint, TypeZ(), frame.placement * placement, joint_name, max_effort, - max_velocity, min_config, max_config, friction, damping); + frame.parentJoint, TypeZ(), frame.placement * placement, joint_name, min_effort, + max_effort, min_velocity, max_velocity, min_config, max_config, config_limit_margin, + min_dry_friction, max_dry_friction, damping); break; case AXIS_UNALIGNED: return model.addJoint( frame.parentJoint, TypeUnaligned(axis.normalized()), frame.placement * placement, - joint_name, max_effort, max_velocity, min_config, max_config, friction, damping); + joint_name, min_effort, max_effort, min_velocity, max_velocity, min_config, + max_config, config_limit_margin, min_dry_friction, max_dry_friction, damping); break; default: PINOCCHIO_CHECK_INPUT_ARGUMENT(false, "The axis type of the joint is of wrong type."); @@ -484,19 +531,23 @@ namespace pinocchio const Frame & frame, const SE3 & placement, const std::string & joint_name, + const VectorConstRef & min_effort, const VectorConstRef & max_effort, + const VectorConstRef & min_velocity, const VectorConstRef & max_velocity, const VectorConstRef & min_config, const VectorConstRef & max_config, - const VectorConstRef & friction, + const VectorConstRef & config_limit_margin, + const VectorConstRef & min_dry_friction, + const VectorConstRef & max_dry_friction, const VectorConstRef & damping, - const MimicInfo_ & mimic_info) + const MimicInfo & mimic_info) { if (!model.existJointName(mimic_info.mimicked_name)) PINOCCHIO_CHECK_INPUT_ARGUMENT( false, "The parent joint of the mimic joint is not in the kinematic tree"); - auto mimicked_joint = model.joints[getJointId(mimic_info.mimicked_name)]; + const auto & mimicked_joint = model.joints[getJointId(mimic_info.mimicked_name)]; CartesianAxis axisType = extractCartesianAxis(mimic_info.axis); switch (axisType) @@ -506,16 +557,18 @@ namespace pinocchio frame.parentJoint, typename JointCollection::JointModelMimic( TypeX(), mimicked_joint, mimic_info.multiplier, mimic_info.offset), - frame.placement * placement, joint_name, max_effort, max_velocity, min_config, - max_config, friction, damping); + frame.placement * placement, joint_name, min_effort, max_effort, min_velocity, + max_velocity, min_config, max_config, config_limit_margin, min_dry_friction, + max_dry_friction, damping); break; case AXIS_Y: return model.addJoint( frame.parentJoint, typename JointCollection::JointModelMimic( TypeY(), mimicked_joint, mimic_info.multiplier, mimic_info.offset), - frame.placement * placement, joint_name, max_effort, max_velocity, min_config, - max_config, friction, damping); + frame.placement * placement, joint_name, min_effort, max_effort, min_velocity, + max_velocity, min_config, max_config, config_limit_margin, min_dry_friction, + max_dry_friction, damping); break; case AXIS_Z: @@ -523,8 +576,9 @@ namespace pinocchio frame.parentJoint, typename JointCollection::JointModelMimic( TypeZ(), mimicked_joint, mimic_info.multiplier, mimic_info.offset), - frame.placement * placement, joint_name, max_effort, max_velocity, min_config, - max_config, friction, damping); + frame.placement * placement, joint_name, min_effort, max_effort, min_velocity, + max_velocity, min_config, max_config, config_limit_margin, min_dry_friction, + max_dry_friction, damping); break; case AXIS_UNALIGNED: @@ -532,8 +586,9 @@ namespace pinocchio frame.parentJoint, typename JointCollection::JointModelMimic( TypeUnaligned(), mimicked_joint, mimic_info.multiplier, mimic_info.offset), - frame.placement * placement, joint_name, max_effort, max_velocity, min_config, - max_config, friction, damping); + frame.placement * placement, joint_name, min_effort, max_effort, min_velocity, + max_velocity, min_config, max_config, config_limit_margin, min_dry_friction, + max_dry_friction, damping); break; default: @@ -574,59 +629,26 @@ namespace pinocchio } }; - template class JointCollectionTpl> - class UrdfVisitorWithRootJoint : public UrdfVisitor - { - public: - typedef UrdfVisitor Base; - typedef typename Base::Inertia Inertia; - using Base::appendBodyToJoint; - using Base::model; - - typedef ModelTpl Model; - typedef typename Model::JointCollection JointCollection; - typedef typename Model::JointModel JointModel; - - JointModel root_joint; - - UrdfVisitorWithRootJoint( - Model & model, - const JointModelBase & root_joint, - const std::string & rjn = "root_joint") - : Base(model, rjn) - , root_joint(root_joint.derived()) - { - } - - void addRootJoint(const Inertia & Y, const std::string & body_name) - { - const Frame & frame = model.frames[0]; - - PINOCCHIO_THROW( - !model.existJointName(this->root_joint_name), std::invalid_argument, - "root_joint already exists as a joint in the kinematic tree."); - - JointIndex idx = model.addJoint( - frame.parentJoint, root_joint, SE3::Identity(), this->root_joint_name - // TODO ,max_effort,max_velocity,min_config,max_config - ); - - FrameIndex jointFrameId = model.addJointFrame(idx, 0); - appendBodyToJoint(jointFrameId, Y, SE3::Identity(), body_name); - } - }; - - typedef UrdfVisitorBaseTpl UrdfVisitorBase; - typedef MimicInfo MimicInfo_; - PINOCCHIO_PARSERS_DLLAPI void parseRootTree( - const ::urdf::ModelInterface * urdfTree, UrdfVisitorBase & model, const bool mimic = false); + const ::urdf::ModelInterface * urdfTree, + UrdfVisitor & model, + const boost::optional rootJoint = boost::none, + const boost::optional rootJointName = boost::none, + const bool mimic = false); PINOCCHIO_PARSERS_DLLAPI void parseRootTree( - const std::string & filename, UrdfVisitorBase & model, const bool mimic = false); + const std::string & filename, + UrdfVisitor & model, + const boost::optional rootJoint = boost::none, + const boost::optional rootJointName = boost::none, + const bool mimic = false); PINOCCHIO_PARSERS_DLLAPI void parseRootTreeFromXML( - const std::string & xmlString, UrdfVisitorBase & model, const bool mimic = false); + const std::string & xmlString, + UrdfVisitor & model, + const boost::optional rootJoint = boost::none, + const boost::optional rootJointName = boost::none, + const bool mimic = false); } // namespace details template class JointCollectionTpl> @@ -638,15 +660,26 @@ namespace pinocchio const bool verbose, const bool mimic) { + typedef ::pinocchio::parsers::Model Model; + typedef ::pinocchio::parsers::JointModel JointModel; if (rootJointName.empty()) throw std::invalid_argument( "rootJoint was given without a name. Please fill the argument root_joint_name"); - details::UrdfVisitorWithRootJoint visitor( - model, rootJoint, rootJointName); + // copy in case incoming model is not empty + Model urdf_model = model; + JointModel root_joint = rootJoint; + + details::UrdfVisitor visitor(urdf_model); if (verbose) visitor.log = &std::cout; - details::parseRootTree(filename, visitor, mimic); + + boost::optional root_joint_opt(root_joint); + boost::optional root_joint_name_opt(rootJointName); + details::parseRootTree(filename, visitor, root_joint_opt, root_joint_name_opt, mimic); + + // cast back to the input model's joint collection + model = visitor.model; return model; } @@ -668,10 +701,15 @@ namespace pinocchio const bool verbose, const bool mimic) { - details::UrdfVisitor visitor(model); + typedef ::pinocchio::parsers::Model Model; + Model urdf_model = model; + + details::UrdfVisitor visitor(urdf_model); if (verbose) visitor.log = &std::cout; - details::parseRootTree(filename, visitor, mimic); + details::parseRootTree(filename, visitor, boost::none, boost::none, mimic); + + model = visitor.model; return model; } @@ -684,15 +722,24 @@ namespace pinocchio const bool verbose, const bool mimic) { + typedef ::pinocchio::parsers::Model Model; + typedef ::pinocchio::parsers::JointModel JointModel; if (rootJointName.empty()) throw std::invalid_argument( "rootJoint was given without a name. Please fill the argument rootJointName"); - details::UrdfVisitorWithRootJoint visitor( - model, rootJoint, rootJointName); + Model urdf_model = model; + JointModel root_joint = rootJoint; + + details::UrdfVisitor visitor(urdf_model); if (verbose) visitor.log = &std::cout; - details::parseRootTreeFromXML(xmlStream, visitor, mimic); + + boost::optional root_joint_opt(root_joint); + boost::optional root_joint_name_opt(rootJointName); + details::parseRootTreeFromXML(xmlStream, visitor, root_joint_opt, root_joint_name_opt, mimic); + + model = visitor.model; return model; } @@ -714,10 +761,15 @@ namespace pinocchio const bool verbose, const bool mimic) { - details::UrdfVisitor visitor(model); + typedef ::pinocchio::parsers::Model Model; + Model urdf_model = model; + + details::UrdfVisitor visitor(urdf_model); if (verbose) visitor.log = &std::cout; - details::parseRootTreeFromXML(xmlStream, visitor, mimic); + details::parseRootTreeFromXML(xmlStream, visitor, boost::none, boost::none, mimic); + + model = visitor.model; return model; } @@ -730,16 +782,26 @@ namespace pinocchio const bool verbose, const bool mimic) { + typedef ::pinocchio::parsers::Model Model; + typedef ::pinocchio::parsers::JointModel JointModel; if (rootJointName.empty()) throw std::invalid_argument( "rootJoint was given without a name. Please fill the argument rootJointName"); PINOCCHIO_CHECK_INPUT_ARGUMENT(urdfTree != NULL); - details::UrdfVisitorWithRootJoint visitor( - model, rootJoint, rootJointName); + + Model urdf_model = model; + JointModel root_joint = rootJoint; + + details::UrdfVisitor visitor(urdf_model); if (verbose) visitor.log = &std::cout; - details::parseRootTree(urdfTree.get(), visitor, mimic); + + boost::optional root_joint_opt(root_joint); + boost::optional root_joint_name_opt(rootJointName); + details::parseRootTree(urdfTree.get(), visitor, root_joint_opt, root_joint_name_opt, mimic); + + model = visitor.model; return model; } @@ -761,11 +823,16 @@ namespace pinocchio const bool verbose, const bool mimic) { + typedef ::pinocchio::parsers::Model Model; PINOCCHIO_CHECK_INPUT_ARGUMENT(urdfTree != NULL); - details::UrdfVisitor visitor(model); + Model urdf_model = model; + + details::UrdfVisitor visitor(urdf_model); if (verbose) visitor.log = &std::cout; - details::parseRootTree(urdfTree.get(), visitor, mimic); + details::parseRootTree(urdfTree.get(), visitor, boost::none, boost::none, mimic); + + model = visitor.model; return model; } diff --git a/include/pinocchio/serialization/boost-blank.hpp b/include/pinocchio/serialization/boost-blank.hpp new file mode 100644 index 0000000000..b83e88d724 --- /dev/null +++ b/include/pinocchio/serialization/boost-blank.hpp @@ -0,0 +1,21 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_serialization_boost_blank_hpp__ +#define __pinocchio_serialization_boost_blank_hpp__ + +namespace boost +{ + namespace serialization + { + + template + void serialize(Archive &, ::boost::blank &, const unsigned int) + { + // do nothing + } + } // namespace serialization +} // namespace boost + +#endif // __pinocchio_serialization_boost_blank_hpp__ diff --git a/include/pinocchio/serialization/constraints-data.hpp b/include/pinocchio/serialization/constraints-data.hpp new file mode 100644 index 0000000000..5fe19ca518 --- /dev/null +++ b/include/pinocchio/serialization/constraints-data.hpp @@ -0,0 +1,169 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_serialization_constraints_data_hpp__ +#define __pinocchio_serialization_constraints_data_hpp__ + +#include "pinocchio/algorithm/constraints/constraints.hpp" +#include "pinocchio/serialization/eigen.hpp" +#include "pinocchio/serialization/se3.hpp" +#include "pinocchio/serialization/boost-blank.hpp" + +#include + +namespace boost +{ + namespace serialization + { + + template + void serialize( + Archive & ar, ::pinocchio::ConstraintDataBase & cdata, const unsigned int version) + { + PINOCCHIO_UNUSED_VARIABLE(ar); + PINOCCHIO_UNUSED_VARIABLE(cdata); + PINOCCHIO_UNUSED_VARIABLE(version); + } + + template + void serialize( + Archive & ar, + ::pinocchio::JointLimitConstraintDataTpl & cdata, + const unsigned int /*version*/) + { + typedef ::pinocchio::JointLimitConstraintDataTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cdata)); + + ar & make_nvp("compact_tangent_map", cdata.compact_tangent_map); + ar & make_nvp("activable_constraint_residual", cdata.activable_constraint_residual); + ar & make_nvp("constraint_residual_storage", cdata.constraint_residual_storage); + + if (Archive::is_loading::value) + { + cdata.constraint_residual = cdata.constraint_residual_storage.map(); + } + } + + template + void serialize( + Archive & ar, + ::pinocchio::FrictionalJointConstraintDataTpl & cdata, + const unsigned int /*version*/) + { + typedef ::pinocchio::FrictionalJointConstraintDataTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cdata)); + } + + template + void serialize( + Archive & ar, + ::pinocchio::PointConstraintDataBase & cdata, + const unsigned int /*version*/) + { + typedef ::pinocchio::PointConstraintDataBase Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cdata)); + + ar & make_nvp("constraint_force", cdata.constraint_force); + ar & make_nvp("oMc1", cdata.oMc1); + ar & make_nvp("oMc2", cdata.oMc2); + ar & make_nvp("c1Mc2", cdata.c1Mc2); + ar & make_nvp("constraint_position_error", cdata.constraint_position_error); + ar & make_nvp("constraint_velocity_error", cdata.constraint_velocity_error); + ar & make_nvp("constraint_acceleration_error", cdata.constraint_acceleration_error); + ar & make_nvp("constraint_acceleration_biais_term", cdata.constraint_acceleration_biais_term); + + ar & make_nvp("A1_world", cdata.A1_world); + ar & make_nvp("A2_world", cdata.A2_world); + ar & make_nvp("A_world", cdata.A_world); + ar & make_nvp("A1_local", cdata.A1_local); + ar & make_nvp("A2_local", cdata.A2_local); + ar & make_nvp("A_local", cdata.A_local); + } + + template + void serialize( + Archive & ar, + ::pinocchio::BilateralPointConstraintDataTpl & cdata, + const unsigned int /*version*/) + { + typedef ::pinocchio::BilateralPointConstraintDataTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cdata)); + } + + template + void serialize( + Archive & ar, + ::pinocchio::FrictionalPointConstraintDataTpl & cdata, + const unsigned int /*version*/) + { + typedef ::pinocchio::FrictionalPointConstraintDataTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cdata)); + } + + template + void serialize( + Archive & ar, + ::pinocchio::FrameConstraintDataBase & cdata, + const unsigned int /*version*/) + { + typedef ::pinocchio::FrameConstraintDataBase Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cdata)); + + ar & make_nvp("constraint_force", cdata.constraint_force); + ar & make_nvp("oMc1", cdata.oMc1); + ar & make_nvp("oMc2", cdata.oMc2); + ar & make_nvp("c1Mc2", cdata.c1Mc2); + ar & make_nvp("constraint_position_error", cdata.constraint_position_error); + ar & make_nvp("constraint_velocity_error", cdata.constraint_velocity_error); + ar & make_nvp("constraint_acceleration_error", cdata.constraint_acceleration_error); + ar & make_nvp("constraint_acceleration_biais_term", cdata.constraint_acceleration_biais_term); + + ar & make_nvp("A1_world", cdata.A1_world); + ar & make_nvp("A2_world", cdata.A2_world); + ar & make_nvp("A_world", cdata.A_world); + ar & make_nvp("A1_local", cdata.A1_local); + ar & make_nvp("A2_local", cdata.A2_local); + ar & make_nvp("A_local", cdata.A_local); + } + + template + void serialize( + Archive & ar, + ::pinocchio::WeldConstraintDataTpl & cdata, + const unsigned int /*version*/) + { + typedef ::pinocchio::WeldConstraintDataTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cdata)); + } + + template< + typename Archive, + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + void serialize( + Archive & ar, + pinocchio::ConstraintDataTpl & cdata, + const unsigned int /*version*/) + { + typedef ::pinocchio::ConstraintDataTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cdata)); + + typedef typename ConstraintCollectionTpl::ConstraintDataVariant + ConstraintDataVariant; + ar & make_nvp("base_variant", base_object(cdata)); + } + + } // namespace serialization +} // namespace boost + +#endif // __pinocchio_serialization_constraints_data_hpp__ diff --git a/include/pinocchio/serialization/constraints-model.hpp b/include/pinocchio/serialization/constraints-model.hpp new file mode 100644 index 0000000000..ccf337cd26 --- /dev/null +++ b/include/pinocchio/serialization/constraints-model.hpp @@ -0,0 +1,379 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_serialization_constraints_model_hpp__ +#define __pinocchio_serialization_constraints_model_hpp__ + +#include "pinocchio/algorithm/constraints/constraints.hpp" +#include "pinocchio/serialization/eigen.hpp" +#include "pinocchio/serialization/se3.hpp" +#include "pinocchio/serialization/eigen-storage.hpp" +#include "pinocchio/serialization/constraints-set.hpp" +#include "pinocchio/serialization/boost-blank.hpp" + +#include + +namespace boost +{ + namespace serialization + { + + template + void serialize( + Archive & ar, + ::pinocchio::BaumgarteCorrectorVectorParametersTpl & baumgarte_vector_parameters, + const unsigned int /*version*/) + { + ar & make_nvp("Kp", baumgarte_vector_parameters.Kp); + ar & make_nvp("Kd", baumgarte_vector_parameters.Kd); + } + + template + void serialize( + Archive & ar, + ::pinocchio::BaumgarteCorrectorParametersTpl & baumgarte_parameters, + const unsigned int /*version*/) + { + ar & make_nvp("Kp", baumgarte_parameters.Kp); + ar & make_nvp("Kd", baumgarte_parameters.Kd); + } + + template + void serialize( + Archive & ar, ::pinocchio::ConstraintModelBase & cmodel, const unsigned int version) + { + PINOCCHIO_UNUSED_VARIABLE(version); + ar & make_nvp("name", cmodel.name); + } + + template + void serialize( + Archive & ar, + ::pinocchio::KinematicsConstraintModelBase & cmodel, + const unsigned int /*version*/) + { + typedef ::pinocchio::KinematicsConstraintModelBase Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cmodel)); + + ar & make_nvp("joint1_id", cmodel.joint1_id); + ar & make_nvp("joint2_id", cmodel.joint2_id); + } + + template + void serialize( + Archive & ar, + ::pinocchio::JointWiseConstraintModelBase & cmodel, + const unsigned int /*version*/) + { + typedef ::pinocchio::JointWiseConstraintModelBase Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cmodel)); + } + + namespace internal + { + template + struct ConstraintModelCommonParametersAccessor + : public ::pinocchio::ConstraintModelCommonParameters + { + typedef ::pinocchio::ConstraintModelCommonParameters Base; + using Base::m_compliance; + // CHOICE: right now we use the scalar Baumgarte + // using Base::m_baumgarte_vector_parameters; + using Base::m_baumgarte_parameters; + }; + } // namespace internal + + template + void serialize( + Archive & ar, + ::pinocchio::ConstraintModelCommonParameters & cmodel, + const unsigned int version) + { + PINOCCHIO_UNUSED_VARIABLE(version); + typedef internal::ConstraintModelCommonParametersAccessor Accessor; + auto & cmodel_ = reinterpret_cast(cmodel); + ar & make_nvp("m_compliance", cmodel_.m_compliance); + // CHOICE: right now we use the scalar Baumgarte + // ar & make_nvp("m_baumgarte_vector_parameters", cmodel_.m_baumgarte_vector_parameters); + ar & make_nvp("m_baumgarte_parameters", cmodel_.m_baumgarte_parameters); + } + + namespace internal + { + template + struct JointLimitConstraintModelAccessor + : public ::pinocchio::JointLimitConstraintModelTpl + { + typedef ::pinocchio::JointLimitConstraintModelTpl Base; + using Base::activable_idx_qs; + using Base::activable_idx_qs_reduce; + using Base::activable_idx_rows; + using Base::activable_idx_vs; + using Base::activable_joints; + using Base::activable_nvs; + using Base::active_compliance; + using Base::active_compliance_storage; + using Base::active_idx_qs_reduce; + using Base::active_idx_rows; + using Base::active_idx_vs; + using Base::active_nvs; + using Base::active_set_indexes; + using Base::bound_position_limit; + using Base::bound_position_margin; + using Base::lower_activable_size; + using Base::lower_active_size; + using Base::m_set; + using Base::nq_reduce; + using Base::nv_max_atom; + using Base::row_indexes; + using Base::row_sparsity_pattern; + }; + } // namespace internal + + template + void serialize( + Archive & ar, + ::pinocchio::JointLimitConstraintModelTpl & cmodel, + const unsigned int /*version*/) + { + typedef ::pinocchio::JointLimitConstraintModelTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cmodel)); + typedef typename Self::BaseCommonParameters BaseCommonParameters; + ar & make_nvp( + "base_common_parameters", boost::serialization::base_object(cmodel)); + + typedef internal::JointLimitConstraintModelAccessor Accessor; + auto & cmodel_ = reinterpret_cast(cmodel); + ar & make_nvp("m_set", cmodel_.m_set); + ar & make_nvp("activable_joints", cmodel_.activable_joints); + ar & make_nvp("nq_reduce", cmodel_.nq_reduce); + ar & make_nvp("nv_max_atom", cmodel_.nv_max_atom); + ar & make_nvp("lower_activable_size", cmodel_.lower_activable_size); + ar & make_nvp("lower_active_size", cmodel_.lower_active_size); + ar & make_nvp("row_sparsity_pattern", cmodel_.row_sparsity_pattern); + ar & make_nvp("row_indexes", cmodel_.row_indexes); + ar & make_nvp("bound_position_limit", cmodel_.bound_position_limit); + ar & make_nvp("bound_position_margin", cmodel_.bound_position_margin); + ar & make_nvp("activable_idx_qs", cmodel_.activable_idx_qs); + ar & make_nvp("active_set_indexes", cmodel_.active_set_indexes); + ar & make_nvp("activable_idx_rows", cmodel_.activable_idx_rows); + ar & make_nvp("activable_idx_qs_reduce", cmodel_.activable_idx_qs_reduce); + ar & make_nvp("activable_nvs", cmodel_.activable_nvs); + ar & make_nvp("activable_idx_vs", cmodel_.activable_idx_vs); + ar & make_nvp("active_idx_rows", cmodel_.active_idx_rows); + ar & make_nvp("active_idx_qs_reduce", cmodel_.active_idx_qs_reduce); + ar & make_nvp("active_nvs", cmodel_.active_nvs); + ar & make_nvp("active_idx_vs", cmodel_.active_idx_vs); + ar & make_nvp("m_set", cmodel_.m_set); + ar & make_nvp("active_compliance_storage", cmodel_.active_compliance_storage); + + if (Archive::is_loading::value) + { + cmodel_.active_compliance = cmodel_.active_compliance_storage.map(); + } + } + + namespace internal + { + template + struct FrictionalJointConstraintModelAccessor + : public ::pinocchio::FrictionalJointConstraintModelTpl + { + typedef ::pinocchio::FrictionalJointConstraintModelTpl Base; + using Base::active_dofs; + using Base::active_joints; + using Base::m_set; + using Base::row_active_indexes; + using Base::row_sparsity_pattern; + }; + } // namespace internal + + template + void serialize( + Archive & ar, + ::pinocchio::FrictionalJointConstraintModelTpl & cmodel, + const unsigned int /*version*/) + { + typedef ::pinocchio::FrictionalJointConstraintModelTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cmodel)); + typedef typename Self::BaseCommonParameters BaseCommonParameters; + ar & make_nvp( + "base_common_parameters", boost::serialization::base_object(cmodel)); + + typedef internal::FrictionalJointConstraintModelAccessor Accessor; + auto & cmodel_ = reinterpret_cast(cmodel); + ar & make_nvp("active_joints", cmodel_.active_joints); + ar & make_nvp("active_dofs", cmodel_.active_dofs); + ar & make_nvp("row_sparsity_pattern", cmodel_.row_sparsity_pattern); + ar & make_nvp("row_active_indexes", cmodel_.row_active_indexes); + ar & make_nvp("m_set", cmodel_.m_set); + } + + template + void serialize( + Archive & ar, + ::pinocchio::PointConstraintModelBase & cmodel, + const unsigned int /*version*/) + { + typedef ::pinocchio::PointConstraintModelBase Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cmodel)); + typedef typename Self::BaseCommonParameters BaseCommonParameters; + ar & make_nvp( + "base_common_parameters", boost::serialization::base_object(cmodel)); + + ar & make_nvp("joint1_placement", cmodel.joint1_placement); + ar & make_nvp("joint2_placement", cmodel.joint2_placement); + ar & make_nvp("desired_constraint_offset", cmodel.desired_constraint_offset); + ar & make_nvp("desired_constraint_velocity", cmodel.desired_constraint_velocity); + ar & make_nvp("desired_constraint_acceleration", cmodel.desired_constraint_acceleration); + ar & make_nvp("colwise_joint1_sparsity", cmodel.colwise_joint1_sparsity); + ar & make_nvp("colwise_joint2_sparsity", cmodel.colwise_joint2_sparsity); + ar & make_nvp("joint1_span_indexes", cmodel.joint1_span_indexes); + ar & make_nvp("joint2_span_indexes", cmodel.joint2_span_indexes); + ar & make_nvp("loop_span_indexes", cmodel.loop_span_indexes); + ar & make_nvp("colwise_sparsity", cmodel.colwise_sparsity); + ar & make_nvp("colwise_span_indexes", cmodel.colwise_span_indexes); + ar & make_nvp("nv", cmodel.nv); + ar & make_nvp("depth_joint1", cmodel.depth_joint1); + ar & make_nvp("depth_joint2", cmodel.depth_joint2); + } + + namespace internal + { + template + struct BilateralPointConstraintModelAccessor + : public ::pinocchio::BilateralPointConstraintModelTpl + { + typedef ::pinocchio::BilateralPointConstraintModelTpl Base; + using Base::m_set; + }; + } // namespace internal + + template + void serialize( + Archive & ar, + ::pinocchio::BilateralPointConstraintModelTpl & cmodel, + const unsigned int /*version*/) + { + typedef ::pinocchio::BilateralPointConstraintModelTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cmodel)); + + typedef internal::BilateralPointConstraintModelAccessor Accessor; + auto & cmodel_ = reinterpret_cast(cmodel); + ar & make_nvp("m_set", cmodel_.m_set); + } + + namespace internal + { + template + struct FrictionalPointConstraintModelAccessor + : public ::pinocchio::FrictionalPointConstraintModelTpl + { + typedef ::pinocchio::FrictionalPointConstraintModelTpl Base; + using Base::m_set; + }; + } // namespace internal + + template + void serialize( + Archive & ar, + ::pinocchio::FrictionalPointConstraintModelTpl & cmodel, + const unsigned int /*version*/) + { + typedef ::pinocchio::FrictionalPointConstraintModelTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cmodel)); + + typedef internal::FrictionalPointConstraintModelAccessor Accessor; + auto & cmodel_ = reinterpret_cast(cmodel); + ar & make_nvp("m_set", cmodel_.m_set); + } + + template + void serialize( + Archive & ar, + ::pinocchio::FrameConstraintModelBase & cmodel, + const unsigned int /*version*/) + { + typedef ::pinocchio::FrameConstraintModelBase Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cmodel)); + typedef typename Self::BaseCommonParameters BaseCommonParameters; + ar & make_nvp( + "base_common_parameters", boost::serialization::base_object(cmodel)); + + // TODO: point/frame constraint models data structure are identical, factor them + ar & make_nvp("joint1_placement", cmodel.joint1_placement); + ar & make_nvp("joint2_placement", cmodel.joint2_placement); + ar & make_nvp("desired_constraint_offset", cmodel.desired_constraint_offset); + ar & make_nvp("desired_constraint_velocity", cmodel.desired_constraint_velocity); + ar & make_nvp("desired_constraint_acceleration", cmodel.desired_constraint_acceleration); + ar & make_nvp("colwise_joint1_sparsity", cmodel.colwise_joint1_sparsity); + ar & make_nvp("colwise_joint2_sparsity", cmodel.colwise_joint2_sparsity); + ar & make_nvp("joint1_span_indexes", cmodel.joint1_span_indexes); + ar & make_nvp("joint2_span_indexes", cmodel.joint2_span_indexes); + ar & make_nvp("loop_span_indexes", cmodel.loop_span_indexes); + ar & make_nvp("colwise_sparsity", cmodel.colwise_sparsity); + ar & make_nvp("colwise_span_indexes", cmodel.colwise_span_indexes); + ar & make_nvp("nv", cmodel.nv); + ar & make_nvp("depth_joint1", cmodel.depth_joint1); + ar & make_nvp("depth_joint2", cmodel.depth_joint2); + } + + namespace internal + { + template + struct WeldConstraintModelAccessor + : public ::pinocchio::WeldConstraintModelTpl + { + typedef ::pinocchio::WeldConstraintModelTpl Base; + using Base::m_set; + }; + } // namespace internal + + template + void serialize( + Archive & ar, + ::pinocchio::WeldConstraintModelTpl & cmodel, + const unsigned int /*version*/) + { + typedef ::pinocchio::WeldConstraintModelTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cmodel)); + + typedef internal::WeldConstraintModelAccessor Accessor; + auto & cmodel_ = reinterpret_cast(cmodel); + ar & make_nvp("m_set", cmodel_.m_set); + } + + template< + typename Archive, + typename Scalar, + int Options, + template class ConstraintCollectionTpl> + void serialize( + Archive & ar, + pinocchio::ConstraintModelTpl & cmodel, + const unsigned int /*version*/) + { + typedef ::pinocchio::ConstraintModelTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(cmodel)); + + typedef typename ConstraintCollectionTpl::ConstraintModelVariant + ConstraintModelVariant; + ar & make_nvp( + "base_variant", boost::serialization::base_object(cmodel)); + } + + } // namespace serialization +} // namespace boost + +#endif // __pinocchio_serialization_constraints_model_hpp__ diff --git a/include/pinocchio/serialization/constraints-set.hpp b/include/pinocchio/serialization/constraints-set.hpp new file mode 100644 index 0000000000..40a0eb5a81 --- /dev/null +++ b/include/pinocchio/serialization/constraints-set.hpp @@ -0,0 +1,211 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_serialization_constraints_set_hpp__ +#define __pinocchio_serialization_constraints_set_hpp__ + +#include "pinocchio/algorithm/constraints/sets.hpp" +#include "pinocchio/serialization/eigen.hpp" + +#include + +namespace boost +{ + namespace serialization + { + + template + void serialize(Archive & ar, ::pinocchio::SetBase & set, const unsigned int version) + { + // Nothing to do + PINOCCHIO_UNUSED_VARIABLE(ar); + PINOCCHIO_UNUSED_VARIABLE(set); + PINOCCHIO_UNUSED_VARIABLE(version); + } + + template + void + serialize(Archive & ar, ::pinocchio::ConeBase & set, const unsigned int /*version*/) + { + typedef ::pinocchio::ConeBase Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(set)); + } + + namespace internal + { + template + struct BoxSetAccessor : public ::pinocchio::BoxSetTpl + { + typedef ::pinocchio::BoxSetTpl Base; + using Base::m_lb; + using Base::m_ub; + }; + } // namespace internal + + template + void serialize( + Archive & ar, ::pinocchio::BoxSetTpl & set, const unsigned int /*version*/) + { + typedef ::pinocchio::BoxSetTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(set)); + + typedef internal::BoxSetAccessor Accessor; + auto & set_ = reinterpret_cast(set); + ar & make_nvp("m_lb", set_.m_lb); + ar & make_nvp("m_ub", set_.m_ub); + } + + namespace internal + { + template + struct UnboundedSetAccessor : public ::pinocchio::UnboundedSetTpl + { + typedef ::pinocchio::UnboundedSetTpl Base; + using Base::m_size; + }; + } // namespace internal + + template + void serialize( + Archive & ar, + ::pinocchio::UnboundedSetTpl & set, + const unsigned int /*version*/) + { + typedef ::pinocchio::UnboundedSetTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(set)); + + typedef internal::UnboundedSetAccessor Accessor; + auto & set_ = reinterpret_cast(set); + ar & make_nvp("m_size", set_.m_size); + } + + namespace internal + { + template + struct NullSetAccessor : public ::pinocchio::NullSetTpl + { + typedef ::pinocchio::NullSetTpl Base; + using Base::m_size; + }; + } // namespace internal + + template + void serialize( + Archive & ar, ::pinocchio::NullSetTpl & set, const unsigned int /*version*/) + { + typedef ::pinocchio::NullSetTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(set)); + + typedef internal::NullSetAccessor Accessor; + auto & set_ = reinterpret_cast(set); + ar & make_nvp("m_size", set_.m_size); + } + + template + void serialize( + Archive & ar, + ::pinocchio::CoulombFrictionConeTpl & set, + const unsigned int /*version*/) + { + typedef ::pinocchio::CoulombFrictionConeTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(set)); + + ar & make_nvp("mu", set.mu); + } + + template + void serialize( + Archive & ar, + ::pinocchio::DualCoulombFrictionConeTpl & set, + const unsigned int /*version*/) + { + typedef ::pinocchio::DualCoulombFrictionConeTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(set)); + + ar & make_nvp("mu", set.mu); + } + + namespace internal + { + template + struct OrthantConeBaseAccessor : public ::pinocchio::OrthantConeBase + { + typedef ::pinocchio::OrthantConeBase Base; + using Base::m_size; + }; + } // namespace internal + + template + void serialize( + Archive & ar, ::pinocchio::OrthantConeBase & set, const unsigned int /*version*/) + { + typedef ::pinocchio::OrthantConeBase Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(set)); + + typedef internal::OrthantConeBaseAccessor Accessor; + auto & set_ = reinterpret_cast(set); + ar & make_nvp("m_size", set_.m_size); + } + + template + void serialize( + Archive & ar, + ::pinocchio::PositiveOrthantConeTpl & set, + const unsigned int /*version*/) + { + typedef ::pinocchio::PositiveOrthantConeTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(set)); + } + + template + void serialize( + Archive & ar, + ::pinocchio::NegativeOrthantConeTpl & set, + const unsigned int /*version*/) + { + typedef ::pinocchio::NegativeOrthantConeTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(set)); + } + + namespace internal + { + template + struct JointLimitConstraintConeAccessor + : public ::pinocchio::JointLimitConstraintConeTpl + { + typedef ::pinocchio::JointLimitConstraintConeTpl Base; + using Base::negative_orthant; + using Base::positive_orthant; + }; + } // namespace internal + + template + void serialize( + Archive & ar, + ::pinocchio::JointLimitConstraintConeTpl & set, + const unsigned int /*version*/) + { + typedef ::pinocchio::JointLimitConstraintConeTpl Self; + typedef typename Self::Base Base; + ar & make_nvp("base", boost::serialization::base_object(set)); + + typedef internal::JointLimitConstraintConeAccessor Accessor; + auto & set_ = reinterpret_cast(set); + ar & make_nvp("positive_orthant", set_.positive_orthant); + ar & make_nvp("negative_orthant", set_.negative_orthant); + } + + } // namespace serialization +} // namespace boost + +#endif // __pinocchio_serialization_constraints_set_hpp__ diff --git a/include/pinocchio/serialization/csv.hpp b/include/pinocchio/serialization/csv.hpp index 9bc24e3878..4e6cd0549f 100644 --- a/include/pinocchio/serialization/csv.hpp +++ b/include/pinocchio/serialization/csv.hpp @@ -7,7 +7,6 @@ #include "pinocchio/serialization/fwd.hpp" -#include #include namespace pinocchio diff --git a/include/pinocchio/serialization/data.hpp b/include/pinocchio/serialization/data.hpp index 8ac69063c5..eca178cb49 100644 --- a/include/pinocchio/serialization/data.hpp +++ b/include/pinocchio/serialization/data.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2019 INRIA +// Copyright (c) 2019-2025 INRIA // #ifndef __pinocchio_multibody_data_serialization_hpp__ @@ -7,12 +7,14 @@ #include #include +#include #include "pinocchio/serialization/aligned-vector.hpp" #include "pinocchio/serialization/spatial.hpp" #include "pinocchio/serialization/eigen.hpp" #include "pinocchio/serialization/joints.hpp" #include "pinocchio/serialization/frame.hpp" +#include "pinocchio/serialization/double-entry-container.hpp" #define PINOCCHIO_MAKE_DATA_NVP(ar, data, field_name) ar & make_nvp(#field_name, data.field_name) @@ -31,6 +33,11 @@ namespace boost const unsigned int /*version*/) { PINOCCHIO_MAKE_DATA_NVP(ar, data, joints); + PINOCCHIO_MAKE_DATA_NVP(ar, data, joints_augmented); + PINOCCHIO_MAKE_DATA_NVP(ar, data, q_in); + PINOCCHIO_MAKE_DATA_NVP(ar, data, v_in); + PINOCCHIO_MAKE_DATA_NVP(ar, data, a_in); + PINOCCHIO_MAKE_DATA_NVP(ar, data, tau_in); PINOCCHIO_MAKE_DATA_NVP(ar, data, a); PINOCCHIO_MAKE_DATA_NVP(ar, data, oa); PINOCCHIO_MAKE_DATA_NVP(ar, data, oa_drift); @@ -71,7 +78,7 @@ namespace boost PINOCCHIO_MAKE_DATA_NVP(ar, data, ddq); PINOCCHIO_MAKE_DATA_NVP(ar, data, Yaba); PINOCCHIO_MAKE_DATA_NVP(ar, data, oYaba); - PINOCCHIO_MAKE_DATA_NVP(ar, data, oYaba_contact); + PINOCCHIO_MAKE_DATA_NVP(ar, data, oYaba_augmented); PINOCCHIO_MAKE_DATA_NVP(ar, data, oL); PINOCCHIO_MAKE_DATA_NVP(ar, data, oK); PINOCCHIO_MAKE_DATA_NVP(ar, data, u); @@ -81,7 +88,6 @@ namespace boost PINOCCHIO_MAKE_DATA_NVP(ar, data, dhg); PINOCCHIO_MAKE_DATA_NVP(ar, data, Ig); PINOCCHIO_MAKE_DATA_NVP(ar, data, Fcrb); - PINOCCHIO_MAKE_DATA_NVP(ar, data, lastChild); PINOCCHIO_MAKE_DATA_NVP(ar, data, nvSubtree); PINOCCHIO_MAKE_DATA_NVP(ar, data, start_idx_v_fromRow); PINOCCHIO_MAKE_DATA_NVP(ar, data, end_idx_v_fromRow); @@ -143,6 +149,19 @@ namespace boost PINOCCHIO_MAKE_DATA_NVP(ar, data, d2tau_dadq); PINOCCHIO_MAKE_DATA_NVP(ar, data, kinematic_hessians); PINOCCHIO_MAKE_DATA_NVP(ar, data, primal_dual_contact_solution); + + // Related to constraints handling + PINOCCHIO_MAKE_DATA_NVP(ar, data, extended_motion_propagator); + PINOCCHIO_MAKE_DATA_NVP(ar, data, extended_motion_propagator2); + PINOCCHIO_MAKE_DATA_NVP(ar, data, spatial_inv_inertia); + PINOCCHIO_MAKE_DATA_NVP(ar, data, accumulation_descendant); + PINOCCHIO_MAKE_DATA_NVP(ar, data, accumulation_ancestor); + PINOCCHIO_MAKE_DATA_NVP(ar, data, constraints_supported_dim); + PINOCCHIO_MAKE_DATA_NVP(ar, data, constraints_supported); + PINOCCHIO_MAKE_DATA_NVP(ar, data, constraints_on_joint); + PINOCCHIO_MAKE_DATA_NVP(ar, data, neighbour_links); + PINOCCHIO_MAKE_DATA_NVP(ar, data, joint_cross_coupling); + PINOCCHIO_MAKE_DATA_NVP(ar, data, joint_apparent_inertia); } } // namespace serialization diff --git a/include/pinocchio/serialization/delassus.hpp b/include/pinocchio/serialization/delassus.hpp new file mode 100644 index 0000000000..6b0549931d --- /dev/null +++ b/include/pinocchio/serialization/delassus.hpp @@ -0,0 +1,76 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_serialization_delassus_hpp__ +#define __pinocchio_serialization_delassus_hpp__ + +#include "pinocchio/serialization/eigen.hpp" +#include "pinocchio/algorithm/delassus-operator.hpp" + +namespace boost +{ + namespace serialization + { + + template + void serialize( + Archive & ar, + ::pinocchio::DelassusOperatorBase & delassus, + const unsigned int version) + { + // Nothing to do yet + PINOCCHIO_UNUSED_VARIABLE(ar); + PINOCCHIO_UNUSED_VARIABLE(delassus); + PINOCCHIO_UNUSED_VARIABLE(version); + } + + namespace internal + { + + template + struct DelassusOperatorDenseAccessor + : public ::pinocchio::DelassusOperatorDenseTpl + { + typedef ::pinocchio::DelassusOperatorDenseTpl Base; + using Base::compliance; + using Base::damping; + using Base::delassus_matrix; + using Base::llt; + using Base::mat_tmp; + }; + + } // namespace internal + + template + void serialize( + Archive & ar, + ::pinocchio::DelassusOperatorDenseTpl & delassus, + const unsigned int /*version*/) + { + typedef ::pinocchio::DelassusOperatorDenseTpl Self; + typedef typename Self::Base Base; + typedef typename Self::CholeskyDecomposition CholeskyDecomposition; + typedef ::pinocchio::DelassusOperatorDenseTpl Self; + + ar & make_nvp("base", boost::serialization::base_object(delassus)); + + typedef internal::DelassusOperatorDenseAccessor Accessor; + auto & delassus_ = reinterpret_cast(delassus); + ar & make_nvp("delassus_matrix", delassus_.delassus_matrix); + ar & make_nvp("compliance", delassus_.compliance); + ar & make_nvp("damping", delassus_.damping); + ar & make_nvp("compliance", delassus_.compliance); + + if (Archive::is_loading::value) + { + delassus_.llt = CholeskyDecomposition(delassus_.delassus_matrix); + delassus_.mat_tmp.resize( + delassus_.delassus_matrix.rows(), delassus_.delassus_matrix.cols()); + } + } + + } // namespace serialization +} // namespace boost + +#endif // __pinocchio_serialization_delassus_hpp__ diff --git a/include/pinocchio/serialization/double-entry-container.hpp b/include/pinocchio/serialization/double-entry-container.hpp new file mode 100644 index 0000000000..2bd2ac1b96 --- /dev/null +++ b/include/pinocchio/serialization/double-entry-container.hpp @@ -0,0 +1,43 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_serialization_double_entry_container_hpp__ +#define __pinocchio_serialization_double_entry_container_hpp__ + +#include "pinocchio/serialization/eigen.hpp" +#include "pinocchio/container/double-entry-container.hpp" + +namespace boost +{ + namespace serialization + { + + namespace internal + { + template + struct DoubleEntryContainerAccessor + : public ::pinocchio::container::DoubleEntryContainer + { + typedef ::pinocchio::container::DoubleEntryContainer Base; + using Base::m_keys; + using Base::m_values; + }; + } // namespace internal + + template + void serialize( + Archive & ar, + ::pinocchio::container::DoubleEntryContainer & container, + const unsigned int /*version*/) + { + typedef internal::DoubleEntryContainerAccessor Accessor; + Accessor & container_ = static_cast(container); + ar & make_nvp("m_keys", container_.m_keys); + ar & make_nvp("m_values", container_.m_values); + } + + } // namespace serialization +} // namespace boost + +#endif // ifndef __pinocchio_serialization_double_entry_container_hpp__ diff --git a/include/pinocchio/serialization/eigen-storage.hpp b/include/pinocchio/serialization/eigen-storage.hpp new file mode 100644 index 0000000000..6661d5e556 --- /dev/null +++ b/include/pinocchio/serialization/eigen-storage.hpp @@ -0,0 +1,52 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_serialization_eigen_storage_hpp__ +#define __pinocchio_serialization_eigen_storage_hpp__ + +#include "pinocchio/serialization/eigen.hpp" + +#include "pinocchio/container/storage.hpp" + +namespace boost +{ + namespace serialization + { + + namespace internal + { + template + struct EigenStorageAccessor : public ::pinocchio::EigenStorageTpl + { + typedef ::pinocchio::EigenStorageTpl Base; + using Base::m_map; + using Base::m_storage; + }; + } // namespace internal + + template + void serialize( + Archive & ar, + ::pinocchio::EigenStorageTpl & storage, + const unsigned int /*version*/) + { + Eigen::Index rows = storage.rows(); + Eigen::Index cols = storage.cols(); + ar & make_nvp("rows", rows); + ar & make_nvp("cols", cols); + + typedef internal::EigenStorageAccessor Accessor; + Accessor & storage_ = static_cast(storage); + ar & make_nvp("m_storage", storage_.m_storage); + + if (Archive::is_loading::value) + { + storage.resize(rows, cols); // reset internal map to point to storage + } + } + + } // namespace serialization +} // namespace boost + +#endif // __pinocchio_serialization_eigen_storage_hpp__ diff --git a/include/pinocchio/serialization/eigen.hpp b/include/pinocchio/serialization/eigen.hpp index ea8e2c1fea..f8f698c0d0 100644 --- a/include/pinocchio/serialization/eigen.hpp +++ b/include/pinocchio/serialization/eigen.hpp @@ -1,11 +1,11 @@ // -// Copyright (c) 2017-2020 CNRS INRIA +// Copyright (c) 2017-2018 CNRS +// Copyright (c) 2018-2025 INRIA // #ifndef __pinocchio_serialization_eigen_matrix_hpp__ #define __pinocchio_serialization_eigen_matrix_hpp__ -#include #include "pinocchio/math/tensor.hpp" #include @@ -128,6 +128,33 @@ namespace boost { namespace serialization { + namespace internal + { + namespace Eigen + { + template + void serialize_eigen_plain_object( + Archive & ar, EigenPlainObjectBase & m, const unsigned int /*version*/) + { + + ::Eigen::DenseIndex rows(m.rows()), cols(m.cols()); + if (EigenPlainObjectBase::RowsAtCompileTime == ::Eigen::Dynamic) + ar & BOOST_SERIALIZATION_NVP(rows); + if (EigenPlainObjectBase::ColsAtCompileTime == ::Eigen::Dynamic) + ar & BOOST_SERIALIZATION_NVP(cols); + + if (Archive::is_loading::value) + m.resize(rows, cols); + ar & make_nvp("data", make_array(m.data(), (size_t)m.size())); + } + } // namespace Eigen + } // namespace internal + + template + void serialize(Archive & ar, ::Eigen::PlainObjectBase & m, const unsigned int version) + { + internal::Eigen::serialize_eigen_plain_object(ar, m, version); + } template< class Archive, @@ -137,39 +164,23 @@ namespace boost int Options, int MaxRows, int MaxCols> - void save( + void serialize( Archive & ar, - const Eigen::Matrix & m, - const unsigned int /*version*/) + ::Eigen::Matrix & m, + const unsigned int version) { - Eigen::DenseIndex rows(m.rows()), cols(m.cols()); - if (Rows == Eigen::Dynamic) - ar & BOOST_SERIALIZATION_NVP(rows); - if (Cols == Eigen::Dynamic) - ar & BOOST_SERIALIZATION_NVP(cols); - ar & make_nvp("data", make_array(m.data(), (size_t)m.size())); + typedef ::Eigen::Matrix Self; + typedef typename Self::Base Base; + serialize(ar, static_cast(m), version); } - template< - class Archive, - typename Scalar, - int Rows, - int Cols, - int Options, - int MaxRows, - int MaxCols> - void load( + template + void serialize( Archive & ar, - Eigen::Matrix & m, - const unsigned int /*version*/) + ::Eigen::Map & m, + const unsigned int version) { - Eigen::DenseIndex rows = Rows, cols = Cols; - if (Rows == Eigen::Dynamic) - ar >> BOOST_SERIALIZATION_NVP(rows); - if (Cols == Eigen::Dynamic) - ar >> BOOST_SERIALIZATION_NVP(cols); - m.resize(rows, cols); - ar >> make_nvp("data", make_array(m.data(), (size_t)m.size())); + internal::Eigen::serialize_eigen_plain_object(ar, m, version); } template< @@ -182,49 +193,12 @@ namespace boost int MaxCols> void serialize( Archive & ar, - Eigen::Matrix & m, - const unsigned int version) - { - split_free(ar, m, version); - } - - template - void save( - Archive & ar, - const Eigen::Map & m, - const unsigned int /*version*/) - { - Eigen::DenseIndex rows(m.rows()), cols(m.cols()); - if (PlainObjectBase::RowsAtCompileTime == Eigen::Dynamic) - ar & BOOST_SERIALIZATION_NVP(rows); - if (PlainObjectBase::ColsAtCompileTime == Eigen::Dynamic) - ar & BOOST_SERIALIZATION_NVP(cols); - ar & make_nvp("data", make_array(m.data(), (size_t)m.size())); - } - - template - void load( - Archive & ar, - Eigen::Map & m, - const unsigned int /*version*/) - { - Eigen::DenseIndex rows = PlainObjectBase::RowsAtCompileTime, - cols = PlainObjectBase::ColsAtCompileTime; - if (PlainObjectBase::RowsAtCompileTime == Eigen::Dynamic) - ar >> BOOST_SERIALIZATION_NVP(rows); - if (PlainObjectBase::ColsAtCompileTime == Eigen::Dynamic) - ar >> BOOST_SERIALIZATION_NVP(cols); - m.resize(rows, cols); - ar >> make_nvp("data", make_array(m.data(), (size_t)m.size())); - } - - template - void serialize( - Archive & ar, - Eigen::Map & m, + ::Eigen::Array & m, const unsigned int version) { - split_free(ar, m, version); + typedef ::Eigen::Array Self; + typedef typename Self::Base Base; + serialize(ar, static_cast(m), version); } #if !defined(PINOCCHIO_WITH_EIGEN_TENSOR_MODULE) \ diff --git a/include/pinocchio/serialization/model.hpp b/include/pinocchio/serialization/model.hpp index 1116cd8067..8194492139 100644 --- a/include/pinocchio/serialization/model.hpp +++ b/include/pinocchio/serialization/model.hpp @@ -58,12 +58,16 @@ namespace boost ar & make_nvp("armature", model.armature); ar & make_nvp("rotorInertia", model.rotorInertia); ar & make_nvp("rotorGearRatio", model.rotorGearRatio); - ar & make_nvp("friction", model.friction); + ar & make_nvp("lowerDryFrictionLimit", model.lowerDryFrictionLimit); + ar & make_nvp("upperDryFrictionLimit", model.upperDryFrictionLimit); ar & make_nvp("damping", model.damping); - ar & make_nvp("effortLimit", model.effortLimit); - ar & make_nvp("velocityLimit", model.velocityLimit); + ar & make_nvp("lowerEffortLimit", model.lowerEffortLimit); + ar & make_nvp("upperEffortLimit", model.upperEffortLimit); + ar & make_nvp("lowerVelocityLimit", model.lowerVelocityLimit); + ar & make_nvp("upperVelocityLimit", model.upperVelocityLimit); ar & make_nvp("lowerPositionLimit", model.lowerPositionLimit); ar & make_nvp("upperPositionLimit", model.upperPositionLimit); + ar & make_nvp("positionLimitMargin", model.positionLimitMargin); ar & make_nvp("inertias", model.inertias); ar & make_nvp("jointPlacements", model.jointPlacements); diff --git a/include/pinocchio/serialization/serializable.hpp b/include/pinocchio/serialization/serializable.hpp index d08a8fcda7..88bc9c56b8 100644 --- a/include/pinocchio/serialization/serializable.hpp +++ b/include/pinocchio/serialization/serializable.hpp @@ -16,11 +16,11 @@ namespace pinocchio struct Serializable { private: - Derived & derived() + Derived & serializableDerived() { return *static_cast(this); } - const Derived & derived() const + const Derived & serializableDerived() const { return *static_cast(this); } @@ -29,85 +29,85 @@ namespace pinocchio /// \brief Loads a Derived object from a text file. void loadFromText(const std::string & filename) { - pinocchio::serialization::loadFromText(derived(), filename); + pinocchio::serialization::loadFromText(serializableDerived(), filename); } /// \brief Saves a Derived object as a text file. void saveToText(const std::string & filename) const { - pinocchio::serialization::saveToText(derived(), filename); + pinocchio::serialization::saveToText(serializableDerived(), filename); } /// \brief Loads a Derived object from a stream string. void loadFromStringStream(std::istringstream & is) { - pinocchio::serialization::loadFromStringStream(derived(), is); + pinocchio::serialization::loadFromStringStream(serializableDerived(), is); } /// \brief Saves a Derived object to a string stream. void saveToStringStream(std::stringstream & ss) const { - pinocchio::serialization::saveToStringStream(derived(), ss); + pinocchio::serialization::saveToStringStream(serializableDerived(), ss); } /// \brief Loads a Derived object from a string. void loadFromString(const std::string & str) { - pinocchio::serialization::loadFromString(derived(), str); + pinocchio::serialization::loadFromString(serializableDerived(), str); } /// \brief Saves a Derived object to a string. std::string saveToString() const { - return pinocchio::serialization::saveToString(derived()); + return pinocchio::serialization::saveToString(serializableDerived()); } /// \brief Loads a Derived object from an XML file. void loadFromXML(const std::string & filename, const std::string & tag_name) { - pinocchio::serialization::loadFromXML(derived(), filename, tag_name); + pinocchio::serialization::loadFromXML(serializableDerived(), filename, tag_name); } /// \brief Saves a Derived object as an XML file. void saveToXML(const std::string & filename, const std::string & tag_name) const { - pinocchio::serialization::saveToXML(derived(), filename, tag_name); + pinocchio::serialization::saveToXML(serializableDerived(), filename, tag_name); } /// \brief Loads a Derived object from an binary file. void loadFromBinary(const std::string & filename) { - pinocchio::serialization::loadFromBinary(derived(), filename); + pinocchio::serialization::loadFromBinary(serializableDerived(), filename); } /// \brief Saves a Derived object as an binary file. void saveToBinary(const std::string & filename) const { - pinocchio::serialization::saveToBinary(derived(), filename); + pinocchio::serialization::saveToBinary(serializableDerived(), filename); } /// \brief Loads a Derived object from a binary container. void loadFromBinary(boost::asio::streambuf & container) { - pinocchio::serialization::loadFromBinary(derived(), container); + pinocchio::serialization::loadFromBinary(serializableDerived(), container); } /// \brief Saves a Derived object as a binary container. void saveToBinary(boost::asio::streambuf & container) const { - pinocchio::serialization::saveToBinary(derived(), container); + pinocchio::serialization::saveToBinary(serializableDerived(), container); } /// \brief Loads a Derived object from a static binary container. void loadFromBinary(StaticBuffer & container) { - pinocchio::serialization::loadFromBinary(derived(), container); + pinocchio::serialization::loadFromBinary(serializableDerived(), container); } /// \brief Saves a Derived object as a static binary container. void saveToBinary(StaticBuffer & container) const { - pinocchio::serialization::saveToBinary(derived(), container); + pinocchio::serialization::saveToBinary(serializableDerived(), container); } }; diff --git a/include/pinocchio/spatial/explog.hpp b/include/pinocchio/spatial/explog.hpp index 8c37ad9792..9f063d0e7b 100644 --- a/include/pinocchio/spatial/explog.hpp +++ b/include/pinocchio/spatial/explog.hpp @@ -15,8 +15,6 @@ #include "pinocchio/spatial/skew.hpp" #include "pinocchio/spatial/se3.hpp" -#include - #include "pinocchio/spatial/log.hpp" namespace pinocchio diff --git a/include/pinocchio/spatial/fcl-pinocchio-conversions.hpp b/include/pinocchio/spatial/fcl-pinocchio-conversions.hpp index a0824b3f1e..c7872f5e2f 100644 --- a/include/pinocchio/spatial/fcl-pinocchio-conversions.hpp +++ b/include/pinocchio/spatial/fcl-pinocchio-conversions.hpp @@ -8,7 +8,7 @@ #include "pinocchio/macros.hpp" // clang-format off -PINOCCHIO_PRAGMA_DEPRECATED_HEADER( +PINOCCHIO_DEPRECATED_MOVED_HEADER( pinocchio/spatial/fcl-pinocchio-conversions.hpp, pinocchio/collision/fcl-pinocchio-conversions.hpp) // clang-format on diff --git a/include/pinocchio/spatial/force-dense.hpp b/include/pinocchio/spatial/force-dense.hpp index 9301d9f575..bf2ac4a483 100644 --- a/include/pinocchio/spatial/force-dense.hpp +++ b/include/pinocchio/spatial/force-dense.hpp @@ -1,10 +1,13 @@ // -// Copyright (c) 2017-2020 CNRS INRIA +// Copyright (c) 2017-2020 CNRS +// Copyright (c) 2018-2024 INRIA // #ifndef __pinocchio_spatial_force_dense_hpp__ #define __pinocchio_spatial_force_dense_hpp__ +#include "pinocchio/math/matrix.hpp" + namespace pinocchio { @@ -202,7 +205,8 @@ namespace pinocchio const ForceDense & f, const Scalar & prec = Eigen::NumTraits::dummy_precision()) const { - return linear().isApprox(f.linear(), prec) && angular().isApprox(f.angular(), prec); + return isApproxOrZero(linear(), f.linear(), prec) + && isApproxOrZero(angular(), f.angular(), prec); } bool isZero_impl(const Scalar & prec = Eigen::NumTraits::dummy_precision()) const diff --git a/include/pinocchio/spatial/force-tpl.hpp b/include/pinocchio/spatial/force-tpl.hpp index db007c710c..b8161bef74 100644 --- a/include/pinocchio/spatial/force-tpl.hpp +++ b/include/pinocchio/spatial/force-tpl.hpp @@ -1,5 +1,6 @@ // -// Copyright (c) 2015-2019 CNRS INRIA +// Copyright (c) 2015-2018 CNRS +// Copyright (c) 2018-2024 INRIA // Copyright (c) 2015-2016 Wandercraft, 86 rue de Paris 91400 Orsay, France. // @@ -32,6 +33,15 @@ namespace pinocchio typedef ForceRef ForceRefType; }; // traits ForceTpl + /// + /// \brief This class represents a SpatialForce composed of a linear component representing a 3d + /// force vector and an angular component corresponding to a 3d torque vector. Internally, the + /// data are stored in a compact 6d vector. + /// + /// \tparam _Scalar Scalar type of the ForceTpl + /// \tparam _Options Eigen Options related to the internal 6d vector storing the data. In most + /// cases, you don't have to worry about this templated quantities. + /// template class ForceTpl : public ForceDense> { @@ -49,68 +59,114 @@ namespace pinocchio using Base::angular; using Base::linear; - // Constructors + /// \brief Default constructor ForceTpl() { } - template - ForceTpl(const Eigen::MatrixBase & v, const Eigen::MatrixBase & w) - { - EIGEN_STATIC_ASSERT_VECTOR_ONLY(V1); - EIGEN_STATIC_ASSERT_VECTOR_ONLY(V2); - linear() = v; - angular() = w; - } - - template - explicit ForceTpl(const Eigen::MatrixBase & v) - : m_data(v) - { - EIGEN_STATIC_ASSERT_VECTOR_ONLY(V6); - } - - ForceTpl(const ForceTpl & clone) // Copy constructor - : m_data(clone.toVector()) - { - } - + /// + /// \brief Constructor from a force vector and a torque vector, both considered as 3d vectors. + /// + /// \tparam ForceVectorLike type of the force vector. + /// \tparam TorqueVectorLike type of the torque vector. + /// + /// \param[in] force force vector associated with the linear component of the spatial force. + /// \param[in] torque torque vector associated with the angular component of the spatial force. + /// + template + ForceTpl( + const Eigen::MatrixBase & force, + const Eigen::MatrixBase & torque) + { + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(ForceVectorLike, 3); + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(TorqueVectorLike, 3); + linear() = force; + angular() = torque; + } + + /// + /// \brief Constructor from a 6d vector representing a spatial force. + /// + /// \tparam Vector6Like type of the vector + /// + /// \param[in] f 6d vector whose values represent the data associated with a spatial vector. + /// + template + explicit ForceTpl(const Eigen::MatrixBase & f) + : m_data(f) + { + EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector6Like, 6); + } + + /// + /// \brief Copy constructor + /// + /// \param[in] other to copy into *this. + /// + ForceTpl(const ForceTpl & other) + : m_data(other.toVector()) + { + } + + /// + /// \brief Copy constructor with a cast + /// + /// + /// \param[in] other to copy into *this after a cast. + /// template explicit ForceTpl(const ForceTpl & other) { *this = other.template cast(); } - template - explicit ForceTpl(const ForceBase & clone) + /// + /// \brief Copy constructor from a the base class. + /// + /// \param[in] other to copy into *this. + /// + template + explicit ForceTpl(const ForceBase & other) { - *this = clone; + *this = other.derived(); } - ForceTpl & operator=(const ForceTpl & clone) // Copy assignment operator - { - m_data = clone.toVector(); - return *this; - } - - template - explicit ForceTpl(const ForceTpl & clone) - : m_data(clone.toVector()) + /// + /// \brief Copy constructor from a spatial dense force. + /// + /// \param[in] other to copy into *this. + /// + template + explicit ForceTpl(const ForceDense & other) { + linear() = other.linear(); + angular() = other.angular(); } - template - explicit ForceTpl(const ForceDense & clone) + /// + /// \brief Copy operator + /// + /// \param[in] other to copy into *this. + /// + ForceTpl & operator=(const ForceTpl & other) // Copy assignment operator { - linear() = clone.linear(); - angular() = clone.angular(); + m_data = other.toVector(); + return *this; } - // initializers + /// + /// \brief Returns a spatial force set to zero. + /// static ForceTpl Zero() { return ForceTpl(Vector6::Zero()); } + + /// + /// \brief Returns a spatial force set to random. + /// + /// \remark This static constructor calls the random function of Eigen. + /// static ForceTpl Random() { return ForceTpl(Vector6::Random()); @@ -156,12 +212,13 @@ namespace pinocchio linear_impl() = v; } + /// \returns *this as a ForceRef vector ForceRef ref() { return ForceRef(m_data); } - /// \returns An expression of *this with the Scalar type casted to NewScalar. + /// \returns a cast version of *this. template ForceTpl cast() const { diff --git a/include/pinocchio/spatial/inertia.hpp b/include/pinocchio/spatial/inertia.hpp index 50c8989319..31b48a0066 100644 --- a/include/pinocchio/spatial/inertia.hpp +++ b/include/pinocchio/spatial/inertia.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2015-2018 CNRS +// Copyright (c) 2015-2021 CNRS // Copyright (c) 2018-2025 INRIA // Copyright (c) 2016 Wandercraft, 86 rue de Paris 91400 Orsay, France. // @@ -542,14 +542,26 @@ namespace pinocchio Vector10 toDynamicParameters() const { Vector10 v; - - v[0] = mass(); - v.template segment<3>(1).noalias() = mass() * lever(); - v.template segment<6>(4) = (inertia() - AlphaSkewSquare(mass(), lever())).data(); - + toDynamicParameters(v); return v; } + /** Fill the vector of dynamic parameters. + * The parameters are given as + * \f$ v = [m, mc_x, mc_y, mc_z, I_{xx}, I_{xy}, I_{yy}, I_{xz}, I_{yz}, I_{zz}]^T \f$ + * where \f$ c \f$ is the center of mass, \f$ I = I_C + mS^T(c)S(c) \f$ and \f$ I_C \f$ has its + * origin at the barycenter and \f$ S(c) \f$ is the the skew matrix representation of the cross + * product operator. + */ + template + void toDynamicParameters(const Eigen::MatrixBase & vec10_) const + { + Vector10Like & vec10 = vec10_.const_cast_derived(); + vec10[0] = mass(); + vec10.template segment<3>(1).noalias() = mass() * lever(); + vec10.template segment<6>(4) = (inertia() - AlphaSkewSquare(mass(), lever())).data(); + } + /** Builds and inertia matrix from a vector of dynamic parameters. * * @param[in] params The dynamic parameters. @@ -628,7 +640,8 @@ namespace pinocchio const Scalar & prec = Eigen::NumTraits::dummy_precision()) const { using math::fabs; - return fabs(static_cast(mass() - other.mass())) <= prec + return (fabs(static_cast(mass() - other.mass())) + <= (prec * math::max(math::fabs(mass()), math::fabs(other.mass())))) && lever().isApprox(other.lever(), prec) && inertia().isApprox(other.inertia(), prec); } diff --git a/include/pinocchio/spatial/motion-dense.hpp b/include/pinocchio/spatial/motion-dense.hpp index ff99d19bd1..ba7adcbd11 100644 --- a/include/pinocchio/spatial/motion-dense.hpp +++ b/include/pinocchio/spatial/motion-dense.hpp @@ -1,11 +1,13 @@ // -// Copyright (c) 2017-2020 CNRS INRIA +// Copyright (c) 2017-2020 CNRS +// Copyright (c) 2018-2024 INRIA // #ifndef __pinocchio_spatial_motion_dense_hpp__ #define __pinocchio_spatial_motion_dense_hpp__ #include "pinocchio/spatial/skew.hpp" +#include "pinocchio/math/matrix.hpp" namespace pinocchio { @@ -247,7 +249,8 @@ namespace pinocchio const MotionDense & m2, const Scalar & prec = Eigen::NumTraits::dummy_precision()) const { - return linear().isApprox(m2.linear(), prec) && angular().isApprox(m2.angular(), prec); + return isApproxOrZero(linear(), m2.linear(), prec) + && isApproxOrZero(angular(), m2.angular(), prec); } bool isZero_impl(const Scalar & prec = Eigen::NumTraits::dummy_precision()) const diff --git a/include/pinocchio/spatial/se3-base.hpp b/include/pinocchio/spatial/se3-base.hpp index 97304ffb33..1ab165dd83 100644 --- a/include/pinocchio/spatial/se3-base.hpp +++ b/include/pinocchio/spatial/se3-base.hpp @@ -135,9 +135,10 @@ namespace pinocchio derived().toDualActionMatrix_impl(dual_action_matrix); } - typename SE3GroupAction::ReturnType operator*(const Derived & m2) const + template + typename SE3GroupAction::ReturnType operator*(const SE3Base & m2) const { - return derived().__mult__(m2); + return derived().act(m2.derived()); } /// ay = aXb.act(by) diff --git a/include/pinocchio/spatial/se3-tpl.hpp b/include/pinocchio/spatial/se3-tpl.hpp index 8eabc5742d..2de9a6c2bf 100644 --- a/include/pinocchio/spatial/se3-tpl.hpp +++ b/include/pinocchio/spatial/se3-tpl.hpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2015-2021 CNRS INRIA +// Copyright (c) 2015-2024 CNRS INRIA // Copyright (c) 2016 Wandercraft, 86 rue de Paris 91400 Orsay, France. // @@ -13,8 +13,6 @@ #include "pinocchio/math/rotation.hpp" #include "pinocchio/spatial/cartesian-axis.hpp" -#include - namespace pinocchio { template @@ -323,12 +321,6 @@ namespace pinocchio rot.transpose() * m2.rotation(), rot.transpose() * (m2.translation() - translation())); } - template - SE3Tpl __mult__(const SE3Tpl & m2) const - { - return this->act_impl(m2); - } - template bool isEqual(const SE3Tpl & m2) const { diff --git a/include/pinocchio/spatial/symmetric3.hpp b/include/pinocchio/spatial/symmetric3.hpp index 05c2db74ac..a5131850da 100644 --- a/include/pinocchio/spatial/symmetric3.hpp +++ b/include/pinocchio/spatial/symmetric3.hpp @@ -283,8 +283,8 @@ namespace pinocchio // { // const Scalar & x = v[0], & y = v[1], & z = v[2]; // return Symmetric3Tpl(-y*y-z*z, - // x*y, -x*x-z*z, - // x*z, y*z, -x*x-y*y ); + // x*y, -x*x-z*z, + // x*z, y*z, -x*x-y*y ); // } /* Shoot a positive definite matrix. */ diff --git a/include/pinocchio/unsupported.hpp b/include/pinocchio/unsupported.hpp index 7b06063493..dafdc2d18b 100644 --- a/include/pinocchio/unsupported.hpp +++ b/include/pinocchio/unsupported.hpp @@ -5,7 +5,7 @@ #ifndef __pinocchio_unsupported_hpp__ #define __pinocchio_unsupported_hpp__ -#include "pinocchio/deprecation.hpp" +#include "pinocchio/deprecated.hpp" #define PINOCCHIO_UNSUPPORTED PINOCCHIO_DEPRECATED #define PINOCCHIO_UNSUPPORTED_MESSAGE PINOCCHIO_DEPRECATED_MESSAGE diff --git a/include/pinocchio/utils/cast.hpp b/include/pinocchio/utils/cast.hpp index 1b7a2c4704..51b2300101 100644 --- a/include/pinocchio/utils/cast.hpp +++ b/include/pinocchio/utils/cast.hpp @@ -5,7 +5,7 @@ #ifndef __pinocchio_utils_cast_hpp__ #define __pinocchio_utils_cast_hpp__ -#include +#include "pinocchio/fwd.hpp" namespace pinocchio { diff --git a/include/pinocchio/utils/check.hpp b/include/pinocchio/utils/check.hpp index 8b58abbe6c..27a07a5506 100644 --- a/include/pinocchio/utils/check.hpp +++ b/include/pinocchio/utils/check.hpp @@ -5,7 +5,7 @@ #ifndef __pinocchio_utils_check_hpp__ #define __pinocchio_utils_check_hpp__ -#include +#include namespace pinocchio { @@ -13,7 +13,7 @@ namespace pinocchio template< typename Scalar, bool default_value = true, - bool is_real_valued = boost::is_floating_point::value> + bool is_real_valued = ::std::is_floating_point::value> struct check_expression_if_real_valued { static bool run(const void *) diff --git a/include/pinocchio/utils/eigen-fix.hpp b/include/pinocchio/utils/eigen-fix.hpp index e87fa66de7..7a6311681e 100644 --- a/include/pinocchio/utils/eigen-fix.hpp +++ b/include/pinocchio/utils/eigen-fix.hpp @@ -1,10 +1,15 @@ // // Copyright (c) 2017-2018 CNRS +// Copyright (c) 2025 INRIA // #ifndef __pinocchio_utils_eigen_fix_hpp__ #define __pinocchio_utils_eigen_fix_hpp__ +#if EIGEN_VERSION_AT_LEAST(3, 4, 90) + #define EIGEN_EMPTY_STRUCT_CTOR(x) +#endif + #if EIGEN_VERSION_AT_LEAST(3, 2, 90) && !EIGEN_VERSION_AT_LEAST(3, 3, 0) namespace pinocchio { diff --git a/include/pinocchio/utils/openmp.hpp b/include/pinocchio/utils/openmp.hpp index 278c88ceb5..9d9f5d163d 100644 --- a/include/pinocchio/utils/openmp.hpp +++ b/include/pinocchio/utils/openmp.hpp @@ -1,11 +1,16 @@ // -// Copyright (c) 2021 INRIA +// Copyright (c) 2021-2024 INRIA // #ifndef __pinocchio_utils_openmp_hpp__ #define __pinocchio_utils_openmp_hpp__ #include +#include +#include +#include + +#include "pinocchio/deprecated.hpp" namespace pinocchio { @@ -22,6 +27,79 @@ namespace pinocchio return num_threads; } + + inline void setDefaultOpenMPSettings(const size_t num_threads = (size_t)omp_get_max_threads()) + { + omp_set_num_threads((int)num_threads); + omp_set_dynamic(0); + } + + PINOCCHIO_DEPRECATED_MESSAGE( + "This function is now deprecated and has been renamed setDefaultOpenMPSettings.") + inline void set_default_omp_options(const size_t num_threads = (size_t)omp_get_max_threads()) + { + setDefaultOpenMPSettings(num_threads); + } + + struct OpenMPException + { + explicit OpenMPException(const bool throw_on_deletion = false) + : m_exception_ptr(nullptr) + , m_throw_on_deletion(throw_on_deletion) + { + } + + void rethrowException() const + { + if (this->m_exception_ptr) + std::rethrow_exception(this->m_exception_ptr); + } + + std::exception_ptr getException() const + { + return m_exception_ptr; + } + + bool hasThrown() const + { + return this->m_exception_ptr != nullptr; + } + + template + void run(Function f, Parameters... params) + { + try + { + f(params...); + } + catch (...) + { + this->captureException(); + } + } + + void captureException() + { + std::unique_lock guard(this->m_lock); + this->m_exception_ptr = std::current_exception(); + } + + void reset() + { + this->m_exception_ptr = nullptr; + } + + ~OpenMPException() + { + if (m_throw_on_deletion) + this->rethrowException(); + } + + protected: + std::exception_ptr m_exception_ptr; + std::mutex m_lock; + const bool m_throw_on_deletion; + }; // struct OpenMPException } // namespace pinocchio #endif // ifndef __pinocchio_utils_openmp_hpp__ diff --git a/include/pinocchio/utils/reference.hpp b/include/pinocchio/utils/reference.hpp new file mode 100644 index 0000000000..b7598ecd13 --- /dev/null +++ b/include/pinocchio/utils/reference.hpp @@ -0,0 +1,190 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#ifndef __pinocchio_utils_reference_hpp__ +#define __pinocchio_utils_reference_hpp__ + +#include +#include + +namespace pinocchio +{ + namespace helper + { + // std::reference_wrapper + template + T * get_pointer(const std::reference_wrapper & ref) + { + return &ref.get(); + } + template + const T * get_pointer(const std::reference_wrapper & ref) + { + return &ref.get(); + } + + // std::shared_ptr + template + T * get_pointer(const std::shared_ptr & ptr) + { + return ptr.get(); + } + template + const T * get_pointer(const std::shared_ptr & ptr) + { + return ptr.get(); + } + + template + std::reference_wrapper make_ref(T & value) + { + return std::reference_wrapper(value); + } + + template + std::reference_wrapper make_ref(const T & value) + { + return std::reference_wrapper(value); + } + + template + struct remove_ref + { + typedef T type; + static T & get_ref(T & v) + { + return v; + } + }; + + // template + // struct remove_ref + // { + // typedef const T type; + // static const T & get_ref(const T & v) + // { + // return v; + // } + // }; + + template + struct remove_ref> + { + typedef typename remove_ref::type type; + + static T & get_ref(const std::reference_wrapper & ref) + { + return ref.get(); + } + }; + + template + struct remove_ref> + { + typedef typename remove_ref::type type; + + static const T & get_ref(const std::reference_wrapper & ref) + { + return ref.get(); + } + }; + + template + struct remove_ref> + { + typedef typename remove_ref::type type; + + static T & get_ref(const std::shared_ptr & ptr) + { + return *ptr; + } + }; + + template + struct remove_ref> : remove_ref> + { + }; + + template + struct remove_ref> + { + typedef typename remove_ref::type type; + + static const T & get_ref(const std::shared_ptr & ptr) + { + return *ptr; + } + }; + + template + struct remove_ref> : remove_ref> + { + }; + + template + struct remove_ref> + { + typedef typename remove_ref::type type; + + static T & get_ref(const std::unique_ptr & ptr) + { + return *ptr; + } + }; + + template + struct remove_ref> : remove_ref> + { + }; + + template + struct remove_ref> + { + typedef typename remove_ref::type type; + + static const T & get_ref(const std::unique_ptr & ptr) + { + return *ptr; + } + }; + + template + struct remove_ref> : remove_ref> + { + }; + + template + typename remove_ref::type & get_ref(T & v) + { + return remove_ref::get_ref(v); + } + + template + const typename remove_ref::type & get_ref(const T & v) + { + return remove_ref::get_ref(v); + } + + template + struct is_type_holder + { + static constexpr bool value = false; + }; + + template + struct is_type_holder> + { + static constexpr bool value = true; + }; + + template + struct is_type_holder> + { + static constexpr bool value = true; + }; + + } // namespace helper +} // namespace pinocchio + +#endif // ifndef __pinocchio_utils_reference_hpp__ diff --git a/include/pinocchio/utils/std-vector.hpp b/include/pinocchio/utils/std-vector.hpp new file mode 100644 index 0000000000..8098405a00 --- /dev/null +++ b/include/pinocchio/utils/std-vector.hpp @@ -0,0 +1,43 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_utils_std_vector_hpp__ +#define __pinocchio_utils_std_vector_hpp__ + +#include + +#include "pinocchio/utils/template-template-parameter.hpp" + +namespace pinocchio +{ + namespace internal + { + template + struct std_vector_extract_allocator_type + { + template + using type = + typename extract_template_template_parameter::template type; + }; + + template + struct std_vector_with_same_allocator + { + template + using allocator_type = typename std_vector_extract_allocator_type::template type; + + template + using type = std::vector>; + }; + + } // namespace internal + + template + void apply_for_each(std::vector & vector, const Func & func) + { + std::for_each(vector.begin(), vector.end(), func); + } +} // namespace pinocchio + +#endif // __pinocchio_utils_std_vector_hpp__ diff --git a/include/pinocchio/utils/template-template-parameter.hpp b/include/pinocchio/utils/template-template-parameter.hpp new file mode 100644 index 0000000000..04eb06725a --- /dev/null +++ b/include/pinocchio/utils/template-template-parameter.hpp @@ -0,0 +1,29 @@ +// +// Copyright (c) 2025 INRIA +// + +#ifndef __pinocchio_utils_template_template_parameter_hpp__ +#define __pinocchio_utils_template_template_parameter_hpp__ + +namespace pinocchio +{ + namespace internal + { + template + struct extract_template_template_parameter + { + template + using type = C; + }; + + template class C, class... Parameters> + struct extract_template_template_parameter> + { + template + using type = C; + }; + + } // namespace internal +} // namespace pinocchio + +#endif // __pinocchio_utils_template_template_parameter_hpp__ diff --git a/include/pinocchio/visualizers/base-visualizer.hpp b/include/pinocchio/visualizers/base-visualizer.hpp index b5051057b2..52106a0489 100644 --- a/include/pinocchio/visualizers/base-visualizer.hpp +++ b/include/pinocchio/visualizers/base-visualizer.hpp @@ -156,8 +156,8 @@ namespace pinocchio const GeometryModel & collisionModel() const { - PINOCCHIO_THROW( - hasCollisionModel(), std::logic_error, "No collision model in the visualizer."); + PINOCCHIO_THROW_IF( + !hasCollisionModel(), std::logic_error, "No collision model in the visualizer."); return *m_collisionModel; } @@ -192,15 +192,15 @@ namespace pinocchio GeometryData & collisionData() { - PINOCCHIO_THROW( - hasCollisionModel(), std::logic_error, "No collision model in the visualizer."); + PINOCCHIO_THROW_IF( + !hasCollisionModel(), std::logic_error, "No collision model in the visualizer."); return *m_collisionData; } const GeometryData & collisionData() const { - PINOCCHIO_THROW( - hasCollisionModel(), std::logic_error, "No collision model in the visualizer."); + PINOCCHIO_THROW_IF( + !hasCollisionModel(), std::logic_error, "No collision model in the visualizer."); return *m_collisionData; } diff --git a/package.xml b/package.xml index d0dda610e5..4244b6e394 100644 --- a/package.xml +++ b/package.xml @@ -1,7 +1,7 @@ pinocchio - 3.6.0 + 3.7.0 A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives. diff --git a/pixi.lock b/pixi.lock index 7584f574b3..06ff790376 100644 --- a/pixi.lock +++ b/pixi.lock @@ -7,7 +7,7 @@ environments: linux-64: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.43-h4bf12b8_4.conda @@ -15,24 +15,25 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cyrus-sasl-2.1.27-h54b06d7_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -41,18 +42,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda @@ -61,7 +63,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.86.0-h1a2810e_3.conda @@ -72,17 +74,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -90,16 +94,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libhiredis-1.0.2-h2cc385e_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -107,22 +111,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.10.1-py312h7900ff3_0.conda @@ -130,54 +134,53 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -185,7 +188,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -209,43 +212,45 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py312h55856b6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.8-py312h9275861_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-devel-1.86.0-h20888b2_3.conda @@ -256,66 +261,71 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.10.1-py312hb401068_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.10.1-py312h535dea3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py312hd9f36e3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py312h3520af0_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/rhash-1.4.5-ha44c9a9_0.conda @@ -324,15 +334,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py312h01d7ebd_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py312h01d7ebd_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda @@ -345,43 +355,45 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py312h6ba4d93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.8-py312h2c4a281_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-devel-1.86.0-hf450f58_3.conda @@ -392,69 +404,72 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.10.1-py312h1f38498_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.10.1-py312hdbc7e53_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py312h50aef2c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py312h998013c_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/rhash-1.4.5-h7ab814d_0.conda @@ -463,15 +478,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py312hea69d52_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py312hea69d52_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda @@ -485,21 +500,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -507,19 +523,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -530,31 +547,33 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libiconv-1.18-h135ad9c_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.10.1-py312h2e8e312_0.conda @@ -563,51 +582,51 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -622,7 +641,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/_x86_64-microarch-level-1-2_x86_64.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ampl-asl-1.0.0-h5888daf_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/assimp-5.4.3-h8943939_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda @@ -632,17 +651,17 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/casadi-3.7.0-py312h09e09b4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/casadi-3.7.0-py312h399c79b_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/coal-python-3.0.0-py312he880d2f_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cppad-20240000.6-he02047a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cppadcodegen-2.5.0-h5888daf_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda @@ -651,10 +670,11 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -663,21 +683,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gmp-6.3.0-hac33072_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyhd3e5650_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ipopt-3.14.17-h59d4785_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ipopt-3.14.17-h7fd866c_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda @@ -686,7 +707,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblasfeo-0.1.4.2-h544d10a_100.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda @@ -698,12 +719,12 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcoal-3.0.0-ha55d5d9_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda @@ -711,6 +732,8 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libfatrop-0.0.4-h5888daf_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -718,7 +741,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda @@ -727,11 +750,11 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libignition-cmake2-2.17.2-hac33072_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libignition-math6-6.15.1-py312h76e88e7_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-devel-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-devel-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -740,26 +763,26 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libosqp-0.6.3-h5888daf_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libqdldl-0.1.7-hcb278e6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libscotch-7.0.4-h2fe6a88_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsdformat-9.8.0-hd8b6797_7.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsdformat-9.8.0-hd8b6797_8.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libspral-2024.05.08-h2b245be_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libspral-2025.03.06-h39c1cf3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.10.1-py312h7900ff3_0.conda @@ -768,44 +791,43 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/metis-5.1.0-hd0bcaf9_1007.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/mpfr-4.2.1-h90cbb55_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mumps-include-5.7.3-h23d43cc_9.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/mumps-include-5.7.3-h82cca05_10.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/mumps-seq-5.7.3-h27a6a8b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/octomap-1.10.0-h84d6215_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/pycppad-1.2.4-py312hf7903ae_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-static-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda @@ -813,17 +835,17 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml-2.6.2-h4bd325d_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -831,7 +853,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -847,9 +869,9 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxrender-0.9.12-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxtst-1.2.5-hb9d3cd8_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxxf86vm-1.1.6-hb9d3cd8_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.6.4-hbcc6ac9_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-gpl-tools-5.6.4-hbcc6ac9_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-tools-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.8.1-hbcc6ac9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-gpl-tools-5.8.1-hbcc6ac9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-tools-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda @@ -862,51 +884,53 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/casadi-3.7.0-py312hc4f9d4a_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/casadi-3.7.0-py312hd531e53_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/coal-python-3.0.0-py312hd8f6730_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cppad-20240000.6-hf036a51_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cppadcodegen-2.5.0-hac325c4_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py312h55856b6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/gmp-6.3.0-hf036a51_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyhd3e5650_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ipopt-3.14.17-hd603822_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ipopt-3.14.17-h12baa73_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.8-py312h9275861_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblasfeo-0.1.4.2-h16a7471_100.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda @@ -918,46 +942,49 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcoal-3.0.0-h1752fee_5.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libfatrop-0.0.4-h240833e_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libignition-cmake2-2.17.2-hf036a51_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libignition-math6-6.15.1-py312hf1cefc6_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libosqp-0.6.3-h97d8b74_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libqdldl-0.1.7-hf0c8a7f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libscotch-7.0.6-h7a28ce2_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libsdformat-9.8.0-h5728b0d_7.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libsdformat-9.8.0-h5728b0d_8.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.10.1-py312hb401068_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.10.1-py312h535dea3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda @@ -968,31 +995,33 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/mumps-seq-5.7.3-heb77934_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/octomap-1.10.0-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py312hd9f36e3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/pycppad-1.2.4-py312h3396e0f_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py312h3520af0_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-static-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda @@ -1003,15 +1032,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml-2.6.2-h65a07b1_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py312h01d7ebd_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py312h01d7ebd_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda @@ -1027,51 +1056,53 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/casadi-3.7.0-py312h2a9d200_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/casadi-3.7.0-py312h74b190f_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/coal-python-3.0.0-py312hc43833c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cppad-20240000.6-h00cdb27_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cppadcodegen-2.5.0-hf9b8971_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py312h6ba4d93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gmp-6.3.0-h7bae524_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyhd3e5650_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ipopt-3.14.17-h3e4dc2c_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ipopt-3.14.17-h945cc1c_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.8-py312h2c4a281_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblasfeo-0.1.4.2-h37ef02a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda @@ -1083,48 +1114,50 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcoal-3.0.0-hf5bebb4_5.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfatrop-0.0.4-h286801f_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libignition-cmake2-2.17.2-h00cdb27_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libignition-math6-6.15.1-py312he17536b_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libosqp-0.6.3-h5833ebf_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libqdldl-0.1.7-hb7217d7_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libscotch-7.0.6-he56f69b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsdformat-9.8.0-hc9d0b99_7.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsdformat-9.8.0-hb05c10c_8.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.10.1-py312h1f38498_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.10.1-py312hdbc7e53_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda @@ -1135,32 +1168,33 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/mumps-seq-5.7.3-h29d90bc_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/octomap-1.10.0-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py312h50aef2c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pycppad-1.2.4-py312h2c00c33_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py312h998013c_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-static-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda @@ -1171,15 +1205,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml-2.6.2-h260d524_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py312hea69d52_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py312hea69d52_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda @@ -1196,25 +1230,26 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/casadi-3.7.0-py312hef5f0c3_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/casadi-3.7.0-py312h226cf95_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/win-64/coal-python-3.0.0-py312h2716052_5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cppad-20240000.7-he0c23c2_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -1222,22 +1257,23 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/gmp-6.3.0-hfeafd45_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyh5279557_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ipopt-3.14.17-h905d1ba_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ipopt-3.14.17-h812a801_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -1248,14 +1284,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcoal-3.0.0-hd2388e2_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda @@ -1263,82 +1301,82 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libignition-cmake2-2.17.2-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libignition-math6-6.15.1-py312h4fd29d7_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libosqp-0.6.3-he0c23c2_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libqdldl-0.1.7-h63175ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libsdformat-9.8.0-h9776664_7.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libsdformat-9.8.0-h9776664_8.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/llvm-openmp-20.1.1-h30eaf37_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/llvm-openmp-20.1.3-h30eaf37_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.10.1-py312h2e8e312_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-base-3.10.1-py312h90004f6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mpfr-4.2.1-hbc20e70_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/mumps-seq-5.7.3-hbaa6519_9.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/mumps-seq-5.7.3-hbaa6519_10.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/octomap-1.10.0-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/pycppad-1.2.4-py312h299e564_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml-2.6.2-h2d74725_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -1354,7 +1392,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/_x86_64-microarch-level-1-2_x86_64.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ampl-asl-1.0.0-h5888daf_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/assimp-5.4.3-h8943939_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda @@ -1362,21 +1400,21 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.43-h4bf12b8_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_linux-64-2.43-h4852527_4.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/casadi-3.7.0-py312h09e09b4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/casadi-3.7.0-py312h399c79b_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/coal-python-3.0.0-py312he880d2f_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cppad-20240000.6-he02047a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cppadcodegen-2.5.0-h5888daf_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda @@ -1385,10 +1423,11 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -1397,21 +1436,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gmp-6.3.0-hac33072_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyhd3e5650_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ipopt-3.14.17-h59d4785_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ipopt-3.14.17-h7fd866c_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jinja2-3.1.6-pyhd8ed1ab_0.conda @@ -1421,7 +1461,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblasfeo-0.1.4.2-h544d10a_100.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda @@ -1433,12 +1473,12 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcoal-3.0.0-ha55d5d9_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda @@ -1446,6 +1486,8 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libfatrop-0.0.4-h5888daf_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -1453,7 +1495,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda @@ -1462,11 +1504,11 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libignition-cmake2-2.17.2-hac33072_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libignition-math6-6.15.1-py312h76e88e7_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-devel-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-devel-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -1475,26 +1517,26 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libosqp-0.6.3-h5888daf_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libqdldl-0.1.7-hcb278e6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libscotch-7.0.4-h2fe6a88_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsdformat-9.8.0-hd8b6797_7.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsdformat-9.8.0-hd8b6797_8.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libspral-2024.05.08-h2b245be_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libspral-2025.03.06-h39c1cf3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/markupsafe-3.0.2-py312h178313f_1.conda @@ -1504,48 +1546,47 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/metis-5.1.0-hd0bcaf9_1007.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/mpfr-4.2.1-h90cbb55_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mumps-include-5.7.3-h23d43cc_9.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/mumps-include-5.7.3-h82cca05_10.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/mumps-seq-5.7.3-h27a6a8b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.33.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.37.0-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/octomap-1.10.0-h84d6215_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pandas-2.2.3-py312hf9745cd_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pandas-2.2.3-py312hf9745cd_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/pycppad-1.2.4-py312hf7903ae_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-tzdata-2025.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2024.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2025.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-static-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda @@ -1553,17 +1594,17 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml-2.6.2-h4bd325d_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -1571,7 +1612,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -1587,10 +1628,10 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxrender-0.9.12-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxtst-1.2.5-hb9d3cd8_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxxf86vm-1.1.6-hb9d3cd8_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.1.0-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.6.4-hbcc6ac9_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-gpl-tools-5.6.4-hbcc6ac9_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-tools-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.4.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.8.1-hbcc6ac9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-gpl-tools-5.8.1-hbcc6ac9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-tools-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda @@ -1601,56 +1642,58 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/assimp-5.4.3-hf9fe5ce_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/benchmark-1.9.2-h240833e_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/casadi-3.7.0-py312hc4f9d4a_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/casadi-3.7.0-py312hd531e53_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/coal-python-3.0.0-py312hd8f6730_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cppad-20240000.6-hf036a51_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cppadcodegen-2.5.0-hac325c4_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py312h55856b6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/gmp-6.3.0-hf036a51_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyhd3e5650_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ipopt-3.14.17-hd603822_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ipopt-3.14.17-h12baa73_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jinja2-3.1.6-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.8-py312h9275861_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblasfeo-0.1.4.2-h16a7471_100.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda @@ -1662,46 +1705,49 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcoal-3.0.0-h1752fee_5.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libfatrop-0.0.4-h240833e_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libignition-cmake2-2.17.2-hf036a51_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libignition-math6-6.15.1-py312hf1cefc6_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libosqp-0.6.3-h97d8b74_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libqdldl-0.1.7-hf0c8a7f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libscotch-7.0.6-h7a28ce2_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libsdformat-9.8.0-h5728b0d_7.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libsdformat-9.8.0-h5728b0d_8.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/markupsafe-3.0.2-py312h3520af0_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.10.1-py312hb401068_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.10.1-py312h535dea3_0.conda @@ -1712,36 +1758,38 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/mumps-include-5.7.3-h991c767_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/mumps-seq-5.7.3-heb77934_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.33.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.37.0-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/octomap-1.10.0-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pandas-2.2.3-py312h98e817e_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pandas-2.2.3-py312hec45ffd_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py312hd9f36e3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/pycppad-1.2.4-py312h3396e0f_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-tzdata-2025.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2024.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2025.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py312h3520af0_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-static-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda @@ -1752,20 +1800,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml-2.6.2-h65a07b1_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py312h01d7ebd_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py312h01d7ebd_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxdmcp-1.1.5-h00291cd_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.1.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.4.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/yaml-0.2.5-h0d85af4_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-h7130eaa_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zlib-1.3.1-hd23fc13_2.conda @@ -1775,56 +1823,58 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/assimp-5.4.3-ha9c0b8d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/benchmark-1.9.2-h286801f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/casadi-3.7.0-py312h2a9d200_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/casadi-3.7.0-py312h74b190f_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/coal-python-3.0.0-py312hc43833c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cppad-20240000.6-h00cdb27_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cppadcodegen-2.5.0-hf9b8971_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py312h6ba4d93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gmp-6.3.0-h7bae524_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyhd3e5650_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ipopt-3.14.17-h3e4dc2c_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ipopt-3.14.17-h945cc1c_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jinja2-3.1.6-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.8-py312h2c4a281_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblasfeo-0.1.4.2-h37ef02a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda @@ -1836,48 +1886,50 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcoal-3.0.0-hf5bebb4_5.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfatrop-0.0.4-h286801f_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libignition-cmake2-2.17.2-h00cdb27_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libignition-math6-6.15.1-py312he17536b_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libosqp-0.6.3-h5833ebf_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libqdldl-0.1.7-hb7217d7_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libscotch-7.0.6-he56f69b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsdformat-9.8.0-hc9d0b99_7.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsdformat-9.8.0-hb05c10c_8.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/markupsafe-3.0.2-py312h998013c_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.10.1-py312h1f38498_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.10.1-py312hdbc7e53_0.conda @@ -1888,37 +1940,38 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/mumps-include-5.7.3-h8c5b6c6_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/mumps-seq-5.7.3-h29d90bc_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.33.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.37.0-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/octomap-1.10.0-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pandas-2.2.3-py312hcd31e36_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pandas-2.2.3-py312hcb1e3ce_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py312h50aef2c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pycppad-1.2.4-py312h2c00c33_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-tzdata-2025.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2024.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2025.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py312h998013c_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-static-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda @@ -1929,20 +1982,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml-2.6.2-h260d524_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py312hea69d52_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py312hea69d52_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxdmcp-1.1.5-hd74edd7_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.1.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.4.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/yaml-0.2.5-h3422bc3_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-hc1bb282_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zlib-1.3.1-h8359307_2.conda @@ -1953,29 +2006,30 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/assimp-5.4.3-hf1e84b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/benchmark-1.9.2-he0c23c2_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/casadi-3.7.0-py312hef5f0c3_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/casadi-3.7.0-py312h226cf95_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/win-64/coal-python-3.0.0-py312h2716052_5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cppad-20240000.7-he0c23c2_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -1983,23 +2037,24 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/gmp-6.3.0-hfeafd45_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyh5279557_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ipopt-3.14.17-h905d1ba_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ipopt-3.14.17-h812a801_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jinja2-3.1.6-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -2010,14 +2065,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcoal-3.0.0-hd2388e2_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda @@ -2025,25 +2082,25 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libignition-cmake2-2.17.2-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libignition-math6-6.15.1-py312h4fd29d7_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libosqp-0.6.3-he0c23c2_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libqdldl-0.1.7-h63175ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libsdformat-9.8.0-h9776664_7.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libsdformat-9.8.0-h9776664_8.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/llvm-openmp-20.1.1-h30eaf37_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/llvm-openmp-20.1.3-h30eaf37_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/markupsafe-3.0.2-py312h31fea79_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.10.1-py312h2e8e312_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-base-3.10.1-py312h90004f6_0.conda @@ -2051,65 +2108,65 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mpfr-4.2.1-hbc20e70_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/mumps-seq-5.7.3-hbaa6519_9.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/mumps-seq-5.7.3-hbaa6519_10.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.33.0-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.37.0-pyh29332c3_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/octomap-1.10.0-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pandas-2.2.3-py312h72972c8_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pandas-2.2.3-py312h72972c8_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/pycppad-1.2.4-py312h299e564_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-tzdata-2025.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2024.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2025.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml-2.6.2-h2d74725_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.1.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.4.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/yaml-0.2.5-h8ffe710_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/zeromq-4.3.5-ha9f60a1_7.conda - conda: https://conda.anaconda.org/conda-forge/win-64/zlib-1.3.1-h2466b09_2.conda @@ -2126,25 +2183,26 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/casadi-3.7.0-py312hef5f0c3_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/casadi-3.7.0-py312h226cf95_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/win-64/coal-python-3.0.0-py312h2716052_5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cppad-20240000.7-he0c23c2_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -2152,22 +2210,23 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/gmp-6.3.0-hfeafd45_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyh5279557_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ipopt-3.14.17-h905d1ba_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ipopt-3.14.17-h812a801_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -2178,14 +2237,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcoal-3.0.0-hd2388e2_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda @@ -2193,82 +2254,82 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libignition-cmake2-2.17.2-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libignition-math6-6.15.1-py312h4fd29d7_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libosqp-0.6.3-he0c23c2_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libqdldl-0.1.7-h63175ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libsdformat-9.8.0-h9776664_7.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libsdformat-9.8.0-h9776664_8.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/llvm-openmp-20.1.1-h30eaf37_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/llvm-openmp-20.1.3-h30eaf37_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.10.1-py312h2e8e312_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-base-3.10.1-py312h90004f6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mpfr-4.2.1-hbc20e70_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/mumps-seq-5.7.3-hbaa6519_9.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/mumps-seq-5.7.3-hbaa6519_10.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/octomap-1.10.0-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/pycppad-1.2.4-py312h299e564_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml-2.6.2-h2d74725_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -2284,7 +2345,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/_x86_64-microarch-level-1-2_x86_64.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ampl-asl-1.0.0-h5888daf_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/assimp-5.4.3-h8943939_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda @@ -2294,14 +2355,14 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/casadi-3.7.0-py39hc9664a4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/casadi-3.7.0-py39h19ee5b0_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/certifi-2025.1.31-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/coal-python-3.0.0-py39h2b5945f_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 @@ -2314,10 +2375,11 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py39h7ec7272_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -2326,22 +2388,23 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py39h9399b63_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py39h9399b63_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gmp-6.3.0-hac33072_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyhd3e5650_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib-resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ipopt-3.14.17-h59d4785_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ipopt-3.14.17-h7fd866c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-8.18.1-pyh707e725_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda @@ -2350,7 +2413,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblasfeo-0.1.4.2-h544d10a_100.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda @@ -2362,12 +2425,12 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcoal-3.0.0-ha55d5d9_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda @@ -2375,6 +2438,8 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libfatrop-0.0.4-h5888daf_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -2382,7 +2447,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda @@ -2391,11 +2456,11 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libignition-cmake2-2.17.2-hac33072_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libignition-math6-6.15.1-py39h46f9f43_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-devel-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-devel-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -2404,26 +2469,26 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libosqp-0.6.3-h5888daf_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libqdldl-0.1.7-hcb278e6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libscotch-7.0.4-h2fe6a88_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsdformat-9.8.0-hd8b6797_7.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsdformat-9.8.0-hd8b6797_8.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libspral-2024.05.08-h2b245be_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libspral-2025.03.06-h39c1cf3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.9.4-py39hf3d152e_0.conda @@ -2432,44 +2497,43 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/metis-5.1.0-hd0bcaf9_1007.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/mpfr-4.2.1-h90cbb55_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mumps-include-5.7.3-h23d43cc_9.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/mumps-include-5.7.3-h82cca05_10.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/mumps-seq-5.7.3-h27a6a8b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.0.2-py39h9cb892a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/octomap-1.10.0-h84d6215_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py39h15c0740_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/pycppad-1.2.4-py39h6c5f618_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py39h0383914_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.9.21-h9c0c6dc_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py39h0383914_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.9.22-h85ef794_1_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.9-5_cp39.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.9-7_cp39.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py39h9399b63_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py39h4e4fb57_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py39h4e4fb57_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-static-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.13.1-py39haf93ffa_0.conda @@ -2477,17 +2541,17 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml-2.6.2-h4bd325d_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py39h8cd3c5a_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py39h8cd3c5a_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -2495,7 +2559,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -2511,9 +2575,9 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxrender-0.9.12-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxtst-1.2.5-hb9d3cd8_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxxf86vm-1.1.6-hb9d3cd8_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.6.4-hbcc6ac9_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-gpl-tools-5.6.4-hbcc6ac9_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-tools-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.8.1-hbcc6ac9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-gpl-tools-5.8.1-hbcc6ac9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-tools-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/noarch/zipp-3.21.0-pyhd8ed1ab_1.conda @@ -2527,22 +2591,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/casadi-3.7.0-py39h0ba0775_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/casadi-3.7.0-py39h6d613ad_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda - conda: https://conda.anaconda.org/conda-forge/noarch/certifi-2025.1.31-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/coal-python-3.0.0-py39hd693ebf_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda @@ -2554,26 +2618,28 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py39h16cfbdb_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py39hd18e689_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py39hd18e689_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/gmp-6.3.0-hf036a51_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyhd3e5650_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib-resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ipopt-3.14.17-hd603822_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ipopt-3.14.17-h12baa73_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-8.18.1-pyh707e725_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.7-py39h0d8d0ca_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblasfeo-0.1.4.2-h16a7471_100.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda @@ -2585,46 +2651,49 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcoal-3.0.0-h1752fee_5.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libfatrop-0.0.4-h240833e_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libignition-cmake2-2.17.2-hf036a51_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libignition-math6-6.15.1-py39h86b6583_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libosqp-0.6.3-h97d8b74_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libqdldl-0.1.7-hf0c8a7f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libscotch-7.0.6-h7a28ce2_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libsdformat-9.8.0-h5728b0d_7.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libsdformat-9.8.0-h5728b0d_8.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.9.4-py39h6e9494a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.9.4-py39hda06d36_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda @@ -2635,31 +2704,33 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/mumps-seq-5.7.3-heb77934_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.0.2-py39h277832c_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/octomap-1.10.0-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py39h1fda9f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/pycppad-1.2.4-py39hf891364_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.9.21-h7fafba3_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.9.22-h55ef250_1_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.9-5_cp39.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.9-7_cp39.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py39hd18e689_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py39hf094b8e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py39hf094b8e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-static-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda @@ -2670,15 +2741,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml-2.6.2-h65a07b1_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py39h80efdc8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py39h80efdc8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda @@ -2695,22 +2766,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/casadi-3.7.0-py39hc8fcb4c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/casadi-3.7.0-py39hb80b00f_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda - conda: https://conda.anaconda.org/conda-forge/noarch/certifi-2025.1.31-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/coal-python-3.0.0-py39h00601d9_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda @@ -2722,26 +2793,28 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py39hc3d805d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py39hefdd603_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py39hefdd603_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gmp-6.3.0-h7bae524_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyhd3e5650_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib-resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ipopt-3.14.17-h3e4dc2c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ipopt-3.14.17-h945cc1c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-8.18.1-pyh707e725_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.7-py39h157d57c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblasfeo-0.1.4.2-h37ef02a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda @@ -2753,48 +2826,50 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcoal-3.0.0-hf5bebb4_5.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfatrop-0.0.4-h286801f_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libignition-cmake2-2.17.2-h00cdb27_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libignition-math6-6.15.1-py39hc9d7496_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libosqp-0.6.3-h5833ebf_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libqdldl-0.1.7-hb7217d7_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libscotch-7.0.6-he56f69b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsdformat-9.8.0-hc9d0b99_7.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsdformat-9.8.0-hb05c10c_8.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.9.4-py39hdf13c20_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.9.4-py39h7251d6c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda @@ -2805,32 +2880,33 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/mumps-seq-5.7.3-h29d90bc_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.0.2-py39h3ba1154_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/octomap-1.10.0-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py39hfea3036_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pycppad-1.2.4-py39h50fbb99_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.9.21-h5f1b60f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.9.22-hdec7a8b_1_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.9-5_cp39.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.9-7_cp39.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py39hefdd603_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py39h80d5f2a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py39h80d5f2a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-static-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda @@ -2841,15 +2917,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml-2.6.2-h260d524_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py39hf3bc14e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py39hf3bc14e_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda @@ -2867,12 +2943,12 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/casadi-3.7.0-py39h078d07b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/casadi-3.7.0-py39h70862e4_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/certifi-2025.1.31-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/win-64/coal-python-3.0.0-py39h4dfa7ed_5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda @@ -2883,10 +2959,11 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py39h9d35a09_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -2894,23 +2971,24 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py39hf73967f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py39hf73967f_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/gmp-6.3.0-hfeafd45_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyh5279557_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib-resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ipopt-3.14.17-h905d1ba_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ipopt-3.14.17-h812a801_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-8.18.1-pyh7428d3b_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.7-py39h2b77a98_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -2921,14 +2999,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcoal-3.0.0-hd2388e2_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda @@ -2936,82 +3016,82 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libignition-cmake2-2.17.2-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libignition-math6-6.15.1-py39hffc9e95_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libosqp-0.6.3-he0c23c2_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libqdldl-0.1.7-h63175ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libsdformat-9.8.0-h9776664_7.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libsdformat-9.8.0-h9776664_8.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/llvm-openmp-20.1.1-h30eaf37_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/llvm-openmp-20.1.3-h30eaf37_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.9.4-py39hcbf5309_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-base-3.9.4-py39h5376392_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mpfr-4.2.1-hbc20e70_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/mumps-seq-5.7.3-hbaa6519_9.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/mumps-seq-5.7.3-hbaa6519_10.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-1.26.4-py39hddb5d58_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/octomap-1.10.0-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py39h73ef694_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/pycppad-1.2.4-py39h21e56dd_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py39h0285922_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.9.21-h37870fc_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py39h5cc861e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.9.22-hfdde91d_1_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.9-5_cp39.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.9-7_cp39.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py39hf73967f_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py39h03e5c00_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py39h03e5c00_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.13.1-py39h1a10956_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml-2.6.2-h2d74725_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py39ha55e580_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py39ha55e580_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -3027,7 +3107,7 @@ environments: linux-64: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.43-h4bf12b8_4.conda @@ -3035,14 +3115,14 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cppad-20240000.6-he02047a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cppadcodegen-2.5.0-h5888daf_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda @@ -3051,10 +3131,11 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -3063,18 +3144,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda @@ -3083,7 +3165,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.86.0-h1a2810e_3.conda @@ -3094,17 +3176,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -3112,16 +3196,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libhiredis-1.0.2-h2cc385e_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -3129,22 +3213,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.10.1-py312h7900ff3_0.conda @@ -3152,55 +3236,54 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pycppad-1.2.4-py312hf7903ae_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -3208,7 +3291,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -3232,45 +3315,47 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cppad-20240000.6-hf036a51_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cppadcodegen-2.5.0-hac325c4_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py312h55856b6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.8-py312h9275861_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-devel-1.86.0-h20888b2_3.conda @@ -3281,67 +3366,72 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.10.1-py312hb401068_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.10.1-py312h535dea3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py312hd9f36e3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pycppad-1.2.4-py312h3396e0f_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py312h3520af0_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/rhash-1.4.5-ha44c9a9_0.conda @@ -3350,15 +3440,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py312h01d7ebd_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py312h01d7ebd_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda @@ -3371,45 +3461,47 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cppad-20240000.6-h00cdb27_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cppadcodegen-2.5.0-hf9b8971_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py312h6ba4d93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.8-py312h2c4a281_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-devel-1.86.0-hf450f58_3.conda @@ -3420,70 +3512,73 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.10.1-py312h1f38498_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.10.1-py312hdbc7e53_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py312h50aef2c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pycppad-1.2.4-py312h2c00c33_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py312h998013c_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/rhash-1.4.5-h7ab814d_0.conda @@ -3492,15 +3587,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py312hea69d52_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py312hea69d52_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda @@ -3514,22 +3609,23 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cppad-20240000.7-he0c23c2_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -3537,19 +3633,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -3560,31 +3657,33 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libiconv-1.18-h135ad9c_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.10.1-py312h2e8e312_0.conda @@ -3593,52 +3692,52 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pycppad-1.2.4-py312h299e564_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -3652,34 +3751,35 @@ environments: linux-64: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/benchmark-1.9.2-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.43-h4bf12b8_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_linux-64-2.43-h4852527_4.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cyrus-sasl-2.1.27-h54b06d7_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.3-np20py312hf621b31_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.11.0-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -3688,18 +3788,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jinja2-3.1.6-pyhd8ed1ab_0.conda @@ -3709,7 +3810,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.86.0-h1a2810e_3.conda @@ -3720,17 +3821,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -3738,16 +3841,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libhiredis-1.0.2-h2cc385e_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -3755,22 +3858,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/markupsafe-3.0.2-py312h178313f_1.conda @@ -3779,58 +3882,57 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.33.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.37.0-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pandas-2.2.3-py312hf9745cd_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pandas-2.2.3-py312hf9745cd_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-tzdata-2025.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2024.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2025.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -3838,7 +3940,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -3854,55 +3956,57 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxrender-0.9.12-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxtst-1.2.5-hb9d3cd8_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxxf86vm-1.1.6-hb9d3cd8_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.1.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.4.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zstd-1.5.7-hb8e6e7a_2.conda osx-64: - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/benchmark-1.9.2-h240833e_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.3-np20py312h9bc5bda_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.11.0-np20py312h9bc5bda_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jinja2-3.1.6-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.8-py312h9275861_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-devel-1.86.0-h20888b2_3.conda @@ -3913,71 +4017,76 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-13_2_0_h97931a8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-13.2.0-h2873a65_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/markupsafe-3.0.2-py312h3520af0_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.10.1-py312hb401068_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.10.1-py312h535dea3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.33.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.37.0-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pandas-2.2.3-py312h98e817e_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pandas-2.2.3-py312hec45ffd_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py312hd9f36e3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-tzdata-2025.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2024.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2025.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py312h3520af0_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/rhash-1.4.5-ha44c9a9_0.conda @@ -3986,68 +4095,70 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py312h01d7ebd_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py312h01d7ebd_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxdmcp-1.1.5-h00291cd_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.1.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.4.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/yaml-0.2.5-h0d85af4_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/zeromq-4.3.5-h7130eaa_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/zstd-1.5.7-h8210216_2.conda osx-arm64: - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/benchmark-1.9.2-h286801f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.3-np20py312h03850db_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.11.0-np20py312h03850db_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jinja2-3.1.6-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.8-py312h2c4a281_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-devel-1.86.0-hf450f58_3.conda @@ -4058,74 +4169,77 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-13_2_0_hd922786_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-13.2.0-hf226fd6_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/markupsafe-3.0.2-py312h998013c_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.10.1-py312h1f38498_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.10.1-py312hdbc7e53_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.33.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.37.0-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pandas-2.2.3-py312hcd31e36_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pandas-2.2.3-py312hcb1e3ce_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py312h50aef2c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-tzdata-2025.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2024.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2025.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py312h998013c_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/rhash-1.4.5-h7ab814d_0.conda @@ -4134,20 +4248,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py312hea69d52_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py312hea69d52_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxdmcp-1.1.5-hd74edd7_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.1.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.4.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/yaml-0.2.5-h3422bc3_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zeromq-4.3.5-hc1bb282_7.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/zstd-1.5.7-h6491c7d_2.conda @@ -4155,25 +4269,26 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/_openmp_mutex-4.5-2_gnu.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/benchmark-1.9.2-he0c23c2_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.3-py312h00c8ebc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.11.0-py312h00c8ebc_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -4181,20 +4296,21 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jinja2-3.1.6-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -4205,31 +4321,33 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libiconv-1.18-h135ad9c_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/markupsafe-3.0.2-py312h31fea79_1.conda @@ -4239,59 +4357,59 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.33.0-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.37.0-pyh29332c3_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pandas-2.2.3-py312h72972c8_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pandas-2.2.3-py312h72972c8_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-tzdata-2025.2-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2024.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2025.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.1.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.4.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/yaml-0.2.5-h8ffe710_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/zeromq-4.3.5-ha9f60a1_7.conda - conda: https://conda.anaconda.org/conda-forge/win-64/zstd-1.5.7-hbeecb71_2.conda @@ -4303,7 +4421,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/_x86_64-microarch-level-1-2_x86_64.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ampl-asl-1.0.0-h5888daf_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda @@ -4312,25 +4430,26 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/casadi-3.7.0-py312h09e09b4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/casadi-3.7.0-py312h399c79b_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cyrus-sasl-2.1.27-h54b06d7_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -4339,19 +4458,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ipopt-3.14.17-h59d4785_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ipopt-3.14.17-h7fd866c_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda @@ -4360,7 +4480,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblasfeo-0.1.4.2-h544d10a_100.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda @@ -4372,11 +4492,11 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda @@ -4384,6 +4504,8 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libfatrop-0.0.4-h5888daf_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -4391,18 +4513,18 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libhiredis-1.0.2-h2cc385e_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/libhwloc-2.11.2-default_h0d58e46_1001.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-devel-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-devel-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -4411,25 +4533,25 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libosqp-0.6.3-h5888daf_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libqdldl-0.1.7-hcb278e6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libscotch-7.0.4-h2fe6a88_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libspral-2024.05.08-h2b245be_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libspral-2025.03.06-h39c1cf3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.10.1-py312h7900ff3_0.conda @@ -4437,57 +4559,56 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/metis-5.1.0-hd0bcaf9_1007.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mumps-include-5.7.3-h23d43cc_9.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/mumps-include-5.7.3-h82cca05_10.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/mumps-seq-5.7.3-h27a6a8b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -4495,7 +4616,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -4511,9 +4632,9 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxrender-0.9.12-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxtst-1.2.5-hb9d3cd8_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libxxf86vm-1.1.6-hb9d3cd8_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.6.4-hbcc6ac9_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-gpl-tools-5.6.4-hbcc6ac9_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-tools-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.8.1-hbcc6ac9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-gpl-tools-5.8.1-hbcc6ac9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xz-tools-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/zeromq-4.3.5-h3b0a872_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/zlib-1.3.1-hb9d3cd8_2.conda @@ -4525,45 +4646,47 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/casadi-3.7.0-py312hc4f9d4a_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/casadi-3.7.0-py312hd531e53_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py312h55856b6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ipopt-3.14.17-hd603822_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ipopt-3.14.17-h12baa73_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.8-py312h9275861_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblasfeo-0.1.4.2-h16a7471_100.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda @@ -4575,24 +4698,27 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libfatrop-0.0.4-h240833e_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libosqp-0.6.3-h97d8b74_1.conda @@ -4601,16 +4727,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libscotch-7.0.6-h7a28ce2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.10.1-py312hb401068_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.10.1-py312h535dea3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda @@ -4620,28 +4746,30 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/mumps-seq-5.7.3-heb77934_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py312hd9f36e3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py312h3520af0_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/rhash-1.4.5-ha44c9a9_0.conda @@ -4650,15 +4778,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py312h01d7ebd_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py312h01d7ebd_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda @@ -4672,45 +4800,47 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/casadi-3.7.0-py312h2a9d200_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/casadi-3.7.0-py312h74b190f_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py312h6ba4d93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ipopt-3.14.17-h3e4dc2c_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ipopt-3.14.17-h945cc1c_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.8-py312h2c4a281_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblasfeo-0.1.4.2-h37ef02a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda @@ -4722,26 +4852,28 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfatrop-0.0.4-h286801f_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libosqp-0.6.3-h5833ebf_1.conda @@ -4750,16 +4882,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libscotch-7.0.6-he56f69b_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.10.1-py312h1f38498_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.10.1-py312hdbc7e53_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda @@ -4769,29 +4901,30 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/mumps-seq-5.7.3-h29d90bc_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py312h50aef2c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py312h998013c_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/rhash-1.4.5-h7ab814d_0.conda @@ -4800,15 +4933,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py312hea69d52_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py312hea69d52_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda @@ -4823,22 +4956,23 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/casadi-3.7.0-py312hef5f0c3_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/casadi-3.7.0-py312h226cf95_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -4846,20 +4980,21 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ipopt-3.14.17-h905d1ba_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ipopt-3.14.17-h812a801_2.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -4870,88 +5005,90 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libiconv-1.18-h135ad9c_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libosqp-0.6.3-he0c23c2_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libqdldl-0.1.7-h63175ca_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/llvm-openmp-20.1.1-h30eaf37_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/llvm-openmp-20.1.3-h30eaf37_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.10.1-py312h2e8e312_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-base-3.10.1-py312h90004f6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/mumps-seq-5.7.3-hbaa6519_9.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/mumps-seq-5.7.3-hbaa6519_10.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -4965,7 +5102,7 @@ environments: linux-64: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.43-h4bf12b8_4.conda @@ -4973,27 +5110,28 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/clang-20-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/clang-20.1.1-default_h9e3a008_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/clangxx-20.1.1-default_ha78316a_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/clang-20-20.1.3-default_h1df26ce_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/clang-20.1.3-default_hfa515fb_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/clangxx-20.1.3-default_h0982aa1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cyrus-sasl-2.1.27-h54b06d7_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.3-np20py312hf621b31_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.11.0-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -5002,18 +5140,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321h59d505e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda @@ -5022,7 +5161,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.86.0-h1a2810e_3.conda @@ -5033,17 +5172,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.3-default_h1df26ce_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.3-default_he06ed0a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -5051,16 +5192,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.1-h2ff4ddf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libhiredis-1.0.2-h2cc385e_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.4-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -5068,22 +5209,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.0-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h4bc477f_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.10.1-py312h7900ff3_0.conda @@ -5091,54 +5232,55 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.2.0-h266115a_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.2.0-he0572af_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hc749103_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h6441bc3_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -5146,7 +5288,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -5172,7 +5314,7 @@ environments: linux-64: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.43-h4bf12b8_4.conda @@ -5180,14 +5322,14 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cppad-20240000.6-he02047a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cppadcodegen-2.5.0-h5888daf_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda @@ -5196,10 +5338,11 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -5208,18 +5351,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda @@ -5228,7 +5372,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.86.0-h1a2810e_3.conda @@ -5239,17 +5383,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -5257,16 +5403,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libhiredis-1.0.2-h2cc385e_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -5274,22 +5420,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.10.1-py312h7900ff3_0.conda @@ -5297,55 +5443,54 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pycppad-1.2.4-py312hf7903ae_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -5353,7 +5498,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -5377,45 +5522,47 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cppad-20240000.6-hf036a51_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cppadcodegen-2.5.0-hac325c4_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py312h55856b6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.8-py312h9275861_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-devel-1.86.0-h20888b2_3.conda @@ -5426,67 +5573,72 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.10.1-py312hb401068_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.10.1-py312h535dea3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py312hd9f36e3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pycppad-1.2.4-py312h3396e0f_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py312h3520af0_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/rhash-1.4.5-ha44c9a9_0.conda @@ -5495,15 +5647,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py312h01d7ebd_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py312h01d7ebd_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda @@ -5516,45 +5668,47 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cppad-20240000.6-h00cdb27_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cppadcodegen-2.5.0-hf9b8971_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py312h6ba4d93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.8-py312h2c4a281_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-devel-1.86.0-hf450f58_3.conda @@ -5565,70 +5719,73 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.10.1-py312h1f38498_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.10.1-py312hdbc7e53_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py312h50aef2c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pycppad-1.2.4-py312h2c00c33_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py312h998013c_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/rhash-1.4.5-h7ab814d_0.conda @@ -5637,15 +5794,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py312hea69d52_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py312hea69d52_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda @@ -5659,22 +5816,23 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cppad-20240000.7-he0c23c2_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -5682,19 +5840,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -5705,31 +5864,33 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libiconv-1.18-h135ad9c_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.10.1-py312h2e8e312_0.conda @@ -5738,52 +5899,52 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pycppad-1.2.4-py312h299e564_9.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -5797,7 +5958,7 @@ environments: linux-64: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/assimp-5.4.3-h8943939_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda @@ -5806,26 +5967,27 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/coal-python-3.0.0-py312he880d2f_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cyrus-sasl-2.1.27-h54b06d7_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -5834,19 +5996,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyhd3e5650_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda @@ -5855,7 +6018,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.86.0-h1a2810e_3.conda @@ -5866,18 +6029,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcoal-3.0.0-ha55d5d9_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -5885,16 +6050,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libhiredis-1.0.2-h2cc385e_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -5902,22 +6067,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.10.1-py312h7900ff3_0.conda @@ -5925,56 +6090,55 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/octomap-1.10.0-h84d6215_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-static-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -5982,7 +6146,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -6008,46 +6172,48 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/coal-python-3.0.0-py312hd8f6730_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py312h55856b6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyhd3e5650_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.8-py312h9275861_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-devel-1.86.0-h20888b2_3.conda @@ -6058,68 +6224,73 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcoal-3.0.0-h1752fee_5.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.10.1-py312hb401068_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.10.1-py312h535dea3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/octomap-1.10.0-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py312hd9f36e3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py312h3520af0_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-static-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda @@ -6129,15 +6300,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py312h01d7ebd_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py312h01d7ebd_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda @@ -6152,46 +6323,48 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/coal-python-3.0.0-py312hc43833c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py312h6ba4d93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyhd3e5650_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.8-py312h2c4a281_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-devel-1.86.0-hf450f58_3.conda @@ -6202,71 +6375,74 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcoal-3.0.0-hf5bebb4_5.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.10.1-py312h1f38498_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.10.1-py312hdbc7e53_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/octomap-1.10.0-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py312h50aef2c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py312h998013c_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-static-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda @@ -6276,15 +6452,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py312hea69d52_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py312hea69d52_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda @@ -6300,23 +6476,24 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/win-64/coal-python-3.0.0-py312h2716052_5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -6324,20 +6501,21 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyh5279557_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -6348,32 +6526,34 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcoal-3.0.0-hd2388e2_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libiconv-1.18-h135ad9c_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.10.1-py312h2e8e312_0.conda @@ -6382,52 +6562,52 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/octomap-1.10.0-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -6442,7 +6622,7 @@ environments: linux-64: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.43-h4bf12b8_4.conda @@ -6450,24 +6630,25 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cyrus-sasl-2.1.27-h54b06d7_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -6476,18 +6657,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda @@ -6496,7 +6678,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.86.0-h1a2810e_3.conda @@ -6507,17 +6689,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -6525,16 +6709,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libhiredis-1.0.2-h2cc385e_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -6542,22 +6726,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.10.1-py312h7900ff3_0.conda @@ -6565,54 +6749,53 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -6620,7 +6803,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -6644,43 +6827,45 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py312h55856b6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.8-py312h9275861_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-devel-1.86.0-h20888b2_3.conda @@ -6691,66 +6876,71 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.10.1-py312hb401068_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.10.1-py312h535dea3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py312hd9f36e3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py312h3520af0_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/rhash-1.4.5-ha44c9a9_0.conda @@ -6759,15 +6949,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py312h01d7ebd_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py312h01d7ebd_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda @@ -6780,43 +6970,45 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py312h6ba4d93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.8-py312h2c4a281_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-devel-1.86.0-hf450f58_3.conda @@ -6827,69 +7019,72 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.10.1-py312h1f38498_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.10.1-py312hdbc7e53_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py312h50aef2c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py312h998013c_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/rhash-1.4.5-h7ab814d_0.conda @@ -6898,15 +7093,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py312hea69d52_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py312hea69d52_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda @@ -6920,21 +7115,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -6942,19 +7138,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -6965,31 +7162,33 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libiconv-1.18-h135ad9c_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.10.1-py312h2e8e312_0.conda @@ -6998,51 +7197,51 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -7056,7 +7255,7 @@ environments: linux-64: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.43-h4bf12b8_4.conda @@ -7064,24 +7263,25 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cyrus-sasl-2.1.27-h54b06d7_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -7090,18 +7290,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda @@ -7110,7 +7311,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.86.0-h1a2810e_3.conda @@ -7121,17 +7322,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -7139,16 +7342,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libhiredis-1.0.2-h2cc385e_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -7156,22 +7359,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.10.1-py312h7900ff3_0.conda @@ -7179,55 +7382,54 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-static-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -7235,7 +7437,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -7259,43 +7461,45 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py312h55856b6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.8-py312h9275861_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-devel-1.86.0-h20888b2_3.conda @@ -7306,66 +7510,71 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.10.1-py312hb401068_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.10.1-py312h535dea3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py312hd9f36e3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py312h3520af0_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-static-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda @@ -7375,15 +7584,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py312h01d7ebd_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py312h01d7ebd_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda @@ -7396,43 +7605,45 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py312h6ba4d93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.8-py312h2c4a281_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-devel-1.86.0-hf450f58_3.conda @@ -7443,69 +7654,72 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.10.1-py312h1f38498_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.10.1-py312hdbc7e53_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py312h50aef2c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py312h998013c_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-static-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda @@ -7515,15 +7729,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py312hea69d52_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py312hea69d52_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda @@ -7537,21 +7751,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -7559,19 +7774,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -7582,31 +7798,33 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libiconv-1.18-h135ad9c_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.10.1-py312h2e8e312_0.conda @@ -7615,51 +7833,51 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -7673,7 +7891,7 @@ environments: linux-64: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.43-h4bf12b8_4.conda @@ -7681,16 +7899,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cffi-1.17.1-py312h06ac9bb_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cfgv-3.3.1-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cyrus-sasl-2.1.27-h54b06d7_7.conda @@ -7698,10 +7916,11 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/distlib-0.3.9-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/filelock-3.18.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 @@ -7711,19 +7930,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/identify-2.6.9-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/identify-2.6.10-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda @@ -7732,7 +7952,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.86.0-h1a2810e_3.conda @@ -7743,17 +7963,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -7761,16 +7983,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libhiredis-1.0.2-h2cc385e_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -7778,22 +8000,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.10.1-py312h7900ff3_0.conda @@ -7801,61 +8023,60 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/nodeenv-1.9.1-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - conda: https://conda.anaconda.org/conda-forge/noarch/platformdirs-4.3.7-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pre-commit-4.2.0-pyha770c72_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pycparser-2.22-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-75.8.2-pyhff2d567_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-79.0.1-pyhff2d567_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ukkonen-1.0.1-py312h68727a3_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/virtualenv-20.30.0-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -7863,7 +8084,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -7887,48 +8108,50 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cffi-1.17.1-py312hf857d28_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cfgv-3.3.1-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/distlib-0.3.9-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py312h55856b6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/filelock-3.18.0-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/identify-2.6.9-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/identify-2.6.10-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.8-py312h9275861_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-devel-1.86.0-h20888b2_3.conda @@ -7939,89 +8162,94 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.10.1-py312hb401068_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.10.1-py312h535dea3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/nodeenv-1.9.1-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py312hd9f36e3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - conda: https://conda.anaconda.org/conda-forge/noarch/platformdirs-4.3.7-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pre-commit-4.2.0-pyha770c72_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pycparser-2.22-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py312h3520af0_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/rhash-1.4.5-ha44c9a9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/scipy-1.15.2-py312hd04560d_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-75.8.2-pyhff2d567_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-79.0.1-pyhff2d567_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/sigtool-0.1.3-h88f4db0_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py312h01d7ebd_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ukkonen-1.0.1-py312hc5c4d5f_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py312h01d7ebd_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/virtualenv-20.30.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda @@ -8035,48 +8263,50 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cffi-1.17.1-py312h0fad829_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cfgv-3.3.1-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/distlib-0.3.9-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py312h6ba4d93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/filelock-3.18.0-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/identify-2.6.9-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/identify-2.6.10-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.8-py312h2c4a281_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-devel-1.86.0-hf450f58_3.conda @@ -8087,92 +8317,95 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.10.1-py312h1f38498_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.10.1-py312hdbc7e53_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/nodeenv-1.9.1-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py312h50aef2c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - conda: https://conda.anaconda.org/conda-forge/noarch/platformdirs-4.3.7-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pre-commit-4.2.0-pyha770c72_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pycparser-2.22-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py312h998013c_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/rhash-1.4.5-h7ab814d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/scipy-1.15.2-py312h99a188d_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-75.8.2-pyhff2d567_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-79.0.1-pyhff2d567_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/sigtool-0.1.3-h44b9a77_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py312hea69d52_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ukkonen-1.0.1-py312h6142ec9_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py312hea69d52_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/virtualenv-20.30.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda @@ -8187,24 +8420,25 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cffi-1.17.1-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cfgv-3.3.1-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/distlib-0.3.9-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/filelock-3.18.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -8213,20 +8447,21 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/identify-2.6.9-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/identify-2.6.10-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -8237,31 +8472,33 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libiconv-1.18-h135ad9c_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.10.1-py312h2e8e312_0.conda @@ -8270,58 +8507,58 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/nodeenv-1.9.1-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - conda: https://conda.anaconda.org/conda-forge/noarch/platformdirs-4.3.7-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pre-commit-4.2.0-pyha770c72_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pycparser-2.22-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-75.8.2-pyhff2d567_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-79.0.1-pyhff2d567_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ukkonen-1.0.1-py312hd5eb7cc_5.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/noarch/virtualenv-20.30.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -8335,7 +8572,7 @@ environments: linux-64: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.43-h4bf12b8_4.conda @@ -8343,24 +8580,25 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cyrus-sasl-2.1.27-h54b06d7_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -8369,19 +8607,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gmp-6.3.0-hac33072_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda @@ -8390,7 +8629,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.86.0-h1a2810e_3.conda @@ -8401,17 +8640,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -8419,16 +8660,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libhiredis-1.0.2-h2cc385e_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -8436,22 +8677,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.10.1-py312h7900ff3_0.conda @@ -8460,54 +8701,53 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/mpfr-4.2.1-h90cbb55_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -8515,7 +8755,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -8539,44 +8779,46 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py312h55856b6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/gmp-6.3.0-hf036a51_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.8-py312h9275861_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-devel-1.86.0-h20888b2_3.conda @@ -8587,38 +8829,41 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.10.1-py312hb401068_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.10.1-py312h535dea3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda @@ -8626,28 +8871,30 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/mpfr-4.2.1-haed47dc_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py312hd9f36e3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py312h3520af0_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/rhash-1.4.5-ha44c9a9_0.conda @@ -8656,15 +8903,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py312h01d7ebd_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py312h01d7ebd_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda @@ -8677,44 +8924,46 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py312h6ba4d93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/gmp-6.3.0-h7bae524_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.8-py312h2c4a281_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-devel-1.86.0-hf450f58_3.conda @@ -8725,40 +8974,42 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.10.1-py312h1f38498_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.10.1-py312hdbc7e53_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda @@ -8766,29 +9017,30 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/mpfr-4.2.1-hb693164_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py312h50aef2c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py312h998013c_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/rhash-1.4.5-h7ab814d_0.conda @@ -8797,15 +9049,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py312hea69d52_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py312hea69d52_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda @@ -8819,21 +9071,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -8841,20 +9094,21 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/gmp-6.3.0-hfeafd45_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -8865,31 +9119,33 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libiconv-1.18-h135ad9c_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.10.1-py312h2e8e312_0.conda @@ -8899,51 +9155,51 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mpfr-4.2.1-hbc20e70_3.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -8957,7 +9213,7 @@ environments: linux-64: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/assimp-5.4.3-h8943939_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda @@ -8966,26 +9222,27 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/coal-python-3.0.0-py312he880d2f_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cyrus-sasl-2.1.27-h54b06d7_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -8994,19 +9251,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyhd3e5650_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda @@ -9015,7 +9273,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.86.0-h1a2810e_3.conda @@ -9026,18 +9284,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcoal-3.0.0-ha55d5d9_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -9045,16 +9305,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libhiredis-1.0.2-h2cc385e_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -9062,22 +9322,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.10.1-py312h7900ff3_0.conda @@ -9085,57 +9345,56 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/octomap-1.10.0-h84d6215_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-static-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tomlkit-0.13.2-pyha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -9143,7 +9402,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -9169,46 +9428,48 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/coal-python-3.0.0-py312hd8f6730_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py312h55856b6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyhd3e5650_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.8-py312h9275861_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-devel-1.86.0-h20888b2_3.conda @@ -9219,68 +9480,73 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcoal-3.0.0-h1752fee_5.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.10.1-py312hb401068_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.10.1-py312h535dea3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/octomap-1.10.0-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py312hd9f36e3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py312h3520af0_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-static-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda @@ -9290,16 +9556,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tomlkit-0.13.2-pyha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py312h01d7ebd_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py312h01d7ebd_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda @@ -9314,46 +9580,48 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/coal-python-3.0.0-py312hc43833c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py312h6ba4d93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyhd3e5650_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.8-py312h2c4a281_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-devel-1.86.0-hf450f58_3.conda @@ -9364,71 +9632,74 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcoal-3.0.0-hf5bebb4_5.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.10.1-py312h1f38498_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.10.1-py312hdbc7e53_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/octomap-1.10.0-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py312h50aef2c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py312h998013c_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-static-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda @@ -9438,16 +9709,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tomlkit-0.13.2-pyha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py312hea69d52_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py312hea69d52_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda @@ -9463,23 +9734,24 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda - conda: https://conda.anaconda.org/conda-forge/win-64/coal-python-3.0.0-py312h2716052_5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -9487,20 +9759,21 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyh5279557_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -9511,32 +9784,34 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcoal-3.0.0-hd2388e2_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libiconv-1.18-h135ad9c_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.10.1-py312h2e8e312_0.conda @@ -9545,53 +9820,53 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/octomap-1.10.0-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tomlkit-0.13.2-pyha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -9606,7 +9881,7 @@ environments: linux-64: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.43-h4bf12b8_4.conda @@ -9614,24 +9889,25 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cyrus-sasl-2.1.27-h54b06d7_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -9640,18 +9916,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda @@ -9660,7 +9937,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.86.0-h1a2810e_3.conda @@ -9671,17 +9948,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -9689,16 +9968,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libhiredis-1.0.2-h2cc385e_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -9706,22 +9985,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.10.1-py312h7900ff3_0.conda @@ -9729,54 +10008,53 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -9784,7 +10062,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -9808,43 +10086,45 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py312h55856b6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.8-py312h9275861_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-devel-1.86.0-h20888b2_3.conda @@ -9855,66 +10135,71 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.10.1-py312hb401068_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.10.1-py312h535dea3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py312hd9f36e3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py312h3520af0_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/rhash-1.4.5-ha44c9a9_0.conda @@ -9923,15 +10208,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py312h01d7ebd_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py312h01d7ebd_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda @@ -9944,43 +10229,45 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py312h6ba4d93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.8-py312h2c4a281_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-devel-1.86.0-hf450f58_3.conda @@ -9991,69 +10278,72 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.10.1-py312h1f38498_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.10.1-py312hdbc7e53_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py312h50aef2c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py312h998013c_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/rhash-1.4.5-h7ab814d_0.conda @@ -10062,15 +10352,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py312hea69d52_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py312hea69d52_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda @@ -10084,21 +10374,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -10106,19 +10397,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -10129,31 +10421,33 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libiconv-1.18-h135ad9c_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.10.1-py312h2e8e312_0.conda @@ -10162,51 +10456,51 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -10220,7 +10514,7 @@ environments: linux-64: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.43-h4bf12b8_4.conda @@ -10228,13 +10522,13 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/certifi-2025.1.31-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.0-py39h74842e3_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda @@ -10243,10 +10537,11 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py39h7ec7272_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -10255,16 +10550,17 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py39h9399b63_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py39h9399b63_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib-resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda @@ -10276,7 +10572,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.86.0-h1a2810e_3.conda @@ -10287,17 +10583,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -10305,16 +10603,16 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libhiredis-1.0.2-h2cc385e_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -10322,22 +10620,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.9.4-py39hf3d152e_0.conda @@ -10345,54 +10643,53 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.0.2-py39h9cb892a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py39h15c0740_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py39h0383914_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.9.21-h9c0c6dc_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py39h0383914_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.9.22-h85ef794_1_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.9-5_cp39.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.9-7_cp39.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py39h9399b63_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py39h4e4fb57_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py39h4e4fb57_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.13.1-py39haf93ffa_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py39h8cd3c5a_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py39h8cd3c5a_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -10400,7 +10697,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -10425,21 +10722,21 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda - conda: https://conda.anaconda.org/conda-forge/noarch/certifi-2025.1.31-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 @@ -10447,12 +10744,14 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py39h16cfbdb_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py39hd18e689_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py39hd18e689_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib-resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda @@ -10461,9 +10760,9 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.7-py39h0d8d0ca_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-devel-1.86.0-h20888b2_3.conda @@ -10474,66 +10773,71 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.9.4-py39h6e9494a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.9.4-py39hda06d36_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.0.2-py39h277832c_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py39h1fda9f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.9.21-h7fafba3_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.9.22-h55ef250_1_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.9-5_cp39.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.9-7_cp39.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py39hd18e689_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py39hf094b8e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py39hf094b8e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/rhash-1.4.5-ha44c9a9_0.conda @@ -10542,15 +10846,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py39h80efdc8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py39h80efdc8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda @@ -10564,21 +10868,21 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda - conda: https://conda.anaconda.org/conda-forge/noarch/certifi-2025.1.31-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 @@ -10586,12 +10890,14 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py39hc3d805d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py39hefdd603_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py39hefdd603_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib-resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda @@ -10600,9 +10906,9 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.7-py39h157d57c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-devel-1.86.0-hf450f58_3.conda @@ -10613,69 +10919,72 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.9.4-py39hdf13c20_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.9.4-py39h7251d6c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.0.2-py39h3ba1154_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py39hfea3036_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.9.21-h5f1b60f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.9.22-hdec7a8b_1_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.9-5_cp39.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.9-7_cp39.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py39hefdd603_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py39h80d5f2a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py39h80d5f2a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/rhash-1.4.5-h7ab814d_0.conda @@ -10684,15 +10993,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py39hf3bc14e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py39hf3bc14e_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda @@ -10707,11 +11016,11 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/certifi-2025.1.31-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.0-py39h2b77a98_2.conda @@ -10719,10 +11028,11 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py39h9d35a09_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -10730,10 +11040,11 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py39hf73967f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py39hf73967f_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib-resources-6.5.2-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/importlib_resources-6.5.2-pyhd8ed1ab_0.conda @@ -10743,7 +11054,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.7-py39h2b77a98_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -10754,31 +11065,33 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libiconv-1.18-h135ad9c_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.9.4-py39hcbf5309_0.conda @@ -10787,51 +11100,51 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-1.26.4-py39hddb5d58_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py39h73ef694_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py39h0285922_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.9.21-h37870fc_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py39h5cc861e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.9.22-hfdde91d_1_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.9-5_cp39.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.9-7_cp39.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py39hf73967f_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py39h03e5c00_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py39h03e5c00_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.13.1-py39h1a10956_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py39ha55e580_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py39ha55e580_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -10846,7 +11159,7 @@ environments: linux-64: - conda: https://conda.anaconda.org/conda-forge/linux-64/_libgcc_mutex-0.1-conda_forge.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/linux-64/_openmp_mutex-4.5-2_gnu.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/asttokens-3.0.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils-2.43-h4852527_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/binutils_impl_linux-64-2.43-h4bf12b8_4.conda @@ -10854,24 +11167,25 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-bin-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/bzip2-1.0.8-h4bc722e_7.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/console_bridge-1.0.2-h924138e_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cxx-compiler-1.9.0-h1a2810e_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/cyrus-sasl-2.1.27-h54b06d7_7.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/dbus-1.13.6-h5008d03_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/double-conversion-3.3.1-h5888daf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.1-np20py312hf621b31_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 @@ -10880,18 +11194,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/fontconfig-2.15.0-h7e30c49_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_impl_linux-64-13.3.0-h1e990d8_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/graphite2-1.3.13-h59595ed_1003.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx-13.3.0-h9576a4e_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_impl_linux-64-13.3.0-hae580e1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/icu-75.1-he02047a_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/kernel-headers_linux-64-3.10.0-he073ed8_18.conda @@ -10900,7 +11215,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/krb5-1.21.3-h659f571_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/lcms2-2.17-h717163a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-1.86.0-h6c02f8c_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libboost-devel-1.86.0-h1a2810e_3.conda @@ -10911,17 +11226,19 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlidec-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libbrotlienc-1.1.0-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcblas-3.9.0-31_he106b2a_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libcups-2.3.3-h4637d8d_4.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libedit-3.1.20250104-pl5321h7949ede_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libegl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libev-4.33-hd590300_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libexpat-2.7.0-h5888daf_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libffi-3.4.6-h2dba641_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libgcc-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-ng-14.2.0-h69a702a_2.conda @@ -10929,7 +11246,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran5-14.2.0-hf1ad2bd_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libglx-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libgomp-14.2.0-h767d61c_2.conda @@ -10937,10 +11254,10 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libiconv-1.18-h4ce23a2_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libignition-cmake2-2.17.2-hac33072_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libignition-math6-6.15.1-py312h76e88e7_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libnsl-2.0.1-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libntlm-1.8-hb9d3cd8_0.conda @@ -10948,23 +11265,23 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/libopengl-1.7.0-ha4b6fd6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpciaccess-0.18-hd590300_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libpng-1.6.47-h943b412_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsanitizer-13.3.0-he8ea267_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsdformat-9.8.0-hd8b6797_7.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsdformat-9.8.0-hd8b6797_8.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/libstdcxx-devel_linux-64-13.3.0-hc03c837_102.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-ng-14.2.0-h4852527_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libuv-1.50.0-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libwebp-base-1.5.0-h851e524_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcb-1.17.0-h8a09558_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxcrypt-4.4.36-hd590300_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/libzlib-1.3.1-hb9d3cd8_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/matplotlib-3.10.1-py312h7900ff3_0.conda @@ -10972,38 +11289,37 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openjpeg-2.5.3-h5fbd93e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/openldap-2.6.9-he970967_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pillow-11.1.0-py312h80c1187_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/rhash-1.4.5-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/scipy-1.15.2-py312ha707e6e_0.conda @@ -11011,17 +11327,17 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/sysroot_linux-64-2.17-h0157908_18.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml-2.6.2-h4bd325d_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/tornado-6.4.2-py312h66e93f0_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/unicodedata2-16.0.0-py312h66e93f0_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-0.4.1-hb711507_2.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-cursor-0.1.5-hb9d3cd8_0.conda @@ -11029,7 +11345,7 @@ environments: - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-keysyms-0.4.1-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-renderutil-0.3.10-hb711507_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xcb-util-wm-0.4.2-hb711507_0.conda - - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda + - conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libsm-1.2.6-he73a12e_0.conda - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libx11-1.8.12-h4f16b4b_0.conda @@ -11053,43 +11369,45 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/brotli-bin-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/bzip2-1.0.8-hfdf4475_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/c-compiler-1.9.0-h09a7c41_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/ccache-4.11.2-h30d2cd9_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_osx-64-18.1.8-h7e5c614_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/compiler-rt-18.1.8-h1020d70_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-64-18.1.8-hf2b8a54_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/console_bridge-1.0.2-hbb4e6a2_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/cxx-compiler-1.9.0-h20888b2_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigen-3.4.0-h1c7c39f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py312h55856b6_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/icu-75.1-h120a0e1_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/kiwisolver-1.4.8-py312h9275861_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/krb5-1.21.3-h37d8d59_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/lcms2-2.17-h72f5680_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libblas-3.9.0-31_h7f60823_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-1.86.0-hf0da243_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libboost-devel-1.86.0-h20888b2_3.conda @@ -11100,70 +11418,75 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlidec-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libbrotlienc-1.1.0-h00291cd_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcblas-3.9.0-31_hff6cab4_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libedit-3.1.20250104-pl5321ha958ccf_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libev-4.33-h10d778d_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libexpat-2.7.0-h240833e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libffi-3.4.6-h281671d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libhiredis-1.0.2-h2beb688_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/libiconv-1.18-h4b5e92a_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libignition-cmake2-2.17.2-hf036a51_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libignition-math6-6.15.1-py312hf1cefc6_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/liblapack-3.9.0-31_h236ab99_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libnghttp2-1.64.0-hc7306c3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libopenblas-0.3.29-openmp_hbf64a52_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libpng-1.6.47-h3c4a55f_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libsdformat-9.8.0-h5728b0d_7.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libsdformat-9.8.0-h5728b0d_8.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsodium-1.0.20-hfdf4475_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libuv-1.50.0-h4cb831e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libwebp-base-1.5.0-h6cf52b4_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libxcb-1.17.0-hf1f96e2_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/libzlib-1.3.1-hd23fc13_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-3.10.1-py312hb401068_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/matplotlib-base-3.10.1-py312h535dea3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-64/ncurses-6.5-h0622a9a_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/openjpeg-2.5.3-h7fd6d84_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pillow-11.1.0-py312hd9f36e3_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pkg-config-0.29.2-hf7e621a_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pthread-stubs-0.4-h00291cd_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/pyyaml-6.0.2-py312h3520af0_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/qhull-2020.2-h3c5361c_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/readline-8.2-h7cca4af_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/rhash-1.4.5-ha44c9a9_0.conda @@ -11173,15 +11496,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tapi-1300.6.5-h390ca13_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml-2.6.2-h65a07b1_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tk-8.6.13-h1abcd95_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/tornado-6.4.2-py312h01d7ebd_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/unicodedata2-16.0.0-py312h01d7ebd_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom_headers-1.1.2-h37c8870_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-64/xorg-libxau-1.0.12-h6e16a3a_0.conda @@ -11194,43 +11517,45 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/brotli-bin-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/bzip2-1.0.8-h99b78c6_7.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-compiler-1.9.0-hdf49b6b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ccache-4.11.2-h5a0df06_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_impl_osx-arm64-18.1.8-h2ae9ea5_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_impl_osx-arm64-18.1.8-h555f467_24.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx_osx-arm64-18.1.8-h07b0088_24.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/compiler-rt-18.1.8-h856b3c1_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/compiler-rt_osx-arm64-18.1.8-h832e737_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/console_bridge-1.0.2-h3e96240_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/cxx-compiler-1.9.0-hba80287_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigen-3.4.0-h1995070_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py312h6ba4d93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/icu-75.1-hfee45f7_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/kiwisolver-1.4.8-py312h2c4a281_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/krb5-1.21.3-h237132a_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lcms2-2.17-h7eeda09_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libblas-3.9.0-31_h10e41b3_openblas.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-1.86.0-hc9fb7c5_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libboost-devel-1.86.0-hf450f58_3.conda @@ -11241,73 +11566,76 @@ environments: - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlidec-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libbrotlienc-1.1.0-hd74edd7_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcblas-3.9.0-31_hb3479ef_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-devel-18.1.8-h6dc3340_8.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libedit-3.1.20250104-pl5321hafb1f1b_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libev-4.33-h93a5062_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libexpat-2.7.0-h286801f_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libffi-3.4.6-h1da3d7d_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libhiredis-1.0.2-hbec66e7_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libiconv-1.18-hfe07756_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libignition-cmake2-2.17.2-h00cdb27_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libignition-math6-6.15.1-py312he17536b_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblapack-3.9.0-31_hc9a63f6_openblas.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libnghttp2-1.64.0-h6d7220d_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libopenblas-0.3.29-openmp_hf332438_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libpng-1.6.47-h3783ad8_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsdformat-9.8.0-hc9d0b99_7.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsdformat-9.8.0-hb05c10c_8.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsodium-1.0.20-h99b78c6_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsqlite-3.49.1-h3f77e49_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libuv-1.50.0-h5505292_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libwebp-base-1.5.0-h2471fea_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxcb-1.17.0-hdb1d25a_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/libzlib-1.3.1-h8359307_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-3.10.1-py312h1f38498_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/matplotlib-base-3.10.1-py312hdbc7e53_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/matplotlib-inline-0.1.7-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ncurses-6.5-h5e97a16_3.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openjpeg-2.5.3-h8a3d83b_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pillow-11.1.0-py312h50aef2c_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pkg-config-0.29.2-hde07d2e_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pthread-stubs-0.4-hd74edd7_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ptyprocess-0.7.0-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyyaml-6.0.2-py312h998013c_2.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/qhull-2020.2-h420ef59_5.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/readline-8.2-h1d1bf99_2.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/rhash-1.4.5-h7ab814d_0.conda @@ -11317,15 +11645,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tapi-1300.6.5-h03f4b80_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml-2.6.2-h260d524_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tk-8.6.13-h5083fa2_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/tornado-6.4.2-py312hea69d52_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/unicodedata2-16.0.0-py312hea69d52_0.conda - - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda + - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom_headers-1.1.2-h7b3277c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/osx-arm64/xorg-libxau-1.0.12-h5505292_0.conda @@ -11339,21 +11667,22 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/brotli-bin-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/bzip2-1.0.8-h2466b09_7.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cairo-1.18.4-h5782bbf_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ccache-4.11.2-h65df0e8_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/colorama-0.4.6-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/console_bridge-1.0.2-h5362a0b_1.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/cxx-compiler-1.9.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/cycler-0.12.1-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/decorator-5.2.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/double-conversion-3.3.1-he0c23c2_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigen-3.4.0-h91493d7_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-dejavu-sans-mono-2.37-hab24e00_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-inconsolata-3.000-h77eed37_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/font-ttf-source-code-pro-2.038-h77eed37_0.tar.bz2 @@ -11361,19 +11690,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/fontconfig-2.15.0-h765892d_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-ecosystem-1-0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/fonts-conda-forge-1-0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/graphite2-1.3.13-h63175ca_1003.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/icu-75.1-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/intel-openmp-2024.2.1-h57928b3_1083.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/jedi-0.19.2-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/kiwisolver-1.4.8-py312hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/krb5-1.21.3-hdf4eb48_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/lcms2-2.17-hbcf6048_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 + - conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libblas-3.9.0-31_h641d27c_mkl.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-1.86.0-hb0986bb_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libboost-devel-1.86.0-h91493d7_3.conda @@ -11384,13 +11714,15 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlidec-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libbrotlienc-1.1.0-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libcblas-3.9.0-31_h5e41251_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libexpat-2.7.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libffi-3.4.6-h537db12_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgcc-14.2.0-h1383e82_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libgomp-14.2.0-h1383e82_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libhiredis-1.0.2-h0e60522_0.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/win-64/libhwloc-2.11.2-default_ha69328c_1001.conda @@ -11398,20 +11730,20 @@ environments: - conda: https://conda.anaconda.org/conda-forge/win-64/libignition-cmake2-2.17.2-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libignition-math6-6.15.1-py312h4fd29d7_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/liblapack-3.9.0-31_h1aa476e_mkl.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libsdformat-9.8.0-h9776664_7.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libsdformat-9.8.0-h9776664_8.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsodium-1.0.20-hc70643c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libsqlite-3.49.1-h67fdade_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libuv-1.50.0-h2466b09_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwebp-base-1.5.0-h3b0e114_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libwinpthread-12.0.0.r4.gg4f2fc60ca-h57928b3_9.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxcb-1.17.0-h0e4246c_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libxslt-1.1.39-h3df6e99_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/libzlib-1.3.1-h2466b09_2.conda - conda: https://conda.anaconda.org/conda-forge/win-64/matplotlib-3.10.1-py312h2e8e312_0.conda @@ -11420,53 +11752,53 @@ environments: - conda: https://conda.anaconda.org/conda-forge/noarch/meshcat-python-0.3.2-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/mkl-2024.2.2-h66d3029_15.conda - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/openjpeg-2.5.3-h4d64b90_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pickleshare-0.7.5-pyhd8ed1ab_1004.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pillow-11.1.0-py312h078707f_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pkg-config-0.29.2-h88c491f_1009.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pthread-stubs-0.4-h0e40799_1002.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pure_eval-0.2.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pybind11-abi-4-hd8ed1ab_3.tar.bz2 - conda: https://conda.anaconda.org/conda-forge/noarch/pygments-2.19.1-pyhd8ed1ab_0.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda - conda: https://conda.anaconda.org/conda-forge/win-64/pyyaml-6.0.2-py312h31fea79_2.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/qhull-2020.2-hc790b64_5.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/scipy-1.15.2-py312h451d5c4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/six-1.17.0-pyhd8ed1ab_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/stack_data-0.6.3-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tbb-2021.13.0-h62715c5_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml-2.6.2-h2d74725_2.tar.bz2 - - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tk-8.6.13-h5226925_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/tornado-6.4.2-py312h4389bb4_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/traitlets-5.14.3-pyhd8ed1ab_1.conda - - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda - conda: https://conda.anaconda.org/conda-forge/noarch/u-msgpack-python-2.8.0-pyhff2d567_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/ucrt-10.0.22621.0-h57928b3_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/unicodedata2-16.0.0-py312h4389bb4_0.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda + - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda - conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom_headers-1.1.2-hc790b64_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc-14.3-h2b53caa_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vc14_runtime-14.42.34438-hfd919c2_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda - conda: https://conda.anaconda.org/conda-forge/win-64/vs2019_win-64-19.29.30139-h7dcff83_26.conda - - conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda + - conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxau-1.0.12-h0e40799_0.conda - conda: https://conda.anaconda.org/conda-forge/win-64/xorg-libxdmcp-1.1.5-h0e40799_0.conda @@ -11517,16 +11849,16 @@ packages: license_family: BSD size: 7773 timestamp: 1717599240447 -- conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.13-hb9d3cd8_0.conda - sha256: f507b58f77eabc0cc133723cb7fc45c053d551f234df85e70fb3ede082b0cd53 - md5: ae1370588aa6a5157c34c73e9bbb36a0 +- conda: https://conda.anaconda.org/conda-forge/linux-64/alsa-lib-1.2.14-hb9d3cd8_0.conda + sha256: b9214bc17e89bf2b691fad50d952b7f029f6148f4ac4fe7c60c08f093efdf745 + md5: 76df83c2a9035c54df5d04ff81bcc02d depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 license: LGPL-2.1-or-later license_family: GPL - size: 560238 - timestamp: 1731489643707 + size: 566531 + timestamp: 1744668655747 - conda: https://conda.anaconda.org/conda-forge/linux-64/ampl-asl-1.0.0-h5888daf_2.conda sha256: c5c1057778bec78e07a4a8f122c3659767817fc0a9fa034724ff931ad90af57b md5: ef757816a8f0fee2650b6c7e19980b6b @@ -11708,9 +12040,9 @@ packages: license_family: GPL size: 35657 timestamp: 1740155500723 -- conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.0-pyhd8ed1ab_0.conda - sha256: a237952a471a43c35de73d0bb7371a93a149fe78db550376cbc7e0efda95b7b0 - md5: 2c34e2d15cb430b880cd24eedfa9901b +- conda: https://conda.anaconda.org/conda-forge/noarch/bokeh-3.7.2-pyhd8ed1ab_1.conda + sha256: 08242b239354ff98fdf6909d8b77bba96b450445c60c0f8e3aadfafeb8625ba0 + md5: 2f31c581e29bdb830ec77e112f3776ae depends: - contourpy >=1.2 - jinja2 >=2.9 @@ -11725,8 +12057,8 @@ packages: - xyzservices >=2021.09.1 license: BSD-3-Clause license_family: BSD - size: 4626784 - timestamp: 1741848638920 + size: 4965019 + timestamp: 1743516468561 - conda: https://conda.anaconda.org/conda-forge/linux-64/brotli-1.1.0-hb9d3cd8_2.conda sha256: fcb0b5b28ba7492093e54f3184435144e074dfceab27ac8e6a9457e736565b0b md5: 98514fe74548d768907ce7a13f680e8f @@ -11864,34 +12196,34 @@ packages: license_family: BSD size: 54927 timestamp: 1720974860185 -- conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.4-hb9d3cd8_0.conda - sha256: d4f28d87b6339b94f74762c0076e29c8ef8ddfff51a564a92da2843573c18320 - md5: e2775acf57efd5af15b8e3d1d74d72d3 +- conda: https://conda.anaconda.org/conda-forge/linux-64/c-ares-1.34.5-hb9d3cd8_0.conda + sha256: f8003bef369f57396593ccd03d08a8e21966157269426f71e943f96e4b579aeb + md5: f7f0d6cc2dc986d42ac2689ec88192be depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 license: MIT license_family: MIT - size: 206085 - timestamp: 1734208189009 -- conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.4-hf13058a_0.conda - sha256: 8dcc1628d34fe7d759f3a7dee52e09c5162a3f9669dddd6100bff965450f4a0a - md5: 133255af67aaf1e0c0468cc753fd800b + size: 206884 + timestamp: 1744127994291 +- conda: https://conda.anaconda.org/conda-forge/osx-64/c-ares-1.34.5-hf13058a_0.conda + sha256: b37f5dacfe1c59e0a207c1d65489b760dff9ddb97b8df7126ceda01692ba6e97 + md5: eafe5d9f1a8c514afe41e6e833f66dfd depends: - __osx >=10.13 license: MIT license_family: MIT - size: 184455 - timestamp: 1734208242547 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.4-h5505292_0.conda - sha256: 09c0c8476e50b2955f474a4a1c17c4c047dd52993b5366b6ea8e968e583b921f - md5: c1c999a38a4303b29d75c636eaa13cf9 + size: 184824 + timestamp: 1744128064511 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/c-ares-1.34.5-h5505292_0.conda + sha256: b4bb55d0806e41ffef94d0e3f3c97531f322b3cb0ca1f7cdf8e47f62538b7a2b + md5: f8cd1beb98240c7edb1a95883360ccfa depends: - __osx >=11.0 license: MIT license_family: MIT - size: 179496 - timestamp: 1734208291879 + size: 179696 + timestamp: 1744128058734 - conda: https://conda.anaconda.org/conda-forge/linux-64/c-compiler-1.9.0-h2b85faf_0.conda sha256: 1e4b86b0f3d4ce9f3787b8f62e9f2c5683287f19593131640eed01cbdad38168 md5: 3cb814f83f1f71ac1985013697f80cc1 @@ -11927,30 +12259,22 @@ packages: license_family: BSD size: 6244 timestamp: 1736437056672 -- conda: https://conda.anaconda.org/conda-forge/linux-64/ca-certificates-2025.1.31-hbcca054_0.conda - sha256: bf832198976d559ab44d6cdb315642655547e26d826e34da67cbee6624cda189 - md5: 19f3a56f68d2fd06c516076bff482c52 - license: ISC - size: 158144 - timestamp: 1738298224464 -- conda: https://conda.anaconda.org/conda-forge/osx-64/ca-certificates-2025.1.31-h8857fd0_0.conda - sha256: 42e911ee2d8808eacedbec46d99b03200a6138b8e8a120bd8acabe1cac41c63b - md5: 3418b6c8cac3e71c0bc089fc5ea53042 - license: ISC - size: 158408 - timestamp: 1738298385933 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/ca-certificates-2025.1.31-hf0a4a13_0.conda - sha256: 7e12816618173fe70f5c638b72adf4bfd4ddabf27794369bb17871c5bb75b9f9 - md5: 3569d6a9141adc64d2fe4797f3289e06 +- conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-h4c7d964_0.conda + sha256: 1454f3f53a3b828d3cb68a3440cb0fa9f1cc0e3c8c26e9e023773dc19d88cc06 + md5: 23c7fd5062b48d8294fc7f61bf157fba + depends: + - __win license: ISC - size: 158425 - timestamp: 1738298167688 -- conda: https://conda.anaconda.org/conda-forge/win-64/ca-certificates-2025.1.31-h56e8100_0.conda - sha256: 1bedccdf25a3bd782d6b0e57ddd97cdcda5501716009f2de4479a779221df155 - md5: 5304a31607974dfc2110dfbb662ed092 + size: 152945 + timestamp: 1745653639656 +- conda: https://conda.anaconda.org/conda-forge/noarch/ca-certificates-2025.4.26-hbd8a1cb_0.conda + sha256: 2a70ed95ace8a3f8a29e6cd1476a943df294a7111dfb3e152e3478c4c889b7ac + md5: 95db94f75ba080a22eb623590993167b + depends: + - __unix license: ISC - size: 158690 - timestamp: 1738298232550 + size: 152283 + timestamp: 1745653616541 - conda: https://conda.anaconda.org/conda-forge/linux-64/cairo-1.18.4-h3394656_0.conda sha256: 3bd6a391ad60e471de76c0e9db34986c4b5058587fbf2efa5a7f54645e28c2c7 md5: 09262e66b19567aff4f592fb53b28760 @@ -11995,9 +12319,9 @@ packages: license: LGPL-2.1-only or MPL-1.1 size: 1524254 timestamp: 1741555212198 -- conda: https://conda.anaconda.org/conda-forge/linux-64/casadi-3.7.0-py312h09e09b4_0.conda - sha256: d78f6835d45da6188550ffd70796c2ea0399ad1b12057b7efa027094aaa48749 - md5: 5a485b1297098eacacecc12967fcce29 +- conda: https://conda.anaconda.org/conda-forge/linux-64/casadi-3.7.0-py312h399c79b_2.conda + sha256: f869bd69a169528f4989910b3ca13db4b18d1ef1ad355d26851f858f2c7aee22 + md5: 37d58c37ca159b02e02a4d0054a9052d depends: - __glibc >=2.17,<3.0.a0 - ipopt >=3.14.17,<3.14.18.0a0 @@ -12006,21 +12330,20 @@ packages: - libcblas >=3.9.0,<4.0a0 - libfatrop >=0.0.4,<0.0.5.0a0 - libgcc >=13 - - libgfortran - - libgfortran5 >=13.3.0 - liblapack >=3.9.0,<4.0a0 - libosqp >=0.6.3,<0.6.4.0a0 - libstdcxx >=13 - numpy >=1.19,<3 - python >=3.12,<3.13.0a0 - python_abi 3.12.* *_cp312 - - tinyxml2 >=10.0.0,<10.1.0a0 + - tinyxml2 >=11.0.0,<11.1.0a0 license: LGPL-3.0-or-later - size: 6180668 - timestamp: 1743452997222 -- conda: https://conda.anaconda.org/conda-forge/linux-64/casadi-3.7.0-py39hc9664a4_0.conda - sha256: 80690149cc86af4aaf6d826797111d44e793517ead510cdea4f759b7b517a0ce - md5: 74dc1097925eb2eb5b8847bc6f0dd198 + license_family: LGPL + size: 6293201 + timestamp: 1745474205066 +- conda: https://conda.anaconda.org/conda-forge/linux-64/casadi-3.7.0-py39h19ee5b0_2.conda + sha256: a55cabdadebb3bcef9748514a88c42e0b5c67fbe26abc5b67908441a81fbc742 + md5: 63b48a6b5415bc8032f06bfc677cfba7 depends: - __glibc >=2.17,<3.0.a0 - ipopt >=3.14.17,<3.14.18.0a0 @@ -12029,21 +12352,20 @@ packages: - libcblas >=3.9.0,<4.0a0 - libfatrop >=0.0.4,<0.0.5.0a0 - libgcc >=13 - - libgfortran - - libgfortran5 >=13.3.0 - liblapack >=3.9.0,<4.0a0 - libosqp >=0.6.3,<0.6.4.0a0 - libstdcxx >=13 - numpy >=1.19,<3 - python >=3.9,<3.10.0a0 - python_abi 3.9.* *_cp39 - - tinyxml2 >=10.0.0,<10.1.0a0 + - tinyxml2 >=11.0.0,<11.1.0a0 license: LGPL-3.0-or-later - size: 6275745 - timestamp: 1743453176569 -- conda: https://conda.anaconda.org/conda-forge/osx-64/casadi-3.7.0-py312hc4f9d4a_0.conda - sha256: fd87b4bb48401c60e96993e87618783f1a143c583eee1f8a3524f447cb0b1e0a - md5: e09e577f35b29279414c32bc383259d4 + license_family: LGPL + size: 6268443 + timestamp: 1745474549899 +- conda: https://conda.anaconda.org/conda-forge/osx-64/casadi-3.7.0-py312hd531e53_2.conda + sha256: bb3e1ed64174cd6be564c412065e8d6f931b765c85c03739ce5f532f26d5dc47 + md5: 8ff23ef16bf8aab560823af891e08b46 depends: - __osx >=10.13 - ipopt >=3.14.17,<3.14.18.0a0 @@ -12052,21 +12374,19 @@ packages: - libcblas >=3.9.0,<4.0a0 - libcxx >=18 - libfatrop >=0.0.4,<0.0.5.0a0 - - libgfortran 5.* - - libgfortran5 >=13.3.0 - - libgfortran5 >=14.2.0 - liblapack >=3.9.0,<4.0a0 - libosqp >=0.6.3,<0.6.4.0a0 - numpy >=1.19,<3 - python >=3.12,<3.13.0a0 - python_abi 3.12.* *_cp312 - - tinyxml2 >=10.0.0,<10.1.0a0 + - tinyxml2 >=11.0.0,<11.1.0a0 license: LGPL-3.0-or-later - size: 5154521 - timestamp: 1743452922323 -- conda: https://conda.anaconda.org/conda-forge/osx-64/casadi-3.7.0-py39h0ba0775_0.conda - sha256: 51e380894d288c6aeae49e4fc44e4c0bb7ce02efd73b7685c0d64384abd264ae - md5: 32da9a6d0add9983a970e5057102e12a + license_family: LGPL + size: 5279420 + timestamp: 1745474197455 +- conda: https://conda.anaconda.org/conda-forge/osx-64/casadi-3.7.0-py39h6d613ad_2.conda + sha256: 6bea0a1b381ea8ab3dac291d18055726d98944033e55e734b6e88c5222f0e043 + md5: 0fae5d76d05db587d6f28afb1f4fa7b5 depends: - __osx >=10.13 - ipopt >=3.14.17,<3.14.18.0a0 @@ -12075,21 +12395,19 @@ packages: - libcblas >=3.9.0,<4.0a0 - libcxx >=18 - libfatrop >=0.0.4,<0.0.5.0a0 - - libgfortran 5.* - - libgfortran5 >=13.3.0 - - libgfortran5 >=14.2.0 - liblapack >=3.9.0,<4.0a0 - libosqp >=0.6.3,<0.6.4.0a0 - numpy >=1.19,<3 - python >=3.9,<3.10.0a0 - python_abi 3.9.* *_cp39 - - tinyxml2 >=10.0.0,<10.1.0a0 + - tinyxml2 >=11.0.0,<11.1.0a0 license: LGPL-3.0-or-later - size: 5293368 - timestamp: 1743453213414 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/casadi-3.7.0-py312h2a9d200_0.conda - sha256: 1d14ee0851074b96a8b90f14510b5a3665349ac554ae59710ad6d3768a8be1d0 - md5: 1723417d47167789a5cd2109dd7e38f7 + license_family: LGPL + size: 5189111 + timestamp: 1745474378882 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/casadi-3.7.0-py312h74b190f_2.conda + sha256: ae008bb0cd026b64d6cbcd7726fbbbb98904bd868fca3b7d53f258f0c80c27e7 + md5: 8431af5d6849a519573d8ed6ffaa8e28 depends: - __osx >=11.0 - ipopt >=3.14.17,<3.14.18.0a0 @@ -12098,22 +12416,20 @@ packages: - libcblas >=3.9.0,<4.0a0 - libcxx >=18 - libfatrop >=0.0.4,<0.0.5.0a0 - - libgfortran 5.* - - libgfortran5 >=13.3.0 - - libgfortran5 >=14.2.0 - liblapack >=3.9.0,<4.0a0 - libosqp >=0.6.3,<0.6.4.0a0 - numpy >=1.19,<3 - python >=3.12,<3.13.0a0 - python >=3.12,<3.13.0a0 *_cpython - python_abi 3.12.* *_cp312 - - tinyxml2 >=10.0.0,<10.1.0a0 + - tinyxml2 >=11.0.0,<11.1.0a0 license: LGPL-3.0-or-later - size: 4785633 - timestamp: 1743453398475 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/casadi-3.7.0-py39hc8fcb4c_0.conda - sha256: 5e1f9e76c01e6b48156526d52ff2570c9a04380f862a008024e5d6e9866306f7 - md5: 86b36d8d56ffa34bd504531c6b14c579 + license_family: LGPL + size: 4681272 + timestamp: 1745474347317 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/casadi-3.7.0-py39hb80b00f_2.conda + sha256: c45bdfa3460c3bf8235912446be99bb82fa6caee3ebc86af71c9db88006f67a6 + md5: 99d25883a79b0916877aea756fb7a1c6 depends: - __osx >=11.0 - ipopt >=3.14.17,<3.14.18.0a0 @@ -12122,22 +12438,20 @@ packages: - libcblas >=3.9.0,<4.0a0 - libcxx >=18 - libfatrop >=0.0.4,<0.0.5.0a0 - - libgfortran 5.* - - libgfortran5 >=13.3.0 - - libgfortran5 >=14.2.0 - liblapack >=3.9.0,<4.0a0 - libosqp >=0.6.3,<0.6.4.0a0 - numpy >=1.19,<3 - python >=3.9,<3.10.0a0 - python >=3.9,<3.10.0a0 *_cpython - python_abi 3.9.* *_cp39 - - tinyxml2 >=10.0.0,<10.1.0a0 + - tinyxml2 >=11.0.0,<11.1.0a0 license: LGPL-3.0-or-later - size: 4813746 - timestamp: 1743453552449 -- conda: https://conda.anaconda.org/conda-forge/win-64/casadi-3.7.0-py312hef5f0c3_0.conda - sha256: acc9bf346195e7eb5053671eacb64bc56c6c9090f2e361b52a98605e47131b94 - md5: 4d6e5224c3102d1368d5f7f44e206278 + license_family: LGPL + size: 4779429 + timestamp: 1745474241058 +- conda: https://conda.anaconda.org/conda-forge/win-64/casadi-3.7.0-py312h226cf95_2.conda + sha256: 8a502c8a3f31b40999a0a3586a314d4af87b4084a3b73be8a2f02f43a7eb1406 + md5: 224198eaf1ee2cf06e55a5c09eecd688 depends: - ipopt >=3.14.17,<3.14.18.0a0 - libblas >=3.9.0,<4.0a0 @@ -12147,16 +12461,17 @@ packages: - numpy >=1.19,<3 - python >=3.12,<3.13.0a0 - python_abi 3.12.* *_cp312 - - tinyxml2 >=10.0.0,<10.1.0a0 + - tinyxml2 >=11.0.0,<11.1.0a0 - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: LGPL-3.0-or-later - size: 5629942 - timestamp: 1743454367967 -- conda: https://conda.anaconda.org/conda-forge/win-64/casadi-3.7.0-py39h078d07b_0.conda - sha256: 94b6da1e2039d4a4f34c2e19cd64b34fd9d7ef088c3707dd902e497589de482d - md5: 6cb8a2cef5a72bc4a06ed2933c8aa77e + license_family: LGPL + size: 5579303 + timestamp: 1745474974843 +- conda: https://conda.anaconda.org/conda-forge/win-64/casadi-3.7.0-py39h70862e4_2.conda + sha256: 93e2721880db96d6a5f6ff12f82d41d77b251daf6a694fe6dec7da85dc9ab446 + md5: 9e0082e63c7c4d9f831babee68ae8dc2 depends: - ipopt >=3.14.17,<3.14.18.0a0 - libblas >=3.9.0,<4.0a0 @@ -12166,13 +12481,14 @@ packages: - numpy >=1.19,<3 - python >=3.9,<3.10.0a0 - python_abi 3.9.* *_cp39 - - tinyxml2 >=10.0.0,<10.1.0a0 + - tinyxml2 >=11.0.0,<11.1.0a0 - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: LGPL-3.0-or-later - size: 5560398 - timestamp: 1743453773846 + license_family: LGPL + size: 5555271 + timestamp: 1745475280339 - conda: https://conda.anaconda.org/conda-forge/linux-64/ccache-4.11.2-hd714d17_0.conda sha256: 360f578a85e049dac2211c0b719860e6df69fb1748a979542cc33e1697f89c90 md5: 35ae7ce74089ab05fdb1cb9746c0fbe4 @@ -12227,31 +12543,31 @@ packages: license_family: GPL size: 663504 timestamp: 1742708103663 -- conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_4.conda - sha256: 2113fe10f67ddaf2b34522c755924f0f89a4c9507604baddb5a3091b8fac03dc - md5: df1dfc9721444ad44d0916d9454e55f3 +- conda: https://conda.anaconda.org/conda-forge/osx-64/cctools-1010.6-ha66f10e_6.conda + sha256: c716942cddaaf6afb618da32020c5a8ab2aec547bd3f0766c40b95680b998f05 + md5: a126dcde2752751ac781b67238f7fac4 depends: - - cctools_osx-64 1010.6 hd19c6af_4 - - ld64 951.9 h4e51db5_4 + - cctools_osx-64 1010.6 hd19c6af_6 + - ld64 951.9 h4e51db5_6 - libllvm18 >=18.1.8,<18.2.0a0 license: APSL-2.0 license_family: Other - size: 21571 - timestamp: 1742512411843 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_4.conda - sha256: 02f7ab57ddf0bfe291dac3a3e59ab7c65a3ae0a3a086440a7e2666b0e862b922 - md5: 2fecdd2278ff651073e9373f32151e41 - depends: - - cctools_osx-arm64 1010.6 h3b4f5d3_4 - - ld64 951.9 h4c6efb1_4 + size: 22135 + timestamp: 1743872208832 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools-1010.6-hb4fb6a3_6.conda + sha256: 393fc3bf21b0187384e652aa4fab184d633e57e3e63f2b10f16a3d5f7bb0717b + md5: e0ba8df6997102eb4d367e3e70f90778 + depends: + - cctools_osx-arm64 1010.6 h3b4f5d3_6 + - ld64 951.9 h4c6efb1_6 - libllvm18 >=18.1.8,<18.2.0a0 license: APSL-2.0 license_family: Other - size: 21539 - timestamp: 1742512631773 -- conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_4.conda - sha256: 4ca98572322a0dcc227b499fec46e37a46f81dded92a7d299ac3ec6cc3a4beed - md5: 1ddf5221f68b7df9e22795cdb01933e2 + size: 22254 + timestamp: 1743872374133 +- conda: https://conda.anaconda.org/conda-forge/osx-64/cctools_osx-64-1010.6-hd19c6af_6.conda + sha256: 7b2b765be41040c749d10ba848c4afbaae89a9ebb168bbf809c8133486f39bcb + md5: 4694e9e497454a8ce5b9fb61e50d9c5d depends: - __osx >=10.13 - ld64_osx-64 >=951.9,<951.10.0a0 @@ -12261,16 +12577,16 @@ packages: - llvm-tools 18.1.* - sigtool constrains: + - clang 18.1.* - cctools 1010.6.* - ld64 951.9.* - - clang 18.1.* license: APSL-2.0 license_family: Other - size: 1119334 - timestamp: 1742512370787 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_4.conda - sha256: e223912a174344cddfe7ea8a598d091b18e5defbc63c2037c3e42165654b09dc - md5: 57ce83eec79eff26016ae3e1af07e431 + size: 1119992 + timestamp: 1743872180962 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/cctools_osx-arm64-1010.6-h3b4f5d3_6.conda + sha256: 6e9463499dddad0ee61c999031c84bd1b8233676bcd220aece1b754667c680d7 + md5: b876da50fbe92a19737933c7aa92fb02 depends: - __osx >=11.0 - ld64_osx-arm64 >=951.9,<951.10.0a0 @@ -12280,13 +12596,13 @@ packages: - llvm-tools 18.1.* - sigtool constrains: - - clang 18.1.* - cctools 1010.6.* - ld64 951.9.* + - clang 18.1.* license: APSL-2.0 license_family: Other - size: 1104264 - timestamp: 1742512583707 + size: 1103413 + timestamp: 1743872332962 - conda: https://conda.anaconda.org/conda-forge/noarch/certifi-2025.1.31-pyhd8ed1ab_0.conda sha256: 42a78446da06a2568cb13e69be3355169fbd0ea424b00fc80b7d840f5baaacf3 md5: c207fa5ac7ea99b149344385a9c0880d @@ -12359,73 +12675,73 @@ packages: license_family: MIT size: 12973 timestamp: 1734267180483 -- conda: https://conda.anaconda.org/conda-forge/linux-64/clang-20.1.1-default_h9e3a008_0.conda - sha256: 0bbcc6eb77f2597af1b2d0ffc6f7b48db09f1b716c769af350388235c2614fab - md5: 88ad01cded2b46ab4a77aafeac17cb3e +- conda: https://conda.anaconda.org/conda-forge/linux-64/clang-20.1.3-default_hfa515fb_0.conda + sha256: a2e4817d9c4d376b5f2c2a78c369332c1043ee6f39ced7e4d544ebd92efd35ec + md5: 43ed7368180467a95d6c534ab8ae487b depends: - binutils_impl_linux-64 - - clang-20 20.1.1 default_hb5137d0_0 + - clang-20 20.1.3 default_h1df26ce_0 - libgcc-devel_linux-64 - sysroot_linux-64 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 23982 - timestamp: 1742506317665 -- conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_8.conda - sha256: ff3ec1361dadb7d47ae0e1276e861e48f1a3e5a23c11eb832915cbada3da0861 - md5: 0a7a5caf8e1f0b52b96104bbd2ee677f + size: 24112 + timestamp: 1744876687081 +- conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18.1.8-default_h576c50e_9.conda + sha256: 0e7e33950d9dc2a01a14e3830bfa37575642f338d09526c5b3b78af381311352 + md5: 266e7e8fa2190df09e6f236571c91511 depends: - - clang-18 18.1.8 default_h3571c67_8 + - clang-18 18.1.8 default_h3571c67_9 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 76209 - timestamp: 1742267099930 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_8.conda - sha256: 42965afb7a7a2af44b164d079b256127a9d9580e756cce08f8a00836d1e82952 - md5: 2c01e8675aa80bf6a25494b76005ffdc + size: 76304 + timestamp: 1744061943238 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18.1.8-default_h474c9e2_9.conda + sha256: 2c800b88d50cc4c83a24e0ad92db1cc617f29f299ef2b090c1bce8b0ee4d78b1 + md5: ac42b10184bf26c80a3de9f049cf183e depends: - - clang-18 18.1.8 default_hf90f093_8 + - clang-18 18.1.8 default_hf90f093_9 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 76217 - timestamp: 1742266196177 -- conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_8.conda - sha256: 25f572a069d9ff1d6306d6d29a2b42d0395017cc36e9df581c98d6ad2c5876aa - md5: c40e72e808995df189d70d9a438d77ac + size: 76181 + timestamp: 1744062704325 +- conda: https://conda.anaconda.org/conda-forge/osx-64/clang-18-18.1.8-default_h3571c67_9.conda + sha256: 6033b98373bbf8b8748eee1e6ac6fb57ff3ff20dc49c93c11e3a5fc6f1bba224 + md5: e29d8d2866f15f3b167938cc0e775b2f depends: - __osx >=10.13 - - libclang-cpp18.1 18.1.8 default_h3571c67_8 + - libclang-cpp18.1 18.1.8 default_h3571c67_9 - libcxx >=18.1.8 - libllvm18 >=18.1.8,<18.2.0a0 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 815278 - timestamp: 1742266953803 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_8.conda - sha256: 984da230a6197273060fcdb4c97e7d2430f8393547a478ac4e8b32d33a64c89c - md5: 8d92b636afa379ae7845575d87ae1ad0 + size: 811182 + timestamp: 1744061841745 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/clang-18-18.1.8-default_hf90f093_9.conda + sha256: 3b3e0ab23f4b473e89f756c65208f5a3cfb0ddc52114dbc6cc25a25eb238618a + md5: d6e73d7ad81e92ffe60f69eee87e0bca depends: - __osx >=11.0 - - libclang-cpp18.1 18.1.8 default_hf90f093_8 + - libclang-cpp18.1 18.1.8 default_hf90f093_9 - libcxx >=18.1.8 - libllvm18 >=18.1.8,<18.2.0a0 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 811547 - timestamp: 1742266095150 -- conda: https://conda.anaconda.org/conda-forge/linux-64/clang-20-20.1.1-default_hb5137d0_0.conda - sha256: d293037dcd8377011dad0cc822e88335d0a10f0d504e4649e57dbdb72690809f - md5: cef16ac880dc2fa050bdfb15fe1d2a8b + size: 808948 + timestamp: 1744062517394 +- conda: https://conda.anaconda.org/conda-forge/linux-64/clang-20-20.1.3-default_h1df26ce_0.conda + sha256: 137f36a2a94c57d8214819c2dcf5517f47f3aa47aae3a643bd7d103616fccf21 + md5: c9e6c82919e293156fddda8c6ca3504f depends: - __glibc >=2.17,<3.0.a0 - - libclang-cpp20.1 20.1.1 default_hb5137d0_0 + - libclang-cpp20.1 20.1.3 default_h1df26ce_0 - libgcc >=13 - - libllvm20 >=20.1.1,<20.2.0a0 + - libllvm20 >=20.1.3,<20.2.0a0 - libstdcxx >=13 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 820809 - timestamp: 1742506260799 + size: 808254 + timestamp: 1744876631600 - conda: https://conda.anaconda.org/conda-forge/osx-64/clang_impl_osx-64-18.1.8-h6a44ed1_24.conda sha256: 27b5f4400cee37eea37160d0f65061804d34e403ed3d43a5e8fcad585b6efc6e md5: 5224d53acc2604a86d790f664d7fcbc4 @@ -12470,36 +12786,36 @@ packages: license_family: BSD size: 21584 timestamp: 1742540373638 -- conda: https://conda.anaconda.org/conda-forge/linux-64/clangxx-20.1.1-default_ha78316a_0.conda - sha256: 734aba45ca6f2b9f9211fddd01d1c35e13f5d29058631aff0269596b64fa8901 - md5: 985e5315109da087e043b2fb1ea148bd +- conda: https://conda.anaconda.org/conda-forge/linux-64/clangxx-20.1.3-default_h0982aa1_0.conda + sha256: 554c033776e0b7cc3d8431ce15f0911d6ce38ed9f0988e9f1f02c8d2a84cebb2 + md5: 38395061a6096c6ce75eee4b448a88d0 depends: - - clang 20.1.1 default_h9e3a008_0 + - clang 20.1.3 default_hfa515fb_0 - libstdcxx-devel_linux-64 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 24029 - timestamp: 1742506328762 -- conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_8.conda - sha256: a99947172ab2a3bf244ea1c024e7e3a8e1aabb8921cc5e648004f246f5df87c7 - md5: 06a53a18fa886ec96f519b9022eeb449 + size: 24215 + timestamp: 1744876698295 +- conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx-18.1.8-default_heb2e8d1_9.conda + sha256: f09da8c88a60115821bb6dded23116bd900d42188154012196068251fb28c344 + md5: 4ba6bd39da787a7306eba77555e86dd3 depends: - - clang 18.1.8 default_h576c50e_8 + - clang 18.1.8 default_h576c50e_9 - libcxx-devel 18.1.8.* license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 76312 - timestamp: 1742267130243 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_8.conda - sha256: c002e7ff1511a0278c693fb05d8c6f729fda4e76b65faef91bb6721b93b24d4b - md5: 6f88136be9a2b5e5e6e7bb69c35d8180 + size: 76375 + timestamp: 1744061961403 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/clangxx-18.1.8-default_h1ffe849_9.conda + sha256: 445427ded667d57c8e5dc9484e66b21a2b3f92c79ff4e29a69a91d6ff789171f + md5: e0c5555dcbcd2f588f7926554fd14a0c depends: - - clang 18.1.8 default_h474c9e2_8 + - clang 18.1.8 default_h474c9e2_9 - libcxx-devel 18.1.8.* license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 76359 - timestamp: 1742266208123 + size: 76287 + timestamp: 1744062725915 - conda: https://conda.anaconda.org/conda-forge/osx-64/clangxx_impl_osx-64-18.1.8-h4b7810f_24.conda sha256: 1735b123cebcffaa54699fcae4295c0bd308c9bf27df3924cab78f3b3d1a9890 md5: 9d27517a71e7268679f1c47e7f34e47b @@ -12544,16 +12860,16 @@ packages: license_family: BSD size: 19975 timestamp: 1742540410050 -- conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.0-h74e3db0_0.conda - sha256: 1178601b5969001e1797fdc8564a1bcb2d448a45ad20dacb233faaaeda6f794c - md5: b8f039327d73a96c66c0e9c56d8c1cd8 +- conda: https://conda.anaconda.org/conda-forge/linux-64/cmake-4.0.1-h74e3db0_0.conda + sha256: 7b4d6adf1b7336199c9f473a4f1b0dc0bb519cf6439bc822afb7f3f9eab7281e + md5: 01e7e2cf3ebc8e6609d509f520151ca8 depends: - __glibc >=2.17,<3.0.a0 - bzip2 >=1.0.8,<2.0a0 - - libcurl >=8.12.1,<9.0a0 - - libexpat >=2.6.4,<3.0a0 + - libcurl >=8.13.0,<9.0a0 + - libexpat >=2.7.0,<3.0a0 - libgcc >=13 - - liblzma >=5.6.4,<6.0a0 + - liblzma >=5.8.1,<6.0a0 - libstdcxx >=13 - libuv >=1.50.0,<2.0a0 - libzlib >=1.3.1,<2.0a0 @@ -12562,18 +12878,18 @@ packages: - zstd >=1.5.7,<1.6.0a0 license: BSD-3-Clause license_family: BSD - size: 20440638 - timestamp: 1743111798861 -- conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.0-h477996e_0.conda - sha256: 94e65e5fbc6cf2946ded09ae37b267cea4ffaaf2f3a37dba48e0dec1040e42df - md5: 7f0957e75034c42c20fd138e4a327691 + size: 20412445 + timestamp: 1744313604462 +- conda: https://conda.anaconda.org/conda-forge/osx-64/cmake-4.0.1-h477996e_0.conda + sha256: bfe566316ecfe598f91620b3fdbd7c5d16de5b97575c433badb5afb306a1672d + md5: c9d55d7eca21660ac2e4d0c9a487132a depends: - __osx >=10.13 - bzip2 >=1.0.8,<2.0a0 - - libcurl >=8.12.1,<9.0a0 + - libcurl >=8.13.0,<9.0a0 - libcxx >=18 - - libexpat >=2.6.4,<3.0a0 - - liblzma >=5.6.4,<6.0a0 + - libexpat >=2.7.0,<3.0a0 + - liblzma >=5.8.1,<6.0a0 - libuv >=1.50.0,<2.0a0 - libzlib >=1.3.1,<2.0a0 - ncurses >=6.5,<7.0a0 @@ -12581,18 +12897,18 @@ packages: - zstd >=1.5.7,<1.6.0a0 license: BSD-3-Clause license_family: BSD - size: 17720983 - timestamp: 1743113275115 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.0-ha25475f_0.conda - sha256: 5b1b1d5f3db73d9b82f1580423c53448aa74e27ba6a6e05a49bc0a1b4afa6a0b - md5: e967b04fabfca84c75b8e15435d3ec59 + size: 17733384 + timestamp: 1744314025053 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/cmake-4.0.1-ha25475f_0.conda + sha256: ec494fd064aad391d2e3ab78f5958311ff141dc40a43aff0dbf3478d98b781b9 + md5: e5f1e85d51cd119bcf7d870388b4c918 depends: - __osx >=11.0 - bzip2 >=1.0.8,<2.0a0 - - libcurl >=8.12.1,<9.0a0 + - libcurl >=8.13.0,<9.0a0 - libcxx >=18 - - libexpat >=2.6.4,<3.0a0 - - liblzma >=5.6.4,<6.0a0 + - libexpat >=2.7.0,<3.0a0 + - liblzma >=5.8.1,<6.0a0 - libuv >=1.50.0,<2.0a0 - libzlib >=1.3.1,<2.0a0 - ncurses >=6.5,<7.0a0 @@ -12600,16 +12916,16 @@ packages: - zstd >=1.5.7,<1.6.0a0 license: BSD-3-Clause license_family: BSD - size: 16604612 - timestamp: 1743113438157 -- conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.0-hff78f93_0.conda - sha256: bf7f60442afdba22e318d66bfe0742b98c645528d99dc64721b07cd0d89afc0a - md5: 29b9dec93f7a47ee0de7598d5bd39169 + size: 16627400 + timestamp: 1744313747348 +- conda: https://conda.anaconda.org/conda-forge/win-64/cmake-4.0.1-hff78f93_0.conda + sha256: 60c2a4bd329503b6961384df381357af6a9a23a49d162598937fcd5ccca881d8 + md5: edd34ed9be06e022f519be71c927ff3f depends: - bzip2 >=1.0.8,<2.0a0 - - libcurl >=8.12.1,<9.0a0 - - libexpat >=2.6.4,<3.0a0 - - liblzma >=5.6.4,<6.0a0 + - libcurl >=8.13.0,<9.0a0 + - libexpat >=2.7.0,<3.0a0 + - liblzma >=5.8.1,<6.0a0 - libuv >=1.50.0,<2.0a0 - libzlib >=1.3.1,<2.0a0 - ucrt >=10.0.20348.0 @@ -12617,8 +12933,8 @@ packages: - zstd >=1.5.7,<1.6.0a0 license: BSD-3-Clause license_family: BSD - size: 14584206 - timestamp: 1743112872186 + size: 14673519 + timestamp: 1744314128231 - conda: https://conda.anaconda.org/conda-forge/noarch/coal-3.0.0-hd8ed1ab_5.conda sha256: cf243275f62b0423f2439bfc506081413018a9e3e2ff46e4b8ce6fffbbed6d3e md5: 94ff2b5979e79648af83527bb60fdc9e @@ -12906,9 +13222,9 @@ packages: license_family: BSD size: 261801 timestamp: 1727293684267 -- conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.1-py312h68727a3_0.conda - sha256: e977af50b844b5b8cfec358131a4e923f0aa718e8334321cf8d84f5093576259 - md5: f5fbba0394ee45e9a64a73c2a994126a +- conda: https://conda.anaconda.org/conda-forge/linux-64/contourpy-1.3.2-py312h68727a3_0.conda + sha256: 4c8f2aa34aa031229e6f8aa18f146bce7987e26eae9c6503053722a8695ebf0c + md5: e688276449452cdfe9f8f5d3e74c23f6 depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 @@ -12918,8 +13234,8 @@ packages: - python_abi 3.12.* *_cp312 license: BSD-3-Clause license_family: BSD - size: 276332 - timestamp: 1731428454756 + size: 276533 + timestamp: 1744743235779 - conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.0-py39h0d3c867_2.conda sha256: e0e06531f855aa84bc66625fecaf9305d5cf05781f0427292ce182558134048e md5: f31ddc6c146667d9595bf98c4a8125c3 @@ -12933,9 +13249,9 @@ packages: license_family: BSD size: 245001 timestamp: 1729602646623 -- conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.1-py312hc47a885_0.conda - sha256: e05d4c6b4284684a020c386861342fa22706ff747f1f8909b14dbc0fe489dcb2 - md5: 94715deb514df3f341f62bc2ffea5637 +- conda: https://conda.anaconda.org/conda-forge/osx-64/contourpy-1.3.2-py312hc47a885_0.conda + sha256: 0d1cd1d61951a3785eda1393f62a174ab089703a53b76cac58553e8442417a85 + md5: 16b4934fdd19e9d5990140cb9bd9b0d7 depends: - __osx >=10.13 - libcxx >=18 @@ -12944,8 +13260,8 @@ packages: - python_abi 3.12.* *_cp312 license: BSD-3-Clause license_family: BSD - size: 254416 - timestamp: 1731428639848 + size: 255677 + timestamp: 1744743605195 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.0-py39h85b62ae_2.conda sha256: f35a6359e0e33f4df03558c1523b91e4c06dcb8a29e40ea35192dfa10fbae1b2 md5: 78be56565acee571fc0f1343afde6306 @@ -12960,9 +13276,9 @@ packages: license_family: BSD size: 234286 timestamp: 1729602726665 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.1-py312hb23fbb9_0.conda - sha256: fa1f8505f45eac22f25c48cd46809da0d26bcb028c37517b3474bacddd029b0a - md5: f4408290387836e05ac267cd7ec80c5c +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/contourpy-1.3.2-py312hb23fbb9_0.conda + sha256: 39329ded9d5ea49ab230c4ecd5e7610d3c844faca05fb9385bfe76ff02cc2abd + md5: e8108c7798046eb5b5f95cdde1bb534c depends: - __osx >=11.0 - libcxx >=18 @@ -12972,8 +13288,8 @@ packages: - python_abi 3.12.* *_cp312 license: BSD-3-Clause license_family: BSD - size: 245638 - timestamp: 1731428781337 + size: 245787 + timestamp: 1744743658516 - conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.0-py39h2b77a98_2.conda sha256: 109849cd12af6bfa9c7fe8076755eb16ca5f93d463347d00f748af20a367a721 md5: 37f8619ee96710220ead6bb386b9b24b @@ -12988,9 +13304,9 @@ packages: license_family: BSD size: 196844 timestamp: 1727294312191 -- conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.1-py312hd5eb7cc_0.conda - sha256: b5643ea0dd0bf57e1847679f5985feb649289de872b85c3db900f4110ac83cdd - md5: 83f7a2ec652abd37a178e35493dfd029 +- conda: https://conda.anaconda.org/conda-forge/win-64/contourpy-1.3.2-py312hd5eb7cc_0.conda + sha256: 9b552bcab6c1e3a364cbc010bdef3d26831c90984b7d0852a1dd70659d9cf84a + md5: bfcbb98aff376f62298f0801ca9bcfc3 depends: - numpy >=1.23 - python >=3.12,<3.13.0a0 @@ -13000,8 +13316,8 @@ packages: - vc14_runtime >=14.29.30139 license: BSD-3-Clause license_family: BSD - size: 216484 - timestamp: 1731428831843 + size: 217491 + timestamp: 1744743749434 - conda: https://conda.anaconda.org/conda-forge/linux-64/cppad-20240000.6-he02047a_0.conda sha256: cb6e4fd1f3592237980a89031bce80085d2d520184b24c738a2036d5807a49cb md5: 819dfe22d83c35760ac7c67ea887691c @@ -13184,6 +13500,52 @@ packages: license_family: BSD size: 71355 timestamp: 1739570178995 +- conda: https://conda.anaconda.org/conda-forge/linux-64/doxygen-1.13.2-h8e693c7_0.conda + sha256: 349c4c872357b4a533e127b2ade8533796e8e062abc2cd685756a1a063ae1e35 + md5: 0869f41ea5c64643dd2f5b47f32709ca + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libiconv >=1.17,<2.0a0 + - libstdcxx >=13 + license: GPL-2.0-only + license_family: GPL + size: 13148627 + timestamp: 1738164137421 +- conda: https://conda.anaconda.org/conda-forge/osx-64/doxygen-1.13.2-h27064b9_0.conda + sha256: 3eae05a4e8453698a52a265455a7045c70570e312db82c0829d33c576471da08 + md5: c8504720e9ad1565788e8bf91bfb0aeb + depends: + - __osx >=10.13 + - libcxx >=18 + - libiconv >=1.17,<2.0a0 + license: GPL-2.0-only + license_family: GPL + size: 11693372 + timestamp: 1738164323712 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/doxygen-1.13.2-h493aca8_0.conda + sha256: 2327ad4e6214accc1e71aea371aee9b9fed864ec36c20f829fd1cb71d4c85202 + md5: 3f5795e9004521711fa3a586b65fde05 + depends: + - __osx >=11.0 + - libcxx >=18 + - libiconv >=1.17,<2.0a0 + license: GPL-2.0-only + license_family: GPL + size: 11260324 + timestamp: 1738164659 +- conda: https://conda.anaconda.org/conda-forge/win-64/doxygen-1.13.2-hbf3f430_0.conda + sha256: 7a0fd40fd704e97a8f6533a081ba29579766d7a60bcb8e5de76679b066c4a72e + md5: 5cb2e11931773612d7a24b53f0c57594 + depends: + - libiconv >=1.17,<2.0a0 + - ucrt >=10.0.20348.0 + - vc >=14.2,<15 + - vc14_runtime >=14.29.30139 + license: GPL-2.0-only + license_family: GPL + size: 9219343 + timestamp: 1738165042524 - conda: https://conda.anaconda.org/conda-forge/linux-64/eigen-3.4.0-h00ab1b0_0.conda sha256: 53b15a98aadbe0704479bacaf7a5618fcb32d1577be320630674574241639b34 md5: b1b879d6d093f55dd40d58b5eb2f0699 @@ -13259,24 +13621,24 @@ packages: license_family: BSD size: 3337874 timestamp: 1730380465398 -- conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.10.3-np20py312hf621b31_0.conda - sha256: 99568c41e72cc3344c57d36c6559f97d71926058ea0dc7d5c20846348cc64c10 - md5: 0730cc329d8cd964528b0a5915f3d2c9 +- conda: https://conda.anaconda.org/conda-forge/linux-64/eigenpy-3.11.0-np20py312hf621b31_0.conda + sha256: 6d6cfbafe40229a5582f8d86348574d5af643a1226f03bf73c4630ac16e358eb + md5: 9b8e41ff9d6410d078d6d31d2701cd03 depends: - eigen - libboost-python-devel - python - scipy - - __glibc >=2.17,<3.0.a0 - libstdcxx >=13 - libgcc >=13 + - __glibc >=2.17,<3.0.a0 - python_abi 3.12.* *_cp312 - - numpy >=1.19,<3 - libboost-python >=1.86.0,<1.87.0a0 + - numpy >=1.19,<3 license: BSD-2-Clause license_family: BSD - size: 3324387 - timestamp: 1739356422954 + size: 3300552 + timestamp: 1745598389418 - conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.1-np20py312h55856b6_0.conda sha256: 69ea59e84ee176358c2e02553ec173238a1083fb298e4d1c35bfa930996a80c9 md5: 5bc8fa4a57980acf6d3d1d30a30d2b1a @@ -13311,23 +13673,23 @@ packages: license_family: BSD size: 3005594 timestamp: 1730380508185 -- conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.10.3-np20py312h9bc5bda_0.conda - sha256: 269b7c8f55d7f4704bf70f7ae5485c15752dc60abb0918523be9962bfbf9ce61 - md5: 05838f9f642c6ae8142d9842e1393d34 +- conda: https://conda.anaconda.org/conda-forge/osx-64/eigenpy-3.11.0-np20py312h9bc5bda_0.conda + sha256: 416938b3739508f61da86907fab6361c67cee078c3433327f6b5601914071f07 + md5: 8072427cb11898c4ea4d9c7faf29ffea depends: - eigen - libboost-python-devel - python - scipy - - __osx >=10.13 - libcxx >=18 - - libboost-python >=1.86.0,<1.87.0a0 + - __osx >=10.13 - numpy >=1.19,<3 + - libboost-python >=1.86.0,<1.87.0a0 - python_abi 3.12.* *_cp312 license: BSD-2-Clause license_family: BSD - size: 3192783 - timestamp: 1739356514911 + size: 3178884 + timestamp: 1745598412903 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.1-np20py312h6ba4d93_0.conda sha256: 0631b2d4e91f1a02248cccaf4448b04e2f660c02605b5298faed2946bd5f55bb md5: d580db23cee9eac6dbdedd430b9a293c @@ -13364,24 +13726,24 @@ packages: license_family: BSD size: 2476545 timestamp: 1730380537791 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.10.3-np20py312h03850db_0.conda - sha256: 89fd664abb9d05e0ef3d61958e4d785ffe07098eb7f34fe11ce6de60cba9d2f3 - md5: 2b0516dd2bb5a9670ae6de179803ef8d +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/eigenpy-3.11.0-np20py312h03850db_0.conda + sha256: 102296a03d3686d15285a886d4be3bef99ac4c4daab9ee99e642ff38a5b42cd0 + md5: 5d5a1e60649150dd85df0770debc9a5b depends: - eigen - libboost-python-devel - python - scipy - - python 3.12.* *_cpython - libcxx >=18 - __osx >=11.0 - - numpy >=1.19,<3 + - python 3.12.* *_cpython - libboost-python >=1.86.0,<1.87.0a0 - python_abi 3.12.* *_cp312 + - numpy >=1.19,<3 license: BSD-2-Clause license_family: BSD - size: 2542684 - timestamp: 1739356488971 + size: 2529061 + timestamp: 1745598423404 - conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.1-np20py312hbca496c_0.conda sha256: aeb226601cb3083e3e9b78063a2c41c7414e049c69b4c66f3413c7146ee20174 md5: d958d5905109bf9bd769dedc72fcb3b2 @@ -13426,9 +13788,9 @@ packages: license_family: BSD size: 1724218 timestamp: 1730380488745 -- conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.10.3-py312h00c8ebc_0.conda - sha256: 8547876cc3504a3b15de4198facc1b12f94e92b16ae86f73bf796b5cfefdeb1a - md5: 6453ff5e3da036e0f717cf07545b2599 +- conda: https://conda.anaconda.org/conda-forge/win-64/eigenpy-3.11.0-py312h00c8ebc_0.conda + sha256: a3036d22e9f1daab6c17e181d7c35bb25d3e4a2bd6e552b1b08471b05262a03b + md5: 31329d9a69ab698e23dae30668cd7085 depends: - eigen - libboost-python-devel @@ -13441,13 +13803,13 @@ packages: - vc >=14.2,<15 - vc14_runtime >=14.29.30139 - ucrt >=10.0.20348.0 + - numpy >=1.21,<3 - libboost-python >=1.86.0,<1.87.0a0 - python_abi 3.12.* *_cp312 - - numpy >=1.21,<3 license: BSD-2-Clause license_family: BSD - size: 1679770 - timestamp: 1739356461414 + size: 1651971 + timestamp: 1745598392612 - conda: https://conda.anaconda.org/conda-forge/noarch/exceptiongroup-1.2.2-pyhd8ed1ab_1.conda sha256: cbde2c64ec317118fc06b223c5fd87c8a680255e7348dd60e7b292d2e103e701 md5: a16662747cdeb9abbac74d0057cc976e @@ -13456,15 +13818,15 @@ packages: license: MIT and PSF-2.0 size: 20486 timestamp: 1733208916977 -- conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.1.0-pyhd8ed1ab_1.conda - sha256: 28d25ea375ebab4bf7479228f8430db20986187b04999136ff5c722ebd32eb60 - md5: ef8b5fca76806159fc25b4f48d8737eb +- conda: https://conda.anaconda.org/conda-forge/noarch/executing-2.2.0-pyhd8ed1ab_0.conda + sha256: 7510dd93b9848c6257c43fdf9ad22adf62e7aa6da5f12a6a757aed83bcfedf05 + md5: 81d30c08f9a3e556e8ca9e124b044d14 depends: - python >=3.9 license: MIT license_family: MIT - size: 28348 - timestamp: 1733569440265 + size: 29652 + timestamp: 1745502200340 - conda: https://conda.anaconda.org/conda-forge/linux-64/expat-2.7.0-h5888daf_0.conda sha256: dd5530ddddca93b17318838b97a2c9d7694fa4d57fc676cf0d06da649085e57a md5: d6845ae4dea52a2f90178bf1829a21f8 @@ -13562,9 +13924,9 @@ packages: license_family: BSD size: 4102 timestamp: 1566932280397 -- conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py312h178313f_0.conda - sha256: 76ca95b4111fe27e64d74111b416b3462ad3db99f7109cbdf50e6e4b67dcf5b7 - md5: 2f8a66f2f9eb931cdde040d02c6ab54c +- conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py312h178313f_0.conda + sha256: 3d230ff0d9e9fc482de22b807adf017736bd6d19b932eea68d68eeb52b139e04 + md5: 97907388593b27ac01237a1023d58d3d depends: - __glibc >=2.17,<3.0.a0 - brotli @@ -13575,11 +13937,11 @@ packages: - unicodedata2 >=15.1.0 license: MIT license_family: MIT - size: 2834054 - timestamp: 1738940929849 -- conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.56.0-py39h9399b63_0.conda - sha256: 17f420f66af1e36fd1d37f827c8f823b75eb32a8d9edbefb668d68c659d8550d - md5: fed18e24826e17df15b5d5caaa3b3aa3 + size: 2842050 + timestamp: 1743732552050 +- conda: https://conda.anaconda.org/conda-forge/linux-64/fonttools-4.57.0-py39h9399b63_0.conda + sha256: 1fdab0a4f2cd2009613080cd38e80fc8f756e13d3da409717c7382d93a9abe8a + md5: f992d663eb838219b744ccbf89bad217 depends: - __glibc >=2.17,<3.0.a0 - brotli @@ -13590,11 +13952,11 @@ packages: - unicodedata2 >=15.1.0 license: MIT license_family: MIT - size: 2296965 - timestamp: 1738940796422 -- conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py312h3520af0_0.conda - sha256: 9b206989c9d5e68120d264b6798b9afdfbca6b9a8705cdd71b68a75ce58f81b7 - md5: 9b603b2fa3072c966ef2ff119e8203f3 + size: 2339982 + timestamp: 1743732450224 +- conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py312h3520af0_0.conda + sha256: 45e0a8d7b1911ca1d01a1d9679ba3e5678f79b4c856e85bf1bf329590b4ba2f9 + md5: 72459752c526a5e73dcd0f17662b2d12 depends: - __osx >=10.13 - brotli @@ -13604,11 +13966,11 @@ packages: - unicodedata2 >=15.1.0 license: MIT license_family: MIT - size: 2761261 - timestamp: 1738940558929 -- conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.56.0-py39hd18e689_0.conda - sha256: bc0fbe3c2231e8db47fd7ff884bf5eacb3abadf290eb019148c0de50949ec8f5 - md5: 52ca7c232781e5c7a22d29c1dca12169 + size: 2788283 + timestamp: 1743732547993 +- conda: https://conda.anaconda.org/conda-forge/osx-64/fonttools-4.57.0-py39hd18e689_0.conda + sha256: 90ff2e08e67334f6c90766ed752562d1cc7bfba58ea94d9e9f5dfb2063883b32 + md5: 33ab474abead20409a38fcf079960c7a depends: - __osx >=10.13 - brotli @@ -13618,11 +13980,11 @@ packages: - unicodedata2 >=15.1.0 license: MIT license_family: MIT - size: 2257079 - timestamp: 1738940599731 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py312h998013c_0.conda - sha256: 6b003a5100ec58e1bd456bf55d0727606f7b067628aed1a7c5d8cf4f0174bfc5 - md5: a5cf7d0629863be81d90054882de908c + size: 2262632 + timestamp: 1743732515265 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py312h998013c_0.conda + sha256: ff8b4b5b461d7e1e4444aff3cf06f160f6f1b2ab44e4d010de8b128324a125b3 + md5: 657512bc3ceb378aa59a5b5f5d7d1fe4 depends: - __osx >=11.0 - brotli @@ -13633,11 +13995,11 @@ packages: - unicodedata2 >=15.1.0 license: MIT license_family: MIT - size: 2753059 - timestamp: 1738940607300 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.56.0-py39hefdd603_0.conda - sha256: f1c105c0dc31559c50b87ee9561a2c8edc7e43114b08ab5849da9d35d71420d8 - md5: 80835045b628a24cde690bd68fbf2b66 + size: 2733512 + timestamp: 1743732533022 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/fonttools-4.57.0-py39hefdd603_0.conda + sha256: 8a3a8dd76ecb06e84eebab601fd72b926b63c4372bf3601fd1022065e0d180b5 + md5: e82290c4545f2aa38697b0cbc6c9de04 depends: - __osx >=11.0 - brotli @@ -13648,11 +14010,11 @@ packages: - unicodedata2 >=15.1.0 license: MIT license_family: MIT - size: 2223758 - timestamp: 1738940666769 -- conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py312h31fea79_0.conda - sha256: 31f245d4ceb7a8e9df8d292ff1efdb4be9a8fa7a9be7a1d0394465aa7f824d50 - md5: 7c08698c54ca6390314c19167c16745e + size: 2235281 + timestamp: 1743732469707 +- conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py312h31fea79_0.conda + sha256: eaa9fa1c6c0f290a24066a170460e292b111cb4c67c8d7cb7eb54ca68c608646 + md5: 5bcdfae9aaf166ad83edebfa2f6359e2 depends: - brotli - munkres @@ -13664,11 +14026,11 @@ packages: - vc14_runtime >=14.29.30139 license: MIT license_family: MIT - size: 2413563 - timestamp: 1738940929060 -- conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.56.0-py39hf73967f_0.conda - sha256: c79c6e6acf81e2ea44be39591b94795ec85b9bb4646230697c0b49f8d4397b2a - md5: a46ce06755e392a444bd2a11fbb8b36b + size: 2410183 + timestamp: 1743732853 +- conda: https://conda.anaconda.org/conda-forge/win-64/fonttools-4.57.0-py39hf73967f_0.conda + sha256: 00c8d589e118e2e94c6394dc9639c165462c44ca59a7ee2e73e880cfd6d07655 + md5: 7a0c5bd6b82182718d3b7dfb71f7f63a depends: - brotli - munkres @@ -13680,51 +14042,44 @@ packages: - vc14_runtime >=14.29.30139 license: MIT license_family: MIT - size: 1925817 - timestamp: 1738940916484 -- conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-h48d6fc4_0.conda - sha256: 7385577509a9c4730130f54bb6841b9b416249d5f4e9f74bf313e6378e313c57 - md5: 9ecfd6f2ca17077dd9c2d24770bb9ccd - depends: - - __glibc >=2.17,<3.0.a0 - - libgcc >=13 - - libpng >=1.6.47,<1.7.0a0 - - libzlib >=1.3.1,<2.0a0 + size: 1926385 + timestamp: 1743732684845 +- conda: https://conda.anaconda.org/conda-forge/linux-64/freetype-2.13.3-ha770c72_1.conda + sha256: 7ef7d477c43c12a5b4cddcf048a83277414512d1116aba62ebadfa7056a7d84f + md5: 9ccd736d31e0c6e41f54e704e5312811 + depends: + - libfreetype 2.13.3 ha770c72_1 + - libfreetype6 2.13.3 h48d6fc4_1 license: GPL-2.0-only OR FTL - size: 639682 - timestamp: 1741863789964 -- conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h40dfd5c_0.conda - sha256: 66cc36a313accf28f4ab9b40ad11e4a8ff757c11314cd499435d9b8df1fa0150 - md5: e391f0c2d07df272cf7c6df235e97bb9 - depends: - - __osx >=10.13 - - libpng >=1.6.47,<1.7.0a0 - - libzlib >=1.3.1,<2.0a0 + size: 172450 + timestamp: 1745369996765 +- conda: https://conda.anaconda.org/conda-forge/osx-64/freetype-2.13.3-h694c41f_1.conda + sha256: e2870e983889eec73fdc0d4ab27d3f6501de4750ffe32d7d0a3a287f00bc2f15 + md5: 126dba1baf5030cb6f34533718924577 + depends: + - libfreetype 2.13.3 h694c41f_1 + - libfreetype6 2.13.3 h40dfd5c_1 license: GPL-2.0-only OR FTL - size: 602964 - timestamp: 1741863884014 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-h1d14073_0.conda - sha256: 2c273de32431c431a118a8cd33afb6efc616ddbbab9e5ba0fe31e3b4d1ff57a3 - md5: 630445a505ea6e59f55714853d8c9ed0 - depends: - - __osx >=11.0 - - libpng >=1.6.47,<1.7.0a0 - - libzlib >=1.3.1,<2.0a0 + size: 172649 + timestamp: 1745370231293 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/freetype-2.13.3-hce30654_1.conda + sha256: 6b63c72ea51a41d41964841404564c0729fdddd3e952e2715839fd759b7cfdfc + md5: e684de4644067f1956a580097502bf03 + depends: + - libfreetype 2.13.3 hce30654_1 + - libfreetype6 2.13.3 h1d14073_1 license: GPL-2.0-only OR FTL - size: 590002 - timestamp: 1741863913870 -- conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h0b5ce68_0.conda - sha256: 67e3af0fbe6c25f5ab1af9a3d3000464c5e88a8a0b4b06602f4a5243a8a1fd42 - md5: 9c461ed7b07fb360d2c8cfe726c7d521 - depends: - - libpng >=1.6.47,<1.7.0a0 - - libzlib >=1.3.1,<2.0a0 - - ucrt >=10.0.20348.0 - - vc >=14.2,<15 - - vc14_runtime >=14.29.30139 + size: 172220 + timestamp: 1745370149658 +- conda: https://conda.anaconda.org/conda-forge/win-64/freetype-2.13.3-h57928b3_1.conda + sha256: 0bcc9c868d769247c12324f957c97c4dbee7e4095485db90d9c295bcb3b1bb43 + md5: 633504fe3f96031192e40e3e6c18ef06 + depends: + - libfreetype 2.13.3 h57928b3_1 + - libfreetype6 2.13.3 h0b5ce68_1 license: GPL-2.0-only OR FTL - size: 510718 - timestamp: 1741864688363 + size: 184162 + timestamp: 1745370242683 - conda: https://conda.anaconda.org/conda-forge/linux-64/gcc-13.3.0-h9576a4e_2.conda sha256: 300f077029e7626d69cc250a69acd6018c1fced3f5bf76adf37854f3370d2c45 md5: d92e51bf4b6bdbfe45e5884fb0755afe @@ -13749,17 +14104,87 @@ packages: license_family: GPL size: 66770653 timestamp: 1740240400031 -- conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_8.conda - sha256: 0294daf83875d475424f16eda49a17017f733bf565f9e8b3367d0374733f43f3 - md5: 0c56ca4bfe2b04e71fe67652d5aa3079 +- conda: https://conda.anaconda.org/conda-forge/linux-64/gcc_linux-64-13.3.0-hc28eda2_10.conda + sha256: 2526f358e0abab84d6f93b2bae932e32712025a3547400393a1cfa6240257323 + md5: d151142bbafe5e68ec7fc065c5e6f80c depends: - binutils_linux-64 - gcc_impl_linux-64 13.3.0.* - sysroot_linux-64 license: BSD-3-Clause license_family: BSD - size: 32448 - timestamp: 1740665998589 + size: 32570 + timestamp: 1745040775220 +- conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321h59d505e_0.conda + sha256: 9279eaa7c973f474a73607d65f9afc9c7d18e8374c45eaf5461c0969947a35be + md5: 757e04df008ac271bf9fcc3ee21d5ea8 + depends: + - __glibc >=2.17,<3.0.a0 + - libcurl >=8.12.1,<9.0a0 + - libexpat >=2.6.4,<3.0a0 + - libgcc >=13 + - libiconv >=1.18,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + - openssl >=3.4.1,<4.0a0 + - pcre2 >=10.44,<10.45.0a0 + - perl 5.* + license: GPL-2.0-or-later and LGPL-2.1-or-later + size: 10702380 + timestamp: 1742298221381 +- conda: https://conda.anaconda.org/conda-forge/linux-64/git-2.49.0-pl5321hc2ff736_1.conda + sha256: 2b0ff36cf9bb1b6ca8c512aeb1908f886ef38a358a194345252c062c62148de4 + md5: 245f8de3067054533c6e8e46ff23aa0a + depends: + - __glibc >=2.17,<3.0.a0 + - libcurl >=8.13.0,<9.0a0 + - libexpat >=2.7.0,<3.0a0 + - libgcc >=13 + - libiconv >=1.18,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + - openssl >=3.5.0,<4.0a0 + - pcre2 >=10.45,<10.46.0a0 + - perl 5.* + license: GPL-2.0-or-later and LGPL-2.1-or-later + size: 10627521 + timestamp: 1747243512398 +- conda: https://conda.anaconda.org/conda-forge/osx-64/git-2.49.0-pl5321h3bb66fe_1.conda + sha256: 2763ed05b9426e873a0027d5851fee53dca02f05f0f36317913d75e6d7b094ce + md5: f868766975818340f5eaff1e6ef697b7 + depends: + - __osx >=10.10 + - libcurl >=8.13.0,<9.0a0 + - libexpat >=2.7.0,<3.0a0 + - libiconv >=1.18,<2.0a0 + - libintl >=0.24.1,<1.0a0 + - libzlib >=1.3.1,<2.0a0 + - openssl >=3.5.0,<4.0a0 + - pcre2 >=10.45,<10.46.0a0 + - perl 5.* + license: GPL-2.0-or-later and LGPL-2.1-or-later + size: 12123128 + timestamp: 1747243766064 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/git-2.49.0-pl5321ha659579_1.conda + sha256: cb771ea5af8f588b031f21ed52d8d79ae4531a30bbe50db5b863fa74765579c8 + md5: 2f73d1205848db09444042609c8fb7e7 + depends: + - __osx >=11.0 + - libcurl >=8.13.0,<9.0a0 + - libexpat >=2.7.0,<3.0a0 + - libiconv >=1.18,<2.0a0 + - libintl >=0.24.1,<1.0a0 + - libzlib >=1.3.1,<2.0a0 + - openssl >=3.5.0,<4.0a0 + - pcre2 >=10.45,<10.46.0a0 + - perl 5.* + license: GPL-2.0-or-later and LGPL-2.1-or-later + size: 11974493 + timestamp: 1747243663594 +- conda: https://conda.anaconda.org/conda-forge/win-64/git-2.49.0-h57928b3_1.conda + sha256: ec2e366e4dbd350621ce8c73b91dd6ce5cc1b156ab2c6c006eaa7942f3635d0f + md5: 4005324dbb3cc47767ab259856b6d687 + license: GPL-2.0-or-later and LGPL-2.1-or-later + size: 125425138 + timestamp: 1747243619887 - conda: https://conda.anaconda.org/conda-forge/linux-64/gmp-6.3.0-hac33072_2.conda sha256: 309cf4f04fec0c31b6771a5809a1909b4b3154a2208f52351e1ada006f4c750c md5: c94a5994ef49749880a8139cf9afcbe1 @@ -13842,54 +14267,54 @@ packages: license_family: GPL size: 13362974 timestamp: 1740240672045 -- conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_8.conda - sha256: 59f0236194a8ea93baf33b58f250edfc775a34ddf49d262f8d5852fc35711c02 - md5: e66a842289d61d859d6df8589159b07b +- conda: https://conda.anaconda.org/conda-forge/linux-64/gxx_linux-64-13.3.0-h6834431_10.conda + sha256: 03de108ca10b693a1b03e7d5cf9173837281d15bc5da7743ffba114fa9389476 + md5: 9a8ebde471cec5cc9c48f8682f434f92 depends: - binutils_linux-64 - - gcc_linux-64 13.3.0 hc28eda2_8 + - gcc_linux-64 13.3.0 hc28eda2_10 - gxx_impl_linux-64 13.3.0.* - sysroot_linux-64 license: BSD-3-Clause license_family: BSD - size: 30781 - timestamp: 1740666017241 -- conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.0.0-h76408a6_0.conda - sha256: 9d33201d3e12a61d4ea4b1252a3468afb18b11a418f095dceffdf09bc6792f59 - md5: 347cb348bfc8d77062daee11c326e518 + size: 30904 + timestamp: 1745040794452 +- conda: https://conda.anaconda.org/conda-forge/linux-64/harfbuzz-11.1.0-h3beb420_0.conda + sha256: d93b8535a2d66dabfb6e4a2a0dea1b37aab968b5f5bba2b0378f8933429fe2e3 + md5: 95e3bb97f9cdc251c0c68640e9c10ed3 depends: - __glibc >=2.17,<3.0.a0 - cairo >=1.18.4,<2.0a0 - freetype >=2.13.3,<3.0a0 - graphite2 - icu >=75.1,<76.0a0 - - libexpat >=2.6.4,<3.0a0 + - libexpat >=2.7.0,<3.0a0 - libgcc >=13 - - libglib >=2.84.0,<3.0a0 + - libglib >=2.84.1,<3.0a0 - libstdcxx >=13 - libzlib >=1.3.1,<2.0a0 license: MIT license_family: MIT - size: 1720702 - timestamp: 1743082646624 -- conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.0.0-h9e37d49_0.conda - sha256: f1ab5960a52a11186f528249bec5ce5e43bb4c44c87ffa24334255f07c3fd4b8 - md5: b7648427f5b6797ae3904ad76e4c7f19 + size: 1729836 + timestamp: 1744894321480 +- conda: https://conda.anaconda.org/conda-forge/win-64/harfbuzz-11.1.0-h8796e6f_0.conda + sha256: fcb867daea82208cc90a2c9bacc8e0879324cd360227423bb7eae24f16d16cc8 + md5: dcc4a63f231cc52197c558f5e07e0a69 depends: - cairo >=1.18.4,<2.0a0 - freetype >=2.13.3,<3.0a0 - graphite2 - icu >=75.1,<76.0a0 - - libexpat >=2.6.4,<3.0a0 - - libglib >=2.84.0,<3.0a0 + - libexpat >=2.7.0,<3.0a0 + - libglib >=2.84.1,<3.0a0 - libzlib >=1.3.1,<2.0a0 - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: MIT license_family: MIT - size: 1125019 - timestamp: 1743083466989 + size: 1124659 + timestamp: 1744895521700 - conda: https://conda.anaconda.org/conda-forge/noarch/hpp-fcl-3.0.1-pyh5279557_0.conda sha256: dd10cb933c066a7be56bbc08c67e161969b4252fd5260c2c25222760260ba1fe md5: f9c1f766fabfae8a5470355a130429f7 @@ -13952,16 +14377,16 @@ packages: license_family: MIT size: 14544252 timestamp: 1720853966338 -- conda: https://conda.anaconda.org/conda-forge/noarch/identify-2.6.9-pyhd8ed1ab_0.conda - sha256: b74a2ffa7be9278d7b8770b6870c360747149c683865e63476b0e1db23038429 - md5: 542f45bf054c6b9cf8d00a3b1976f945 +- conda: https://conda.anaconda.org/conda-forge/noarch/identify-2.6.10-pyhd8ed1ab_0.conda + sha256: 02f47df6c6982b796aecb086b434627207e87c0a90a50226f11f2cc99c089770 + md5: 8d5b9b702810fb3054d52ba146023bc3 depends: - python >=3.9 - ukkonen license: MIT license_family: MIT - size: 78600 - timestamp: 1741502780749 + size: 79057 + timestamp: 1745098917031 - conda: https://conda.anaconda.org/conda-forge/noarch/importlib-resources-6.5.2-pyhd8ed1ab_0.conda sha256: a99a3dafdfff2bb648d2b10637c704400295cb2ba6dc929e2d814870cf9f6ae5 md5: e376ea42e9ae40f3278b0f79c9bf9826 @@ -13991,56 +14416,50 @@ packages: license_family: Proprietary size: 1852356 timestamp: 1723739573141 -- conda: https://conda.anaconda.org/conda-forge/linux-64/ipopt-3.14.17-h59d4785_0.conda - sha256: e13728d611c18ba8f82af9a301cba0d40aa7fd10b16687001dc36ee8bbd10baa - md5: f399793ae8915f22c8f679a479286d6c +- conda: https://conda.anaconda.org/conda-forge/linux-64/ipopt-3.14.17-h7fd866c_2.conda + sha256: d124757f419e90f6f4fe29a0ee669e0a7f54904c780561e56ddf5d0ecde57076 + md5: f24915488231e60a1312915ae846f5fe depends: - __glibc >=2.17,<3.0.a0 - ampl-asl >=1.0.0,<1.0.1.0a0 - libblas >=3.9.0,<4.0a0 - libgcc >=13 - - libgfortran - - libgfortran5 >=13.3.0 - liblapack >=3.9.0,<4.0a0 - - libspral >=2024.5.8,<2024.5.9.0a0 + - libspral >=2025.3.6,<2025.3.7.0a0 - libstdcxx >=13 - mumps-seq >=5.7.3,<5.7.4.0a0 license: EPL-1.0 - size: 1005951 - timestamp: 1734357247894 -- conda: https://conda.anaconda.org/conda-forge/osx-64/ipopt-3.14.17-hd603822_0.conda - sha256: 3f6dcd7ad57d00b2f5994de61404cec3eb66149e983077b545c89324d6085d00 - md5: da9eac17f92c036e2470a31873453cb0 + size: 1007553 + timestamp: 1745419704203 +- conda: https://conda.anaconda.org/conda-forge/osx-64/ipopt-3.14.17-h12baa73_2.conda + sha256: 543a747dc759fdb79041095489693bff408f933ab03534cf443456082d2e06f2 + md5: f29cc13ed237f3fff0f996d0a53ec2d1 depends: - __osx >=10.13 - ampl-asl >=1.0.0,<1.0.1.0a0 - libblas >=3.9.0,<4.0a0 - libcxx >=18 - - libgfortran 5.* - - libgfortran5 >=13.2.0 - liblapack >=3.9.0,<4.0a0 - mumps-seq >=5.7.3,<5.7.4.0a0 license: EPL-1.0 - size: 795216 - timestamp: 1734357628909 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/ipopt-3.14.17-h3e4dc2c_0.conda - sha256: df3d48e6ce44d3e2484377cd0b5c4d5f9c7285bfeca2ac34eb463b218f9ff77b - md5: af3cbc0bc8263888744a4530e87f24c0 + size: 794558 + timestamp: 1745419940932 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/ipopt-3.14.17-h945cc1c_2.conda + sha256: 379d9b44fc265493a8a42ca3694bb8d7538ed8c7bbaf8626dcf8d75f454317cc + md5: e465f880544e1e6b8d904fb65e25b130 depends: - __osx >=11.0 - ampl-asl >=1.0.0,<1.0.1.0a0 - libblas >=3.9.0,<4.0a0 - libcxx >=18 - - libgfortran 5.* - - libgfortran5 >=13.2.0 - liblapack >=3.9.0,<4.0a0 - mumps-seq >=5.7.3,<5.7.4.0a0 license: EPL-1.0 - size: 726576 - timestamp: 1734357440818 -- conda: https://conda.anaconda.org/conda-forge/win-64/ipopt-3.14.17-h905d1ba_0.conda - sha256: 9995e314005190bd3d67d525536ae62bc7fddee72641f9c4724cbb679e9589f6 - md5: 20c4bc6e15e6b285f681560154c39e14 + size: 727718 + timestamp: 1745419955303 +- conda: https://conda.anaconda.org/conda-forge/win-64/ipopt-3.14.17-h812a801_2.conda + sha256: b6105922c20c6f3ce741974e33b7d99b9415020fc756ef5107d06b43dff04859 + md5: 9e88c23515821c214e3af2fb6fcda202 depends: - ampl-asl >=1.0.0,<1.0.1.0a0 - libblas >=3.9.0,<4.0a0 @@ -14050,8 +14469,8 @@ packages: - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: EPL-1.0 - size: 942940 - timestamp: 1734357715361 + size: 939947 + timestamp: 1745420480246 - conda: https://conda.anaconda.org/conda-forge/noarch/ipython-8.18.1-pyh707e725_3.conda sha256: d98d615ac8ad71de698afbc50e8269570d4b89706821c4ff3058a4ceec69bd9b md5: 15c6f45a45f7ac27f6d60b0b084f6761 @@ -14094,9 +14513,9 @@ packages: license_family: BSD size: 590143 timestamp: 1701832398069 -- conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhca29cf9_0.conda - sha256: 72ad5d59719d7639641f21032de870fadd43ec2349229161728b736f1df720d1 - md5: e5ba968166136311157765e8b2ccb9d0 +- conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhca29cf9_0.conda + sha256: 83e4cfdcf09c1273ec31548aacf7f81076dc4245548e78ac3b47d1da361da03b + md5: a7b419c1d0ae931d86cd9cab158f698e depends: - __win - colorama @@ -14115,11 +14534,11 @@ packages: - python license: BSD-3-Clause license_family: BSD - size: 614763 - timestamp: 1741457145171 -- conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.0.2-pyhfb0248b_0.conda - sha256: 98f14471e0f492d290c4882f1e2c313fffc67a0f9a3a36e699d7b0c5d42a5196 - md5: b031bcd65b260a0a3353531eab50d465 + size: 619872 + timestamp: 1745672185321 +- conda: https://conda.anaconda.org/conda-forge/noarch/ipython-9.2.0-pyhfb0248b_0.conda + sha256: 539d003c379c22a71df1eb76cd4167a3e2d59f45e6dbc3416c45619f4c1381fb + md5: 7330ee1244209cfebfb23d828dd9aae5 depends: - __unix - pexpect >4.3 @@ -14138,8 +14557,8 @@ packages: - python license: BSD-3-Clause license_family: BSD - size: 615519 - timestamp: 1741457126430 + size: 620691 + timestamp: 1745672166398 - conda: https://conda.anaconda.org/conda-forge/noarch/ipython_pygments_lexers-1.1.1-pyhd8ed1ab_0.conda sha256: 894682a42a7d659ae12878dbcb274516a7031bbea9104e92f8e88c1f2765a104 md5: bd80ba060603cc228d9d81c257093119 @@ -14387,35 +14806,35 @@ packages: license_family: MIT size: 510641 timestamp: 1739161381270 -- conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_4.conda - sha256: ec0bb8cc8cce0237fe84a737a6367fd3621126076b739ea89de49f451e92506a - md5: a35ccc73726f64d22dc9c4349f5c58bd +- conda: https://conda.anaconda.org/conda-forge/osx-64/ld64-951.9-h4e51db5_6.conda + sha256: e40a618bfa56eba6f18bc30ec45e5b63797e5be0c64b632a09e13853b216ed8c + md5: 45bf526d53b1bc95bc0b932a91a41576 depends: - - ld64_osx-64 951.9 h33512f0_4 + - ld64_osx-64 951.9 h33512f0_6 - libllvm18 >=18.1.8,<18.2.0a0 constrains: - - cctools 1010.6.* - cctools_osx-64 1010.6.* + - cctools 1010.6.* license: APSL-2.0 license_family: Other - size: 18874 - timestamp: 1742512391779 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_4.conda - sha256: 4806f1356117fe4a6c0c9927587cd456ee9a891bb943e300b03aff9f17ad3a5c - md5: de921c0941f051f3b019d46a0c83fdda + size: 19401 + timestamp: 1743872196322 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64-951.9-h4c6efb1_6.conda + sha256: 2c796872c89dee18c8455bd5e4d7dcc6c4f8544c873856d12a64585ac60e315f + md5: f756d0a0ffba157687a29077f3408016 depends: - - ld64_osx-arm64 951.9 hb6b49e2_4 + - ld64_osx-arm64 951.9 hb6b49e2_6 - libllvm18 >=18.1.8,<18.2.0a0 constrains: - cctools 1010.6.* - cctools_osx-arm64 1010.6.* license: APSL-2.0 license_family: Other - size: 18894 - timestamp: 1742512610229 -- conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_4.conda - sha256: 809c88c6ca19e08707320dff428ea4936b151324faed71ca5600f6bf54ce5504 - md5: b1678041160c249a3df7937be93c56aa + size: 19446 + timestamp: 1743872353403 +- conda: https://conda.anaconda.org/conda-forge/osx-64/ld64_osx-64-951.9-h33512f0_6.conda + sha256: e048342a05e77440f355c46a47871dc71d9d8884a4bf73dedf1a16c84aabb834 + md5: 6cd120f5c9dae65b858e1fad2b7959a0 depends: - __osx >=10.13 - libcxx @@ -14424,16 +14843,16 @@ packages: - tapi >=1300.6.5,<1301.0a0 constrains: - cctools_osx-64 1010.6.* - - cctools 1010.6.* - - clang >=18.1.8,<19.0a0 - ld 951.9.* + - clang >=18.1.8,<19.0a0 + - cctools 1010.6.* license: APSL-2.0 license_family: Other - size: 1099376 - timestamp: 1742512322014 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_4.conda - sha256: 0376873d88573688168b5b7618391dd68fa0b309ddce7fa77c5f9037ada7cf66 - md5: d01a78a16542f235dd755ca66772795e + size: 1099095 + timestamp: 1743872136626 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/ld64_osx-arm64-951.9-hb6b49e2_6.conda + sha256: 5ab2c15358d0ebfe26bafd2f768f524962f1a785c81d42518afb4f5d397e83f9 + md5: 61743b006633f5e1f9aa9e707f44fcb1 depends: - __osx >=11.0 - libcxx @@ -14443,12 +14862,12 @@ packages: constrains: - ld 951.9.* - clang >=18.1.8,<19.0a0 - - cctools 1010.6.* - cctools_osx-arm64 1010.6.* + - cctools 1010.6.* license: APSL-2.0 license_family: Other - size: 1019138 - timestamp: 1742512519169 + size: 1022641 + timestamp: 1743872275249 - conda: https://conda.anaconda.org/conda-forge/linux-64/ld_impl_linux-64-2.43-h712a8e2_4.conda sha256: db73f38155d901a610b2320525b9dd3b31e4949215c870685fd92ea61b5ce472 md5: 01f8d123c96816249efd255a31ad7712 @@ -14460,44 +14879,48 @@ packages: license_family: GPL size: 671240 timestamp: 1740155456116 -- conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h27087fc_0.tar.bz2 - sha256: cb55f36dcd898203927133280ae1dc643368af041a48bcf7c026acb7c47b0c12 - md5: 76bbff344f0134279f225174e9064c8f +- conda: https://conda.anaconda.org/conda-forge/linux-64/lerc-4.0.0-h0aef613_1.conda + sha256: 412381a43d5ff9bbed82cd52a0bbca5b90623f62e41007c9c42d3870c60945ff + md5: 9344155d33912347b37f0ae6c410a835 depends: - - libgcc-ng >=12 - - libstdcxx-ng >=12 + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libstdcxx >=13 license: Apache-2.0 license_family: Apache - size: 281798 - timestamp: 1657977462600 -- conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hb486fe8_0.tar.bz2 - sha256: e41790fc0f4089726369b3c7f813117bbc14b533e0ed8b94cf75aba252e82497 - md5: f9d6a4c82889d5ecedec1d90eb673c55 + size: 264243 + timestamp: 1745264221534 +- conda: https://conda.anaconda.org/conda-forge/osx-64/lerc-4.0.0-hcca01a6_1.conda + sha256: cc1f1d7c30aa29da4474ec84026ec1032a8df1d7ec93f4af3b98bb793d01184e + md5: 21f765ced1a0ef4070df53cb425e1967 depends: - - libcxx >=13.0.1 + - __osx >=10.13 + - libcxx >=18 license: Apache-2.0 license_family: Apache - size: 290319 - timestamp: 1657977526749 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-h9a09cb3_0.tar.bz2 - sha256: 6f068bb53dfb6147d3147d981bb851bb5477e769407ad4e6a68edf482fdcb958 - md5: de462d5aacda3b30721b512c5da4e742 + size: 248882 + timestamp: 1745264331196 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/lerc-4.0.0-hd64df32_1.conda + sha256: 12361697f8ffc9968907d1a7b5830e34c670e4a59b638117a2cdfed8f63a38f8 + md5: a74332d9b60b62905e3d30709df08bf1 depends: - - libcxx >=13.0.1 + - __osx >=11.0 + - libcxx >=18 license: Apache-2.0 license_family: Apache - size: 215721 - timestamp: 1657977558796 -- conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h63175ca_0.tar.bz2 - sha256: f4f39d7f6a2f9b407f8fb567a6c25755270421731d70f0ff331f5de4fa367488 - md5: 1900cb3cab5055833cfddb0ba233b074 + size: 188306 + timestamp: 1745264362794 +- conda: https://conda.anaconda.org/conda-forge/win-64/lerc-4.0.0-h6470a55_1.conda + sha256: 868a3dff758cc676fa1286d3f36c3e0101cca56730f7be531ab84dc91ec58e9d + md5: c1b81da6d29a14b542da14a36c9fbf3f depends: + - ucrt >=10.0.20348.0 - vc >=14.2,<15 - - vs2015_runtime >=14.29.30037 + - vc14_runtime >=14.29.30139 license: Apache-2.0 license_family: Apache - size: 194365 - timestamp: 1657977692274 + size: 164701 + timestamp: 1745264384716 - conda: https://conda.anaconda.org/conda-forge/linux-64/libblas-3.9.0-31_h59b9bed_openblas.conda build_number: 31 sha256: 9839fc4ac0cbb0aa3b9eea520adfb57311838959222654804e58f6f2d1771db5 @@ -15163,55 +15586,79 @@ packages: license_family: BSD size: 3733549 timestamp: 1740088502127 -- conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_8.conda - sha256: 9e9af164c1ddfd114a786aceacf64df0041c3528a97cc96c06f3bf1040485e29 - md5: 1444a2cd1f78fccea7dacb658f8aeb39 +- conda: https://conda.anaconda.org/conda-forge/osx-64/libclang-cpp18.1-18.1.8-default_h3571c67_9.conda + sha256: a3453cf08393f4a369a70795036d60dd8ea0de1efbf683594cbcaba49d8e3e74 + md5: ef1a444913775b76f3391431967090a9 depends: - __osx >=10.13 - libcxx >=18.1.8 - libllvm18 >=18.1.8,<18.2.0a0 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 13905920 - timestamp: 1742266347128 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_8.conda - sha256: b736c4c3a32d4aa16b4af7b2094b4f3786ea34723cccb9918579206706000f90 - md5: a5f883cd77dcc0f62a0eca8445d9e147 + size: 13908110 + timestamp: 1744061729284 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libclang-cpp18.1-18.1.8-default_hf90f093_9.conda + sha256: 23eb5b180fadbe0b9a1d1aa123e44ef7ff774174b8a43fa40495c4ecc80f1328 + md5: 88893bbbccb1400d677f747b0c8f226f depends: - __osx >=11.0 - libcxx >=18.1.8 - libllvm18 >=18.1.8,<18.2.0a0 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 13330731 - timestamp: 1742265504673 -- conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.1-default_hb5137d0_0.conda - sha256: 3b79cdf6bb6d5f42a73f5db5f3dd9fb5563b44f24e761d02faeb52b9506019f4 - md5: 331dee424fabc0c26331767acc93a074 + size: 13330734 + timestamp: 1744062341062 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.3-default_h1df26ce_0.conda + sha256: e49690c45269e504a4a020c689941aea58bc44e3cce2a5da93340cf838999c1c + md5: bbce8ba7f25af8b0928f13fca1eb7405 depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 - - libllvm20 >=20.1.1,<20.2.0a0 + - libllvm20 >=20.1.3,<20.2.0a0 - libstdcxx >=13 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 20878931 - timestamp: 1742506161165 -- conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.1-default_h9c6a7e4_0.conda - sha256: e73fef6a7eeb800220b435561126597639e78e3bc1d8f2f32ad6f89de07b5308 - md5: f8b1b8c13c0a0fede5e1a204eafb48f8 + size: 20864165 + timestamp: 1744876524529 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libclang-cpp20.1-20.1.5-default_h1df26ce_1.conda + sha256: 1938ac6a3ac89e2eeed89a01e3c998f87d83cdbde5dd7650c84c64e4b5502f34 + md5: 330b1dadfa7c3205a01fa9599fabe808 depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 - - libllvm20 >=20.1.1,<20.2.0a0 + - libllvm20 >=20.1.5,<20.2.0a0 - libstdcxx >=13 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 12114034 - timestamp: 1742506367797 -- conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.1-default_ha5278ca_0.conda - sha256: f8aa908391700fc19e736ab1c598a952bef1bbb72192790988a414216929cab8 - md5: c432d7ab334986169fd534725fc9375d + size: 20894564 + timestamp: 1747697571531 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.3-default_he06ed0a_0.conda + sha256: 99c9d0dc741d3675e1ffcaab90a4a1e80090076f9fa1aa71fe8c114d3dcdc61a + md5: 1bb2ec3c550f7589b2d16e271aeaeddb + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libllvm20 >=20.1.3,<20.2.0a0 + - libstdcxx >=13 + license: Apache-2.0 WITH LLVM-exception + license_family: Apache + size: 12098268 + timestamp: 1744876737219 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libclang13-20.1.5-default_he06ed0a_1.conda + sha256: e3047ed743f54160715a58d9f0a3deff2f76cd847412a6270982c849547a13ef + md5: 12117145218e7e1a528c8396ed803058 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libllvm20 >=20.1.5,<20.2.0a0 + - libstdcxx >=13 + license: Apache-2.0 WITH LLVM-exception + license_family: Apache + size: 12116539 + timestamp: 1747697840742 +- conda: https://conda.anaconda.org/conda-forge/win-64/libclang13-20.1.3-default_h6e92b77_0.conda + sha256: b4c3d60f0096b8303caf531bf14e51c3e83db6c596fe1b99351f8f3a0a6a9a50 + md5: e7530cd4a3b5e3d2348be3d836cb196c depends: - libzlib >=1.3.1,<2.0a0 - ucrt >=10.0.20348.0 @@ -15220,8 +15667,8 @@ packages: - zstd >=1.5.7,<1.6.0a0 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 28339961 - timestamp: 1742537164 + size: 28343558 + timestamp: 1744881010137 - conda: https://conda.anaconda.org/conda-forge/linux-64/libcoal-3.0.0-ha55d5d9_5.conda sha256: ea770e4812fe36a5523d842260bf97c3b068cd6928d6309340aefd88b7cebb06 md5: c778a16b765ceea53fb5d65fb722bced @@ -15299,9 +15746,9 @@ packages: license_family: Apache size: 4519402 timestamp: 1689195353551 -- conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.12.1-h332b0f4_0.conda - sha256: 2ebc3039af29269e4cdb858fca36265e5e400c1125a4bcd84ae73a596e0e76ca - md5: 45e9dc4e7b25e2841deb392be085500e +- conda: https://conda.anaconda.org/conda-forge/linux-64/libcurl-8.13.0-h332b0f4_0.conda + sha256: 38e528acfaa0276b7052f4de44271ff9293fdb84579650601a8c49dac171482a + md5: cbdc92ac0d93fe3c796e36ad65c7905c depends: - __glibc >=2.17,<3.0.a0 - krb5 >=1.21.3,<1.22.0a0 @@ -15310,14 +15757,14 @@ packages: - libssh2 >=1.11.1,<2.0a0 - libzlib >=1.3.1,<2.0a0 - openssl >=3.4.1,<4.0a0 - - zstd >=1.5.6,<1.6.0a0 + - zstd >=1.5.7,<1.6.0a0 license: curl license_family: MIT - size: 426675 - timestamp: 1739512336799 -- conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.12.1-h5dec5d8_0.conda - sha256: 51168abcbee14814b94dea3358300de4053423c6ce8d4627475464fb8cf0e5d3 - md5: b39e6b74b4eb475eacdfd463fce82138 + size: 438088 + timestamp: 1743601695669 +- conda: https://conda.anaconda.org/conda-forge/osx-64/libcurl-8.13.0-h5dec5d8_0.conda + sha256: 137d92f1107141d9eb39598fb05837be4f9aad4ead957194d94364834f3cc590 + md5: a35b1976d746d55cd7380c8842d9a1b5 depends: - __osx >=10.13 - krb5 >=1.21.3,<1.22.0a0 @@ -15325,14 +15772,14 @@ packages: - libssh2 >=1.11.1,<2.0a0 - libzlib >=1.3.1,<2.0a0 - openssl >=3.4.1,<4.0a0 - - zstd >=1.5.6,<1.6.0a0 + - zstd >=1.5.7,<1.6.0a0 license: curl license_family: MIT - size: 410703 - timestamp: 1739512524410 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.12.1-h73640d1_0.conda - sha256: 0bddd1791eb0602c8c6aa465802e9d4526d3ec1251d900b209e767753565d5df - md5: 105f0cceef753644912f42e11c1ae9cf + size: 418479 + timestamp: 1743601943696 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcurl-8.13.0-h73640d1_0.conda + sha256: 747f7e8aad390b9b39a300401579ff1b5731537a586869b724dc071a9b315f03 + md5: 4a5d33f75f9ead15089b04bed8d0eafe depends: - __osx >=11.0 - krb5 >=1.21.3,<1.22.0a0 @@ -15340,14 +15787,14 @@ packages: - libssh2 >=1.11.1,<2.0a0 - libzlib >=1.3.1,<2.0a0 - openssl >=3.4.1,<4.0a0 - - zstd >=1.5.6,<1.6.0a0 + - zstd >=1.5.7,<1.6.0a0 license: curl license_family: MIT - size: 387893 - timestamp: 1739512564746 -- conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.12.1-h88aaa65_0.conda - sha256: 4c8e62fd32d59e5fbfad0f37e33083928bbb3c8800258650d4e7911e6f6fd1aa - md5: 2b1c729d91f3b07502981b6e0c7727cc + size: 397929 + timestamp: 1743601888428 +- conda: https://conda.anaconda.org/conda-forge/win-64/libcurl-8.13.0-h88aaa65_0.conda + sha256: 185553b37c0299b7a15dc66a7a7e2a0d421adaac784ec9298a0b2ad745116ca5 + md5: c9cf6eb842decbb66c2f34e72c3580d6 depends: - krb5 >=1.21.3,<1.22.0a0 - libssh2 >=1.11.1,<2.0a0 @@ -15357,26 +15804,26 @@ packages: - vc14_runtime >=14.29.30139 license: curl license_family: MIT - size: 349696 - timestamp: 1739512628733 -- conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.1-hf95d169_0.conda - sha256: b30ef239517cfffb71d8ece7b903afe2a1bac0425f5bd38976b35d3cbf77312b - md5: 85cff0ed95d940c4762d5a99a6fe34ae + size: 357142 + timestamp: 1743602240803 +- conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-20.1.4-hf95d169_0.conda + sha256: 491ae6c8b5dc678581b52d24de73e303b895fd5f600da2f6f721b385692083d0 + md5: 9a38a63cfe950dd3e1b3adfcba731d3a depends: - __osx >=10.13 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 562132 - timestamp: 1742449741333 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.1-ha82da77_0.conda - sha256: 80dd8ae3fbcf508ed72f074ada2c7784298e822e8d19c3b84c266bb31456d77c - md5: 833c4899914bf96caf64b52ef415e319 + size: 559984 + timestamp: 1745991583464 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libcxx-20.1.4-ha82da77_0.conda + sha256: 1837e2c65f8fc8cfd8b240cfe89406d0ce83112ac63f98c9fb3c9a15b4f2d4e1 + md5: 10c809af502fcdab799082d338170994 depends: - __osx >=11.0 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 561543 - timestamp: 1742449846779 + size: 565811 + timestamp: 1745991653948 - conda: https://conda.anaconda.org/conda-forge/osx-64/libcxx-devel-18.1.8-h7c275be_8.conda sha256: cb3cce2b312aa1fb7391672807001bbab4d6e2deb16d912caecf6219f58ee1f4 md5: a9513c41f070a9e2d5c370ba5d6c0c00 @@ -15395,45 +15842,45 @@ packages: license_family: Apache size: 794791 timestamp: 1742451369695 -- conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h4ddbbb0_0.conda - sha256: 511d801626d02f4247a04fff957cc6e9ec4cc7e8622bd9acd076bcdc5de5fe66 - md5: 8dfae1d2e74767e9ce36d5fa0d8605db +- conda: https://conda.anaconda.org/conda-forge/linux-64/libdeflate-1.23-h86f0d12_0.conda + sha256: 4db2f70a1441317d964e84c268e388110ad9cf75ca98994d1336d670e62e6f07 + md5: 27fe770decaf469a53f3e3a6d593067f depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 license: MIT license_family: MIT - size: 72255 - timestamp: 1734373823254 -- conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-he65b83e_0.conda - sha256: 20c1e685e7409bb82c819ba55b9f7d9a654e8e6d597081581493badb7464520e - md5: 120f8f7ba6a8defb59f4253447db4bb4 + size: 72783 + timestamp: 1745260463421 +- conda: https://conda.anaconda.org/conda-forge/osx-64/libdeflate-1.23-hcc1b750_0.conda + sha256: 9105bb8656649f9676008f95b0f058d2b8ef598e058190dcae1678d6ebc1f9b3 + md5: 5d3507f22dda24f7d9a79325ad313e44 depends: - __osx >=10.13 license: MIT license_family: MIT - size: 69309 - timestamp: 1734374105905 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-hec38601_0.conda - sha256: 887c02deaed6d583459eba6367023e36d8761085b2f7126e389424f57155da53 - md5: 1d8b9588be14e71df38c525767a1ac30 + size: 69911 + timestamp: 1745260530684 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libdeflate-1.23-h5773f1b_0.conda + sha256: ebc06154e9a2085e8c9edf81f8f5196b73a1698e18ac6386c9b43fb426103327 + md5: 4dc332b504166d7f89e4b3b18ab5e6ea depends: - __osx >=11.0 license: MIT license_family: MIT - size: 54132 - timestamp: 1734373971372 -- conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h9062f6e_0.conda - sha256: 96c47725a8258159295996ea2758fa0ff9bea330e72b59641642e16be8427ce8 - md5: a9624935147a25b06013099d3038e467 + size: 54685 + timestamp: 1745260666631 +- conda: https://conda.anaconda.org/conda-forge/win-64/libdeflate-1.23-h76ddb4d_0.conda + sha256: 881244050587dc658078ee45dfc792ecb458bbb1fdc861da67948d747b117dc2 + md5: 34f03138e46543944d4d7f8538048842 depends: - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: MIT license_family: MIT - size: 155723 - timestamp: 1734374084110 + size: 155548 + timestamp: 1745260818985 - conda: https://conda.anaconda.org/conda-forge/linux-64/libdrm-2.4.124-hb9d3cd8_0.conda sha256: f0d5ffbdf3903a7840184d14c14154b503e1a96767c328f61d99ad24b6963e52 md5: 8bc89311041d7fcb510238cf0848ccae @@ -15631,6 +16078,89 @@ packages: license_family: MIT size: 44978 timestamp: 1743435053850 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype-2.13.3-ha770c72_1.conda + sha256: 7be9b3dac469fe3c6146ff24398b685804dfc7a1de37607b84abd076f57cc115 + md5: 51f5be229d83ecd401fb369ab96ae669 + depends: + - libfreetype6 >=2.13.3 + license: GPL-2.0-only OR FTL + size: 7693 + timestamp: 1745369988361 +- conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype-2.13.3-h694c41f_1.conda + sha256: afe0e2396844c8cfdd6256ac84cabc9af823b1727f704c137b030b85839537a6 + md5: 07c8d3fbbe907f32014b121834b36dd5 + depends: + - libfreetype6 >=2.13.3 + license: GPL-2.0-only OR FTL + size: 7805 + timestamp: 1745370212559 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype-2.13.3-hce30654_1.conda + sha256: 1f8c16703fe333cdc2639f7cdaf677ac2120843453222944a7c6c85ec342903c + md5: d06282e08e55b752627a707d58779b8f + depends: + - libfreetype6 >=2.13.3 + license: GPL-2.0-only OR FTL + size: 7813 + timestamp: 1745370144506 +- conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype-2.13.3-h57928b3_1.conda + sha256: e5bc7d0a8d11b7b234da4fcd9d78f297f7dec3fec8bd06108fd3ac7b2722e32e + md5: 410ba2c8e7bdb278dfbb5d40220e39d2 + depends: + - libfreetype6 >=2.13.3 + license: GPL-2.0-only OR FTL + size: 8159 + timestamp: 1745370227235 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libfreetype6-2.13.3-h48d6fc4_1.conda + sha256: 7759bd5c31efe5fbc36a7a1f8ca5244c2eabdbeb8fc1bee4b99cf989f35c7d81 + md5: 3c255be50a506c50765a93a6644f32fe + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libpng >=1.6.47,<1.7.0a0 + - libzlib >=1.3.1,<2.0a0 + constrains: + - freetype >=2.13.3 + license: GPL-2.0-only OR FTL + size: 380134 + timestamp: 1745369987697 +- conda: https://conda.anaconda.org/conda-forge/osx-64/libfreetype6-2.13.3-h40dfd5c_1.conda + sha256: 058165962aa64fc5a6955593212c0e1ea42ca6d6dba60ee61dff612d4c3818d7 + md5: c76e6f421a0e95c282142f820835e186 + depends: + - __osx >=10.13 + - libpng >=1.6.47,<1.7.0a0 + - libzlib >=1.3.1,<2.0a0 + constrains: + - freetype >=2.13.3 + license: GPL-2.0-only OR FTL + size: 357654 + timestamp: 1745370210187 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libfreetype6-2.13.3-h1d14073_1.conda + sha256: c278df049b1a071841aa0aca140a338d087ea594e07dcf8a871d2cfe0e330e75 + md5: b163d446c55872ef60530231879908b9 + depends: + - __osx >=11.0 + - libpng >=1.6.47,<1.7.0a0 + - libzlib >=1.3.1,<2.0a0 + constrains: + - freetype >=2.13.3 + license: GPL-2.0-only OR FTL + size: 333529 + timestamp: 1745370142848 +- conda: https://conda.anaconda.org/conda-forge/win-64/libfreetype6-2.13.3-h0b5ce68_1.conda + sha256: 61308653e7758ff36f80a60d598054168a1389ddfbac46d7864c415fafe18e69 + md5: a84b7d1a13060a9372bea961a8131dbc + depends: + - libpng >=1.6.47,<1.7.0a0 + - libzlib >=1.3.1,<2.0a0 + - ucrt >=10.0.20348.0 + - vc >=14.2,<15 + - vc14_runtime >=14.29.30139 + constrains: + - freetype >=2.13.3 + license: GPL-2.0-only OR FTL + size: 337007 + timestamp: 1745370226578 - conda: https://conda.anaconda.org/conda-forge/linux-64/libgcc-14.2.0-h767d61c_2.conda sha256: 3a572d031cb86deb541d15c1875aaa097baefc0c580b54dc61f5edab99215792 md5: ef504d1acbd74b7cc6849ef8af47dd03 @@ -15687,42 +16217,24 @@ packages: license_family: GPL size: 53733 timestamp: 1740240690977 -- conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-13_2_0_h97931a8_3.conda - sha256: 4874422e567b68334705c135c17e5acdca1404de8255673ce30ad3510e00be0d - md5: 0b6e23a012ee7a9a5f6b244f5a92c1d5 +- conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-14.2.0-hef36b68_105.conda + sha256: 984040aa98dedcfbe1cf59befd73740e30d368b96cbfa17c002297e67fa5af23 + md5: 6b27baf030f5d6603713c7e72d3f6b9a depends: - - libgfortran5 13.2.0 h2873a65_3 + - libgfortran5 14.2.0 h58528f3_105 license: GPL-3.0-only WITH GCC-exception-3.1 license_family: GPL - size: 110106 - timestamp: 1707328956438 -- conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran-5.0.0-14_2_0_h51e75f0_1.conda - sha256: fcf482d36f4ea05b6183813ff59c893998e568d48cbc82a7ad5f4c3abd35ec6a - md5: e8b6b4962db050d7923e2cee3efff446 + size: 155635 + timestamp: 1743911593527 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-14.2.0-heb5dd2a_105.conda + sha256: 6ca48762c330d1cdbdaa450f197ccc16ffb7181af50d112b4ccf390223d916a1 + md5: ad35937216e65cfeecd828979ee5e9e6 depends: - - libgfortran5 14.2.0 h51e75f0_1 + - libgfortran5 14.2.0 h2c44a93_105 license: GPL-3.0-only WITH GCC-exception-3.1 license_family: GPL - size: 155695 - timestamp: 1742434157938 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-13_2_0_hd922786_3.conda - sha256: 44e541b4821c96b28b27fef5630883a60ce4fee91fd9c79f25a199f8f73f337b - md5: 4a55d9e169114b2b90d3ec4604cd7bbf - depends: - - libgfortran5 13.2.0 hf226fd6_3 - license: GPL-3.0-only WITH GCC-exception-3.1 - license_family: GPL - size: 110233 - timestamp: 1707330749033 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran-5.0.0-14_2_0_h6c33f7e_1.conda - sha256: 00adc502de159fef380cc16150ec328309910e241b4a465500f2084e6c9646dd - md5: d0e8a9e0efd41b9821833d5bbfd7e653 - depends: - - libgfortran5 14.2.0 h6c33f7e_1 - license: GPL-3.0-only WITH GCC-exception-3.1 - license_family: GPL - size: 156084 - timestamp: 1742435107459 + size: 155474 + timestamp: 1743913530958 - conda: https://conda.anaconda.org/conda-forge/linux-64/libgfortran-ng-14.2.0-h69a702a_2.conda sha256: 688a5968852e677d2a64974c8869ffb120eac21997ced7d15c599f152ef6857e md5: 4056c857af1a99ee50589a941059ec55 @@ -15744,50 +16256,28 @@ packages: license_family: GPL size: 1461978 timestamp: 1740240671964 -- conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-13.2.0-h2873a65_3.conda - sha256: da3db4b947e30aec7596a3ef92200d17e774cccbbf7efc47802529a4ca5ca31b - md5: e4fb4d23ec2870ff3c40d10afe305aec - depends: - - llvm-openmp >=8.0.0 - constrains: - - libgfortran 5.0.0 13_2_0_*_3 - license: GPL-3.0-only WITH GCC-exception-3.1 - license_family: GPL - size: 1571379 - timestamp: 1707328880361 -- conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h51e75f0_1.conda - sha256: 4f0b4bed6a3dae0e91c74f84cfc4adde3dbd8bdcf5307ae53489cedfbf1509df - md5: 9e089ae71e7caca1565af0b632027d4d - depends: - - llvm-openmp >=8.0.0 - constrains: - - libgfortran 5.0.0 14_2_0_*_1 - license: GPL-3.0-only WITH GCC-exception-3.1 - license_family: GPL - size: 1223645 - timestamp: 1742433555937 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-13.2.0-hf226fd6_3.conda - sha256: bafc679eedb468a86aa4636061c55966186399ee0a04b605920d208d97ac579a - md5: 66ac81d54e95c534ae488726c1f698ea +- conda: https://conda.anaconda.org/conda-forge/osx-64/libgfortran5-14.2.0-h58528f3_105.conda + sha256: 02fc48106e1ca65cf7de15f58ec567f866f6e8e9dcced157d0cff89f0768bb59 + md5: 94560312ff3c78225bed62ab59854c31 depends: - llvm-openmp >=8.0.0 constrains: - - libgfortran 5.0.0 13_2_0_*_3 + - libgfortran 14.2.0 license: GPL-3.0-only WITH GCC-exception-3.1 license_family: GPL - size: 997381 - timestamp: 1707330687590 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h6c33f7e_1.conda - sha256: a578ecffb79d81eb67bbdeac7bcddbfea5908393d51b0c4a9a461e73a3524274 - md5: fa7750a7197063eed8fdf8e74e148d03 + size: 1224385 + timestamp: 1743911552203 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libgfortran5-14.2.0-h2c44a93_105.conda + sha256: de09987e1080f71e2285deec45ccb949c2620a672b375029534fbb878e471b22 + md5: 06f35a3b1479ec55036e1c9872f97f2c depends: - llvm-openmp >=8.0.0 constrains: - - libgfortran 5.0.0 14_2_0_*_1 + - libgfortran 14.2.0 license: GPL-3.0-only WITH GCC-exception-3.1 license_family: GPL - size: 806707 - timestamp: 1742434439767 + size: 806283 + timestamp: 1743913488925 - conda: https://conda.anaconda.org/conda-forge/linux-64/libgl-1.7.0-ha4b6fd6_2.conda sha256: dc2752241fa3d9e40ce552c1942d0a4b5eeb93740c9723873f6fcf8d39ef8d2d md5: 928b8be80851f5d8ffb016f9c81dae7a @@ -15798,41 +16288,56 @@ packages: license: LicenseRef-libglvnd size: 134712 timestamp: 1731330998354 -- conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.0-h2ff4ddf_0.conda - sha256: 8e8737ca776d897d81a97e3de28c4bb33c45b5877bbe202b9b0ad2f61ca39397 - md5: 40cdeafb789a5513415f7bdbef053cf5 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.1-h2ff4ddf_0.conda + sha256: 18e354d30a60441b0bf5fcbb125b6b22fd0df179620ae834e2533d44d1598211 + md5: 0305434da649d4fb48a425e588b79ea6 depends: - __glibc >=2.17,<3.0.a0 - - libffi >=3.4,<4.0a0 + - libffi >=3.4.6,<3.5.0a0 - libgcc >=13 - libiconv >=1.18,<2.0a0 - libzlib >=1.3.1,<2.0a0 - pcre2 >=10.44,<10.45.0a0 constrains: - - glib 2.84.0 *_0 + - glib 2.84.1 *_0 license: LGPL-2.1-or-later - size: 3998765 - timestamp: 1743038881905 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.0-hdff4504_0.conda - sha256: 70a414faef075e11e7a51861e9e9c953d8373b0089070f98136a7578d8cda67e - md5: 86bdf23c648be3498294c4ab861e7090 + size: 3947789 + timestamp: 1743773764878 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libglib-2.84.2-h3618099_0.conda + sha256: a6b5cf4d443044bc9a0293dd12ca2015f0ebe5edfdc9c4abdde0b9947f9eb7bd + md5: 072ab14a02164b7c0c089055368ff776 + depends: + - __glibc >=2.17,<3.0.a0 + - libffi >=3.4.6,<3.5.0a0 + - libgcc >=13 + - libiconv >=1.18,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + - pcre2 >=10.45,<10.46.0a0 + constrains: + - glib 2.84.2 *_0 + license: LGPL-2.1-or-later + size: 3955066 + timestamp: 1747836671118 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libglib-2.84.2-hbec27ea_0.conda + sha256: 5fcc5e948706cc64e45e2454267f664ed5a1e84f15345aae04a41d852a879c0e + md5: 7bbb8961dca1b4b9f2b01b6e722111a7 depends: - __osx >=11.0 - - libffi >=3.4,<4.0a0 + - libffi >=3.4.6,<3.5.0a0 - libiconv >=1.18,<2.0a0 - - libintl >=0.23.1,<1.0a0 + - libintl >=0.24.1,<1.0a0 - libzlib >=1.3.1,<2.0a0 - - pcre2 >=10.44,<10.45.0a0 + - pcre2 >=10.45,<10.46.0a0 constrains: - - glib 2.84.0 *_0 + - glib 2.84.2 *_0 license: LGPL-2.1-or-later - size: 3698518 - timestamp: 1743039055882 -- conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.0-h7025463_0.conda - sha256: 0b4f9581e2dba58bc38cb00453e145140cf6230a56887ff1195e63e2b1e3f1c2 - md5: ea8df8a5c5c7adf4c03bf9e3db1637c3 + size: 3666180 + timestamp: 1747837044507 +- conda: https://conda.anaconda.org/conda-forge/win-64/libglib-2.84.1-h7025463_0.conda + sha256: 75a35a0134c7b2f3f41dbf24faa417be6a98a70db23dc1225b0c74ea45c0ce61 + md5: 6cbaea9075a4f007eb7d0a90bb9a2a09 depends: - - libffi >=3.4,<4.0a0 + - libffi >=3.4.6,<3.5.0a0 - libiconv >=1.18,<2.0a0 - libintl >=0.22.5,<1.0a0 - libzlib >=1.3.1,<2.0a0 @@ -15841,10 +16346,10 @@ packages: - vc >=14.2,<15 - vc14_runtime >=14.29.30139 constrains: - - glib 2.84.0 *_0 + - glib 2.84.1 *_0 license: LGPL-2.1-or-later - size: 3842095 - timestamp: 1743039211561 + size: 3806534 + timestamp: 1743774256525 - conda: https://conda.anaconda.org/conda-forge/linux-64/libglvnd-1.7.0-ha4b6fd6_2.conda sha256: 1175f8a7a0c68b7f81962699751bb6574e6f07db4c9f72825f978e3016f46850 md5: 434ca7e50e40f4918ab701e3facd59a0 @@ -15900,7 +16405,7 @@ packages: md5: 524282b2c46c9dedf051b3bc2ae05494 depends: - libcxx >=11.1.0 - - libgfortran 5.* + - libgfortran >=5 - libgfortran5 >=9.3.0 license: BSD-3-Clause license_family: BSD @@ -15911,7 +16416,7 @@ packages: md5: 37ca71a16015b17397da4a5e6883f66f depends: - libcxx >=11.1.0 - - libgfortran 5.* + - libgfortran >=5 - libgfortran5 >=11.0.1.dev0 license: BSD-3-Clause license_family: BSD @@ -15934,7 +16439,7 @@ packages: - __glibc >=2.17,<3.0.a0 - libgcc >=13 - libstdcxx >=13 - - libxml2 >=2.13.4,<3.0a0 + - libxml2 >=2.13.4,<2.14.0a0 license: BSD-3-Clause license_family: BSD size: 2423200 @@ -15944,7 +16449,7 @@ packages: md5: b87a0ac5ab6495d8225db5dc72dd21cd depends: - libwinpthread >=12.0.0.r4.gg4f2fc60ca - - libxml2 >=2.13.4,<3.0a0 + - libxml2 >=2.13.4,<2.14.0a0 - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 @@ -16154,15 +16659,24 @@ packages: license_family: APACHE size: 820476 timestamp: 1725375885438 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.23.1-h493aca8_0.conda - sha256: 30d2a8a37070615a61777ce9317968b54c2197d04e9c6c2eea6cdb46e47f94dc - md5: 7b8faf3b5fc52744bda99c4cd1d6438d +- conda: https://conda.anaconda.org/conda-forge/osx-64/libintl-0.24.1-h27064b9_0.conda + sha256: f0a759b35784d5a31aeaf519f8f24019415321e62e52579a3ec854a413a1509d + md5: b3f498d87404090f731cb6a474045150 + depends: + - __osx >=10.13 + - libiconv >=1.18,<2.0a0 + license: LGPL-2.1-or-later + size: 97229 + timestamp: 1746229336518 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libintl-0.24.1-h493aca8_0.conda + sha256: fb6d211d9e75e6becfbf339d255ea01f7bd3a61fe6237b3dad740de1b74b3b81 + md5: 0dca9914f2722b773c863508723dfe6e depends: - __osx >=11.0 - - libiconv >=1.17,<2.0a0 + - libiconv >=1.18,<2.0a0 license: LGPL-2.1-or-later - size: 78921 - timestamp: 1739039271409 + size: 90547 + timestamp: 1746229257769 - conda: https://conda.anaconda.org/conda-forge/win-64/libintl-0.22.5-h5728263_3.conda sha256: c7e4600f28bcada8ea81456a6530c2329312519efcf0c886030ada38976b0511 md5: 2cf0cf76cc15d360dfa2f17fd6cf9772 @@ -16171,35 +16685,40 @@ packages: license: LGPL-2.1-or-later size: 95568 timestamp: 1723629479451 -- conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.0.0-hd590300_1.conda - sha256: b954e09b7e49c2f2433d6f3bb73868eda5e378278b0f8c1dd10a7ef090e14f2f - md5: ea25936bb4080d843790b586850f82b8 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libjpeg-turbo-3.1.0-hb9d3cd8_0.conda + sha256: 98b399287e27768bf79d48faba8a99a2289748c65cd342ca21033fab1860d4a4 + md5: 9fa334557db9f63da6c9285fd2a48638 depends: - - libgcc-ng >=12 + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 constrains: - jpeg <0.0.0a license: IJG AND BSD-3-Clause AND Zlib - size: 618575 - timestamp: 1694474974816 -- conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.0.0-h0dc2134_1.conda - sha256: d9572fd1024adc374aae7c247d0f29fdf4b122f1e3586fe62acc18067f40d02f - md5: 72507f8e3961bc968af17435060b6dd6 + size: 628947 + timestamp: 1745268527144 +- conda: https://conda.anaconda.org/conda-forge/osx-64/libjpeg-turbo-3.1.0-h6e16a3a_0.conda + sha256: 9c0009389c1439ec96a08e3bf7731ac6f0eab794e0a133096556a9ae10be9c27 + md5: 87537967e6de2f885a9fcebd42b7cb10 + depends: + - __osx >=10.13 constrains: - jpeg <0.0.0a license: IJG AND BSD-3-Clause AND Zlib - size: 579748 - timestamp: 1694475265912 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.0.0-hb547adb_1.conda - sha256: a42054eaa38e84fc1e5ab443facac4bbc9d1b6b6f23f54b7bf4f1eb687e1d993 - md5: 3ff1e053dc3a2b8e36b9bfa4256a58d1 + size: 586456 + timestamp: 1745268522731 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libjpeg-turbo-3.1.0-h5505292_0.conda + sha256: 78df2574fa6aa5b6f5fc367c03192f8ddf8e27dc23641468d54e031ff560b9d4 + md5: 01caa4fbcaf0e6b08b3aef1151e91745 + depends: + - __osx >=11.0 constrains: - jpeg <0.0.0a license: IJG AND BSD-3-Clause AND Zlib - size: 547541 - timestamp: 1694475104253 -- conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.0.0-hcfcfb64_1.conda - sha256: 4e7808e3098b4b4ed7e287f63bb24f9045cc4d95bfd39f0db870fc2837d74dff - md5: 3f1b948619c45b1ca714d60c7389092c + size: 553624 + timestamp: 1745268405713 +- conda: https://conda.anaconda.org/conda-forge/win-64/libjpeg-turbo-3.1.0-h2466b09_0.conda + sha256: e61b0adef3028b51251124e43eb6edf724c67c0f6736f1628b02511480ac354e + md5: 7c51d27540389de84852daa1cdb9c63c depends: - ucrt >=10.0.20348.0 - vc >=14.2,<15 @@ -16207,8 +16726,8 @@ packages: constrains: - jpeg <0.0.0a license: IJG AND BSD-3-Clause AND Zlib - size: 822966 - timestamp: 1694475223854 + size: 838154 + timestamp: 1745268437136 - conda: https://conda.anaconda.org/conda-forge/linux-64/liblapack-3.9.0-31_h7ac8fdf_openblas.conda build_number: 31 sha256: f583661921456e798aba10972a8abbd9d33571c655c1f66eff450edc9cbefcf3 @@ -16265,91 +16784,105 @@ packages: license_family: BSD size: 3732648 timestamp: 1740088548986 -- conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-hc29ff6c_3.conda - sha256: c488d96dcd0b2db0438b9ec7ea92627c1c36aa21491ebcd5cc87a9c58aa0a612 - md5: a04c2fc058fd6b0630c1a2faad322676 +- conda: https://conda.anaconda.org/conda-forge/osx-64/libllvm18-18.1.8-default_h3571c67_5.conda + sha256: 6ea08f3343727d171981be54e92117bea0da4199f227efe47c605e0ee345cf33 + md5: 01dd8559b569ad39b64fef0a61ded1e9 depends: - __osx >=10.13 - libcxx >=18 - - libxml2 >=2.13.5,<3.0a0 + - libxml2 >=2.14.0,<2.15.0a0 - libzlib >=1.3.1,<2.0a0 - - zstd >=1.5.6,<1.6.0a0 + - zstd >=1.5.7,<1.6.0a0 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 27771340 - timestamp: 1737837075440 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-hc4b4ae8_3.conda - sha256: eaf337e7323555705ef8fad64778de506828d3b6deab2493170c6fe8ad4b7a76 - md5: 202596038a5dc079ef688bd7e17ffec1 + size: 27768928 + timestamp: 1743989832901 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libllvm18-18.1.8-default_hb458b26_5.conda + sha256: fbc2dd45ef620fd6282a5ad6a25260df921760d717ac727bf62e7702279ec9cc + md5: ce107cf167da0a1abbccc0c8f979ef59 depends: - __osx >=11.0 - libcxx >=18 - - libxml2 >=2.13.5,<3.0a0 + - libxml2 >=2.14.0,<2.15.0a0 - libzlib >=1.3.1,<2.0a0 - - zstd >=1.5.6,<1.6.0a0 + - zstd >=1.5.7,<1.6.0a0 + license: Apache-2.0 WITH LLVM-exception + license_family: Apache + size: 25982718 + timestamp: 1743989933062 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.4-he9d0ab4_0.conda + sha256: 56a375dc36df1a4e2061e30ebbacbc9599a11277422a9a3145fd228f772bab53 + md5: 96c33bbd084ef2b2463503fb7f1482ae + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libstdcxx >=13 + - libxml2 >=2.13.7,<2.14.0a0 + - libzlib >=1.3.1,<2.0a0 + - zstd >=1.5.7,<1.6.0a0 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 25986548 - timestamp: 1737837114740 -- conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.1-ha7bfdaf_0.conda - sha256: 28c4f97a5d03e6fcd7fef80ae415e28ca1bdbe9605172c926099bdb92b092b8b - md5: 2e234fb7d6eeb5c32eb5b256403b5795 + size: 43004201 + timestamp: 1746052658083 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libllvm20-20.1.5-he9d0ab4_0.conda + sha256: c8bb2c5744e4da00f63d53524897a6cb8fa0dcd7853a6ec6e084e8c5aff001d9 + md5: 8d2f5a2f019bd76ccba5eb771852d411 depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 - libstdcxx >=13 - - libxml2 >=2.13.6,<3.0a0 + - libxml2 >=2.13.8,<2.14.0a0 - libzlib >=1.3.1,<2.0a0 - zstd >=1.5.7,<1.6.0a0 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 42997088 - timestamp: 1742460259690 -- conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.6.4-hb9d3cd8_0.conda - sha256: cad52e10319ca4585bc37f0bc7cce99ec7c15dc9168e42ccb96b741b0a27db3f - md5: 42d5b6a0f30d3c10cd88cb8584fda1cb + size: 42996429 + timestamp: 1747318745242 +- conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-5.8.1-hb9d3cd8_0.conda + sha256: f4f21dfc54b08d462f707b771ecce3fa9bc702a2a05b55654f64154f48b141ef + md5: 0e87378639676987af32fee53ba32258 depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 license: 0BSD - size: 111357 - timestamp: 1738525339684 -- conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.6.4-hd471939_0.conda - sha256: a895b5b16468a6ed436f022d72ee52a657f9b58214b91fabfab6230e3592a6dd - md5: db9d7b0152613f097cdb61ccf9f70ef5 + size: 112709 + timestamp: 1743771086123 +- conda: https://conda.anaconda.org/conda-forge/osx-64/liblzma-5.8.1-hd471939_0.conda + sha256: 3369b8ef0b544d17aebc530a687c0480051e825e8ffcd001b1a5f594fe276159 + md5: 8e1197f652c67e87a9ece738d82cef4f depends: - __osx >=10.13 license: 0BSD - size: 103749 - timestamp: 1738525448522 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.6.4-h39f12f2_0.conda - sha256: 560c59d3834cc652a84fb45531bd335ad06e271b34ebc216e380a89798fe8e2c - md5: e3fd1f8320a100f2b210e690a57cd615 + size: 104689 + timestamp: 1743771137842 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/liblzma-5.8.1-h39f12f2_0.conda + sha256: 4291dde55ebe9868491dc29716b84ac3de21b8084cbd4d05c9eea79d206b8ab7 + md5: ba24e6f25225fea3d5b6912e2ac562f8 depends: - __osx >=11.0 license: 0BSD - size: 98945 - timestamp: 1738525462560 -- conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.6.4-h2466b09_0.conda - sha256: 3f552b0bdefdd1459ffc827ea3bf70a6a6920c7879d22b6bfd0d73015b55227b - md5: c48f6ad0ef0a555b27b233dfcab46a90 + size: 92295 + timestamp: 1743771392206 +- conda: https://conda.anaconda.org/conda-forge/win-64/liblzma-5.8.1-h2466b09_0.conda + sha256: 1477e9bff05318f3129d37be0e64c76cce0973c4b8c73d13a467d0b7f03d157c + md5: 8d5cb0016b645d6688e2ff57c5d51302 depends: - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: 0BSD - size: 104465 - timestamp: 1738525557254 -- conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-devel-5.6.4-hb9d3cd8_0.conda - sha256: 34928b36a3946902196a6786db80c8a4a97f6c9418838d67be90a1388479a682 - md5: 5ab1a0df19c8f3ec00d5e63458e0a420 + size: 104682 + timestamp: 1743771561515 +- conda: https://conda.anaconda.org/conda-forge/linux-64/liblzma-devel-5.8.1-hb9d3cd8_0.conda + sha256: 09738df1c1475cc7d35c4bf1062b8cdd4a110809aa49c240a4131e63609c974e + md5: 8f456db836b4d3d00d3b6a6cc47009d8 depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 - - liblzma 5.6.4 hb9d3cd8_0 + - liblzma 5.8.1 hb9d3cd8_0 license: 0BSD - size: 378821 - timestamp: 1738525353119 + size: 440913 + timestamp: 1743771104004 - conda: https://conda.anaconda.org/conda-forge/linux-64/libnghttp2-1.64.0-h161d5f1_0.conda sha256: b0f2b3695b13a989f75d8fd7f4778e1c7aabe3b36db83f0fe80b2cd812c0e975 md5: 19e57602824042dfd0446292ef90488b @@ -16433,7 +16966,7 @@ packages: md5: a30dc52b2a8b6300f17eaabd2f940d41 depends: - __osx >=10.13 - - libgfortran 5.* + - libgfortran >=5 - libgfortran5 >=13.2.0 - llvm-openmp >=18.1.8 constrains: @@ -16447,7 +16980,7 @@ packages: md5: 0cd1148c68f09027ee0b0f0179f77c30 depends: - __osx >=11.0 - - libgfortran 5.* + - libgfortran >=5 - libgfortran5 >=13.2.0 - llvm-openmp >=18.1.8 constrains: @@ -16548,20 +17081,20 @@ packages: license: zlib-acknowledgement size: 259332 timestamp: 1739953032676 -- conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-had7236b_0.conda - sha256: cf8a594b697de103025dcae2c917ec9c100609caf7c917a94c64a683cb1db1ac - md5: 7d717163d9dab337c65f2bf21a676b8f +- conda: https://conda.anaconda.org/conda-forge/win-64/libpng-1.6.47-h7a4582a_0.conda + sha256: e12c46ca882080d901392ae45e0e5a1c96fc3e5acd5cd1a23c2632eb7f024f26 + md5: ad620e92b82d2948bc019e029c574ebb depends: - libzlib >=1.3.1,<2.0a0 - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: zlib-acknowledgement - size: 346101 - timestamp: 1739953426806 -- conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_0.conda - sha256: 9fe3b323116a47631a9492f33f4d2c147a7f925bcd48c3fe986fdd2cc9ad3a6a - md5: d67f3f3c33344ff3e9ef5270001e9011 + size: 346511 + timestamp: 1745771984515 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.4-h27ae623_1.conda + sha256: ba2fd74be9d8c38489b9c6c18fa2fa87437dac76dfe285f86425c1b815e59fa2 + md5: 37fba334855ef3b51549308e61ed7a3d depends: - __glibc >=2.17,<3.0.a0 - icu >=75.1,<76.0a0 @@ -16570,8 +17103,21 @@ packages: - openldap >=2.6.9,<2.7.0a0 - openssl >=3.4.1,<4.0a0 license: PostgreSQL - size: 2607018 - timestamp: 1740071165371 + size: 2736307 + timestamp: 1743504522214 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libpq-17.5-h27ae623_0.conda + sha256: 2dbcef0db82e0e7b6895b6c0dadd3d36c607044c40290c7ca10656f3fca3166f + md5: 6458be24f09e1b034902ab44fe9de908 + depends: + - __glibc >=2.17,<3.0.a0 + - icu >=75.1,<76.0a0 + - krb5 >=1.21.3,<1.22.0a0 + - libgcc >=13 + - openldap >=2.6.9,<2.7.0a0 + - openssl >=3.5.0,<4.0a0 + license: PostgreSQL + size: 2680582 + timestamp: 1746743259857 - conda: https://conda.anaconda.org/conda-forge/linux-64/libqdldl-0.1.7-hcb278e6_0.conda sha256: 62230c93e8f7508a97e5b3a439b2b981eda9aa192cbc08497cbcca220ebf3acc md5: 9221c4cca4d44cf4103fbdd47595e3dd @@ -16642,7 +17188,7 @@ packages: depends: - __osx >=10.13 - bzip2 >=1.0.8,<2.0a0 - - libgfortran 5.* + - libgfortran >=5 - libgfortran5 >=13.2.0 - liblzma >=5.6.3,<6.0a0 - libzlib >=1.3.1,<2.0a0 @@ -16655,16 +17201,16 @@ packages: depends: - __osx >=11.0 - bzip2 >=1.0.8,<2.0a0 - - libgfortran 5.* + - libgfortran >=5 - libgfortran5 >=13.2.0 - liblzma >=5.6.3,<6.0a0 - libzlib >=1.3.1,<2.0a0 license: CECILL-C size: 273604 timestamp: 1737537249207 -- conda: https://conda.anaconda.org/conda-forge/linux-64/libsdformat-9.8.0-hd8b6797_7.conda - sha256: 6014592eea8aab739e78c9f42f84eed4e4398eca4f9c7952489c87f78891caf3 - md5: b5467506b0a352350fdd57c1a7b8d093 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libsdformat-9.8.0-hd8b6797_8.conda + sha256: de61509c9a3dd3eb2c810e04d83506d897e0cbe4c92202dde0e7d437e125dee6 + md5: 3b5399e9f2dc44474d8ae95bac67b76a depends: - __glibc >=2.17,<3.0.a0 - console_bridge >=1.0.2,<1.1.0a0 @@ -16675,11 +17221,11 @@ packages: - urdfdom >=4.0.1,<4.1.0a0 license: Apache-2.0 license_family: APACHE - size: 606466 - timestamp: 1730066867839 -- conda: https://conda.anaconda.org/conda-forge/osx-64/libsdformat-9.8.0-h5728b0d_7.conda - sha256: 2467eb7c2eddebbb3d138dfd693328eff8ca9cfbd746b07ff2e6ed355af29f57 - md5: ccbb8da6178cb7d983590c12cfd46a6c + size: 606654 + timestamp: 1743856393932 +- conda: https://conda.anaconda.org/conda-forge/osx-64/libsdformat-9.8.0-h5728b0d_8.conda + sha256: 1988f76eec1ad99c94b2394652b0f2cd1211619434de0f6acac4f969156c854e + md5: 730953295b8256dd5e9f27e9592c45c0 depends: - __osx >=10.14 - console_bridge >=1.0.2,<1.1.0a0 @@ -16689,11 +17235,11 @@ packages: - urdfdom >=4.0.1,<4.1.0a0 license: Apache-2.0 license_family: APACHE - size: 555453 - timestamp: 1730066751173 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsdformat-9.8.0-hc9d0b99_7.conda - sha256: 1380e7a689286c8122e3642a3168c324df14646becc36f263c8d1144fbc3f050 - md5: e968b315b3328b66bda42e9ded512cfb + size: 555505 + timestamp: 1743856452102 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libsdformat-9.8.0-hb05c10c_8.conda + sha256: 0c29f068304a3103ba063454830179e0902297405d95827adb5a05ba839b187f + md5: 8298d126f5f7fdff6049b7a500db8b5f depends: - __osx >=11.0 - console_bridge >=1.0.2,<1.1.0a0 @@ -16703,11 +17249,11 @@ packages: - urdfdom >=4.0.1,<4.1.0a0 license: Apache-2.0 license_family: APACHE - size: 533430 - timestamp: 1730066748265 -- conda: https://conda.anaconda.org/conda-forge/win-64/libsdformat-9.8.0-h9776664_7.conda - sha256: dfbd0dd3f51390d2aefb460dd09d3dd072e2886f1b4d75d9565f81ee70429446 - md5: c38180451f7309b32d1f3f88a6e8ebbe + size: 534372 + timestamp: 1743856500550 +- conda: https://conda.anaconda.org/conda-forge/win-64/libsdformat-9.8.0-h9776664_8.conda + sha256: e90abb262afbe538922aa0a8d2ea3bee4abb36c14ea4d5a81d0cf4d9a2bbcd3c + md5: 996d016631a552f7661fe681d798c8fc depends: - console_bridge >=1.0.2,<1.1.0a0 - libignition-math6 >=6.15.1,<7.0a0 @@ -16718,8 +17264,8 @@ packages: - vc14_runtime >=14.29.30139 license: Apache-2.0 license_family: APACHE - size: 547053 - timestamp: 1730067277759 + size: 548208 + timestamp: 1743857055872 - conda: https://conda.anaconda.org/conda-forge/linux-64/libsodium-1.0.20-h4ab18f5_0.conda sha256: 0105bd108f19ea8e6a78d2d994a6d4a8db16d19a41212070d2d1d48a63c34161 md5: a587892d3c13b6621a6091be690dbca2 @@ -16754,9 +17300,9 @@ packages: license: ISC size: 202344 timestamp: 1716828757533 -- conda: https://conda.anaconda.org/conda-forge/linux-64/libspral-2024.05.08-h2b245be_4.conda - sha256: 79ebc8f15625aede815019bd58c32ee8327c68e93a52adbdace68fbf7d64a288 - md5: 5e90da1c9b6f156657eaabcbd254e799 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libspral-2025.03.06-h39c1cf3_0.conda + sha256: a4a6b0473ce4d7f74ee4ab128fc5acb2745914981a6c61982d19aaf574d0f3d8 + md5: 23e84e1dc106ce0e073c0404f2f42a38 depends: - __glibc >=2.17,<3.0.a0 - _openmp_mutex >=4.5 @@ -16772,8 +17318,8 @@ packages: - metis >=5.1.0,<5.1.1.0a0 license: BSD-3-Clause license_family: BSD - size: 354213 - timestamp: 1730491842874 + size: 356755 + timestamp: 1741341231735 - conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.1-hee588c1_2.conda sha256: a086289bf75c33adc1daed3f1422024504ffb5c3c8b3285c49f025c29708ed16 md5: 962d6ac93c30b1dfc54c9cccafd1003e @@ -16784,6 +17330,16 @@ packages: license: Unlicense size: 918664 timestamp: 1742083674731 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libsqlite-3.49.2-hee588c1_0.conda + sha256: 525d4a0e24843f90b3ff1ed733f0a2e408aa6dd18b9d4f15465595e078e104a2 + md5: 93048463501053a00739215ea3f36324 + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libzlib >=1.3.1,<2.0a0 + license: Unlicense + size: 916313 + timestamp: 1746637007836 - conda: https://conda.anaconda.org/conda-forge/osx-64/libsqlite-3.49.1-hdb6dae5_2.conda sha256: 82695c9b16a702de615c8303387384c6ec5cf8b98e16458e5b1935b950e4ec38 md5: 1819e770584a7e83a81541d8253cbabe @@ -16812,52 +17368,52 @@ packages: license: Unlicense size: 1081292 timestamp: 1742083956001 -- conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hf672d98_0.conda - sha256: 0407ac9fda2bb67e11e357066eff144c845801d00b5f664efbc48813af1e7bb9 - md5: be2de152d8073ef1c01b7728475f2fe7 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libssh2-1.11.1-hcf80075_0.conda + sha256: fa39bfd69228a13e553bd24601332b7cfeb30ca11a3ca50bb028108fe90a7661 + md5: eecce068c7e4eddeb169591baac20ac4 depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 - libzlib >=1.3.1,<2.0a0 - - openssl >=3.4.0,<4.0a0 + - openssl >=3.5.0,<4.0a0 license: BSD-3-Clause license_family: BSD - size: 304278 - timestamp: 1732349402869 -- conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-h3dc7d44_0.conda - sha256: ef2a81c9a15080b996a37f0e1712881da90a710b234e63d8539d69892353de90 - md5: b1caec4561059e43a5d056684c5a2de0 + size: 304790 + timestamp: 1745608545575 +- conda: https://conda.anaconda.org/conda-forge/osx-64/libssh2-1.11.1-hed3591d_0.conda + sha256: 00654ba9e5f73aa1f75c1f69db34a19029e970a4aeb0fa8615934d8e9c369c3c + md5: a6cb15db1c2dc4d3a5f6cf3772e09e81 depends: - __osx >=10.13 - libzlib >=1.3.1,<2.0a0 - - openssl >=3.4.0,<4.0a0 + - openssl >=3.5.0,<4.0a0 license: BSD-3-Clause license_family: BSD - size: 283874 - timestamp: 1732349525684 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h9cc3647_0.conda - sha256: f7047c6ed44bcaeb04432e8c74da87591940d091b0a3940c0d884b7faa8062e9 - md5: ddc7194676c285513706e5fc64f214d7 + size: 284216 + timestamp: 1745608575796 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libssh2-1.11.1-h1590b86_0.conda + sha256: 8bfe837221390ffc6f111ecca24fa12d4a6325da0c8d131333d63d6c37f27e0a + md5: b68e8f66b94b44aaa8de4583d3d4cc40 depends: - libzlib >=1.3.1,<2.0a0 - - openssl >=3.4.0,<4.0a0 + - openssl >=3.5.0,<4.0a0 license: BSD-3-Clause license_family: BSD - size: 279028 - timestamp: 1732349599461 -- conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-he619c9f_0.conda - sha256: 4b3256bd2b4e4b3183005d3bd8826d651eccd1a4740b70625afa2b7e7123d191 - md5: af0cbf037dd614c34399b3b3e568c557 + size: 279193 + timestamp: 1745608793272 +- conda: https://conda.anaconda.org/conda-forge/win-64/libssh2-1.11.1-h9aa295b_0.conda + sha256: cbdf93898f2e27cefca5f3fe46519335d1fab25c4ea2a11b11502ff63e602c09 + md5: 9dce2f112bfd3400f4f432b3d0ac07b2 depends: - libzlib >=1.3.1,<2.0a0 - - openssl >=3.4.0,<4.0a0 + - openssl >=3.5.0,<4.0a0 - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: BSD-3-Clause license_family: BSD - size: 291889 - timestamp: 1732349796504 + size: 292785 + timestamp: 1745608759342 - conda: https://conda.anaconda.org/conda-forge/linux-64/libstdcxx-14.2.0-h8f9b012_2.conda sha256: 8f5bd92e4a24e1d35ba015c5252e8f818898478cb3bc50bd8b12ab54707dc4da md5: a78c856b6dc6bf4ea8daeb9beaaa3fb0 @@ -16886,71 +17442,71 @@ packages: license_family: GPL size: 53830 timestamp: 1740240722530 -- conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_3.conda - sha256: b224e16b88d76ea95e4af56e2bc638c603bd26a770b98d117d04541d3aafa002 - md5: 0ea6510969e1296cc19966fad481f6de +- conda: https://conda.anaconda.org/conda-forge/linux-64/libtiff-4.7.0-hd9ff511_4.conda + sha256: 7480613af15795281bd338a4d3d2ca148f9c2ecafc967b9cc233e78ba2fe4a6d + md5: 6c1028898cf3a2032d9af46689e1b81a depends: - __glibc >=2.17,<3.0.a0 - lerc >=4.0.0,<5.0a0 - libdeflate >=1.23,<1.24.0a0 - libgcc >=13 - - libjpeg-turbo >=3.0.0,<4.0a0 - - liblzma >=5.6.3,<6.0a0 + - libjpeg-turbo >=3.1.0,<4.0a0 + - liblzma >=5.8.1,<6.0a0 - libstdcxx >=13 - - libwebp-base >=1.4.0,<2.0a0 + - libwebp-base >=1.5.0,<2.0a0 - libzlib >=1.3.1,<2.0a0 - - zstd >=1.5.6,<1.6.0a0 + - zstd >=1.5.7,<1.6.0a0 license: HPND - size: 428173 - timestamp: 1734398813264 -- conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_3.conda - sha256: bb50df7cfc1acb11eae63c5f4fdc251d381cda96bf02c086c3202c83a5200032 - md5: 6f2f9df7b093d6b33bc0c334acc7d2d9 + size: 429381 + timestamp: 1745372713285 +- conda: https://conda.anaconda.org/conda-forge/osx-64/libtiff-4.7.0-hb77a491_4.conda + sha256: 2bf372fb7da33a25b3c555e2f40ffab5f6b1f2a01a0c14a0a3b2f4eaa372564d + md5: b36d793dd65b28e3aeaa3a77abe71678 depends: - __osx >=10.13 - lerc >=4.0.0,<5.0a0 - libcxx >=18 - libdeflate >=1.23,<1.24.0a0 - - libjpeg-turbo >=3.0.0,<4.0a0 - - liblzma >=5.6.3,<6.0a0 - - libwebp-base >=1.4.0,<2.0a0 + - libjpeg-turbo >=3.1.0,<4.0a0 + - liblzma >=5.8.1,<6.0a0 + - libwebp-base >=1.5.0,<2.0a0 - libzlib >=1.3.1,<2.0a0 - - zstd >=1.5.6,<1.6.0a0 + - zstd >=1.5.7,<1.6.0a0 license: HPND - size: 400099 - timestamp: 1734398943635 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_3.conda - sha256: 91417846157e04992801438a496b151df89604b2e7c6775d6f701fcd0cbed5ae - md5: a5d084a957563e614ec0c0196d890654 + size: 400931 + timestamp: 1745372828096 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libtiff-4.7.0-h551f018_4.conda + sha256: 5d3f7a71b70f0d88470eda8e7b6afe3095d66708a70fb912e79d56fc30b35429 + md5: 717e02c4cca2a760438384d48b7cd1b9 depends: - __osx >=11.0 - lerc >=4.0.0,<5.0a0 - libcxx >=18 - libdeflate >=1.23,<1.24.0a0 - - libjpeg-turbo >=3.0.0,<4.0a0 - - liblzma >=5.6.3,<6.0a0 - - libwebp-base >=1.4.0,<2.0a0 + - libjpeg-turbo >=3.1.0,<4.0a0 + - liblzma >=5.8.1,<6.0a0 + - libwebp-base >=1.5.0,<2.0a0 - libzlib >=1.3.1,<2.0a0 - - zstd >=1.5.6,<1.6.0a0 + - zstd >=1.5.7,<1.6.0a0 license: HPND - size: 370600 - timestamp: 1734398863052 -- conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_3.conda - sha256: c363a8baba4ce12b8f01f0ab74fe8b0dc83facd89c6604f4a191084923682768 - md5: defed79ff7a9164ad40320e3f116a138 + size: 370898 + timestamp: 1745372834516 +- conda: https://conda.anaconda.org/conda-forge/win-64/libtiff-4.7.0-h797046b_4.conda + sha256: 3456e2a6dfe6c00fd0cda316f0cbb47caddf77f83d3ed4040b6ad17ec1610d2a + md5: 7d938ca70c64c5516767b4eae0a56172 depends: - lerc >=4.0.0,<5.0a0 - libdeflate >=1.23,<1.24.0a0 - - libjpeg-turbo >=3.0.0,<4.0a0 - - liblzma >=5.6.3,<6.0a0 + - libjpeg-turbo >=3.1.0,<4.0a0 + - liblzma >=5.8.1,<6.0a0 - libzlib >=1.3.1,<2.0a0 - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 - - zstd >=1.5.6,<1.6.0a0 + - zstd >=1.5.7,<1.6.0a0 license: HPND - size: 978878 - timestamp: 1734399004259 + size: 980597 + timestamp: 1745373037447 - conda: https://conda.anaconda.org/conda-forge/linux-64/libuuid-2.38.1-h0b41bf4_0.conda sha256: 787eb542f055a2b3de553614b25f09eefb0a0931b0c87dbcce6efdfd92f04f18 md5: 40b61aab5c7ba9ff276c41cfffe6b80b @@ -17116,64 +17672,93 @@ packages: license: LGPL-2.1-or-later size: 100393 timestamp: 1702724383534 -- conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.8.1-hc4a0caf_0.conda - sha256: 61a282353fcc512b5643ee58898130f5c7f8757c329a21fe407a3ef397d449eb - md5: e7e5b0652227d646b44abdcbd989da7b +- conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.0-h65c71a3_0.conda + sha256: e14b284ec7fe85522c81de383dd499bcd41cafb40442b795c3509e7c2c43c587 + md5: 14fbc598b68d4c6386978f7db09fc5ed depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 - libstdcxx >=13 - libxcb >=1.17.0,<2.0a0 - - libxml2 >=2.13.6,<3.0a0 + - libxml2 >=2.13.7,<2.14.0a0 - xkeyboard-config - xorg-libxau >=1.0.12,<2.0a0 license: MIT/X11 Derivative license_family: MIT - size: 644992 - timestamp: 1741762262672 -- conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h8d12d68_0.conda - sha256: 98f0a11d6b52801daaeefd00bfb38078f439554d64d2e277d92f658faefac366 - md5: 109427e5576d0ce9c42257c2421b1680 + size: 673170 + timestamp: 1745716284939 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libxkbcommon-1.9.2-h65c71a3_0.conda + sha256: 49bbeb112b3242f49e4bb1ac8af2d08c447bf3929b475915d67f02628643ed55 + md5: d045b1d878031eb497cab44e6392b1df + depends: + - __glibc >=2.17,<3.0.a0 + - libgcc >=13 + - libstdcxx >=13 + - libxcb >=1.17.0,<2.0a0 + - libxml2 >=2.13.7,<2.14.0a0 + - xkeyboard-config + - xorg-libxau >=1.0.12,<2.0a0 + license: MIT/X11 Derivative + license_family: MIT + size: 675947 + timestamp: 1746581272970 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.7-h4bc477f_1.conda + sha256: 01c471d9912c482297fd8e83afc193101ff4504c72361b6aec6d07f2fa379263 + md5: ad1f1f8238834cd3c88ceeaee8da444a depends: - __glibc >=2.17,<3.0.a0 - icu >=75.1,<76.0a0 - libgcc >=13 - libiconv >=1.18,<2.0a0 - - liblzma >=5.6.4,<6.0a0 + - liblzma >=5.8.1,<6.0a0 - libzlib >=1.3.1,<2.0a0 license: MIT license_family: MIT - size: 691755 - timestamp: 1743091084063 -- conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.13.7-hebb159f_0.conda - sha256: 21119df0a2267a9fc52d67bdf55e5449a2cdcc799865e2f90ab734fd61234ed8 - md5: 45786cf4067df4fbe9faf3d1c25d3acf + size: 692101 + timestamp: 1743794568181 +- conda: https://conda.anaconda.org/conda-forge/linux-64/libxml2-2.13.8-h4bc477f_0.conda + sha256: b0b3a96791fa8bb4ec030295e8c8bf2d3278f33c0f9ad540e73b5e538e6268e7 + md5: 14dbe05b929e329dbaa6f2d0aa19466d + depends: + - __glibc >=2.17,<3.0.a0 + - icu >=75.1,<76.0a0 + - libgcc >=13 + - libiconv >=1.18,<2.0a0 + - liblzma >=5.8.1,<6.0a0 + - libzlib >=1.3.1,<2.0a0 + license: MIT + license_family: MIT + size: 690864 + timestamp: 1746634244154 +- conda: https://conda.anaconda.org/conda-forge/osx-64/libxml2-2.14.2-h8c082e5_0.conda + sha256: b0059624fbf71ae14fa74030e3e1b061f0422caf3255eaa82aa6eb3e650a8392 + md5: 4adac80accf99fa253f0620444ad01fb depends: - __osx >=10.13 - icu >=75.1,<76.0a0 - libiconv >=1.18,<2.0a0 - - liblzma >=5.6.4,<6.0a0 + - liblzma >=5.8.1,<6.0a0 - libzlib >=1.3.1,<2.0a0 license: MIT license_family: MIT - size: 609769 - timestamp: 1743091248758 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.13.7-h178c5d8_0.conda - sha256: d3ddc9ae8a5474f16f213ca41b3eda394e1eb1253f3ac85d3c6c99adcfb226d8 - md5: aa838a099ba09429cb80cc876b032ac4 + size: 592975 + timestamp: 1744989650507 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/libxml2-2.14.2-h19f518e_0.conda + sha256: 03446d4d827efbfc3dda13cc9ea9683dc7e2b228b1be8a35eca0f4c303eeab3c + md5: 61c97075c8550ba33f2dd890c14d7bdf depends: - __osx >=11.0 - icu >=75.1,<76.0a0 - libiconv >=1.18,<2.0a0 - - liblzma >=5.6.4,<6.0a0 + - liblzma >=5.8.1,<6.0a0 - libzlib >=1.3.1,<2.0a0 license: MIT license_family: MIT - size: 582736 - timestamp: 1743091513375 -- conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-he286e8c_0.conda - sha256: 99182f93f1e7b678534df5f07ff94d7bf13a51386050f8fa9411fec764d0f39f - md5: aec4cf455e4c6cc2644abb348de7ff20 + size: 564710 + timestamp: 1744989628621 +- conda: https://conda.anaconda.org/conda-forge/win-64/libxml2-2.13.7-h442d1da_1.conda + sha256: 0a013527f784f4702dc18460070d8ec79d1ebb5087dd9e678d6afbeaca68d2ac + md5: c14ff7f05e57489df9244917d2b55763 depends: - libiconv >=1.18,<2.0a0 - libzlib >=1.3.1,<2.0a0 @@ -17182,14 +17767,14 @@ packages: - vc14_runtime >=14.29.30139 license: MIT license_family: MIT - size: 1513490 - timestamp: 1743091551681 + size: 1513740 + timestamp: 1743795035107 - conda: https://conda.anaconda.org/conda-forge/linux-64/libxslt-1.1.39-h76b75d6_0.conda sha256: 684e9b67ef7b9ca0ca993762eeb39705ec58e2e7f958555c758da7ef416db9f3 md5: e71f31f8cfb0a91439f2086fc8aa0461 depends: - libgcc-ng >=12 - - libxml2 >=2.12.1,<3.0.0a0 + - libxml2 >=2.12.1,<2.14.0a0 license: MIT license_family: MIT size: 254297 @@ -17198,7 +17783,7 @@ packages: sha256: 6e3d99466d2076c35e7ac8dcdfe604da3d593f55b74a5b8e96c2b2ff63c247aa md5: 279ee338c9b34871d578cb3c7aa68f70 depends: - - libxml2 >=2.12.1,<3.0.0a0 + - libxml2 >=2.12.1,<2.14.0a0 - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 @@ -17253,105 +17838,105 @@ packages: license_family: Other size: 55476 timestamp: 1727963768015 -- conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.1-ha54dae1_1.conda - sha256: 2aeb63d771120fc7a8129ca81417c07cea09e3a0f47e097f1967a9c24888f5cf - md5: a1c6289fb8ae152b8cb53a535639c2c7 +- conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-openmp-20.1.3-ha54dae1_0.conda + sha256: deaba16df3fd04910255188dfbd2924d07476375a2e75472859b3c6a9fabd60b + md5: 16b29a91c8177de8910477ded0f80191 depends: - __osx >=10.13 constrains: - - openmp 20.1.1|20.1.1.* + - openmp 20.1.3|20.1.3.* license: Apache-2.0 WITH LLVM-exception license_family: APACHE - size: 306748 - timestamp: 1742533059358 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.1-hdb05f8b_1.conda - sha256: ae57041a588cd190cb55b602c1ed0ef3604ce28d3891515386a85693edd3c175 - md5: 97236e94c3a82367c5fe3a90557e6207 + size: 306693 + timestamp: 1744934078427 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-openmp-20.1.3-hdb05f8b_0.conda + sha256: daddebd6ebf2960bb3bae945230ed07b254f430642c739c00ebfb4a8c747a033 + md5: 9f2cc154dd184ff808c2c6afd21cb12c depends: - __osx >=11.0 constrains: - - openmp 20.1.1|20.1.1.* + - openmp 20.1.3|20.1.3.* license: Apache-2.0 WITH LLVM-exception license_family: APACHE - size: 282105 - timestamp: 1742533199558 -- conda: https://conda.anaconda.org/conda-forge/win-64/llvm-openmp-20.1.1-h30eaf37_1.conda - sha256: 6c090b43e11e2e02ee06c81e206fe6d664b35b3a5cd724033acde328f30f4581 - md5: b46bba57bbefe505ea795880563ae6a3 + size: 282301 + timestamp: 1744934108744 +- conda: https://conda.anaconda.org/conda-forge/win-64/llvm-openmp-20.1.3-h30eaf37_0.conda + sha256: 27326e733ce7ad87054a409c02b829594cc6276232b987eb135cd1a225eac669 + md5: 183c102075722a7aa993f94de1d135f2 depends: - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 constrains: - - openmp 20.1.1|20.1.1.* + - openmp 20.1.3|20.1.3.* license: Apache-2.0 WITH LLVM-exception license_family: APACHE - size: 293097 - timestamp: 1742533796976 -- conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-hc29ff6c_3.conda - sha256: 694ec5d1753cfff97785f3833173c1277d0ca0711d7c78ffc1011b40e7842741 - md5: 2585f8254d2ce24399a601e9b4e15652 + size: 293046 + timestamp: 1744934822760 +- conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18.1.8-default_h3571c67_5.conda + sha256: 084f1504b38608542f6ff816f9ff7e7ae9ec38b454604144e8ac0d0ec0415f82 + md5: cc07ff74d2547da1f1452c42b67bafd6 depends: - __osx >=10.13 - - libllvm18 18.1.8 hc29ff6c_3 - - libxml2 >=2.13.5,<3.0a0 + - libllvm18 18.1.8 default_h3571c67_5 + - libxml2 >=2.14.0,<2.15.0a0 - libzlib >=1.3.1,<2.0a0 - - llvm-tools-18 18.1.8 hc29ff6c_3 - - zstd >=1.5.6,<1.6.0a0 + - llvm-tools-18 18.1.8 default_h3571c67_5 + - zstd >=1.5.7,<1.6.0a0 constrains: - - clang 18.1.8 - llvm 18.1.8 - clang-tools 18.1.8 - llvmdev 18.1.8 + - clang 18.1.8 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 88081 - timestamp: 1737837724397 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-hc4b4ae8_3.conda - sha256: 3bdd318088fbd425d933f40f149700793094348b47326faa70694fc5cfbffc0e - md5: 6ede59b3835d443abdeace7cad57c8c4 + size: 92923 + timestamp: 1743990036185 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18.1.8-default_hb458b26_5.conda + sha256: caa3f3fcc12b84e815a431706634eb850f05eaafc073ca1216e3fd87ec93134c + md5: 704b3d78d5cd327f3ce1372d07be01fd depends: - __osx >=11.0 - - libllvm18 18.1.8 hc4b4ae8_3 - - libxml2 >=2.13.5,<3.0a0 + - libllvm18 18.1.8 default_hb458b26_5 + - libxml2 >=2.14.0,<2.15.0a0 - libzlib >=1.3.1,<2.0a0 - - llvm-tools-18 18.1.8 hc4b4ae8_3 - - zstd >=1.5.6,<1.6.0a0 + - llvm-tools-18 18.1.8 default_hb458b26_5 + - zstd >=1.5.7,<1.6.0a0 constrains: - - clang-tools 18.1.8 - - llvmdev 18.1.8 - llvm 18.1.8 + - llvmdev 18.1.8 + - clang-tools 18.1.8 - clang 18.1.8 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 88046 - timestamp: 1737837646765 -- conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-hc29ff6c_3.conda - sha256: 7a302073bd476d19474272471a5ed7ecec935e65fe16bb3f35e3d5d070ce0466 - md5: 61dfcd8dc654e2ca399a214641ab549f + size: 92544 + timestamp: 1743990114058 +- conda: https://conda.anaconda.org/conda-forge/osx-64/llvm-tools-18-18.1.8-default_h3571c67_5.conda + sha256: 80e64944776325ebf5c30d3bd588bb29768c589418286ddfb277818a32161128 + md5: 4391981e855468ced32ca1940b3d7613 depends: - __osx >=10.13 - - libllvm18 18.1.8 hc29ff6c_3 - - libxml2 >=2.13.5,<3.0a0 + - libllvm18 18.1.8 default_h3571c67_5 + - libxml2 >=2.14.0,<2.15.0a0 - libzlib >=1.3.1,<2.0a0 - - zstd >=1.5.6,<1.6.0a0 + - zstd >=1.5.7,<1.6.0a0 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 25229705 - timestamp: 1737837655816 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-hc4b4ae8_3.conda - sha256: dae19f3596a8e0edadbf6c3037c8c5d9039d1a9ab57f384108580ec8fb89b06f - md5: 40b505161818b48957269998b4b41114 + size: 25076183 + timestamp: 1743989960006 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/llvm-tools-18-18.1.8-default_hb458b26_5.conda + sha256: 5e12079d864b5ab523cb18e3b9f37dd4764d67a2dfc4450b49b3ad8ebd9cd4d8 + md5: c8734b82ae16cf86b7f74140f09f9121 depends: - __osx >=11.0 - - libllvm18 18.1.8 hc4b4ae8_3 - - libxml2 >=2.13.5,<3.0a0 + - libllvm18 18.1.8 default_hb458b26_5 + - libxml2 >=2.14.0,<2.15.0a0 - libzlib >=1.3.1,<2.0a0 - - zstd >=1.5.6,<1.6.0a0 + - zstd >=1.5.7,<1.6.0a0 license: Apache-2.0 WITH LLVM-exception license_family: Apache - size: 23610271 - timestamp: 1737837584505 + size: 23239573 + timestamp: 1743990043950 - conda: https://conda.anaconda.org/conda-forge/linux-64/markupsafe-3.0.2-py312h178313f_1.conda sha256: 4a6bf68d2a2b669fecc9a4a009abd1cf8e72c2289522ff00d81b5a6e51ae78f5 md5: eb227c3e0bf58f5bd69c0532b157975b @@ -17824,12 +18409,12 @@ packages: license_family: LGPL size: 654269 timestamp: 1725748295260 -- conda: https://conda.anaconda.org/conda-forge/linux-64/mumps-include-5.7.3-h23d43cc_9.conda - sha256: 8985fbb75321b8fcb5f554a933ce614e917f27caae47b45a365c697c8cf65161 - md5: 02eb6294239f527356c90d9885a761a0 +- conda: https://conda.anaconda.org/conda-forge/linux-64/mumps-include-5.7.3-h82cca05_10.conda + sha256: c723d6e331444411db0a871958fc45621758595d12b4d6561fa20324535ce67a + md5: d6c7d8811686ed912ed4317831dd8c44 license: CECILL-C - size: 20782 - timestamp: 1742217626177 + size: 20755 + timestamp: 1745406913902 - conda: https://conda.anaconda.org/conda-forge/osx-64/mumps-include-5.7.3-h991c767_9.conda sha256: 302176ff8e6976bfbaf7dbe2fd72e6efa64cc1a5cabdaa90aa09db5f8d817f93 md5: c8e678da00c617ad078ff25e51d1c39c @@ -17864,7 +18449,7 @@ packages: depends: - mumps-include ==5.7.3 h991c767_9 - __osx >=10.13 - - libgfortran 5.* + - libgfortran >=5 - libgfortran5 >=13.2.0 - llvm-openmp >=18.1.8 - libblas >=3.9.0,<4.0a0 @@ -17881,7 +18466,7 @@ packages: md5: f4059b9b2cec69451420cd39ad518887 depends: - mumps-include ==5.7.3 h8c5b6c6_9 - - libgfortran 5.* + - libgfortran >=5 - libgfortran5 >=13.2.0 - llvm-openmp >=18.1.8 - __osx >=11.0 @@ -17894,9 +18479,9 @@ packages: license: CECILL-C size: 2689399 timestamp: 1742217819440 -- conda: https://conda.anaconda.org/conda-forge/win-64/mumps-seq-5.7.3-hbaa6519_9.conda - sha256: 953c384a1b37b93bf7a2ee39b1c5763887f4d63ed220b65362103d6e6b4440a4 - md5: 3a30d32db33cc226f7a2c78d485b0503 +- conda: https://conda.anaconda.org/conda-forge/win-64/mumps-seq-5.7.3-hbaa6519_10.conda + sha256: 6209255427a10879ca3731ec04eecf112e92b617af60c053073c8330928cb8ab + md5: 5c35d7fd93b2d7cddaa3ce881aadad83 depends: - vc >=14.2,<15 - vc14_runtime >=14.29.30139 @@ -17904,14 +18489,14 @@ packages: - vc >=14.2,<15 - vc14_runtime >=14.29.30139 - ucrt >=10.0.20348.0 - - llvm-openmp >=19.1.7 + - llvm-openmp >=20.1.3 - liblapack >=3.9.0,<4.0a0 - libblas >=3.9.0,<4.0a0 constrains: - libopenblas * *openmp* license: CECILL-C - size: 7876234 - timestamp: 1742217665164 + size: 7876066 + timestamp: 1745406938770 - conda: https://conda.anaconda.org/conda-forge/noarch/munkres-1.1.4-pyh9f0ad1d_0.tar.bz2 sha256: f86fb22b58e93d04b6f25e0d811b56797689d598788b59dcb47f59045b568306 md5: 2ba8498c1018c1e9c61eb99b973dfe19 @@ -17921,9 +18506,9 @@ packages: license_family: Apache size: 12452 timestamp: 1600387789153 -- conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.0.1-h266115a_5.conda - sha256: df9e895e8933ade7d362ab42bfe97e52a6b93d4d30df517324d60f6f35da1540 - md5: 6cf2f0c19b0b7ff3d5349c9826c26a9e +- conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-common-9.2.0-h266115a_0.conda + sha256: 571b6a2bffaf186ab92cdb06852fc5b6b5b7c6605de2b397fb13cfb0bb05c375 + md5: db22a0962c953e81a2a679ecb1fc6027 depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 @@ -17931,31 +18516,33 @@ packages: - openssl >=3.4.1,<4.0a0 license: GPL-2.0-or-later license_family: GPL - size: 633439 - timestamp: 1741896463089 -- conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.0.1-he0572af_5.conda - sha256: f37303d2fb453bbc47d1e09d56ef06b20570d0eaf375115707ffc1e609c9b508 - md5: d13932a2a61de7c0fb7864b592034a6e + size: 653477 + timestamp: 1743939199519 +- conda: https://conda.anaconda.org/conda-forge/linux-64/mysql-libs-9.2.0-he0572af_0.conda + sha256: 41cd870c04961591eabe7a43283d2bbc80a382e007f766edb8396ffd2bdfa418 + md5: 93340b072c393d23c4700a1d40565dca depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 - libstdcxx >=13 - libzlib >=1.3.1,<2.0a0 - - mysql-common 9.0.1 h266115a_5 + - mysql-common 9.2.0 h266115a_0 - openssl >=3.4.1,<4.0a0 - zstd >=1.5.7,<1.6.0a0 license: GPL-2.0-or-later license_family: GPL - size: 1371634 - timestamp: 1741896565103 -- conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.33.0-pyhd8ed1ab_0.conda - sha256: afc5b07659125cd4e2f30a734d56d683661b31541e66ed407abf9b10e1499d02 - md5: 54a495cf873b193aa17fb9517d0487c1 + size: 1371585 + timestamp: 1743939293417 +- conda: https://conda.anaconda.org/conda-forge/noarch/narwhals-1.37.0-pyh29332c3_0.conda + sha256: 95b289ce33c20d3d6156d5562105c74e99b651514fb4a1130c272a2e19e0dd1a + md5: f9ae420fa431efd502a5d5c4c1f08263 depends: - python >=3.9 + - python license: MIT - size: 190185 - timestamp: 1743462181837 + license_family: MIT + size: 211201 + timestamp: 1745863572641 - conda: https://conda.anaconda.org/conda-forge/linux-64/ncurses-6.5-h2d0b736_3.conda sha256: 3fde293232fa3fca98635e1167de6b7c7fda83caf24b9d6c91ec9eefb4f4d586 md5: 47e340acb35de30501a76c7c799c41d7 @@ -17981,47 +18568,51 @@ packages: license: X11 AND BSD-3-Clause size: 797030 timestamp: 1738196177597 -- conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-h297d8ca_0.conda - sha256: 40f7b76b07067935f8a5886aab0164067b7aa71eb5ad20b7278618c0c2c98e06 - md5: 3aa1c7e292afeff25a0091ddd7c69b72 +- conda: https://conda.anaconda.org/conda-forge/linux-64/ninja-1.12.1-hff21bea_1.conda + sha256: 1f2f7e26084971e87bfbb733f17d824ff3323ee9618fb713ae9932386da76aed + md5: 2322531904f27501ee19847b87ba7c64 depends: - - libgcc-ng >=12 - - libstdcxx-ng >=12 + - __glibc >=2.17,<3.0.a0 + - libstdcxx >=13 + - libgcc >=13 license: Apache-2.0 - license_family: Apache - size: 2198858 - timestamp: 1715440571685 -- conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-h3c5361c_0.conda - sha256: 230f11a2f73955b67550be09a0c1fd053772f5e01e98d5873547d63ebea73229 - md5: a0ebabd021c8191aeb82793fe43cfdcb + license_family: APACHE + size: 161883 + timestamp: 1745526264371 +- conda: https://conda.anaconda.org/conda-forge/osx-64/ninja-1.12.1-hd6aca1a_1.conda + sha256: 183bce1186a441b0e6aec8f5f7b85771fa6d36212422a0aaf7a15c0ef5e68cd3 + md5: 1cf196736676270fa876001901e4e1db depends: - __osx >=10.13 - - libcxx >=16 + - libcxx >=18 license: Apache-2.0 - license_family: Apache - size: 124942 - timestamp: 1715440780183 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h420ef59_0.conda - sha256: 11528acfa0f05d0c51639f6b09b51dc6611b801668449bb36c206c4b055be4f4 - md5: 9166c10405d41c95ffde8fcb8e5c3d51 + license_family: APACHE + size: 164846 + timestamp: 1745526274680 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/ninja-1.12.1-h177bc72_1.conda + sha256: 97fe845160df332063dfe9ed4386a32a6221c9add970fd37e161e301fd189088 + md5: bd8af7d5055f2263fc3aa282493d7e8f depends: + - libcxx >=18 - __osx >=11.0 - - libcxx >=16 license: Apache-2.0 - license_family: Apache - size: 112576 - timestamp: 1715440927034 -- conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_0.conda - sha256: b821cb72cb3ef08fab90a9bae899510e6cf3c23b5da6070d1ec30099dfe6a5be - md5: a557dde55343e03c68cd7e29e7f87279 + license_family: APACHE + size: 150474 + timestamp: 1745526261753 +- conda: https://conda.anaconda.org/conda-forge/win-64/ninja-1.12.1-hc790b64_1.conda + sha256: 40c546235c1ff8b452de309d63c86fb558ebaa145193b5c37a37f30aedc00332 + md5: 3974c522f3248d4a93e6940c463d2de7 depends: + - vc >=14.2,<15 + - vc14_runtime >=14.29.30139 - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 + - ucrt >=10.0.20348.0 license: Apache-2.0 - license_family: Apache - size: 285150 - timestamp: 1715441052517 + license_family: APACHE + size: 296368 + timestamp: 1745526338641 - conda: https://conda.anaconda.org/conda-forge/noarch/nodeenv-1.9.1-pyhd8ed1ab_1.conda sha256: 3636eec0e60466a00069b47ce94b6d88b01419b6577d8e393da44bb5bc8d3468 md5: 7ba3f09fceae6a120d664217e58fe686 @@ -18050,9 +18641,9 @@ packages: license_family: BSD size: 7925462 timestamp: 1732314760363 -- conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.4-py312h72c5963_0.conda - sha256: 47b3b2ae21efb227db7410f2701291cf47d816fd96461bdede415d7d75d8a436 - md5: 3f2871f111d8c0abd9c3150a8627507e +- conda: https://conda.anaconda.org/conda-forge/linux-64/numpy-2.2.5-py312h72c5963_0.conda + sha256: af293ba6f715983f71543ed0111e6bb77423d409c1d13062474601257c2eebca + md5: 505bcfc142b97010c162863c38d90016 depends: - __glibc >=2.17,<3.0.a0 - libblas >=3.9.0,<4.0a0 @@ -18066,8 +18657,8 @@ packages: - numpy-base <0a0 license: BSD-3-Clause license_family: BSD - size: 8424727 - timestamp: 1742255434709 + size: 8543883 + timestamp: 1745119461819 - conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.0.2-py39h277832c_1.conda sha256: 3b787112f7da8036c8aeac8ef6c4352496e168ad17f7564224dbab234cbdf8ba md5: d6c114b0d8987c209359b8eb1887a92a @@ -18085,9 +18676,9 @@ packages: license_family: BSD size: 6972004 timestamp: 1732314789731 -- conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.4-py312h6693b03_0.conda - sha256: 21fe25afa23299c02b88114f1f774d124d4b52517f6b275359c281ac06f0996e - md5: 5ac6821ebd39e56eb3e32149340ab51c +- conda: https://conda.anaconda.org/conda-forge/osx-64/numpy-2.2.5-py312h6693b03_0.conda + sha256: ac2c9e186d39087e4515999b0e42d1f7e83c22743e8aab183c3675fd972d7d34 + md5: db10cfa34ff7aa01cb6d0cf03c872f09 depends: - __osx >=10.13 - libblas >=3.9.0,<4.0a0 @@ -18100,8 +18691,8 @@ packages: - numpy-base <0a0 license: BSD-3-Clause license_family: BSD - size: 7565004 - timestamp: 1742255412208 + size: 7635087 + timestamp: 1745119684441 - conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.0.2-py39h3ba1154_1.conda sha256: f5f4b8cad78dd961e763d7850c338004b57dd5fdad2a0bce7da25e2a9bad45cb md5: 786fc37a306970ceee8d3654be4cf936 @@ -18120,9 +18711,9 @@ packages: license_family: BSD size: 5796232 timestamp: 1732314910635 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.4-py312h7c1f314_0.conda - sha256: 68eafd2b7beca8467fe84a8a03767680be686d601a0771d3414c7019f3302ee0 - md5: 001a57e8f4cc0c12841d341b94ef8787 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/numpy-2.2.5-py312h7c1f314_0.conda + sha256: 982aed7df71ae0ca8bc396ae25d43fd9a4f2b15d18faca15d6c27e9efb3955be + md5: 24a41dacf9d624b069d54a6e92594540 depends: - __osx >=11.0 - libblas >=3.9.0,<4.0a0 @@ -18136,8 +18727,8 @@ packages: - numpy-base <0a0 license: BSD-3-Clause license_family: BSD - size: 6559671 - timestamp: 1742255398662 + size: 6498553 + timestamp: 1745119367238 - conda: https://conda.anaconda.org/conda-forge/win-64/numpy-1.26.4-py39hddb5d58_0.conda sha256: 25473fb10de8e3d92ea07777fce90508b5fce76fd942b333625ae27f7c50d74d md5: 6e30ff8f2d3f59f45347dfba8bc22a04 @@ -18156,9 +18747,9 @@ packages: license_family: BSD size: 5920615 timestamp: 1707226471242 -- conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.4-py312h3150e54_0.conda - sha256: 477bd925070dd7122c3d2d8be57e06338f1e946c403a1044908aaf68a5e27cdf - md5: e668b8543944b4d80aaa9c904f3821ee +- conda: https://conda.anaconda.org/conda-forge/win-64/numpy-2.2.5-py312h3150e54_0.conda + sha256: c497607b3e7e0946b8a2566b6587152c7cb376625559addbf606494f5bbe41dd + md5: 00c3b00c9091b7f76faba85795350c7e depends: - libblas >=3.9.0,<4.0a0 - libcblas >=3.9.0,<4.0a0 @@ -18172,8 +18763,8 @@ packages: - numpy-base <0a0 license: BSD-3-Clause license_family: BSD - size: 7058478 - timestamp: 1742255793694 + size: 7132354 + timestamp: 1745119803660 - conda: https://conda.anaconda.org/conda-forge/linux-64/octomap-1.10.0-h84d6215_0.conda sha256: 9b5bcc8be93c8da5be803be357d1096c190339018f688f509a0a295e04fb98be md5: 0dfda663c7d58e8c35c96239ed57c16f @@ -18284,40 +18875,40 @@ packages: license_family: BSD size: 784483 timestamp: 1732674189726 -- conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.4.1-h7b32b05_0.conda - sha256: cbf62df3c79a5c2d113247ddea5658e9ff3697b6e741c210656e239ecaf1768f - md5: 41adf927e746dc75ecf0ef841c454e48 +- conda: https://conda.anaconda.org/conda-forge/linux-64/openssl-3.5.0-h7b32b05_0.conda + sha256: 38285d280f84f1755b7c54baf17eccf2e3e696287954ce0adca16546b85ee62c + md5: bb539841f2a3fde210f387d00ed4bb9d depends: - __glibc >=2.17,<3.0.a0 - ca-certificates - libgcc >=13 license: Apache-2.0 license_family: Apache - size: 2939306 - timestamp: 1739301879343 -- conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.4.1-hc426f3f_0.conda - sha256: 505a46671dab5d66df8e684f99a9ae735a607816b12810b572d63caa512224df - md5: a7d63f8e7ab23f71327ea6d27e2d5eae + size: 3121673 + timestamp: 1744132167438 +- conda: https://conda.anaconda.org/conda-forge/osx-64/openssl-3.5.0-hc426f3f_0.conda + sha256: 7ee137b67f2de89d203e5ac2ebffd6d42252700005bf6af2bbf3dc11a9dfedbd + md5: e06e13c34056b6334a7a1188b0f4c83c depends: - __osx >=10.13 - ca-certificates license: Apache-2.0 license_family: Apache - size: 2591479 - timestamp: 1739302628009 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.4.1-h81ee809_0.conda - sha256: 4f8e2389e1b711b44182a075516d02c80fa7a3a7e25a71ff1b5ace9eae57a17a - md5: 75f9f0c7b1740017e2db83a53ab9a28e + size: 2737547 + timestamp: 1744140967264 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/openssl-3.5.0-h81ee809_0.conda + sha256: 53f825acb8d3e13bdad5c869f6dc7df931941450eea7f6473b955b0aaea1a399 + md5: 3d2936da7e240d24c656138e07fa2502 depends: - __osx >=11.0 - ca-certificates license: Apache-2.0 license_family: Apache - size: 2934522 - timestamp: 1739301896733 -- conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.4.1-ha4e3fda_0.conda - sha256: 56dcc2b4430bfc1724e32661c34b71ae33a23a14149866fc5645361cfd3b3a6a - md5: 0730f8094f7088592594f9bf3ae62b3f + size: 3067649 + timestamp: 1744132084304 +- conda: https://conda.anaconda.org/conda-forge/win-64/openssl-3.5.0-ha4e3fda_0.conda + sha256: 43dd7f56da142ca83c614c8b0085589650ae9032b351a901c190e48eefc73675 + md5: 4ea7db75035eb8c13fa680bb90171e08 depends: - ca-certificates - ucrt >=10.0.20348.0 @@ -18325,20 +18916,21 @@ packages: - vc14_runtime >=14.29.30139 license: Apache-2.0 license_family: Apache - size: 8515197 - timestamp: 1739304103653 -- conda: https://conda.anaconda.org/conda-forge/noarch/packaging-24.2-pyhd8ed1ab_2.conda - sha256: da157b19bcd398b9804c5c52fc000fcb8ab0525bdb9c70f95beaa0bb42f85af1 - md5: 3bfed7e6228ebf2f7b9eaa47f1b4e2aa + size: 8999138 + timestamp: 1744135594688 +- conda: https://conda.anaconda.org/conda-forge/noarch/packaging-25.0-pyh29332c3_1.conda + sha256: 289861ed0c13a15d7bbb408796af4de72c2fe67e2bcb0de98f4c3fce259d7991 + md5: 58335b26c38bf4a20f399384c33cbcf9 depends: - python >=3.8 + - python license: Apache-2.0 license_family: APACHE - size: 60164 - timestamp: 1733203368787 -- conda: https://conda.anaconda.org/conda-forge/linux-64/pandas-2.2.3-py312hf9745cd_1.conda - sha256: ad275a83bfebfa8a8fee9b0569aaf6f513ada6a246b2f5d5b85903d8ca61887e - md5: 8bce4f6caaf8c5448c7ac86d87e26b4b + size: 62477 + timestamp: 1745345660407 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pandas-2.2.3-py312hf9745cd_3.conda + sha256: b0bed36b95757bbd269d30b2367536b802158bdf7947800ee7ae55089cfa8b9c + md5: 2979458c23c7755683a0598fb33e7666 depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 @@ -18346,67 +18938,195 @@ packages: - numpy >=1.19,<3 - numpy >=1.22.4 - python >=3.12,<3.13.0a0 - - python-dateutil >=2.8.1 - - python-tzdata >=2022a + - python-dateutil >=2.8.2 + - python-tzdata >=2022.7 - python_abi 3.12.* *_cp312 - - pytz >=2020.1,<2024.2 + - pytz >=2020.1 + constrains: + - tabulate >=0.9.0 + - pytables >=3.8.0 + - html5lib >=1.1 + - lxml >=4.9.2 + - gcsfs >=2022.11.0 + - odfpy >=1.4.1 + - numexpr >=2.8.4 + - psycopg2 >=2.9.6 + - fsspec >=2022.11.0 + - qtpy >=2.3.0 + - tzdata >=2022.7 + - pyarrow >=10.0.1 + - pyqt5 >=5.15.9 + - xlrd >=2.0.1 + - sqlalchemy >=2.0.0 + - xarray >=2022.12.0 + - scipy >=1.10.0 + - fastparquet >=2022.12.0 + - pyreadstat >=1.2.0 + - matplotlib >=3.6.3 + - bottleneck >=1.3.6 + - s3fs >=2022.11.0 + - zstandard >=0.19.0 + - openpyxl >=3.1.0 + - blosc >=1.21.3 + - beautifulsoup4 >=4.11.2 + - pandas-gbq >=0.19.0 + - xlsxwriter >=3.0.5 + - numba >=0.56.4 + - pyxlsb >=1.0.10 + - python-calamine >=0.1.7 license: BSD-3-Clause license_family: BSD - size: 15436913 - timestamp: 1726879054912 -- conda: https://conda.anaconda.org/conda-forge/osx-64/pandas-2.2.3-py312h98e817e_1.conda - sha256: 86c252ce5718b55129303f7d5c9a8664d8f0b23e303579142d09fcfd701e4fbe - md5: a7f7c58bbbfcdf820edb6e544555fe8f + size: 15392153 + timestamp: 1744430987175 +- conda: https://conda.anaconda.org/conda-forge/osx-64/pandas-2.2.3-py312hec45ffd_3.conda + sha256: b9c98565d165384a53ecdb14c8ccd9144d672b58c81e057598d197c6be0aba98 + md5: 50fcc3531441b73cb493ef9b2604abde depends: - __osx >=10.13 - - libcxx >=17 + - libcxx >=18 - numpy >=1.19,<3 - numpy >=1.22.4 - python >=3.12,<3.13.0a0 - - python-dateutil >=2.8.1 - - python-tzdata >=2022a + - python-dateutil >=2.8.2 + - python-tzdata >=2022.7 - python_abi 3.12.* *_cp312 - - pytz >=2020.1,<2024.2 + - pytz >=2020.1 + constrains: + - sqlalchemy >=2.0.0 + - numba >=0.56.4 + - pyarrow >=10.0.1 + - python-calamine >=0.1.7 + - bottleneck >=1.3.6 + - tzdata >=2022.7 + - lxml >=4.9.2 + - gcsfs >=2022.11.0 + - html5lib >=1.1 + - pandas-gbq >=0.19.0 + - psycopg2 >=2.9.6 + - numexpr >=2.8.4 + - fastparquet >=2022.12.0 + - zstandard >=0.19.0 + - tabulate >=0.9.0 + - xarray >=2022.12.0 + - xlsxwriter >=3.0.5 + - odfpy >=1.4.1 + - pyreadstat >=1.2.0 + - openpyxl >=3.1.0 + - xlrd >=2.0.1 + - beautifulsoup4 >=4.11.2 + - s3fs >=2022.11.0 + - matplotlib >=3.6.3 + - scipy >=1.10.0 + - fsspec >=2022.11.0 + - pytables >=3.8.0 + - qtpy >=2.3.0 + - blosc >=1.21.3 + - pyqt5 >=5.15.9 + - pyxlsb >=1.0.10 license: BSD-3-Clause license_family: BSD - size: 14575645 - timestamp: 1726879062042 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/pandas-2.2.3-py312hcd31e36_1.conda - sha256: ff0cb54b5d058c7987b4a0984066e893642d1865a7bb695294b6172e2fcdc457 - md5: c68bfa69e6086c381c74e16fd72613a8 + size: 14590879 + timestamp: 1744431018654 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/pandas-2.2.3-py312hcb1e3ce_3.conda + sha256: 57beb95a8c5c3c35a87d0c5a6c3235fb3673618445e60be952a2502781534613 + md5: 63af5cccfa8b67825d8358b149e96466 depends: - __osx >=11.0 - - libcxx >=17 + - libcxx >=18 - numpy >=1.19,<3 - numpy >=1.22.4 - python >=3.12,<3.13.0a0 - python >=3.12,<3.13.0a0 *_cpython - - python-dateutil >=2.8.1 - - python-tzdata >=2022a + - python-dateutil >=2.8.2 + - python-tzdata >=2022.7 - python_abi 3.12.* *_cp312 - - pytz >=2020.1,<2024.2 + - pytz >=2020.1 + constrains: + - zstandard >=0.19.0 + - pyreadstat >=1.2.0 + - blosc >=1.21.3 + - fastparquet >=2022.12.0 + - qtpy >=2.3.0 + - openpyxl >=3.1.0 + - psycopg2 >=2.9.6 + - xlsxwriter >=3.0.5 + - lxml >=4.9.2 + - xarray >=2022.12.0 + - pyxlsb >=1.0.10 + - matplotlib >=3.6.3 + - python-calamine >=0.1.7 + - gcsfs >=2022.11.0 + - numba >=0.56.4 + - pandas-gbq >=0.19.0 + - odfpy >=1.4.1 + - fsspec >=2022.11.0 + - numexpr >=2.8.4 + - xlrd >=2.0.1 + - scipy >=1.10.0 + - bottleneck >=1.3.6 + - pyqt5 >=5.15.9 + - s3fs >=2022.11.0 + - html5lib >=1.1 + - pytables >=3.8.0 + - tabulate >=0.9.0 + - beautifulsoup4 >=4.11.2 + - pyarrow >=10.0.1 + - sqlalchemy >=2.0.0 + - tzdata >=2022.7 license: BSD-3-Clause license_family: BSD - size: 14470437 - timestamp: 1726878887799 -- conda: https://conda.anaconda.org/conda-forge/win-64/pandas-2.2.3-py312h72972c8_1.conda - sha256: dfd30e665b1ced1b783ca303799e250d8acc40943bcefb3a9b2bb13c3b17911c - md5: bf6f01c03e0688523d4b5cff8fe8c977 + size: 14442730 + timestamp: 1744431003090 +- conda: https://conda.anaconda.org/conda-forge/win-64/pandas-2.2.3-py312h72972c8_3.conda + sha256: 86fe04c5f0dcae3644e3d2d892ddf6760d89eeb8fe1a31ef30290ac5a6a9f125 + md5: 08b4650b022c9f3233d45f231fb9471f depends: - numpy >=1.19,<3 - numpy >=1.22.4 - python >=3.12,<3.13.0a0 - - python-dateutil >=2.8.1 - - python-tzdata >=2022a + - python-dateutil >=2.8.2 + - python-tzdata >=2022.7 - python_abi 3.12.* *_cp312 - - pytz >=2020.1,<2024.2 + - pytz >=2020.1 - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 + constrains: + - pyxlsb >=1.0.10 + - psycopg2 >=2.9.6 + - bottleneck >=1.3.6 + - html5lib >=1.1 + - openpyxl >=3.1.0 + - python-calamine >=0.1.7 + - tabulate >=0.9.0 + - numexpr >=2.8.4 + - beautifulsoup4 >=4.11.2 + - odfpy >=1.4.1 + - gcsfs >=2022.11.0 + - pytables >=3.8.0 + - pyqt5 >=5.15.9 + - zstandard >=0.19.0 + - scipy >=1.10.0 + - xarray >=2022.12.0 + - blosc >=1.21.3 + - qtpy >=2.3.0 + - sqlalchemy >=2.0.0 + - pyreadstat >=1.2.0 + - fsspec >=2022.11.0 + - lxml >=4.9.2 + - xlrd >=2.0.1 + - tzdata >=2022.7 + - fastparquet >=2022.12.0 + - s3fs >=2022.11.0 + - xlsxwriter >=3.0.5 + - pandas-gbq >=0.19.0 + - numba >=0.56.4 + - pyarrow >=10.0.1 + - matplotlib >=3.6.3 license: BSD-3-Clause license_family: BSD - size: 14218658 - timestamp: 1726879426348 + size: 14150000 + timestamp: 1744431235710 - conda: https://conda.anaconda.org/conda-forge/noarch/parso-0.8.4-pyhd8ed1ab_1.conda sha256: 17131120c10401a99205fc6fe436e7903c0fa092f1b3e80452927ab377239bcc md5: 5c092057b6badd30f75b06244ecd01c9 @@ -18416,32 +19136,55 @@ packages: license_family: MIT size: 75295 timestamp: 1733271352153 -- conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hba22ea6_2.conda - sha256: 1087716b399dab91cc9511d6499036ccdc53eb29a288bebcb19cf465c51d7c0d - md5: df359c09c41cd186fffb93a2d87aa6f5 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.44-hc749103_2.conda + sha256: 09717569649d89caafbf32f6cda1e65aef86e5a86c053d30e4ce77fca8d27b68 + md5: 31614c73d7b103ef76faa4d83d261d34 depends: - __glibc >=2.17,<3.0.a0 - bzip2 >=1.0.8,<2.0a0 - - libgcc-ng >=12 + - libgcc >=13 - libzlib >=1.3.1,<2.0a0 license: BSD-3-Clause license_family: BSD - size: 952308 - timestamp: 1723488734144 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.44-h297a79d_2.conda - sha256: 83153c7d8fd99cab33c92ce820aa7bfed0f1c94fc57010cf227b6e3c50cb7796 - md5: 147c83e5e44780c7492998acbacddf52 + size: 956207 + timestamp: 1745931215744 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pcre2-10.45-hc749103_0.conda + sha256: 27c4014f616326240dcce17b5f3baca3953b6bc5f245ceb49c3fa1e6320571eb + md5: b90bece58b4c2bf25969b70f3be42d25 + depends: + - __glibc >=2.17,<3.0.a0 + - bzip2 >=1.0.8,<2.0a0 + - libgcc >=13 + - libzlib >=1.3.1,<2.0a0 + license: BSD-3-Clause + license_family: BSD + size: 1197308 + timestamp: 1745955064657 +- conda: https://conda.anaconda.org/conda-forge/osx-64/pcre2-10.45-hf733adb_0.conda + sha256: 5b2c93ee8714c17682cd926127f1e712efef00441a79732635a80b24f5adc212 + md5: d9f1976154f2f45588251dcfc48bcdda + depends: + - __osx >=10.13 + - bzip2 >=1.0.8,<2.0a0 + - libzlib >=1.3.1,<2.0a0 + license: BSD-3-Clause + license_family: BSD + size: 1086588 + timestamp: 1745955211398 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/pcre2-10.45-ha881caa_0.conda + sha256: e9ecb706b58b5a2047c077b3a1470e8554f3aad02e9c3c00cfa35d537420fea3 + md5: a52385b93558d8e6bbaeec5d61a21cd7 depends: - __osx >=11.0 - bzip2 >=1.0.8,<2.0a0 - libzlib >=1.3.1,<2.0a0 license: BSD-3-Clause license_family: BSD - size: 618973 - timestamp: 1723488853807 -- conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h3d7b363_2.conda - sha256: f4a12cbf8a7c5bfa2592b9dc92b492c438781898e5b02f397979b0be6e1b5851 - md5: a3a3baddcfb8c80db84bec3cb7746fb8 + size: 837826 + timestamp: 1745955207242 +- conda: https://conda.anaconda.org/conda-forge/win-64/pcre2-10.44-h99c9b8b_2.conda + sha256: 15dffc9a2d6bb6b8ccaa7cbd26b229d24f1a0a1c4f5685b308a63929c56b381f + md5: a912b2c4ff0f03101c751aa79a331831 depends: - bzip2 >=1.0.8,<2.0a0 - libzlib >=1.3.1,<2.0a0 @@ -18450,8 +19193,32 @@ packages: - vc14_runtime >=14.29.30139 license: BSD-3-Clause license_family: BSD - size: 820831 - timestamp: 1723489427046 + size: 816653 + timestamp: 1745931851696 +- conda: https://conda.anaconda.org/conda-forge/linux-64/perl-5.32.1-7_hd590300_perl5.conda + build_number: 7 + sha256: 9ec32b6936b0e37bcb0ed34f22ec3116e75b3c0964f9f50ecea5f58734ed6ce9 + md5: f2cfec9406850991f4e3d960cc9e3321 + depends: + - libgcc-ng >=12 + - libxcrypt >=4.4.36 + license: GPL-1.0-or-later OR Artistic-1.0-Perl + size: 13344463 + timestamp: 1703310653947 +- conda: https://conda.anaconda.org/conda-forge/osx-64/perl-5.32.1-7_h10d778d_perl5.conda + build_number: 7 + sha256: 8ebd35e2940055a93135b9fd11bef3662cecef72d6ee651f68d64a2f349863c7 + md5: dc442e0885c3a6b65e61c61558161a9e + license: GPL-1.0-or-later OR Artistic-1.0-Perl + size: 12334471 + timestamp: 1703311001432 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/perl-5.32.1-7_h4614cfb_perl5.conda + build_number: 7 + sha256: b0c55040d2994fd6bf2f83786561d92f72306d982d6ea12889acad24a9bf43b8 + md5: ba3cbe93f99e896765422cc5f7c3a79e + license: GPL-1.0-or-later OR Artistic-1.0-Perl + size: 14439531 + timestamp: 1703311335652 - conda: https://conda.anaconda.org/conda-forge/noarch/pexpect-4.9.0-pyhd8ed1ab_1.conda sha256: 202af1de83b585d36445dc1fda94266697341994d1a3328fabde4989e1b3d07a md5: d0d408b1f18883a944376da5cf8101ea @@ -18630,28 +19397,26 @@ packages: license: HPND size: 41791546 timestamp: 1735930293357 -- conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.44.2-h29eaf8c_0.conda - sha256: 747c58db800d5583fee78e76240bf89cbaeedf7ab1ef339c2990602332b9c4be - md5: 5e2a7acfa2c24188af39e7944e1b3604 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pixman-0.46.0-h29eaf8c_0.conda + sha256: 1330c3fd424fa2deec6a30678f235049c0ed1b0fad8d2d81ef995c9322d5e49a + md5: d2f1c87d4416d1e7344cf92b1aaee1c4 depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 - libstdcxx >=13 license: MIT - license_family: MIT - size: 381072 - timestamp: 1733698987122 -- conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.44.2-had0cd8c_0.conda - sha256: 6648bd6e050f37c062ced1bbd4201dee617c3dacda1fc3a0de70335cf736f11b - md5: c720ac9a3bd825bf8b4dc7523ea49be4 + size: 398664 + timestamp: 1746011575217 +- conda: https://conda.anaconda.org/conda-forge/win-64/pixman-0.46.0-had0cd8c_0.conda + sha256: d41f4d9faf6aefa138c609b64fe2a22cf252d88e8c393b25847e909d02870491 + md5: 01617534ef71b5385ebba940a6d6150d depends: - ucrt >=10.0.20348.0 - vc >=14.2,<15 - vc14_runtime >=14.29.30139 license: MIT - license_family: MIT - size: 455582 - timestamp: 1733699458861 + size: 472718 + timestamp: 1746016414502 - conda: https://conda.anaconda.org/conda-forge/linux-64/pkg-config-0.29.2-h4bc722e_1009.conda sha256: c9601efb1af5391317e04eca77c6fe4d716bf1ca1ad8da2a05d15cb7c28d7d4e md5: 1bee70681f504ea424fb07cdb090c001 @@ -18719,18 +19484,18 @@ packages: license_family: MIT size: 195854 timestamp: 1742475656293 -- conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.50-pyha770c72_0.conda - sha256: 0749c49a349bf55b8539ce5addce559b77592165da622944a51c630e94d97889 - md5: 7d823138f550b14ecae927a5ff3286de +- conda: https://conda.anaconda.org/conda-forge/noarch/prompt-toolkit-3.0.51-pyha770c72_0.conda + sha256: ebc1bb62ac612af6d40667da266ff723662394c0ca78935340a5b5c14831227b + md5: d17ae9db4dc594267181bd199bf9a551 depends: - python >=3.9 - wcwidth constrains: - - prompt_toolkit 3.0.50 + - prompt_toolkit 3.0.51 license: BSD-3-Clause license_family: BSD - size: 271905 - timestamp: 1737453457168 + size: 271841 + timestamp: 1744724188108 - conda: https://conda.anaconda.org/conda-forge/linux-64/pthread-stubs-0.4-hb9d3cd8_1002.conda sha256: 9c88f8c64590e9567c6c80823f0328e58d3b1efb0e1c539c0315ceca764e0973 md5: b3c17d95b5a10c6e64a21fa17573e70e @@ -18954,16 +19719,16 @@ packages: license_family: BSD size: 888600 timestamp: 1736243563082 -- conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.3-pyhd8ed1ab_0.conda - sha256: 81abbd080ae7e789297216bb6cf4d58bc98a3c6d5e27f64dc2e16d06928a07f0 - md5: 2d2a2d71d0c5d93c822adec31c10db5c +- conda: https://conda.anaconda.org/conda-forge/noarch/pyngrok-7.2.5-pyhd8ed1ab_0.conda + sha256: 10d2aa176d83b9bddd5dfa138d68553500b495e835a630347895b9cac86faba2 + md5: f88e65da804610634a62280648a5a2ba depends: - python >=3.9 - pyyaml >=5.1 license: MIT license_family: MIT - size: 24802 - timestamp: 1736422061767 + size: 25396 + timestamp: 1745503864970 - conda: https://conda.anaconda.org/conda-forge/noarch/pyparsing-3.2.3-pyhd8ed1ab_1.conda sha256: b92afb79b52fcf395fd220b29e0dd3297610f2059afac45298d44e00fcbf23b6 md5: 513d3c262ee49b54a8fec85c5bc99764 @@ -18973,235 +19738,234 @@ packages: license_family: MIT size: 95988 timestamp: 1743089832359 -- conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py312h91f0f75_0.conda - sha256: d1b10366fab77d4fbb0acbec3308731150db756e736151e9900fe55c0065aca7 - md5: d0c9072dee9991b744bd1be149d6e89b +- conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py312h91f0f75_0.conda + sha256: 4db931dccd8347140e79236378096d9a1b97b98bbd206d54cebd42491ad12535 + md5: e3a335c7530a1d0c4db621914f00f9f7 depends: - __glibc >=2.17,<3.0.a0 - - libclang13 >=20.1.1 + - libclang13 >=20.1.2 - libegl >=1.7.0,<2.0a0 - libgcc >=13 - libgl >=1.7.0,<2.0a0 - libopengl >=1.7.0,<2.0a0 - libstdcxx >=13 - - libxml2 >=2.13.7,<3.0a0 + - libxml2 >=2.13.7,<2.14.0a0 - libxslt >=1.1.39,<2.0a0 - python >=3.12,<3.13.0a0 - python_abi 3.12.* *_cp312 - - qt6-main 6.8.3.* - - qt6-main >=6.8.3,<6.9.0a0 + - qt6-main 6.9.0.* + - qt6-main >=6.9.0,<6.10.0a0 license: LGPL-3.0-only license_family: LGPL - size: 10603898 - timestamp: 1743273736994 -- conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.8.3-py39h0383914_0.conda - sha256: 1fb1b501392cf5d8955b50c634e434f0bb2b9ae0210020b9787f64426eaf4f90 - md5: 135c876fffded3c300e5a0b57b0cd154 + size: 10119296 + timestamp: 1743760712824 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pyside6-6.9.0-py39h0383914_0.conda + sha256: 3011c591ee700fca4cda57209b536f562a6d8d9ce074ca5e3b9b4aeb405f705d + md5: e56f5a92c54b787b9af33253e8fdce52 depends: - __glibc >=2.17,<3.0.a0 - - libclang13 >=20.1.1 + - libclang13 >=20.1.2 - libegl >=1.7.0,<2.0a0 - libgcc >=13 - libgl >=1.7.0,<2.0a0 - libopengl >=1.7.0,<2.0a0 - libstdcxx >=13 - - libxml2 >=2.13.7,<3.0a0 + - libxml2 >=2.13.7,<2.14.0a0 - libxslt >=1.1.39,<2.0a0 - python >=3.9,<3.10.0a0 - python_abi 3.9.* *_cp39 - - qt6-main 6.8.3.* - - qt6-main >=6.8.3,<6.9.0a0 + - qt6-main 6.9.0.* + - qt6-main >=6.9.0,<6.10.0a0 license: LGPL-3.0-only license_family: LGPL - size: 10548313 - timestamp: 1743273920056 -- conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py312h2ee7485_0.conda - sha256: 47530ad68c2f9aa995344d579ceb3aa085dfa48a97ec32163a14aeebcadf2671 - md5: f5b89a22912e3b42d477d6de1bfe7e17 - depends: - - libclang13 >=20.1.1 - - libxml2 >=2.13.7,<3.0a0 + size: 10117977 + timestamp: 1743760893133 +- conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py312h520aab8_0.conda + sha256: 808204eb911e20f4e58b0b6a90e424410a66668a57c08e2e6466b23137cb4f90 + md5: 52a05ba3f802633cb2234bb3edc45888 + depends: + - libclang13 >=20.1.2 + - libxml2 >=2.13.7,<2.14.0a0 - libxslt >=1.1.39,<2.0a0 - python >=3.12,<3.13.0a0 - python_abi 3.12.* *_cp312 - - qt6-main 6.8.3.* - - qt6-main >=6.8.3,<6.9.0a0 + - qt6-main 6.9.0.* + - qt6-main >=6.9.0,<6.10.0a0 - ucrt >=10.0.20348.0 - - vc >=14.2,<15 - - vc14_runtime >=14.29.30139 + - vc >=14.3,<15 + - vc14_runtime >=14.42.34438 license: LGPL-3.0-only license_family: LGPL - size: 9487954 - timestamp: 1743274289892 -- conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.8.3-py39h0285922_0.conda - sha256: c7acf73ff22a99d2e5d47072fad2e1ef5b2e5c415227d7b3a2b0c875a50b5328 - md5: 6aa433b4e443b86d2b32ae09c5f01e46 - depends: - - libclang13 >=20.1.1 - - libxml2 >=2.13.7,<3.0a0 + size: 8918147 + timestamp: 1743761403797 +- conda: https://conda.anaconda.org/conda-forge/win-64/pyside6-6.9.0-py39h5cc861e_0.conda + sha256: fcab9f5e04692aab69a6036e0d57bd4656e911d50769a930abd003c16003b8e3 + md5: 57ab97daa86321a58344146cb289a20b + depends: + - libclang13 >=20.1.2 + - libxml2 >=2.13.7,<2.14.0a0 - libxslt >=1.1.39,<2.0a0 - python >=3.9,<3.10.0a0 - python_abi 3.9.* *_cp39 - - qt6-main 6.8.3.* - - qt6-main >=6.8.3,<6.9.0a0 + - qt6-main 6.9.0.* + - qt6-main >=6.9.0,<6.10.0a0 - ucrt >=10.0.20348.0 - - vc >=14.2,<15 - - vc14_runtime >=14.29.30139 + - vc >=14.3,<15 + - vc14_runtime >=14.42.34438 license: LGPL-3.0-only license_family: LGPL - size: 9488908 - timestamp: 1743274387977 -- conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.9-h9e4cc4f_1_cpython.conda - build_number: 1 - sha256: 77f2073889d4c91a57bc0da73a0466d9164dbcf6191ea9c3a7be6872f784d625 - md5: d82342192dfc9145185190e651065aa9 + size: 8868228 + timestamp: 1743761286359 +- conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.12.10-h9e4cc4f_0_cpython.conda + sha256: 4dc1da115805bd353bded6ab20ff642b6a15fcc72ac2f3de0e1d014ff3612221 + md5: a41d26cd4d47092d683915d058380dec depends: - __glibc >=2.17,<3.0.a0 - bzip2 >=1.0.8,<2.0a0 - ld_impl_linux-64 >=2.36.1 - - libexpat >=2.6.4,<3.0a0 - - libffi >=3.4,<4.0a0 + - libexpat >=2.7.0,<3.0a0 + - libffi >=3.4.6,<3.5.0a0 - libgcc >=13 - - liblzma >=5.6.4,<6.0a0 + - liblzma >=5.8.1,<6.0a0 - libnsl >=2.0.1,<2.1.0a0 - libsqlite >=3.49.1,<4.0a0 - libuuid >=2.38.1,<3.0a0 - libxcrypt >=4.4.36 - libzlib >=1.3.1,<2.0a0 - ncurses >=6.5,<7.0a0 - - openssl >=3.4.1,<4.0a0 + - openssl >=3.5.0,<4.0a0 - readline >=8.2,<9.0a0 - tk >=8.6.13,<8.7.0a0 - tzdata constrains: - python_abi 3.12.* *_cp312 license: Python-2.0 - size: 31670716 - timestamp: 1741130026152 -- conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.9.21-h9c0c6dc_1_cpython.conda + size: 31279179 + timestamp: 1744325164633 +- conda: https://conda.anaconda.org/conda-forge/linux-64/python-3.9.22-h85ef794_1_cpython.conda build_number: 1 - sha256: 06042ce946a64719b5ce1676d02febc49a48abcab16ef104e27d3ec11e9b1855 - md5: b4807744af026fdbe8c05131758fb4be + sha256: d55739a308bd343ebe1990562a4ea8c440d246779f6da9b291068ec116699b64 + md5: b23565542b4974e9fe3e81bdfd8799c3 depends: - __glibc >=2.17,<3.0.a0 - bzip2 >=1.0.8,<2.0a0 - ld_impl_linux-64 >=2.36.1 + - libexpat >=2.7.0,<3.0a0 - libffi >=3.4,<4.0a0 - libgcc >=13 - - liblzma >=5.6.3,<6.0a0 + - liblzma >=5.8.1,<6.0a0 - libnsl >=2.0.1,<2.1.0a0 - - libsqlite >=3.47.0,<4.0a0 + - libsqlite >=3.49.1,<4.0a0 - libuuid >=2.38.1,<3.0a0 - libxcrypt >=4.4.36 - libzlib >=1.3.1,<2.0a0 - ncurses >=6.5,<7.0a0 - - openssl >=3.4.0,<4.0a0 + - openssl >=3.5.0,<4.0a0 - readline >=8.2,<9.0a0 - tk >=8.6.13,<8.7.0a0 - tzdata constrains: - python_abi 3.9.* *_cp39 license: Python-2.0 - size: 23622848 - timestamp: 1733407924273 -- conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.9-h9ccd52b_1_cpython.conda - build_number: 1 - sha256: c394f7068a714cad7853992f18292bb34c6d99fe7c21025664b05069c86b9450 - md5: b878567b6b749f993dbdbc2834115bc3 + size: 23620589 + timestamp: 1744674892969 +- conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.12.10-h9ccd52b_0_cpython.conda + sha256: 94835a129330dc1b2f645e12c7857a1aa4246e51777d7a9b7c280747dbb5a9a2 + md5: 597c4102c97504ede5297d06fb763951 depends: - __osx >=10.13 - bzip2 >=1.0.8,<2.0a0 - - libexpat >=2.6.4,<3.0a0 - - libffi >=3.4,<4.0a0 - - liblzma >=5.6.4,<6.0a0 + - libexpat >=2.7.0,<3.0a0 + - libffi >=3.4.6,<3.5.0a0 + - liblzma >=5.8.1,<6.0a0 - libsqlite >=3.49.1,<4.0a0 - libzlib >=1.3.1,<2.0a0 - ncurses >=6.5,<7.0a0 - - openssl >=3.4.1,<4.0a0 + - openssl >=3.5.0,<4.0a0 - readline >=8.2,<9.0a0 - tk >=8.6.13,<8.7.0a0 - tzdata constrains: - python_abi 3.12.* *_cp312 license: Python-2.0 - size: 13833024 - timestamp: 1741129416409 -- conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.9.21-h7fafba3_1_cpython.conda + size: 13783219 + timestamp: 1744324415187 +- conda: https://conda.anaconda.org/conda-forge/osx-64/python-3.9.22-h55ef250_1_cpython.conda build_number: 1 - sha256: 7c351d45f07d40ff57a2e0dce4d2e245f8f03140a42c2e3a12f69036e46eb8c3 - md5: 858da32345b53a39ffa3fd8ffbe789df + sha256: 8149e0d279495033b5ece1808b06e948edc3c8228546a27828043d9c5766328d + md5: 604afff3e1cecbfab86f2391fde5b723 depends: - __osx >=10.13 - bzip2 >=1.0.8,<2.0a0 + - libexpat >=2.7.0,<3.0a0 - libffi >=3.4,<4.0a0 - - liblzma >=5.6.3,<6.0a0 - - libsqlite >=3.47.0,<4.0a0 + - liblzma >=5.8.1,<6.0a0 + - libsqlite >=3.49.1,<4.0a0 - libzlib >=1.3.1,<2.0a0 - ncurses >=6.5,<7.0a0 - - openssl >=3.4.0,<4.0a0 + - openssl >=3.5.0,<4.0a0 - readline >=8.2,<9.0a0 - tk >=8.6.13,<8.7.0a0 - tzdata constrains: - python_abi 3.9.* *_cp39 license: Python-2.0 - size: 11448139 - timestamp: 1733407294540 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.9-hc22306f_1_cpython.conda - build_number: 1 - sha256: fe804fc462396baab8abe525a722d0254c839533c98c47abd2c6d1248ad45e93 - md5: d9fac7b334ff6e5f93abd27509a53060 + size: 11467702 + timestamp: 1744673739188 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.12.10-hc22306f_0_cpython.conda + sha256: 69aed911271e3f698182e9a911250b05bdf691148b670a23e0bea020031e298e + md5: c88f1a7e1e7b917d9c139f03b0960fea depends: - __osx >=11.0 - bzip2 >=1.0.8,<2.0a0 - - libexpat >=2.6.4,<3.0a0 - - libffi >=3.4,<4.0a0 - - liblzma >=5.6.4,<6.0a0 + - libexpat >=2.7.0,<3.0a0 + - libffi >=3.4.6,<3.5.0a0 + - liblzma >=5.8.1,<6.0a0 - libsqlite >=3.49.1,<4.0a0 - libzlib >=1.3.1,<2.0a0 - ncurses >=6.5,<7.0a0 - - openssl >=3.4.1,<4.0a0 + - openssl >=3.5.0,<4.0a0 - readline >=8.2,<9.0a0 - tk >=8.6.13,<8.7.0a0 - tzdata constrains: - python_abi 3.12.* *_cp312 license: Python-2.0 - size: 13042031 - timestamp: 1741128584924 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.9.21-h5f1b60f_1_cpython.conda + size: 12932743 + timestamp: 1744323815320 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/python-3.9.22-hdec7a8b_1_cpython.conda build_number: 1 - sha256: e9f80120e6bbb6fcbe29eb4afb1fc06c0a9b2802a13114cf7c823fce284f4ebb - md5: a7ec592ce8aefc5a681d2c5b8e005a54 + sha256: 664cf6af782b9d7dd8af6408b947c7d3e237d7be383c4fee98ea87dee048f043 + md5: dcce9c2174e4b89e660bbac1fe08a7f6 depends: - __osx >=11.0 - bzip2 >=1.0.8,<2.0a0 + - libexpat >=2.7.0,<3.0a0 - libffi >=3.4,<4.0a0 - - liblzma >=5.6.3,<6.0a0 - - libsqlite >=3.47.0,<4.0a0 + - liblzma >=5.8.1,<6.0a0 + - libsqlite >=3.49.1,<4.0a0 - libzlib >=1.3.1,<2.0a0 - ncurses >=6.5,<7.0a0 - - openssl >=3.4.0,<4.0a0 + - openssl >=3.5.0,<4.0a0 - readline >=8.2,<9.0a0 - tk >=8.6.13,<8.7.0a0 - tzdata constrains: - python_abi 3.9.* *_cp39 license: Python-2.0 - size: 11800492 - timestamp: 1733406732542 -- conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.9-h3f84c4b_1_cpython.conda - build_number: 1 - sha256: 320acd0095442a451c4e0f0f896bed2f52b3b8f05df41774e5b0b433d9fa08e0 - md5: f0a0ad168b815fee4ce9718d4e6c1925 + size: 11895821 + timestamp: 1744674015346 +- conda: https://conda.anaconda.org/conda-forge/win-64/python-3.12.10-h3f84c4b_0_cpython.conda + sha256: a791fa8f5ce68ab00543ecd3798bfa573db327902ccd5cb7598fd7e94ea194d3 + md5: 495e849ebc04562381539d25cf303a9f depends: - bzip2 >=1.0.8,<2.0a0 - - libexpat >=2.6.4,<3.0a0 - - libffi >=3.4,<4.0a0 - - liblzma >=5.6.4,<6.0a0 + - libexpat >=2.7.0,<3.0a0 + - libffi >=3.4.6,<3.5.0a0 + - liblzma >=5.8.1,<6.0a0 - libsqlite >=3.49.1,<4.0a0 - libzlib >=1.3.1,<2.0a0 - - openssl >=3.4.1,<4.0a0 + - openssl >=3.5.0,<4.0a0 - tk >=8.6.13,<8.7.0a0 - tzdata - ucrt >=10.0.20348.0 @@ -19210,19 +19974,20 @@ packages: constrains: - python_abi 3.12.* *_cp312 license: Python-2.0 - size: 15935206 - timestamp: 1741128459438 -- conda: https://conda.anaconda.org/conda-forge/win-64/python-3.9.21-h37870fc_1_cpython.conda + size: 15941050 + timestamp: 1744323489788 +- conda: https://conda.anaconda.org/conda-forge/win-64/python-3.9.22-hfdde91d_1_cpython.conda build_number: 1 - sha256: ccb1dcc59dcfbc0da916f04ce1840b44fc8aed76733604e4c65855b33085b83f - md5: 436316266ec1b6c23065b398e43d3a44 + sha256: d0554ea86cac146e1582ab086ea28c0e4ae85a726524d9df110aec6aeb9624e7 + md5: 956939c05eec0a1f951737cd17773563 depends: - bzip2 >=1.0.8,<2.0a0 + - libexpat >=2.7.0,<3.0a0 - libffi >=3.4,<4.0a0 - - liblzma >=5.6.3,<6.0a0 - - libsqlite >=3.47.0,<4.0a0 + - liblzma >=5.8.1,<6.0a0 + - libsqlite >=3.49.1,<4.0a0 - libzlib >=1.3.1,<2.0a0 - - openssl >=3.4.0,<4.0a0 + - openssl >=3.5.0,<4.0a0 - tk >=8.6.13,<8.7.0a0 - tzdata - ucrt >=10.0.20348.0 @@ -19231,8 +19996,8 @@ packages: constrains: - python_abi 3.9.* *_cp39 license: Python-2.0 - size: 16943409 - timestamp: 1733406595694 + size: 16967550 + timestamp: 1744673584543 - conda: https://conda.anaconda.org/conda-forge/noarch/python-dateutil-2.9.0.post0-pyhff2d567_1.conda sha256: a50052536f1ef8516ed11a844f9413661829aa083304dc624c5925298d078d79 md5: 5ba79d7c71f03c678c8ead841f347d6e @@ -19252,95 +20017,35 @@ packages: license_family: APACHE size: 144160 timestamp: 1742745254292 -- conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.12-5_cp312.conda - build_number: 5 - sha256: d10e93d759931ffb6372b45d65ff34d95c6000c61a07e298d162a3bc2accebb0 - md5: 0424ae29b104430108f5218a66db7260 - constrains: - - python 3.12.* *_cpython - license: BSD-3-Clause - license_family: BSD - size: 6238 - timestamp: 1723823388266 -- conda: https://conda.anaconda.org/conda-forge/linux-64/python_abi-3.9-5_cp39.conda - build_number: 5 - sha256: 019e2f8bca1d1f1365fbb9965cd95bb395c92c89ddd03165db82f5ae89a20812 - md5: 40363a30db350596b5f225d0d5a33328 - constrains: - - python 3.9.* *_cpython - license: BSD-3-Clause - license_family: BSD - size: 6193 - timestamp: 1723823354399 -- conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.12-5_cp312.conda - build_number: 5 - sha256: 4da26c7508d5bc5d8621e84dc510284402239df56aab3587a7d217de9d3c806d - md5: c34dd4920e0addf7cfcc725809f25d8e - constrains: - - python 3.12.* *_cpython - license: BSD-3-Clause - license_family: BSD - size: 6312 - timestamp: 1723823137004 -- conda: https://conda.anaconda.org/conda-forge/osx-64/python_abi-3.9-5_cp39.conda - build_number: 5 - sha256: 18224feb9a5ffb1ad5ae8eac21496f399befce29aeaaf929fff44dc827e9ac16 - md5: 09ac18c0db8f06c3913fa014ec016849 - constrains: - - python 3.9.* *_cpython - license: BSD-3-Clause - license_family: BSD - size: 6294 - timestamp: 1723823176192 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.12-5_cp312.conda - build_number: 5 - sha256: 49d624e4b809c799d2bf257b22c23cf3fc4460f5570d9a58e7ad86350aeaa1f4 - md5: b76f9b1c862128e56ac7aa8cd2333de9 - constrains: - - python 3.12.* *_cpython - license: BSD-3-Clause - license_family: BSD - size: 6278 - timestamp: 1723823099686 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/python_abi-3.9-5_cp39.conda - build_number: 5 - sha256: a942c019a98f4c89bc3a73a6a583f65d1c8fc560ccfdbdd9cba9f5ef719026fb - md5: 1ca4a5e8290873da8963182d9673299d - constrains: - - python 3.9.* *_cpython - license: BSD-3-Clause - license_family: BSD - size: 6326 - timestamp: 1723823464252 -- conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.12-5_cp312.conda - build_number: 5 - sha256: 9486662af81a219e96d343449eff242f38d7c5128ced5ce5acf85857265058d6 - md5: e8681f534453af7afab4cd2bc1423eec +- conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.12-7_cp312.conda + build_number: 7 + sha256: a1bbced35e0df66cc713105344263570e835625c28d1bdee8f748f482b2d7793 + md5: 0dfcdc155cf23812a0c9deada86fb723 constrains: - python 3.12.* *_cpython license: BSD-3-Clause license_family: BSD - size: 6730 - timestamp: 1723823139725 -- conda: https://conda.anaconda.org/conda-forge/win-64/python_abi-3.9-5_cp39.conda - build_number: 5 - sha256: ee9471759ba567d5a4922d4fae95f58a0070db7616cba72e3bfb22cd5c50e37a - md5: 86ba1bbcf9b259d1592201f3c345c810 + size: 6971 + timestamp: 1745258861359 +- conda: https://conda.anaconda.org/conda-forge/noarch/python_abi-3.9-7_cp39.conda + build_number: 7 + sha256: c536863bdc2d7e551b589ddfe105fe5bcd496c554528c577c4ab253c427b944d + md5: 6235ab8d07149f25a0be52f1708aef04 constrains: - python 3.9.* *_cpython license: BSD-3-Clause license_family: BSD - size: 6706 - timestamp: 1723823197703 -- conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2024.1-pyhd8ed1ab_0.conda - sha256: 1a7d6b233f7e6e3bbcbad054c8fd51e690a67b129a899a056a5e45dd9f00cb41 - md5: 3eeeeb9e4827ace8c0c1419c85d590ad + size: 6980 + timestamp: 1745258876036 +- conda: https://conda.anaconda.org/conda-forge/noarch/pytz-2025.2-pyhd8ed1ab_0.conda + sha256: 8d2a8bf110cc1fc3df6904091dead158ba3e614d8402a83e51ed3a8aa93cdeb0 + md5: bc8e3267d44011051f2eb14d22fb0960 depends: - - python >=3.7 + - python >=3.9 license: MIT license_family: MIT - size: 188538 - timestamp: 1706886944988 + size: 189015 + timestamp: 1742920947249 - conda: https://conda.anaconda.org/conda-forge/linux-64/pyyaml-6.0.2-py312h178313f_2.conda sha256: 159cba13a93b3fe084a1eb9bda0a07afc9148147647f0d437c3c3da60980503b md5: cf2485f39740de96e2a7f2bb18ed2fee @@ -19445,9 +20150,9 @@ packages: license_family: MIT size: 157446 timestamp: 1737455304677 -- conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py312hbf22597_0.conda - sha256: aa96b9d13bc74f514ccbc3ad275d23bb837ec63894e6e7fb43786c7c41959bfd - md5: ec243006dd2b7dc72f1fba385e59f693 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py312hbf22597_0.conda + sha256: 65a264837f189b0c69c5431ea8ef44e405c472fedba145b05055f284f08bc663 + md5: fa0ab7d5bee9efbc370e71bcb5da9856 depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 @@ -19458,11 +20163,11 @@ packages: - zeromq >=4.3.5,<4.4.0a0 license: BSD-3-Clause license_family: BSD - size: 381353 - timestamp: 1741805281237 -- conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.3.0-py39h4e4fb57_0.conda - sha256: 0789d661178368f26fd291062613a6c61b14ac52ffb683214552082ae16cccfd - md5: 3c97685ac04cf3f48727fbae77a50bea + size: 379554 + timestamp: 1743831426292 +- conda: https://conda.anaconda.org/conda-forge/linux-64/pyzmq-26.4.0-py39h4e4fb57_0.conda + sha256: ffa2db10e8bc088c7e9b6a50258834f8de661ea9df48ffb434f17d3069b2dd2c + md5: d4b40a77f6b5d70003cd22c98cdc9791 depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 @@ -19473,11 +20178,11 @@ packages: - zeromq >=4.3.5,<4.4.0a0 license: BSD-3-Clause license_family: BSD - size: 339401 - timestamp: 1741805365660 -- conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py312h679dbab_0.conda - sha256: fbada9f6bdd477c6eba4bf0fbeb5d4dcdde8ccdd54df58e0e8a3e7e45f4fc146 - md5: 64faf394b4c93ad0e53e5e7d24cda358 + size: 336956 + timestamp: 1743831370731 +- conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py312h679dbab_0.conda + sha256: 9e89fab2c70a47298e72429b70cbf233d69f16f92c7dcad3b60db2e22afea00d + md5: 7c068120e36588fefecf8e91b1b3ae38 depends: - __osx >=10.13 - libcxx >=18 @@ -19487,11 +20192,11 @@ packages: - zeromq >=4.3.5,<4.4.0a0 license: BSD-3-Clause license_family: BSD - size: 365891 - timestamp: 1741805479302 -- conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.3.0-py39hf094b8e_0.conda - sha256: e197b70c8e290b46e209eefa7478eb6a137d37c6041946df50f1246a7bcc161e - md5: 2404e66f95f1d874aed645da176adc13 + size: 365060 + timestamp: 1743831517482 +- conda: https://conda.anaconda.org/conda-forge/osx-64/pyzmq-26.4.0-py39hf094b8e_0.conda + sha256: fc9afb96db591b51aa9fbbc7d5519c40bd8a725b3cc8efbcbd198b7348ec8e9b + md5: befa72cd93ce92344dceb09642c0fa9f depends: - __osx >=10.13 - libcxx >=18 @@ -19501,11 +20206,11 @@ packages: - zeromq >=4.3.5,<4.4.0a0 license: BSD-3-Clause license_family: BSD - size: 316442 - timestamp: 1741805411135 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py312hf4875e0_0.conda - sha256: 060ae4b599c14f1f2a54fe9e1693503085f8889e3b440586a282199dc03e2044 - md5: 9a37ca625fba18b908c1071d133109c5 + size: 317172 + timestamp: 1743831473532 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py312hf4875e0_0.conda + sha256: b8b41da0aac8aab5e48e62ff341374f12cd0ace7a59b80f56bc75371aa4796d5 + md5: 1e2a85e9493ad7c892ecbca89a11837c depends: - __osx >=11.0 - libcxx >=18 @@ -19516,11 +20221,11 @@ packages: - zeromq >=4.3.5,<4.4.0a0 license: BSD-3-Clause license_family: BSD - size: 363241 - timestamp: 1741805459823 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.3.0-py39h80d5f2a_0.conda - sha256: 59e35f76926bcc9cf88fe3bfd04a0aea3fffc2c65e326b057beefe5fad1ac888 - md5: b3ee0ee09857b4558215ca30a02e8d4b + size: 364333 + timestamp: 1743831518152 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/pyzmq-26.4.0-py39h80d5f2a_0.conda + sha256: cd07e8a7d4b65cdc5f08cdd73c61ac3283cb9f06e70e498310a8357c83d623fe + md5: 6199527c3e4440c29558bc19182b70c9 depends: - __osx >=11.0 - libcxx >=18 @@ -19531,11 +20236,11 @@ packages: - zeromq >=4.3.5,<4.4.0a0 license: BSD-3-Clause license_family: BSD - size: 316160 - timestamp: 1741805442410 -- conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py312hd7027bb_0.conda - sha256: 39e0fb384a516bbff9ee0ffdfbb765d0ee1180ad5d6cbdcf75140fe871b4f615 - md5: 5795400c7af6fcc8dc30b72e77e52dca + size: 314843 + timestamp: 1743831560805 +- conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py312hd7027bb_0.conda + sha256: 07fbf17632c6300e53550f829f2e10d2c6f68923aa139d0618eaeadf2d0043ae + md5: ccfe948627071c03e36aa46d9e94bf12 depends: - libsodium >=1.0.20,<1.0.21.0a0 - python >=3.12,<3.13.0a0 @@ -19546,11 +20251,11 @@ packages: - zeromq >=4.3.5,<4.3.6.0a0 license: BSD-3-Clause license_family: BSD - size: 365047 - timestamp: 1741805733926 -- conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.3.0-py39h03e5c00_0.conda - sha256: 77d174d4dbea769979533735010526c3399593ff9208f2b839ed4ea5444536d8 - md5: 9adced2851f970d0b9de3e9d5062b366 + size: 363177 + timestamp: 1743831815399 +- conda: https://conda.anaconda.org/conda-forge/win-64/pyzmq-26.4.0-py39h03e5c00_0.conda + sha256: c68cca70ff936cf33f8070cad385c5b5d9a54dd5e7c8f8fd96f242618fac2f56 + md5: 7f8020bd020eedb93f8ad3469a7981b3 depends: - libsodium >=1.0.20,<1.0.21.0a0 - python >=3.9,<3.10.0a0 @@ -19561,8 +20266,8 @@ packages: - zeromq >=4.3.5,<4.3.6.0a0 license: BSD-3-Clause license_family: BSD - size: 319465 - timestamp: 1741805744854 + size: 318105 + timestamp: 1743831745748 - conda: https://conda.anaconda.org/conda-forge/linux-64/qhull-2020.2-h434a139_5.conda sha256: 776363493bad83308ba30bcb88c2552632581b143e8ee25b1982c8c743e73abc md5: 353823361b1d27eb3960efb076dfcaf6 @@ -19632,9 +20337,70 @@ packages: license: LicenseRef-Qhull size: 422913 timestamp: 1720814413180 -- conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.8.3-h6441bc3_1.conda - sha256: 8ae89546e5110af9ba37402313e4799369abedf51f08c833f304dae540ff0566 - md5: db96ef4241de437be7b41082045ef7d2 +- conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h0384650_3.conda + sha256: 86770adaa855269aedffec529d33154db695f80ac7275852c0767b9634000178 + md5: 8aa69e15597a205fd6f81781fe62c232 + depends: + - __glibc >=2.17,<3.0.a0 + - alsa-lib >=1.2.14,<1.3.0a0 + - dbus >=1.13.6,<2.0a0 + - double-conversion >=3.3.1,<3.4.0a0 + - fontconfig >=2.15.0,<3.0a0 + - fonts-conda-ecosystem + - harfbuzz >=11.0.1 + - icu >=75.1,<76.0a0 + - krb5 >=1.21.3,<1.22.0a0 + - libclang-cpp20.1 >=20.1.5,<20.2.0a0 + - libclang13 >=20.1.5 + - libcups >=2.3.3,<2.4.0a0 + - libdrm >=2.4.124,<2.5.0a0 + - libegl >=1.7.0,<2.0a0 + - libfreetype >=2.13.3 + - libfreetype6 >=2.13.3 + - libgcc >=13 + - libgl >=1.7.0,<2.0a0 + - libglib >=2.84.1,<3.0a0 + - libjpeg-turbo >=3.1.0,<4.0a0 + - libllvm20 >=20.1.5,<20.2.0a0 + - libpng >=1.6.47,<1.7.0a0 + - libpq >=17.5,<18.0a0 + - libsqlite >=3.49.2,<4.0a0 + - libstdcxx >=13 + - libtiff >=4.7.0,<4.8.0a0 + - libwebp-base >=1.5.0,<2.0a0 + - libxcb >=1.17.0,<2.0a0 + - libxkbcommon >=1.9.2,<2.0a0 + - libxml2 >=2.13.8,<2.14.0a0 + - libzlib >=1.3.1,<2.0a0 + - openssl >=3.5.0,<4.0a0 + - pcre2 >=10.45,<10.46.0a0 + - wayland >=1.23.1,<2.0a0 + - xcb-util >=0.4.1,<0.5.0a0 + - xcb-util-cursor >=0.1.5,<0.2.0a0 + - xcb-util-image >=0.4.0,<0.5.0a0 + - xcb-util-keysyms >=0.4.1,<0.5.0a0 + - xcb-util-renderutil >=0.3.10,<0.4.0a0 + - xcb-util-wm >=0.4.2,<0.5.0a0 + - xorg-libice >=1.1.2,<2.0a0 + - xorg-libsm >=1.2.6,<2.0a0 + - xorg-libx11 >=1.8.12,<2.0a0 + - xorg-libxcomposite >=0.4.6,<1.0a0 + - xorg-libxcursor >=1.2.3,<2.0a0 + - xorg-libxdamage >=1.1.6,<2.0a0 + - xorg-libxext >=1.3.6,<2.0a0 + - xorg-libxrandr >=1.5.4,<2.0a0 + - xorg-libxtst >=1.2.5,<2.0a0 + - xorg-libxxf86vm >=1.1.6,<2.0a0 + - zstd >=1.5.7,<1.6.0a0 + constrains: + - qt 6.9.0 + license: LGPL-3.0-only + license_family: LGPL + size: 51970669 + timestamp: 1747406954921 +- conda: https://conda.anaconda.org/conda-forge/linux-64/qt6-main-6.9.0-h6441bc3_1.conda + sha256: 0485df0e29daf02023b98b0d7f5f4f97bd23650582d8c64d80f22cdb1ad01676 + md5: 4029a8dcb1d97ea241dbe5abfda1fad6 depends: - __glibc >=2.17,<3.0.a0 - alsa-lib >=1.2.13,<1.3.0a0 @@ -19643,19 +20409,19 @@ packages: - fontconfig >=2.15.0,<3.0a0 - fonts-conda-ecosystem - freetype >=2.13.3,<3.0a0 - - harfbuzz >=11.0.0,<12.0a0 + - harfbuzz >=11.0.1 - icu >=75.1,<76.0a0 - krb5 >=1.21.3,<1.22.0a0 - - libclang-cpp20.1 >=20.1.1,<20.2.0a0 - - libclang13 >=20.1.1 + - libclang-cpp20.1 >=20.1.2,<20.2.0a0 + - libclang13 >=20.1.2 - libcups >=2.3.3,<2.4.0a0 - libdrm >=2.4.124,<2.5.0a0 - libegl >=1.7.0,<2.0a0 - libgcc >=13 - libgl >=1.7.0,<2.0a0 - - libglib >=2.84.0,<3.0a0 + - libglib >=2.84.1,<3.0a0 - libjpeg-turbo >=3.0.0,<4.0a0 - - libllvm20 >=20.1.1,<20.2.0a0 + - libllvm20 >=20.1.2,<20.2.0a0 - libpng >=1.6.47,<1.7.0a0 - libpq >=17.4,<18.0a0 - libsqlite >=3.49.1,<4.0a0 @@ -19664,10 +20430,10 @@ packages: - libwebp-base >=1.5.0,<2.0a0 - libxcb >=1.17.0,<2.0a0 - libxkbcommon >=1.8.1,<2.0a0 - - libxml2 >=2.13.7,<3.0a0 + - libxml2 >=2.13.7,<2.14.0a0 - libzlib >=1.3.1,<2.0a0 - - mysql-libs >=9.0.1,<9.1.0a0 - - openssl >=3.4.1,<4.0a0 + - mysql-libs >=9.2.0,<9.3.0a0 + - openssl >=3.5.0,<4.0a0 - pcre2 >=10.44,<10.45.0a0 - wayland >=1.23.1,<2.0a0 - xcb-util >=0.4.1,<0.5.0a0 @@ -19688,39 +20454,39 @@ packages: - xorg-libxxf86vm >=1.1.6,<2.0a0 - zstd >=1.5.7,<1.6.0a0 constrains: - - qt 6.8.3 + - qt 6.9.0 license: LGPL-3.0-only license_family: LGPL - size: 50854227 - timestamp: 1743393321721 -- conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.8.3-h72a539a_1.conda - sha256: 25524f06ca96db6ed353f5a36b4b2f65ad9d2a7674116d0318252d53ca094082 - md5: 1f2b193841a71a412f8af19c9925caf0 + size: 51522155 + timestamp: 1744201848686 +- conda: https://conda.anaconda.org/conda-forge/win-64/qt6-main-6.9.0-h83cda92_1.conda + sha256: 40bb84f5898e60dd7ee27a504c0403ea5dae514ce0638b763bb00ff4d73ab611 + md5: 412f970fc305449b6ee626fe9c6638a8 depends: - double-conversion >=3.3.1,<3.4.0a0 - - harfbuzz >=11.0.0,<12.0a0 + - harfbuzz >=11.0.1 - icu >=75.1,<76.0a0 - krb5 >=1.21.3,<1.22.0a0 - - libclang13 >=20.1.1 - - libglib >=2.84.0,<3.0a0 + - libclang13 >=20.1.2 + - libglib >=2.84.1,<3.0a0 - libjpeg-turbo >=3.0.0,<4.0a0 - libpng >=1.6.47,<1.7.0a0 - libsqlite >=3.49.1,<4.0a0 - libtiff >=4.7.0,<4.8.0a0 - libwebp-base >=1.5.0,<2.0a0 - libzlib >=1.3.1,<2.0a0 - - openssl >=3.4.1,<4.0a0 + - openssl >=3.5.0,<4.0a0 - pcre2 >=10.44,<10.45.0a0 - ucrt >=10.0.20348.0 - - vc >=14.2,<15 - - vc14_runtime >=14.29.30139 + - vc >=14.3,<15 + - vc14_runtime >=14.42.34438 - zstd >=1.5.7,<1.6.0a0 constrains: - - qt 6.8.3 + - qt 6.9.0 license: LGPL-3.0-only license_family: LGPL - size: 93819325 - timestamp: 1743394251854 + size: 94780444 + timestamp: 1744204470975 - conda: https://conda.anaconda.org/conda-forge/linux-64/readline-8.2-h8c095d6_2.conda sha256: 2d6d0c026902561ed77cd646b5021aef2d4db22e57a5b0178dfc669231e06d2c md5: 283b96675859b20a825f8fa30f311446 @@ -19825,7 +20591,7 @@ packages: - libblas >=3.9.0,<4.0a0 - libcblas >=3.9.0,<4.0a0 - libcxx >=16 - - libgfortran 5.* + - libgfortran >=5 - libgfortran5 >=12.3.0 - libgfortran5 >=13.2.0 - liblapack >=3.9.0,<4.0a0 @@ -19845,7 +20611,7 @@ packages: - libblas >=3.9.0,<4.0a0 - libcblas >=3.9.0,<4.0a0 - libcxx >=18 - - libgfortran 5.* + - libgfortran >=5 - libgfortran5 >=13.2.0 - liblapack >=3.9.0,<4.0a0 - numpy <2.5 @@ -19865,7 +20631,7 @@ packages: - libblas >=3.9.0,<4.0a0 - libcblas >=3.9.0,<4.0a0 - libcxx >=16 - - libgfortran 5.* + - libgfortran >=5 - libgfortran5 >=12.3.0 - libgfortran5 >=13.2.0 - liblapack >=3.9.0,<4.0a0 @@ -19886,7 +20652,7 @@ packages: - libblas >=3.9.0,<4.0a0 - libcblas >=3.9.0,<4.0a0 - libcxx >=18 - - libgfortran 5.* + - libgfortran >=5 - libgfortran5 >=13.2.0 - liblapack >=3.9.0,<4.0a0 - numpy <2.5 @@ -19936,15 +20702,15 @@ packages: license_family: BSD size: 15350553 timestamp: 1739793319263 -- conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-75.8.2-pyhff2d567_0.conda - sha256: 91d664ace7c22e787775069418daa9f232ee8bafdd0a6a080a5ed2395a6fa6b2 - md5: 9bddfdbf4e061821a1a443f93223be61 +- conda: https://conda.anaconda.org/conda-forge/noarch/setuptools-79.0.1-pyhff2d567_0.conda + sha256: 5ebc4bb71fbdc8048b08848519150c8d44b8eb18445711d3258c9d402ba87a2c + md5: fa6669cc21abd4b7b6c5393b7bc71914 depends: - python >=3.9 license: MIT license_family: MIT - size: 777736 - timestamp: 1740654030775 + size: 787541 + timestamp: 1745484086827 - conda: https://conda.anaconda.org/conda-forge/osx-64/sigtool-0.1.3-h88f4db0_0.tar.bz2 sha256: 46fdeadf8f8d725819c4306838cdfd1099cd8fe3e17bd78862a5dfdcd6de61cf md5: fbfb84b9de9a6939cb165c02c69b1865 @@ -20062,38 +20828,38 @@ packages: license: Zlib size: 71271 timestamp: 1611562303689 -- conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-10.0.0-h3f2d84a_2.conda - sha256: 997162d7585a3453cf5563ca563d645b512699b3ddf64bb28aaa6f3d771e3cb4 - md5: 4feae0cd8a72cd1ef72b7528730946e5 +- conda: https://conda.anaconda.org/conda-forge/linux-64/tinyxml2-11.0.0-h3f2d84a_0.conda + sha256: 3ae98c2ca54928b2c72dbb4bd8ea229d3c865ad39367d377908294d9fb1e6f2c + md5: aeb0b91014ac8c5d468e32b7a5ce8ac2 depends: - - libgcc >=13 - __glibc >=2.17,<3.0.a0 + - libgcc >=13 - libstdcxx >=13 - libgcc >=13 license: Zlib - size: 130740 - timestamp: 1742462199793 -- conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-10.0.0-h92383a6_2.conda - sha256: c09f62306aaffb38493b2fdb545b5924c98a22ad34ba52007cca215386fb9665 - md5: 43c3597709dab94b6c961e06664ababd + size: 131351 + timestamp: 1742246125630 +- conda: https://conda.anaconda.org/conda-forge/osx-64/tinyxml2-11.0.0-h92383a6_0.conda + sha256: 7707609e716fb3bada13629bda7b6e259d9f19a1f4ea6b24d3d8e7103f3548c9 + md5: 09045c9568f4317e338406747828e45b depends: - - libcxx >=18 - __osx >=10.13 + - libcxx >=18 license: Zlib - size: 122818 - timestamp: 1742462302100 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-10.0.0-ha1acc90_2.conda - sha256: 84df0c8965e584fd0811076cb1d10a64de1a02e38c4106fb3590ad62ef166196 - md5: b37c36b9ff45789fcf52c949d8f2ecbc + size: 123209 + timestamp: 1742246276402 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/tinyxml2-11.0.0-ha1acc90_0.conda + sha256: bbd9294551ff727305f8335819c24d2490d5d79e0f3d90957992c39d2146093a + md5: 6778d917f88222e8f27af8ec5c41f277 depends: - __osx >=11.0 - libcxx >=18 license: Zlib - size: 122003 - timestamp: 1742462238180 -- conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-10.0.0-he0c23c2_2.conda - sha256: 622e6b974f26eb2f09b9080207c10ed7278c302b229062acb35d67b06d5f1c3d - md5: 20cbb014a490241f74d429d2636aba63 + size: 122269 + timestamp: 1742246179980 +- conda: https://conda.anaconda.org/conda-forge/win-64/tinyxml2-11.0.0-he0c23c2_0.conda + sha256: f22e0ef11cce8b25e48a2d4a0ca8a2fc5b89841c36f8ec955b01baff7cd3a924 + md5: e80ff399c7b08f37ecdaeaeb5017b9fb depends: - vc >=14.2,<15 - vc14_runtime >=14.29.30139 @@ -20102,8 +20868,8 @@ packages: - vc14_runtime >=14.29.30139 - ucrt >=10.0.20348.0 license: Zlib - size: 75392 - timestamp: 1742462215649 + size: 75152 + timestamp: 1742246154008 - conda: https://conda.anaconda.org/conda-forge/linux-64/tk-8.6.13-noxft_h4845f30_101.conda sha256: e0569c9caa68bf476bead1bed3d79650bb080b532c64a4af7d8ca286c08dea4e md5: d453b98d9c83e71da0741bb0ff4d76bc @@ -20257,16 +21023,16 @@ packages: license_family: BSD size: 110051 timestamp: 1733367480074 -- conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.0-pyh29332c3_1.conda - sha256: 18eb76e8f19336ecc9733c02901b30503cdc4c1d8de94f7da7419f89b3ff4c2f - md5: 4c446320a86cc5d48e3b80e332d6ebd7 +- conda: https://conda.anaconda.org/conda-forge/noarch/typing_extensions-4.13.2-pyh29332c3_0.conda + sha256: a8aaf351e6461de0d5d47e4911257e25eec2fa409d71f3b643bb2f748bde1c08 + md5: 83fc6ae00127671e301c9f44254c31b8 depends: - python >=3.9 - python license: PSF-2.0 license_family: PSF - size: 52077 - timestamp: 1743201626659 + size: 52189 + timestamp: 1744302253997 - conda: https://conda.anaconda.org/conda-forge/noarch/tzdata-2025b-h78e105d_0.conda sha256: 5aaa366385d716557e365f0a4e9c3fca43ba196872abbbe3d56bb610d131e192 md5: 4222072737ccff51314b5ece9c7d6f5a @@ -20441,49 +21207,49 @@ packages: license_family: Apache size: 400328 timestamp: 1736692859302 -- conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-h2e5d1f2_2.conda - sha256: e8c256eb6fd862445abc0efb2a38b88993e77edadcdc35536efeb1cb13baae6a - md5: c251c3c8818541801841f5c7d69454e9 +- conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom-4.0.1-hae71d53_3.conda + sha256: 70b1e7322bf6306de6186e91fb87c15f7ba5c1aeb6d0fd31780e088c42025fc4 + md5: a7830d1b7ade9d3f8c35191084fe7022 depends: - urdfdom_headers - - __glibc >=2.17,<3.0.a0 - libstdcxx >=13 - libgcc >=13 - - tinyxml2 >=10.0.0,<10.1.0a0 + - __glibc >=2.17,<3.0.a0 + - tinyxml2 >=11.0.0,<11.1.0a0 - console_bridge >=1.0.2,<1.1.0a0 license: BSD-3-Clause license_family: BSD - size: 118730 - timestamp: 1742386855177 -- conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hf5f5f9e_2.conda - sha256: 04bc7649033cd5aa5016d981b00747d9fe836e1203643ccf428110c90e25e47e - md5: 76de579dddd1f71f81a7a3ad36a35701 + size: 118733 + timestamp: 1743679555211 +- conda: https://conda.anaconda.org/conda-forge/osx-64/urdfdom-4.0.1-hdeef459_3.conda + sha256: 9d6e70b83559edccd0a67dae397e710ca17042d6879fdc311798f9e493ffa931 + md5: 1313cdbc2a7772093ecff8ac922d5f51 depends: - urdfdom_headers - libcxx >=18 - __osx >=10.13 + - tinyxml2 >=11.0.0,<11.1.0a0 - console_bridge >=1.0.2,<1.1.0a0 - - tinyxml2 >=10.0.0,<10.1.0a0 license: BSD-3-Clause license_family: BSD - size: 107028 - timestamp: 1742386812373 -- conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h090268e_2.conda - sha256: 7c94f9544062c32b6ef9da6d843a6003e45f213824666aec49a5edbab07b882e - md5: 17d77d29d06edd5afb7be42e223cf755 + size: 107127 + timestamp: 1743679551416 +- conda: https://conda.anaconda.org/conda-forge/osx-arm64/urdfdom-4.0.1-h48bab5a_3.conda + sha256: bfde25d74ac5839d1f7ca0a2f7d6a36dc9ae9b7e2df1c3799be98d1985393b60 + md5: 7e841176ab2b30860123ce7ea0a710c5 depends: - urdfdom_headers - __osx >=11.0 - libcxx >=18 - - tinyxml2 >=10.0.0,<10.1.0a0 + - tinyxml2 >=11.0.0,<11.1.0a0 - console_bridge >=1.0.2,<1.1.0a0 license: BSD-3-Clause license_family: BSD - size: 105635 - timestamp: 1742386821928 -- conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h4358a7e_2.conda - sha256: 59d443e3305a893e974da0b76194dacaad81c749f26ad579854ca44c030cfbbb - md5: e3570629a83afbbdd1c70e61d16b9d4d + size: 105695 + timestamp: 1743679565324 +- conda: https://conda.anaconda.org/conda-forge/win-64/urdfdom-4.0.1-h9d4477b_3.conda + sha256: 63d4b4153a498aef257d53f4d30c71e6f6f55dc31dbb75224602d98f0e5a0867 + md5: 26ae0f0f8f61962bd3bb3c6b7f3e36b3 depends: - urdfdom_headers - vc >=14.2,<15 @@ -20492,12 +21258,12 @@ packages: - vc >=14.2,<15 - vc14_runtime >=14.29.30139 - ucrt >=10.0.20348.0 - - tinyxml2 >=10.0.0,<10.1.0a0 + - tinyxml2 >=11.0.0,<11.1.0a0 - console_bridge >=1.0.2,<1.1.0a0 license: BSD-3-Clause license_family: BSD - size: 103159 - timestamp: 1742386930964 + size: 103147 + timestamp: 1743679676862 - conda: https://conda.anaconda.org/conda-forge/linux-64/urdfdom_headers-1.1.2-h84d6215_0.conda sha256: 9f4090616ed1cb509bb65f1edb11b23c86d929db0ea3af2bf84277caa4337c40 md5: 4872efb515124284f8cee0f957f3edce @@ -20571,6 +21337,7 @@ packages: - platformdirs >=3.9.1,<5 - python >=3.9 license: MIT + license_family: MIT size: 3635535 timestamp: 1743474070226 - conda: https://conda.anaconda.org/conda-forge/win-64/vs2015_runtime-14.42.34438-h7142326_26.conda @@ -20595,26 +21362,28 @@ packages: license_family: BSD size: 20609 timestamp: 1743195166620 -- conda: https://conda.anaconda.org/conda-forge/win-64/vswhere-3.1.7-h57928b3_0.conda - sha256: 8caeda9c0898cb8ee2cf4f45640dbbbdf772ddc01345cfb0f7b352c58b4d8025 - md5: ba83df93b48acfc528f5464c9a882baa +- conda: https://conda.anaconda.org/conda-forge/noarch/vswhere-3.1.7-h40126e0_1.conda + sha256: b72270395326dc56de9bd6ca82f63791b3c8c9e2b98e25242a9869a4ca821895 + md5: f622897afff347b715d046178ad745a5 + depends: + - __win license: MIT license_family: MIT - size: 219013 - timestamp: 1719460515960 -- conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_0.conda - sha256: 0884b2023a32d2620192cf2e2fc6784b8d1e31cf9f137e49e00802d4daf7d1c1 - md5: 0a732427643ae5e0486a727927791da1 + size: 238764 + timestamp: 1745560912727 +- conda: https://conda.anaconda.org/conda-forge/linux-64/wayland-1.23.1-h3e06ad9_1.conda + sha256: 73d809ec8056c2f08e077f9d779d7f4e4c2b625881cad6af303c33dc1562ea01 + md5: a37843723437ba75f42c9270ffe800b1 depends: - __glibc >=2.17,<3.0.a0 - - libexpat >=2.6.2,<3.0a0 - - libffi >=3.4,<4.0a0 - - libgcc-ng >=13 - - libstdcxx-ng >=13 + - libexpat >=2.7.0,<3.0a0 + - libffi >=3.4.6,<3.5.0a0 + - libgcc >=13 + - libstdcxx >=13 license: MIT license_family: MIT - size: 321561 - timestamp: 1724530461598 + size: 321099 + timestamp: 1745806602179 - conda: https://conda.anaconda.org/conda-forge/noarch/wcwidth-0.2.13-pyhd8ed1ab_1.conda sha256: f21e63e8f7346f9074fd00ca3b079bd3d2fa4d71f1f89d5b6934bf31446dc2a5 md5: b68980f2495d096e71c7fd9d7ccf63e6 @@ -20689,17 +21458,17 @@ packages: license_family: MIT size: 51689 timestamp: 1718844051451 -- conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.43-hb9d3cd8_0.conda - sha256: 0d89b5873515a1f05d311f37ea4e087bbccc0418afa38f2f6189e97280db3179 - md5: f725c7425d6d7c15e31f3b99a88ea02f +- conda: https://conda.anaconda.org/conda-forge/linux-64/xkeyboard-config-2.44-hb9d3cd8_0.conda + sha256: 83ad2be5eb1d359b4cd7d7a93a6b25cdbfdce9d27b37508e2a4efe90d3a4ed80 + md5: 7c91bfc90672888259675ad2ad28af9c depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 - - xorg-libx11 >=1.8.10,<2.0a0 + - xorg-libx11 >=1.8.12,<2.0a0 license: MIT license_family: MIT - size: 389475 - timestamp: 1727840188958 + size: 392870 + timestamp: 1745806998840 - conda: https://conda.anaconda.org/conda-forge/linux-64/xorg-libice-1.1.2-hb9d3cd8_0.conda sha256: c12396aabb21244c212e488bbdc4abcdef0b7404b15761d9329f5a4a39113c4b md5: fb901ff28063514abb6046c9ec2c4a45 @@ -20933,48 +21702,48 @@ packages: license_family: MIT size: 17819 timestamp: 1734214575628 -- conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.1.0-pyhd8ed1ab_0.conda - sha256: 9978c22319e85026d5a4134944f73bac820c948ca6b6c32af6b6985b5221cd8a - md5: fdf07e281a9e5e10fc75b2dd444136e9 +- conda: https://conda.anaconda.org/conda-forge/noarch/xyzservices-2025.4.0-pyhd8ed1ab_0.conda + sha256: ac6d4d4133b1e0f69075158cdf00fccad20e29fc6cc45faa480cec37a84af6ae + md5: 5663fa346821cd06dc1ece2c2600be2c depends: - python >=3.8 license: BSD-3-Clause license_family: BSD - size: 48641 - timestamp: 1737234992057 -- conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.6.4-hbcc6ac9_0.conda - sha256: 91fc251034fa5199919680aa50299296d89da54b2d066fb6e6a60461c17c0c4a - md5: bb511c87804cf7220246a3a6efc45c22 + size: 49477 + timestamp: 1745598150265 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xz-5.8.1-hbcc6ac9_0.conda + sha256: 65f32402dc69fb20dc9b6307793405f45b6fd979a55534e1a4f2d39bcabea303 + md5: c9880133bf4750a4c848f8d2c78d498c depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 - - liblzma 5.6.4 hb9d3cd8_0 - - liblzma-devel 5.6.4 hb9d3cd8_0 - - xz-gpl-tools 5.6.4 hbcc6ac9_0 - - xz-tools 5.6.4 hb9d3cd8_0 + - liblzma 5.8.1 hb9d3cd8_0 + - liblzma-devel 5.8.1 hb9d3cd8_0 + - xz-gpl-tools 5.8.1 hbcc6ac9_0 + - xz-tools 5.8.1 hb9d3cd8_0 license: 0BSD AND LGPL-2.1-or-later AND GPL-2.0-or-later - size: 23477 - timestamp: 1738525395307 -- conda: https://conda.anaconda.org/conda-forge/linux-64/xz-gpl-tools-5.6.4-hbcc6ac9_0.conda - sha256: 300fc4e5993a36c979e61b1a38d00f0c23c0c56d5989be537cbc7bd8658254ed - md5: 246840b451f7a66bd68869e56b066dd5 + size: 23859 + timestamp: 1743771157444 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xz-gpl-tools-5.8.1-hbcc6ac9_0.conda + sha256: f48787ef798a44d7ef5618427af7881ae0229a930810963c43acc5444abe2437 + md5: 9177ea2e6886b8070012e1d68531ab2f depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 - - liblzma 5.6.4 hb9d3cd8_0 + - liblzma 5.8.1 hb9d3cd8_0 license: 0BSD AND LGPL-2.1-or-later AND GPL-2.0-or-later - size: 33285 - timestamp: 1738525381548 -- conda: https://conda.anaconda.org/conda-forge/linux-64/xz-tools-5.6.4-hb9d3cd8_0.conda - sha256: 57506a312d8cfbee98217fb382822bd49794ea6318dd4e0413a0d588dc6f4f69 - md5: a098f9f949af52610fdceb8e35b57513 + size: 33622 + timestamp: 1743771139491 +- conda: https://conda.anaconda.org/conda-forge/linux-64/xz-tools-5.8.1-hb9d3cd8_0.conda + sha256: ec01d8c97f77c80a2bf42050b761e199663a4a35d22fc194c950802589e15e59 + md5: 908d29a6cfd9e9a78d07012f5d1a8707 depends: - __glibc >=2.17,<3.0.a0 - libgcc >=13 - - liblzma 5.6.4 hb9d3cd8_0 + - liblzma 5.8.1 hb9d3cd8_0 license: 0BSD AND LGPL-2.1-or-later - size: 89735 - timestamp: 1738525367692 + size: 96051 + timestamp: 1743771123306 - conda: https://conda.anaconda.org/conda-forge/linux-64/yaml-0.2.5-h7f98852_2.tar.bz2 sha256: a4e34c710eeb26945bdbdaba82d3d74f60a78f54a874ec10d373811a5d217535 md5: 4cb3ad778ec2d5a7acbdf254eb1c42ae diff --git a/pixi.toml b/pixi.toml index d42b4a8ae8..d0fff69dea 100644 --- a/pixi.toml +++ b/pixi.toml @@ -1,6 +1,6 @@ [project] name = "pinocchio" -version = "3.6.0" +version = "3.7.0" description = "A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives" platforms = ["linux-64", "osx-64", "osx-arm64", "win-64"] channels = ["conda-forge"] @@ -13,6 +13,8 @@ cmake = ">=3.10" cxx-compiler = ">=1.7.0" ninja = ">=1.11" pkg-config = ">=0.29.2" +doxygen = ">=1.12.0" +git = ">=2.47.1" [dependencies] libboost-devel = ">=1.80.0" diff --git a/sources.cmake b/sources.cmake index 98a64c46bd..bf462fe188 100644 --- a/sources.cmake +++ b/sources.cmake @@ -32,14 +32,44 @@ set(${PROJECT_NAME}_CORE_PUBLIC_HEADERS ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constrained-dynamics.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constrained-dynamics.hxx ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constrained-problem-data.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/baumgarte-corrector-parameters.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/kinematics-constraint-base.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/constraint-ordering.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/constraint-ordering.hxx + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/point-bilateral-constraint.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/weld-constraint.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/box-set.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/cone-base.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/coulomb-friction-cone.hpp - ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/visitors/constraint-model-visitor.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/constraints.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/fictious-constraint.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/constraint-collection-default.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/constraint-data-base.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/constraint-data-generic.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/constraint-model-base.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/constraint-model-common-parameters.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/constraint-model-generic.hpp - ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/constraints.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/frame-constraint-model-base.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/frame-constraint-data-base.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/patch-frictional-constraint.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/point-frictional-constraint.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/fwd.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/joint-limit-constraint.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/joint-limit-constraint.hxx + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/joint-limit-constraint-cone.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/joint-frictional-constraint.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/joint-frictional-constraint.hxx + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/null-set.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/orthant-cone.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/point-constraint-model-base.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/point-constraint-data-base.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/sets.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/set-base.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/jointwise-constraint-base.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/unbounded-set.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/utils.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/constraints/visitors/constraint-model-visitor.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/contact-cholesky.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/contact-cholesky.hxx ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/contact-dynamics.hpp @@ -58,10 +88,15 @@ set(${PROJECT_NAME}_CORE_PUBLIC_HEADERS ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/default-check.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/delassus.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/delassus.hxx - ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/delassus-operartor-ref.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/delassus-operator.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/delassus-operator-ref.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/delassus-operator-base.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/delassus-operator-preconditioned.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/delassus-operator-cholesky-expression.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/delassus-operator-dense.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/delassus-operator-rigid-body.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/delassus-operator-rigid-body.hxx + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/delassus-operator-rigid-body-visitors.hxx ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/delassus-operator-sparse.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/energy.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/energy.hxx @@ -84,8 +119,12 @@ set(${PROJECT_NAME}_CORE_PUBLIC_HEADERS ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/kinematics-derivatives.hxx ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/kinematics.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/kinematics.hxx + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/loop-constrained-aba.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/loop-constrained-aba.hxx ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/model.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/model.hxx + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/preconditioner-base.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/diagonal-preconditioner.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/pgs-solver.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/pgs-solver.hxx ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/proximal.hpp @@ -101,6 +140,7 @@ set(${PROJECT_NAME}_CORE_PUBLIC_HEADERS ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/rnea-second-order-derivatives.hxx ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/utils/force.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/algorithm/utils/motion.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/alloca.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/autodiff/casadi-algo.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/autodiff/casadi.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/autodiff/casadi/math/matrix.hpp @@ -115,11 +155,16 @@ set(${PROJECT_NAME}_CORE_PUBLIC_HEADERS ${PROJECT_SOURCE_DIR}/include/pinocchio/autodiff/cppad/spatial/log.hxx ${PROJECT_SOURCE_DIR}/include/pinocchio/autodiff/cppad/spatial/se3-tpl.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/autodiff/cppad/utils/static-if.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/common/data-entity.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/common/fwd.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/common/model-entity.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/codegen/code-generator-algo.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/codegen/code-generator-base.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/codegen/cppadcg.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/container/aligned-vector.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/container/boost-container-limits.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/container/double-entry-container.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/container/storage.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/context/casadi.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/context/cppad.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/context/cppadcg.hpp @@ -128,23 +173,36 @@ set(${PROJECT_NAME}_CORE_PUBLIC_HEADERS ${PROJECT_SOURCE_DIR}/include/pinocchio/context.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/core/binary-op.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/core/unary-op.hpp - ${PROJECT_SOURCE_DIR}/include/pinocchio/deprecated-macros.hpp - ${PROJECT_SOURCE_DIR}/include/pinocchio/deprecated-namespaces.hpp - ${PROJECT_SOURCE_DIR}/include/pinocchio/deprecation.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/eigen-macros.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/fwd.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/macros.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/unsupported.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/arithmetic-operators.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/math/casadi.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/math/comparison-operators.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/math/cppadcg.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/math/cppad.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/details/matrix-inverse-1x1.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/details/matrix-inverse-2x2.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/details/matrix-inverse-3x3.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/details/matrix-inverse-4x4.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/details/matrix-inverse-5x5.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/details/matrix-inverse-6x6.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/details/matrix-inverse-7x7.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/details/matrix-inverse-8x8.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/details/matrix-inverse-9x9.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/details/matrix-inverse-10x10.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/details/matrix-inverse-11x11.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/details/matrix-inverse-12x12.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/eigen-helpers.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/math/eigenvalues.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/math/fwd.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/math/gram-schmidt-orthonormalisation.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/math/lanczos-decomposition.hpp - ${PROJECT_SOURCE_DIR}/include/pinocchio/math/matrix-block.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/math/matrix.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/matrix-block.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/matrix-inverse.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/matrix-inverse-code-generated.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/math/multiprecision.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/math/multiprecision-mpfr.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/math/quaternion.hpp @@ -157,6 +215,7 @@ set(${PROJECT_NAME}_CORE_PUBLIC_HEADERS ${PROJECT_SOURCE_DIR}/include/pinocchio/math/tensor.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/math/triangular-matrix.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/math/tridiagonal-matrix.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/math/eigenvalues-tridiagonal-matrix.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/data.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/data.hxx ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/fcl.hpp @@ -180,6 +239,7 @@ set(${PROJECT_NAME}_CORE_PUBLIC_HEADERS ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/joint/joint-data-base.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/joint/joint-free-flyer.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/joint/joint-generic.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/joint/joint-generic.hxx ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/joint/joint-helical.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/joint/joint-helical-unaligned.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/joint/joint-mimic.hpp @@ -209,6 +269,7 @@ set(${PROJECT_NAME}_CORE_PUBLIC_HEADERS ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/liegroup/liegroup-base.hxx ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/liegroup/liegroup-collection.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/liegroup/liegroup-generic.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/liegroup/liegroup-joint.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/liegroup/liegroup.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/liegroup/liegroup-variant-visitors.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/liegroup/liegroup-variant-visitors.hxx @@ -229,8 +290,14 @@ set(${PROJECT_NAME}_CORE_PUBLIC_HEADERS ${PROJECT_SOURCE_DIR}/include/pinocchio/multibody/sample-models.hxx ${PROJECT_SOURCE_DIR}/include/pinocchio/serialization/aligned-vector.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/serialization/archive.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/serialization/constraints-data.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/serialization/constraints-model.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/serialization/constraints-set.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/serialization/data.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/serialization/delassus.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/serialization/double-entry-container.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/serialization/eigen.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/serialization/eigen-storage.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/serialization/csv.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/serialization/fcl.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/serialization/force.hpp @@ -286,10 +353,13 @@ set(${PROJECT_NAME}_CORE_PUBLIC_HEADERS ${PROJECT_SOURCE_DIR}/include/pinocchio/utils/file-io.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/utils/helpers.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/utils/openmp.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/utils/reference.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/utils/shared-ptr.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/utils/static-if.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/utils/std-vector.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/utils/string-generator.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/utils/string.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/utils/template-template-parameter.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/utils/timer2.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/utils/timer.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/utils/version.hpp) @@ -339,6 +409,7 @@ set(${PROJECT_NAME}_PARSERS_SOURCES ${PROJECT_SOURCE_DIR}/src/parsers/mjcf/mjcf-graph-geom.cpp) set(${PROJECT_NAME}_PARSERS_PUBLIC_HEADERS + ${PROJECT_SOURCE_DIR}/include/pinocchio/parsers/fwd.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/parsers/meshloader-fwd.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/parsers/srdf.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/parsers/srdf.hxx @@ -473,7 +544,22 @@ set(${PROJECT_NAME}_BINDINGS_PYTHON_PUBLIC_HEADERS ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/delassus-operator.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/proximal.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/algorithms.hpp - ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/coulomb-friction-cone.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/baumgarte-corrector-parameters.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/baumgarte-corrector-vector-parameters.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/constraint-data-base.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/constraint-data.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/constraint-data-inheritance.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/constraint-model-base.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/constraint-model.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/constraint-model-inheritance.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/constraints-datas.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/constraints-models.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/constraints-variant.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/set-base.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/set-box-set.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/set-coulomb-friction-cone.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/set-joint-limit-cone.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/algorithm/constraints/set-trivial-cones.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/context.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/pybind11-all.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/pybind11.hpp @@ -498,6 +584,7 @@ set(${PROJECT_NAME}_BINDINGS_PYTHON_PUBLIC_HEADERS ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/utils/std-map.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/utils/cast.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/utils/deprecation.hpp + ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/utils/keep-alive.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/utils/model-checker.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/utils/namespace.hpp ${PROJECT_SOURCE_DIR}/include/pinocchio/bindings/python/context/cppadcg.hpp @@ -567,6 +654,7 @@ set(${PROJECT_NAME}_BINDINGS_PYTHON_SOURCES ${PROJECT_SOURCE_DIR}/bindings/python/algorithm/expose-rnea.cpp ${PROJECT_SOURCE_DIR}/bindings/python/algorithm/expose-contact-jacobian.cpp ${PROJECT_SOURCE_DIR}/bindings/python/algorithm/constraints/expose-cones.cpp + ${PROJECT_SOURCE_DIR}/bindings/python/algorithm/constraints/expose-constraints.cpp ${PROJECT_SOURCE_DIR}/bindings/python/algorithm/expose-cholesky.cpp ${PROJECT_SOURCE_DIR}/bindings/python/algorithm/expose-regressor.cpp ${PROJECT_SOURCE_DIR}/bindings/python/algorithm/expose-kinematics-derivatives.cpp @@ -586,6 +674,7 @@ set(${PROJECT_NAME}_BINDINGS_PYTHON_SOURCES ${PROJECT_SOURCE_DIR}/bindings/python/math/expose-linalg.cpp ${PROJECT_SOURCE_DIR}/bindings/python/math/expose-tridiagonal-matrix.cpp ${PROJECT_SOURCE_DIR}/bindings/python/math/expose-lanczos-decomposition.cpp + ${PROJECT_SOURCE_DIR}/bindings/python/math/expose-gram-schmidt-orthonormalisation.cpp ${PROJECT_SOURCE_DIR}/bindings/python/math/expose-rpy.cpp ${PROJECT_SOURCE_DIR}/bindings/python/math/expose-eigen-types.cpp ${PROJECT_SOURCE_DIR}/bindings/python/serialization/serialization.cpp diff --git a/src/CMakeLists.txt b/src/CMakeLists.txt index d66adf195e..cb560b2956 100644 --- a/src/CMakeLists.txt +++ b/src/CMakeLists.txt @@ -182,10 +182,26 @@ add_header_group(${PROJECT_NAME}_EXTRA_PUBLIC_HEADERS) add_header_group(${PROJECT_NAME}_CORE_GENERATED_PUBLIC_HEADERS) add_header_group(${PROJECT_NAME}_VISUALIZERS_PUBLIC_HEADERS) +# (optional) define profiling target (tracy) on which downstream targets will depend +if(PINOCCHIO_BUILD_WITH_TRACY) + set(PROFILING_LIB_NAME "${PROJECT_NAME}_tracy") + # No scalar or sources for this target + pinocchio_target(${PROFILING_LIB_NAME} INTERFACE) + # The main CMakeLists file imports cmake/tracy.cmake, which always generates a pinocchio/tracy.hpp + # header file with macros. If PINOCCHIO_TRACY_ENABLE is not defined, the macros do nothing, + # otherwise, the tracy macros are activated. Finally, we set INTERFACE here because the definition + # is only needed by downstream targets consuming this pinocchio profiling target. + target_compile_definitions(${PROFILING_LIB_NAME} INTERFACE PINOCCHIO_TRACY_ENABLE) + target_link_libraries(${PROFILING_LIB_NAME} INTERFACE Tracy::TracyClient) +endif(PINOCCHIO_BUILD_WITH_TRACY) + # Define the default target (double). # # This target will also have hpp-fcl and workspace module in it. pinocchio_specific_type(default DEFAULT_SCOPE) +if(PINOCCHIO_BUILD_WITH_TRACY) + target_link_libraries(${PROJECT_NAME}_default INTERFACE ${PROFILING_LIB_NAME}) +endif(PINOCCHIO_BUILD_WITH_TRACY) # Some core library algorithms have different behavior if PINOCCHIO_WITH_HPP_FCL is defined. Since # some are template instantiated, or some user can link only on pinocchio_default, we muste define diff --git a/src/algorithm/aba-derivatives.cpp b/src/algorithm/aba-derivatives.cpp index f0815c3a54..aefc696da8 100644 --- a/src/algorithm/aba-derivatives.cpp +++ b/src/algorithm/aba-derivatives.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2022 INRIA +// Copyright (c) 2022-2024 INRIA // #include "pinocchio/algorithm/aba-derivatives.hpp" @@ -54,6 +54,8 @@ namespace pinocchio Eigen::Ref, Eigen::Ref, Eigen::Ref, + context::Force, + Eigen::aligned_allocator, Eigen::Ref, Eigen::Ref, Eigen::Ref>( @@ -62,7 +64,7 @@ namespace pinocchio const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, - const container::aligned_vector> &, + const std::vector> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &); @@ -74,6 +76,8 @@ namespace pinocchio Eigen::Ref, Eigen::Ref, Eigen::Ref, + context::Force, + Eigen::aligned_allocator, Eigen::Ref, Eigen::Ref, Eigen::Ref>( @@ -82,7 +86,7 @@ namespace pinocchio const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, - const container::aligned_vector> &, + const std::vector> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &); @@ -106,13 +110,15 @@ namespace pinocchio JointCollectionDefaultTpl, Eigen::Ref, Eigen::Ref, - Eigen::Ref>( + Eigen::Ref, + context::Force, + Eigen::aligned_allocator>( const context::Model &, context::Data &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, - const container::aligned_vector> &); + const std::vector> &); template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void computeABADerivatives< context::Scalar, @@ -138,20 +144,26 @@ namespace pinocchio context::Scalar, context::Options, JointCollectionDefaultTpl, + context::Force, + Eigen::aligned_allocator, Eigen::Ref, Eigen::Ref, Eigen::Ref>( const context::Model &, context::Data &, - const container::aligned_vector> &, + const std::vector> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &); } // namespace impl - template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void - computeABADerivatives( + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void computeABADerivatives< + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + context::Force, + Eigen::aligned_allocator>( const context::Model &, context::Data &, - const container::aligned_vector> &); + const std::vector> &); } // namespace pinocchio diff --git a/src/algorithm/aba.cpp b/src/algorithm/aba.cpp index 1d275ae4d9..9323f21055 100644 --- a/src/algorithm/aba.cpp +++ b/src/algorithm/aba.cpp @@ -27,13 +27,14 @@ namespace pinocchio Eigen::Ref, Eigen::Ref, Eigen::Ref, - ForceTpl>( + context::Force, + Eigen::aligned_allocator>( const context::Model &, context::Data &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, const Eigen::MatrixBase> &, - const container::aligned_vector> &, + const std::vector> &, const Convention); template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI const context::RowMatrixXs & diff --git a/src/algorithm/constrained-dynamics.cpp b/src/algorithm/constrained-dynamics.cpp index 8b0b33e79b..972c02a91c 100644 --- a/src/algorithm/constrained-dynamics.cpp +++ b/src/algorithm/constrained-dynamics.cpp @@ -14,6 +14,7 @@ namespace pinocchio template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void initConstraintDynamics< context::Scalar, context::Options, + RigidConstraintModel, JointCollectionDefaultTpl, typename context::RigidConstraintModelVector::allocator_type>( const context::Model &, context::Data &, const context::RigidConstraintModelVector &); diff --git a/src/algorithm/contact-cholesky.cpp b/src/algorithm/contact-cholesky.cpp index ff4d70b9fe..b8e45a0d53 100644 --- a/src/algorithm/contact-cholesky.cpp +++ b/src/algorithm/contact-cholesky.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2022 INRIA +// Copyright (c) 2022-2025 INRIA // #include "pinocchio/spatial/fwd.hpp" @@ -25,17 +25,18 @@ namespace pinocchio ContactCholeskyDecompositionTpl; template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void - ContactCholeskyDecompositionTpl::allocate< + ContactCholeskyDecompositionTpl::resize< context::Scalar, context::Options, JointCollectionDefaultTpl, + context::RigidConstraintModel, typename context::RigidConstraintModelVector::allocator_type>( const context::Model &, const context::RigidConstraintModelVector &); template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void ContactCholeskyDecompositionTpl:: getInverseOperationalSpaceInertiaMatrix( - const Eigen::MatrixBase &) const; + const Eigen::MatrixBase &, bool) const; template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void ContactCholeskyDecompositionTpl:: @@ -51,7 +52,9 @@ namespace pinocchio context::Scalar, context::Options, JointCollectionDefaultTpl, + context::RigidConstraintModel, typename context::RigidConstraintModelVector::allocator_type, + context::RigidConstraintData, typename context::RigidConstraintDataVector::allocator_type>( const context::Model &, context::Data &, diff --git a/src/algorithm/contact-jacobian.cpp b/src/algorithm/contact-jacobian.cpp index 4f988fb357..6eada04af2 100644 --- a/src/algorithm/contact-jacobian.cpp +++ b/src/algorithm/contact-jacobian.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2022 INRIA +// Copyright (c) 2022-2024 INRIA // #include "pinocchio/spatial/fwd.hpp" @@ -14,11 +14,13 @@ namespace pinocchio context::Scalar, context::Options, JointCollectionDefaultTpl, + context::RigidConstraintModel, + context::RigidConstraintData, context::MatrixXs>( const context::Model &, const context::Data &, - const context::RigidConstraintModel &, - context::RigidConstraintData &, + const ConstraintModelBase &, + ConstraintDataBase &, const Eigen::MatrixBase &); template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void getConstraintsJacobian< @@ -26,7 +28,9 @@ namespace pinocchio context::Options, JointCollectionDefaultTpl, context::MatrixXs, + context::RigidConstraintModel, typename context::RigidConstraintModelVector::allocator_type, + context::RigidConstraintData, typename context::RigidConstraintDataVector::allocator_type>( const context::Model &, const context::Data &, diff --git a/src/algorithm/joint-configuration.cpp b/src/algorithm/joint-configuration.cpp index 56cdce0729..df4b670706 100644 --- a/src/algorithm/joint-configuration.cpp +++ b/src/algorithm/joint-configuration.cpp @@ -187,6 +187,83 @@ namespace pinocchio const ArgumentPosition, const AssignmentOperatorType); + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void tangentMap< + LieGroupMap, + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + context::VectorXs, + context::MatrixXs>( + const context::Model &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const AssignmentOperatorType); + + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void tangentMap< + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + context::VectorXs, + context::MatrixXs>( + const context::Model &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const AssignmentOperatorType); + + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void tangentMapProduct< + LieGroupMap, + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + context::VectorXs, + context::MatrixXs, + context::MatrixXs>( + const context::Model &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const AssignmentOperatorType); + + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void tangentMapProduct< + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + context::VectorXs, + context::MatrixXs, + context::MatrixXs>( + const context::Model &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const AssignmentOperatorType); + + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void tangentMapTransposeProduct< + LieGroupMap, + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + context::VectorXs, + context::MatrixXs, + context::MatrixXs>( + const context::Model &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const AssignmentOperatorType); + + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void tangentMapTransposeProduct< + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + context::VectorXs, + context::MatrixXs, + context::MatrixXs>( + const context::Model &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const Eigen::MatrixBase &, + const AssignmentOperatorType); + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void dIntegrateTransport< LieGroupMap, context::Scalar, @@ -312,6 +389,16 @@ namespace pinocchio normalize( const context::Model &, const Eigen::MatrixBase &); + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void + lieGroup( + const context::Model &, + typename LieGroupMap::template operationProduct::type &); + + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void + lieGroup( + const context::Model &, + typename LieGroupMap::template operationProduct::type &); + #ifndef PINOCCHIO_SKIP_CASADI_UNSUPPORTED template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI bool isNormalized< @@ -493,4 +580,13 @@ namespace pinocchio template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI context::VectorXs neutral(const context::Model &); + + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI + typename LieGroupMap::template operationProduct::type + lieGroup( + const context::Model &); + + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI + typename LieGroupMap::template operationProduct::type + lieGroup(const context::Model &); } // namespace pinocchio diff --git a/src/algorithm/kinematics-derivatives.cpp b/src/algorithm/kinematics-derivatives.cpp index af483f91d7..c74e30b111 100644 --- a/src/algorithm/kinematics-derivatives.cpp +++ b/src/algorithm/kinematics-derivatives.cpp @@ -9,6 +9,18 @@ namespace pinocchio namespace impl { + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void + computeForwardKinematicsDerivatives< + context::Scalar, + context::Options, + JointCollectionDefaultTpl, + Eigen::Ref, + Eigen::Ref>( + const context::Model &, + context::Data &, + const Eigen::MatrixBase> &, + const Eigen::MatrixBase> &); + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void computeForwardKinematicsDerivatives< context::Scalar, diff --git a/src/collision/collision.cpp b/src/collision/collision.cpp index d71ed96ffb..9696bd3b08 100644 --- a/src/collision/collision.cpp +++ b/src/collision/collision.cpp @@ -20,6 +20,14 @@ namespace pinocchio const Eigen::MatrixBase &, const bool stopAtFirstCollision); + template PINOCCHIO_COLLISION_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI std::size_t + computeDistances( + const context::Model &, + context::Data &, + const GeometryModel &, + GeometryData &, + const Eigen::MatrixBase &); + template PINOCCHIO_COLLISION_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void computeBodyRadius( const context::Model &, const GeometryModel &, GeometryData &); diff --git a/src/multibody/model.cpp b/src/multibody/model.cpp index b101e7a462..42966c255b 100644 --- a/src/multibody/model.cpp +++ b/src/multibody/model.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2022 INRIA +// Copyright (c) 2022-2024 INRIA // #include "pinocchio/multibody/model.hpp" @@ -23,6 +23,12 @@ namespace pinocchio const context::VectorXs &, const context::VectorXs &, const context::VectorXs &, + const context::VectorXs &, + const context::VectorXs &, + const context::VectorXs &, + const context::VectorXs &, + const context::VectorXs &, + const context::VectorXs &, const context::VectorXs &); template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI JointIndex @@ -38,9 +44,20 @@ namespace pinocchio const context::VectorXs &, const context::VectorXs &); + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI JointIndex + ModelTpl::addJoint( + const JointIndex, + const JointModel &, + const SE3 &, + const std::string &, + const context::VectorXs &, + const context::VectorXs &, + const context::VectorXs &, + const context::VectorXs &); + template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI FrameIndex ModelTpl::addJointFrame( - const JointIndex &, int); + const JointIndex, int); template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI void ModelTpl::appendBodyToJoint( diff --git a/src/parsers/mjcf/mjcf-graph-geom.cpp b/src/parsers/mjcf/mjcf-graph-geom.cpp index 2a847ee085..e59449a24b 100644 --- a/src/parsers/mjcf/mjcf-graph-geom.cpp +++ b/src/parsers/mjcf/mjcf-graph-geom.cpp @@ -39,6 +39,10 @@ namespace pinocchio { return 4.0 / 3 * pi * size.prod(); } + else if (geomType == "plane") + { + return 0.0; + } else { throw std::invalid_argument("geometry type does not exist"); @@ -74,6 +78,13 @@ namespace pinocchio { if (geom.geomType == "mesh") { + if (currentGraph.mapOfMeshes.find(geom.meshName) == currentGraph.mapOfMeshes.end()) + { + std::stringstream ss; + ss << "Cannot find mesh " << geom.meshName << " for geometry " << geom.geomName; + std::string error_msg = ss.str(); + PINOCCHIO_THROW_PRETTY(std::invalid_argument, error_msg); + } MjcfMesh currentMesh = currentGraph.mapOfMeshes.at(geom.meshName); if (currentMesh.vertices.size() > 0) { @@ -134,8 +145,19 @@ namespace pinocchio double height = geom.size(1) * 2; return std::make_shared(radius, height); } + else if (geom.geomType == "plane") + { + meshPath = "PLANE"; + meshScale << 1, 1, 1; + return std::make_shared(0, 0, 1, 0); + } else - throw std::invalid_argument("Unknown geometry type :"); // Missing plane, hfield and sdf + { + // Missing plane, hfield and sdf + std::stringstream ss; + ss << "Unknown geometry type: " << geom.geomType << "\n"; + PINOCCHIO_THROW(std::invalid_argument, ss.str()); + } } #else static std::shared_ptr retrieveCollisionGeometry( @@ -159,11 +181,24 @@ namespace pinocchio const MjcfGraph & currentGraph, GeometryModel & geomModel, ::hpp::fcl::MeshLoaderPtr & meshLoader, - const GeometryType & type) + const GeometryType & type, + bool isWorldBody = false) { const std::string & bodyName = currentBody.bodyName; - FrameIndex frame_id = currentGraph.urdfVisitor.getBodyId(bodyName); - Frame frame = currentGraph.urdfVisitor.getBodyFrame(bodyName); + FrameIndex frame_id; + Frame frame; + if (isWorldBody) + { + frame_id = 0; + // "universe" frame should be of index 0 + assert(frame_id == currentGraph.mjcfVisitor.model.getFrameId(bodyName)); + frame = currentGraph.mjcfVisitor.model.frames[frame_id]; + } + else + { + frame_id = currentGraph.mjcfVisitor.getBodyId(bodyName); + frame = currentGraph.mjcfVisitor.getBodyFrame(bodyName); + } const SE3 & bodyPlacement = frame.placement; @@ -182,11 +217,30 @@ namespace pinocchio std::string texturePath; if (!geom.materialName.empty()) { + if ( + currentGraph.mapOfMaterials.find(geom.materialName) + == currentGraph.mapOfMaterials.end()) + { + std::stringstream ss; + ss << "Cannot find material " << geom.materialName << " for geometry " + << geom.geomName; + std::string error_msg = ss.str(); + PINOCCHIO_THROW_PRETTY(std::invalid_argument, error_msg); + } MjcfMaterial mat = currentGraph.mapOfMaterials.at(geom.materialName); meshColor = mat.rgba; overrideMaterial = true; if (!mat.texture.empty()) { + if ( + currentGraph.mapOfTextures.find(mat.texture) == currentGraph.mapOfTextures.end()) + { + std::stringstream ss; + ss << "Cannot find texture " << mat.texture << " for material " + << geom.materialName << " for geometry " << geom.geomName; + std::string error_msg = ss.str(); + PINOCCHIO_THROW_PRETTY(std::invalid_argument, error_msg); + } MjcfTexture text = currentGraph.mapOfTextures.at(mat.texture); texturePath = text.filePath; } @@ -194,7 +248,11 @@ namespace pinocchio const SE3 geomPlacement = bodyPlacement * geom.geomPlacement; std::ostringstream geometry_object_suffix; geometry_object_suffix << "_" << objectId; - std::string geometry_object_name = std::string(bodyName + geometry_object_suffix.str()); + std::string geometry_object_name = geom.geomName; + if (geom.geomName.empty()) + { + geometry_object_name = std::string(bodyName + geometry_object_suffix.str()); + } GeometryObject geometry_object( geometry_object_name, frame.parentJoint, frame_id, geomPlacement, geometry, meshPath, @@ -369,7 +427,7 @@ namespace pinocchio size(1) = zaxis.norm() / 2; // to get half height } } - else if (geomType == "mesh") + else if (geomType == "mesh" || geomType == "plane") return; else throw std::invalid_argument("geomType does not exist"); @@ -532,6 +590,7 @@ namespace pinocchio meshLoader = std::make_shared(fcl::MeshLoader()); #endif // ifdef PINOCCHIO_WITH_HPP_FCL + addLinksToGeomModel(worldBody, *this, geomModel, meshLoader, type, true); for (const auto & entry : bodiesList) { const MjcfBody & currentBody = mapOfBodies.at(entry); diff --git a/src/parsers/mjcf/mjcf-graph.cpp b/src/parsers/mjcf/mjcf-graph.cpp index cdd73691d8..27e81ee46e 100644 --- a/src/parsers/mjcf/mjcf-graph.cpp +++ b/src/parsers/mjcf/mjcf-graph.cpp @@ -4,7 +4,8 @@ #include "pinocchio/parsers/mjcf/mjcf-graph.hpp" #include "pinocchio/multibody/model.hpp" -#include "pinocchio/algorithm/contact-info.hpp" +#include "pinocchio/multibody/data.hpp" +#include "pinocchio/algorithm/kinematics.hpp" namespace pinocchio { @@ -13,9 +14,6 @@ namespace pinocchio namespace details { typedef boost::property_tree::ptree ptree; - typedef pinocchio::urdf::details:: - UrdfVisitor - UrdfVisitor; // supported elements from mjcf static const std::array ELEMENTS = {"joint", "geom", "site"}; @@ -119,18 +117,21 @@ namespace pinocchio template RangeJoint RangeJoint::setDimension() const { - typedef UrdfVisitor::Vector Vector; + typedef MjcfVisitor::Vector Vector; const double infty = std::numeric_limits::infinity(); RangeJoint ret; + ret.minEffort = Vector::Constant(Nv, -infty); ret.maxEffort = Vector::Constant(Nv, infty); + ret.minVel = Vector::Constant(Nv, -infty); ret.maxVel = Vector::Constant(Nv, infty); ret.maxConfig = Vector::Constant(Nq, 1.01); ret.minConfig = Vector::Constant(Nq, -1.01); - ret.friction = Vector::Constant(Nv, 0.); + ret.configLimitMargin = Vector::Constant(Nq, 0.); + ret.maxDryFriction = Vector::Constant(Nv, 0.); + ret.minDryFriction = Vector::Constant(Nv, 0.); ret.damping = Vector::Constant(Nv, 0.); ret.armature = Vector::Constant(Nv, armature[0]); - ret.frictionLoss = frictionLoss; ret.springStiffness = springStiffness; ret.springReference = springReference; return ret; @@ -141,10 +142,15 @@ namespace pinocchio { assert(range.maxEffort.size() == Nv); assert(range.minConfig.size() == Nq); + assert(range.configLimitMargin.size() == Nq); RangeJoint ret(*this); + ret.minEffort.conservativeResize(minEffort.size() + Nv); + ret.minEffort.tail(Nv) = range.minEffort; ret.maxEffort.conservativeResize(maxEffort.size() + Nv); ret.maxEffort.tail(Nv) = range.maxEffort; + ret.minVel.conservativeResize(minVel.size() + Nv); + ret.minVel.tail(Nv) = range.minVel; ret.maxVel.conservativeResize(maxVel.size() + Nv); ret.maxVel.tail(Nv) = range.maxVel; @@ -152,11 +158,15 @@ namespace pinocchio ret.minConfig.tail(Nq) = range.minConfig; ret.maxConfig.conservativeResize(maxConfig.size() + Nq); ret.maxConfig.tail(Nq) = range.maxConfig; + ret.configLimitMargin.conservativeResize(configLimitMargin.size() + Nq); + ret.configLimitMargin.tail(Nq) = range.configLimitMargin; ret.damping.conservativeResize(damping.size() + Nv); ret.damping.tail(Nv) = range.damping; - ret.friction.conservativeResize(friction.size() + Nv); - ret.friction.tail(Nv) = range.friction; + ret.minDryFriction.conservativeResize(minDryFriction.size() + Nv); + ret.minDryFriction.tail(Nv) = range.minDryFriction; + ret.maxDryFriction.conservativeResize(maxDryFriction.size() + Nv); + ret.maxDryFriction.tail(Nv) = range.maxDryFriction; ret.springReference.conservativeResize(springReference.size() + 1); ret.springReference.tail(1) = range.springReference; @@ -187,19 +197,32 @@ namespace pinocchio if (ax) axis = internal::getVectorFromStream<3>(*ax); - // Range + // Config limits (upper/lower) auto range_ = el.get_optional(".range"); + bool has_range_limits = false; if (range_) { Eigen::Vector2d rangeT = internal::getVectorFromStream<2>(*range_); range.minConfig[0] = currentCompiler.convertAngle(rangeT(0)); range.maxConfig[0] = currentCompiler.convertAngle(rangeT(1)); + has_range_limits = true; } + + // Config limit margins + auto margin_ = el.get_optional(".margin"); + if (margin_) + { + PINOCCHIO_THROW_PRETTY_IF( + *margin_ < 0, std::invalid_argument, "Negative joint limit margin."); + range.configLimitMargin.array() = currentCompiler.convertAngle(*margin_); + } + // Effort limit range_ = el.get_optional(".actuatorfrcrange"); if (range_) { Eigen::Vector2d rangeT = internal::getVectorFromStream<2>(*range_); + range.minEffort[0] = rangeT(0); range.maxEffort[0] = rangeT(1); } @@ -220,19 +243,33 @@ namespace pinocchio // friction loss value = el.get_optional(".frictionloss"); if (value) - range.frictionLoss = *value; - + { + range.maxDryFriction.array() = *value; + range.minDryFriction = -range.maxDryFriction; + } value = el.get_optional(".ref"); if (value) { + bool has_pos_ref = false; if (jointType == "slide") + { posRef = *value; + has_pos_ref = true; + } else if (jointType == "hinge") + { posRef = currentCompiler.convertAngle(*value); + has_pos_ref = true; + } else PINOCCHIO_THROW_PRETTY( std::invalid_argument, "Reference position can only be used with hinge or slide joints."); + if (has_range_limits && has_pos_ref) + { + range.minConfig[0] -= posRef; + range.maxConfig[0] -= posRef; + } } } @@ -520,26 +557,35 @@ namespace pinocchio auto file = el.get_optional(".file"); auto name_ = el.get_optional(".name"); auto type = el.get_optional(".type"); + auto builtin = el.get_optional(".builtin"); std::string name; if (name_) name = *name_; else if (type && *type == "skybox") name = *type; - if (!file) + if (!builtin || *builtin == "none") { - std::cout << "Warning - Only texture with files are supported" << std::endl; - if (name.empty()) - PINOCCHIO_THROW_PRETTY(std::invalid_argument, "Textures need a name."); + if (!file) + { + std::cout << "Warning - Only texture with files are supported" << std::endl; + if (name.empty()) + PINOCCHIO_THROW_PRETTY(std::invalid_argument, "Textures need a name."); + } + else + { + fs::path filePath(*file); + name = getName(el, filePath); + + text.filePath = + updatePath(compilerInfo.strippath, compilerInfo.texturedir, modelPath, filePath) + .string(); + } } else { - fs::path filePath(*file); - name = getName(el, filePath); - - text.filePath = - updatePath(compilerInfo.strippath, compilerInfo.texturedir, modelPath, filePath) - .string(); + if (name.empty()) + PINOCCHIO_THROW_PRETTY(std::invalid_argument, "Textures need a name."); } auto str_v = el.get_optional(".type"); if (str_v) @@ -812,9 +858,9 @@ namespace pinocchio // The constraints below are not supported and will be ignored with the following // warning: joint, flex, distance, weld - if (type != "connect") + if ((type != "connect") && (type != "weld")) { - // TODO(jcarpent): support extra constraint types such as joint, flex, distance, weld. + // TODO(jcarpent): support extra constraint types such as joint, flex, distance. continue; } @@ -825,27 +871,58 @@ namespace pinocchio auto body1 = v.second.get_optional(".body1"); if (body1) eq.body1 = *body1; - else - PINOCCHIO_THROW_PRETTY(std::invalid_argument, "Equality constraint needs a first body"); // get the name of second body auto body2 = v.second.get_optional(".body2"); if (body2) eq.body2 = *body2; + // get the name of first site + auto site1 = v.second.get_optional(".site1"); + if (site1) + eq.site1 = *site1; + + // get the name of second site + auto site2 = v.second.get_optional(".site2"); + if (site2) + eq.site2 = *site2; + // get the name of the constraint (if it exists) auto name = v.second.get_optional(".name"); if (name) eq.name = *name; - else - eq.name = eq.body1 + "_" + eq.body2 + "_constraint"; + // TODO: argument torqscale present in MJCF for energy base solve // get the anchor position auto anchor = v.second.get_optional(".anchor"); if (anchor) eq.anchor = internal::getVectorFromStream<3>(*anchor); - mapOfEqualities.insert(std::make_pair(eq.name, eq)); + // get the relative pose + auto relpose = v.second.get_optional(".relpose"); + if (relpose) + { + Eigen::Matrix pos_quat = internal::getVectorFromStream<7>(*relpose); + Eigen::Vector4d quat_vec = pos_quat.tail(4); + Eigen::Quaterniond quaternion(pos_quat(3), pos_quat(4), pos_quat(5), pos_quat(6)); + if (quat_vec.isZero(0)) + // Weird default behavior from Mujoco + // If quat is four 0, use the relpose in the reference configuration qref + // then relpose is ignored + // See: https://mujoco.readthedocs.io/en/latest/XMLreference.html#equality-weld + eq.use_qref_relpose = true; + else + { + // We will use relpose argument so we store it as SE3 placement + eq.use_qref_relpose = false; + quaternion.normalize(); + eq.relpose.translation() = pos_quat.head(3); + eq.relpose.rotation() = quaternion.toRotationMatrix(); + } + } + + mapOfEqualities.insert( + std::make_pair(eq.name + eq.body1 + eq.site1 + eq.body2 + eq.site2, eq)); } } @@ -886,6 +963,7 @@ namespace pinocchio if (v.first == "worldbody") { boost::optional childClass; + parseWorldBodyGeoms(el.get_child("worldbody")); parseJointAndBody(el.get_child("worldbody").get_child("body"), childClass); } @@ -896,6 +974,21 @@ namespace pinocchio } } + void MjcfGraph::parseWorldBodyGeoms(const ptree & el) + { + // in pinocchio, the worldbody is called "universe" + worldBody.bodyName = "universe"; + for (const ptree::value_type & v : el) + { + if (v.first == "geom") + { + MjcfGeom currentGeom; + currentGeom.fill(v.second, worldBody, *this); + worldBody.geomChildren.push_back(currentGeom); + } + } + } + void MjcfGraph::parseGraphFromXML(const std::string & xmlStr) { boost::property_tree::read_xml(xmlStr, pt); @@ -921,70 +1014,77 @@ namespace pinocchio FrameIndex parentFrameId = 0; if (!currentBody.bodyParent.empty()) - parentFrameId = urdfVisitor.getBodyId(currentBody.bodyParent); + parentFrameId = mjcfVisitor.getBodyId(currentBody.bodyParent); // get body pose in body parent const SE3 bodyPose = currentBody.bodyPlacement; Inertia inert = currentBody.bodyInertia; SE3 jointInParent = bodyPose * joint.jointPlacement; bodyInJoint = joint.jointPlacement.inverse(); - UrdfVisitor::JointType jType; + JointType jType; RangeJoint range; if (joint.jointType == "free") { - urdfVisitor << "Free Joint " << '\n'; + mjcfVisitor << "Free Joint " << '\n'; range = joint.range.setDimension<7, 6>(); - jType = UrdfVisitor::FLOATING; + jType = JointType::FLOATING; } else if (joint.jointType == "slide") { - urdfVisitor << "joint prismatic with axis " << joint.axis << '\n'; + mjcfVisitor << "joint prismatic with axis " << joint.axis << '\n'; range = joint.range; - jType = UrdfVisitor::PRISMATIC; + jType = JointType::PRISMATIC; } else if (joint.jointType == "ball") { - urdfVisitor << "Sphere Joint " << '\n'; + mjcfVisitor << "Sphere Joint " << '\n'; range = joint.range.setDimension<4, 3>(); - jType = UrdfVisitor::SPHERICAL; + jType = JointType::SPHERICAL; } else if (joint.jointType == "hinge") { - urdfVisitor << "joint revolute with axis " << joint.axis << '\n'; + mjcfVisitor << "joint revolute with axis " << joint.axis << '\n'; range = joint.range; - jType = UrdfVisitor::REVOLUTE; + jType = JointType::REVOLUTE; } else PINOCCHIO_THROW_PRETTY(std::invalid_argument, "Unknown joint type"); - urdfVisitor.addJointAndBody( + mjcfVisitor.addJointAndBody( jType, joint.axis, parentFrameId, jointInParent, joint.jointName, inert, bodyInJoint, - currentBody.bodyName, range.maxEffort, range.maxVel, range.minConfig, range.maxConfig, - range.friction, range.damping); + currentBody.bodyName, range.minEffort, range.maxEffort, range.minVel, range.maxVel, + range.minConfig, range.maxConfig, range.configLimitMargin, range.minDryFriction, + range.maxDryFriction, range.damping); // Add armature info - JointIndex j_id = urdfVisitor.getJointId(joint.jointName); - urdfVisitor.model.armature.segment( - urdfVisitor.model.joints[j_id].idx_v(), urdfVisitor.model.joints[j_id].nv()) = + JointIndex j_id = mjcfVisitor.getJointId(joint.jointName); + mjcfVisitor.model.armature.segment( + mjcfVisitor.model.joints[j_id].idx_v(), mjcfVisitor.model.joints[j_id].nv()) = range.armature; } void MjcfGraph::fillModel(const std::string & nameOfBody) { - typedef UrdfVisitor::SE3 SE3; + typedef MjcfVisitor::SE3 SE3; + if (mapOfBodies.find(nameOfBody) == mapOfBodies.end()) + { + std::stringstream ss; + ss << "Cannot find body " << nameOfBody; + PINOCCHIO_THROW_PRETTY(std::invalid_argument, ss.str()); + } MjcfBody currentBody = mapOfBodies.at(nameOfBody); // get parent body frame FrameIndex parentFrameId = 0; if (!currentBody.bodyParent.empty()) - parentFrameId = urdfVisitor.getBodyId(currentBody.bodyParent); + parentFrameId = mjcfVisitor.getBodyId(currentBody.bodyParent); - Frame frame = urdfVisitor.model.frames[parentFrameId]; + Frame frame = mjcfVisitor.model.frames[parentFrameId]; // get body pose in body parent const SE3 bodyPose = currentBody.bodyPlacement; - Inertia inert = currentBody.bodyInertia; + Inertia inertia = currentBody.bodyInertia; // Fixed Joint if (currentBody.jointChildren.size() == 0) @@ -993,9 +1093,9 @@ namespace pinocchio return; std::string jointName = nameOfBody + "_fixed"; - urdfVisitor << jointName << " being parsed." << '\n'; + mjcfVisitor << jointName << " being parsed." << '\n'; - urdfVisitor.addFixedJointAndBody(parentFrameId, bodyPose, jointName, inert, nameOfBody); + mjcfVisitor.addFixedJointAndBody(parentFrameId, bodyPose, jointName, inertia, nameOfBody); return; } @@ -1071,24 +1171,25 @@ namespace pinocchio } JointIndex joint_id; - joint_id = urdfVisitor.model.addJoint( + joint_id = mjcfVisitor.model.addJoint( frame.parentJoint, jointM, frame.placement * firstJointPlacement, jointName, - rangeCompo.maxEffort, rangeCompo.maxVel, rangeCompo.minConfig, rangeCompo.maxConfig, - rangeCompo.friction, rangeCompo.damping); - FrameIndex jointFrameId = urdfVisitor.model.addJointFrame(joint_id, (int)parentFrameId); - urdfVisitor.appendBodyToJoint(jointFrameId, inert, bodyInJoint, nameOfBody); - - urdfVisitor.model.armature.segment( - urdfVisitor.model.joints[joint_id].idx_v(), urdfVisitor.model.joints[joint_id].nv()) = + rangeCompo.minEffort, rangeCompo.maxEffort, rangeCompo.minVel, rangeCompo.maxVel, + rangeCompo.minConfig, rangeCompo.maxConfig, rangeCompo.configLimitMargin, + rangeCompo.minDryFriction, rangeCompo.maxDryFriction, rangeCompo.damping); + FrameIndex jointFrameId = mjcfVisitor.model.addJointFrame(joint_id, (int)parentFrameId); + mjcfVisitor.appendBodyToJoint(jointFrameId, inertia, bodyInJoint, nameOfBody); + + mjcfVisitor.model.armature.segment( + mjcfVisitor.model.joints[joint_id].idx_v(), mjcfVisitor.model.joints[joint_id].nv()) = rangeCompo.armature; } - FrameIndex bodyId = urdfVisitor.model.getFrameId(nameOfBody, BODY); - frame = urdfVisitor.model.frames[bodyId]; + FrameIndex bodyId = mjcfVisitor.model.getFrameId(nameOfBody, BODY); + frame = mjcfVisitor.model.frames[bodyId]; for (const auto & site : currentBody.siteChildren) { SE3 placement = bodyInJoint * site.sitePlacement; - urdfVisitor.model.addFrame( + mjcfVisitor.model.addFrame( Frame(site.siteName, frame.parentJoint, bodyId, placement, OP_FRAME)); } } @@ -1097,20 +1198,46 @@ namespace pinocchio { for (const auto & joint : currentBody.jointChildren) { + assert(qpos0.size() == referenceConfig.size()); if (joint.jointType == "free") { referenceConfig.conservativeResize(referenceConfig.size() + 7); - referenceConfig.tail(7) << Eigen::Matrix::Zero(); + // In FK of mujoco, the placement of a freeflyer w.r.t its parent is ignored. + // Instead, the freeflyer's components of the configuration vector are used directly in + // the FK. For other joints, the placement w.r.t the parent is taken into consideration. + // In pinocchio, the placement w.r.t the parent is always taken into consideration. + // So for the special case of freeflyers, we apply the opposite transformation + // of the mujoco's freeflyer. + // Consequently, when we adjust the joint placements (see @ref + // updateJointPlacementsFromReferenceConfig), we obtain the same result given a mujoco + // configuration vector. + const SE3::Quaternion q(currentBody.bodyPlacement.rotation()); + const SE3::Quaternion qinv = q.inverse(); + const Eigen::Vector3d t(-currentBody.bodyPlacement.translation()); + referenceConfig.tail(7) << t(0), t(1), t(2), qinv.x(), qinv.y(), qinv.z(), qinv.w(); + + // We store qpos0 in the convention of mujoco. + // The function `addKeyFrame` will convert this qpos0 to the pinocchio's convention. + // The `addKeyFrame` function also deals with composite joints, which is something we + // can't do in this function. + qpos0.conservativeResize(qpos0.size() + 7); + qpos0.tail(7) << -t(0), -t(1), -t(2), q.w(), q.x(), q.y(), q.z(); } else if (joint.jointType == "ball") { referenceConfig.conservativeResize(referenceConfig.size() + 4); - referenceConfig.tail(4) << Eigen::Vector4d::Zero(); + referenceConfig.tail(4) << Eigen::Vector4d(0, 0, 0, 1); + + qpos0.conservativeResize(qpos0.size() + 4); + qpos0.tail(4) << Eigen::Vector4d(1, 0, 0, 0); } else if (joint.jointType == "slide" || joint.jointType == "hinge") { referenceConfig.conservativeResize(referenceConfig.size() + 1); - referenceConfig.tail(1) << joint.posRef; + referenceConfig.tail(1) << -joint.posRef; + + qpos0.conservativeResize(qpos0.size() + 1); + qpos0.tail(1) << joint.posRef; } } } @@ -1118,102 +1245,225 @@ namespace pinocchio void MjcfGraph::addKeyFrame(const Eigen::VectorXd & keyframe, const std::string & keyName) { // Check config vectors and add them if size is right - const int model_nq = urdfVisitor.model.nq; - if (keyframe.size() == model_nq) + const int model_nq = mjcfVisitor.model.nq; + + PINOCCHIO_CHECK_INPUT_ARGUMENT( + keyframe.size() == model_nq, "Keyframe size does not match model size"); + + Eigen::VectorXd qpos(model_nq); + for (std::size_t i = 1; i < mjcfVisitor.model.joints.size(); i++) { - Eigen::VectorXd qpos(model_nq); - for (std::size_t i = 1; i < urdfVisitor.model.joints.size(); i++) - { - const auto & joint = urdfVisitor.model.joints[i]; - int idx_q = joint.idx_q(); - int nq = joint.nq(); + const auto & joint = mjcfVisitor.model.joints[i]; + int idx_q = joint.idx_q(); + int nq = joint.nq(); - Eigen::VectorXd qpos_j = keyframe.segment(idx_q, nq); - Eigen::VectorXd q_ref = referenceConfig.segment(idx_q, nq); - if (joint.shortname() == "JointModelFreeFlyer") - { - Eigen::Vector4d new_quat(qpos_j(4), qpos_j(5), qpos_j(6), qpos_j(3)); - qpos_j.tail(4) = new_quat; - } - else if (joint.shortname() == "JointModelSpherical") - { - Eigen::Vector4d new_quat(qpos_j(1), qpos_j(2), qpos_j(3), qpos_j(0)); - qpos_j = new_quat; - } - else if (joint.shortname() == "JointModelComposite") + Eigen::VectorXd qpos_j = keyframe.segment(idx_q, nq); + if (joint.shortname() == "JointModelFreeFlyer") + { + Eigen::Vector4d new_quat(qpos_j(4), qpos_j(5), qpos_j(6), qpos_j(3)); + qpos_j.tail(4) = new_quat; + } + else if (joint.shortname() == "JointModelSpherical") + { + Eigen::Vector4d new_quat(qpos_j(1), qpos_j(2), qpos_j(3), qpos_j(0)); + qpos_j = new_quat; + } + else if (joint.shortname() == "JointModelComposite") + { + for (const auto & joint_ : boost::get(joint.toVariant()).joints) { - for (const auto & joint_ : boost::get(joint.toVariant()).joints) + int idx_q_ = joint_.idx_q() - idx_q; + int nq_ = joint_.nq(); + if (joint_.shortname() == "JointModelSpherical") { - int idx_q_ = joint_.idx_q() - idx_q; - int nq_ = joint_.nq(); - if (joint_.shortname() == "JointModelSpherical") - { - Eigen::Vector4d new_quat( - qpos_j(idx_q_ + 1), qpos_j(idx_q_ + 2), qpos_j(idx_q_ + 3), qpos_j(idx_q_)); - qpos_j.segment(idx_q_, nq_) = new_quat; - } - else - qpos_j.segment(idx_q_, nq_) -= q_ref.segment(idx_q_, nq_); + Eigen::Vector4d new_quat( + qpos_j(idx_q_ + 1), qpos_j(idx_q_ + 2), qpos_j(idx_q_ + 3), qpos_j(idx_q_)); + qpos_j.segment(idx_q_, nq_) = new_quat; } } - else - qpos_j -= q_ref; - - qpos.segment(idx_q, nq) = qpos_j; } - - urdfVisitor.model.referenceConfigurations.insert(std::make_pair(keyName, qpos)); + qpos.segment(idx_q, nq) = qpos_j; } - else - PINOCCHIO_THROW_PRETTY(std::invalid_argument, "Keyframe size does not match model size"); + + // we normalize in case parsed qpos has numerical errors + ::pinocchio::normalize(mjcfVisitor.model, qpos); + mjcfVisitor.model.referenceConfigurations.insert(std::make_pair(keyName, qpos)); } void MjcfGraph::parseContactInformation( const Model & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models) + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + & bilateral_constraint_models, + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(WeldConstraintModel) & weld_constraint_models) { + Data data(model); + Eigen::VectorXd qref; + if (!model.referenceConfigurations.empty()) + { + // If possible, it's always preferable to select qpos0 to construct the bilateral + // constraints as the mujoco equality constraints are defined w.r.t the default + // configuration of the model (qpos0). + if (model.referenceConfigurations.find("qpos0") != model.referenceConfigurations.end()) + { + mjcfVisitor << "Using qpos0 (default configuration defined by the XML file) to " + "construct bilateral constraints.\n"; + qref = model.referenceConfigurations.at("qpos0"); + } + else + { + mjcfVisitor << "Could not find qpos0 in referenceConfigurations. Using keyframe " + << model.referenceConfigurations.begin()->first + << " to construct bilateral constraints.\n"; + qref = model.referenceConfigurations.begin()->second; + } + } + else + { + mjcfVisitor << "WARNING: Could not find qpos0 nor other keyframes in " + "referenceConfigurations.\n" + << "This is unexpected and may lead to issues for bilateral constraints.\n" + << "Using ::pinocchio::neutral to construct bilateral constraints.\n"; + qref = ::pinocchio::neutral(model); + } + ::pinocchio::forwardKinematics(model, data, qref); for (const auto & entry : mapOfEqualities) { const MjcfEquality & eq = entry.second; + // Retireve parent joints and relative pose + SE3 i1Mc, i2Mc; + JointIndex joint1, joint2; + if (eq.body1 == "") + { + if ((eq.site1 == "") || (eq.site2 == "")) + { + std::stringstream ss; + ss << "Body 1 or both site1 and site2 must be specified for constraint" + << entry.first; + PINOCCHIO_THROW_PRETTY(std::invalid_argument, ss.str()); + } + // It is Mujoco site convention common for weld or connect + const Frame & frame1 = model.frames[model.getFrameId(eq.site1)]; + const Frame & frame2 = model.frames[model.getFrameId(eq.site2)]; + joint1 = frame1.parentJoint; + joint2 = frame2.parentJoint; + i1Mc = frame1.placement; + i2Mc = frame2.placement; + } + else + { + joint1 = mjcfVisitor.getParentId(eq.body1); + const SE3 & oMi1 = data.oMi[joint1]; + // Body 2 default to world joint + joint2 = (eq.body2 == "") ? 0 : mjcfVisitor.getParentId(eq.body2); + const SE3 & oMi2 = data.oMi[joint2]; + if (eq.type == "connect") + { + // For connect, anchor is relative to joint1 + i1Mc.setIdentity(); + i1Mc.translation() = eq.anchor; + // Constaint relative to joint 2 is obtaint thanks to qref pose + i2Mc = (joint2 == 0) ? oMi1 * i1Mc : oMi2.inverse() * oMi1 * i1Mc; + } + else if (eq.type == "weld") + { + // For weld constraint, anchor is relative to joint2 + i2Mc.setIdentity(); + i2Mc.translation() = eq.anchor; + // Constraint location relative to joint 1: i1Mc is calculated using i2Mc and given + // the relative pose i1Mi2. + // Using weird default behavior of mujoco, use qref relative pose if quat is four 0 + // and relpose argument otherwise + SE3 i1Mi2 = eq.use_qref_relpose + ? ((joint2 == 0) ? oMi1.inverse() : oMi1.inverse() * oMi2) + : eq.relpose; + i1Mc = i1Mi2 * i2Mc; + } + } - SE3 jointPlacement; - jointPlacement.setIdentity(); - jointPlacement.translation() = eq.anchor; - - // Get Joint Indices from the model - const JointIndex body1 = urdfVisitor.getParentId(eq.body1); + // Create the constraints + if (eq.type == "connect") + { + BilateralPointConstraintModel bpcm(model, joint1, i1Mc, joint2, i2Mc); + bilateral_constraint_models.push_back(bpcm); + } + else if (eq.type == "weld") + { + WeldConstraintModel wcm(model, joint1, i1Mc, joint2, i2Mc); + weld_constraint_models.push_back(wcm); + } + } + } - // when body2 is not specified, we link to the world - if (eq.body2 == "") + void MjcfGraph::updateJointPlacementsFromReferenceConfig() + { + Data data(mjcfVisitor.model); + ::pinocchio::forwardKinematics(mjcfVisitor.model, data, referenceConfig); + for (std::size_t i = 1; i < mjcfVisitor.model.joints.size(); i++) + { + auto & joint = mjcfVisitor.model.joints[i]; + if (joint.shortname() == "JointModelComposite") { - RigidConstraintModel rcm(CONTACT_3D, model, body1, jointPlacement, LOCAL); - contact_models.push_back(rcm); + JointModelComposite & jmodel = boost::get(joint.toVariant()); + JointDataComposite & jdata = boost::get(data.joints[i]); + for (std::size_t j = 1; j < jmodel.joints.size(); j++) + { + jmodel.jointPlacements[j] = jdata.pjMi[j]; + } } else { - const JointIndex body2 = urdfVisitor.getParentId(eq.body2); - RigidConstraintModel rcm( - CONTACT_3D, model, body1, jointPlacement, body2, jointPlacement.inverse(), LOCAL); - contact_models.push_back(rcm); + const std::size_t parenti = mjcfVisitor.model.parents[i]; + const ::pinocchio::SE3 oMparenti = data.oMi[parenti]; + const ::pinocchio::SE3 oMi = data.oMi[i]; + mjcfVisitor.model.jointPlacements[i] = oMparenti.inverse() * oMi; } } } - void MjcfGraph::parseRootTree() + void MjcfGraph::parseRootTree( + const boost::optional rootJoint, + const boost::optional rootJointName) { - urdfVisitor.setName(modelName); + mjcfVisitor.setName(modelName); // get name and inertia of first root link + PINOCCHIO_THROW_PRETTY_IF( + bodiesList.empty(), std::invalid_argument, "MJCF parser: no body found in parsed tree."); std::string rootLinkName = bodiesList.at(0); MjcfBody rootBody = mapOfBodies.find(rootLinkName)->second; if (rootBody.jointChildren.size() == 0) - urdfVisitor.addRootJoint(rootBody.bodyInertia, rootLinkName); + { + // We only add the root joint if we have a fixed base + // (first body doesn't have any joint). Otherwise, the root joint is ignored. + mjcfVisitor.addRootJoint( + rootBody.bodyInertia, rootLinkName, referenceConfig, qpos0, rootJoint, rootJointName); + } + else + { + if (rootJoint.has_value()) + { + PINOCCHIO_THROW_IF( + !rootJointName.has_value(), std::invalid_argument, + "if root_joint is provided, root_joint_name must be also be provided."); + + mjcfVisitor << "WARNING: trying to add root joint '" << rootJointName.get() + << "' to a model which doesn't have a fixed base." + << " The provided root joint is therefore ignored.\n"; + } + } - fillReferenceConfig(rootBody); for (const auto & entry : bodiesList) { fillModel(entry); } + // We store the default configuration, obtained by parsing the . + // Equality constraints are typically defined w.r.t this default configuration qpos0. + mapOfConfigs.insert(std::make_pair("qpos0", qpos0)); + + // We update the joint placements so their base placement is matching with the + // referenceConfig + updateJointPlacementsFromReferenceConfig(); + for (const auto & entry : mapOfConfigs) { addKeyFrame(entry.second, entry.first); diff --git a/src/parsers/sdf/model.cpp b/src/parsers/sdf/model.cpp index 787ba0ae0d..588852de23 100644 --- a/src/parsers/sdf/model.cpp +++ b/src/parsers/sdf/model.cpp @@ -46,9 +46,10 @@ namespace pinocchio void parseContactInformation( const SdfGraph & graph, - const urdf::details::UrdfVisitorBase & visitor, + const urdf::details::UrdfVisitor & visitor, const Model & model, - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) & contact_models) + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) + & constraint_models) { for (PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR( SdfGraph::ContactDetails)::const_iterator cm = std::cbegin(graph.contact_details); @@ -58,21 +59,25 @@ namespace pinocchio const JointIndex joint_id = visitor.getParentId(cm->name); const SE3 & cMj = graph.childPoseMap.find(cm->name)->second; - RigidConstraintModel rcm( - cm->type, model, cm->joint1_id, cm->joint1_placement, joint_id, cMj.inverse(), - cm->reference_frame); + BilateralPointConstraintModel bpcm( + model, cm->joint1_id, cm->joint1_placement, joint_id, cMj.inverse()); - contact_models.push_back(rcm); + constraint_models.push_back(bpcm); } } - void parseRootTree(SdfGraph & graph, const std::string & rootLinkName) + void parseRootTree( + SdfGraph & graph, + const std::string & rootLinkName, + const boost::optional rootJoint, + const boost::optional rootJointName) { // First joint connecting universe const ::sdf::ElementPtr rootLinkElement = graph.mapOfLinks.find(rootLinkName)->second; const ::sdf::ElementPtr inertialElem = rootLinkElement->GetElement("inertial"); - graph.urdfVisitor.addRootJoint(convertInertiaFromSdf(inertialElem), rootLinkName); + graph.urdfVisitor.addRootJoint( + convertInertiaFromSdf(inertialElem), rootLinkName, rootJoint, rootJointName); const std::vector & childrenOfLink = graph.childrenOfLinks.find(rootLinkName)->second; for (std::vector::const_iterator childOfChild = std::begin(childrenOfLink); diff --git a/src/parsers/urdf/model.cpp b/src/parsers/urdf/model.cpp index 44608f0446..1e7ca1c44a 100644 --- a/src/parsers/urdf/model.cpp +++ b/src/parsers/urdf/model.cpp @@ -49,7 +49,7 @@ namespace pinocchio } static FrameIndex - getParentLinkFrame(const ::urdf::LinkConstSharedPtr link, UrdfVisitorBase & model) + getParentLinkFrame(const ::urdf::LinkConstSharedPtr link, UrdfVisitor & model) { PINOCCHIO_CHECK_INPUT_ARGUMENT(link && link->getParent()); FrameIndex id = model.getBodyId(link->getParent()->name); @@ -64,12 +64,12 @@ namespace pinocchio /// \param[in] link The current URDF link. /// \param[in] model The model where the link must be added. /// - void parseTree(::urdf::LinkConstSharedPtr link, UrdfVisitorBase & model, const bool mimic) + void parseTree(::urdf::LinkConstSharedPtr link, UrdfVisitor & model, const bool mimic) { - typedef UrdfVisitorBase::Scalar Scalar; - typedef UrdfVisitorBase::SE3 SE3; - typedef UrdfVisitorBase::Vector Vector; - typedef UrdfVisitorBase::Vector3 Vector3; + typedef UrdfVisitor::Scalar Scalar; + typedef UrdfVisitor::SE3 SE3; + typedef UrdfVisitor::Vector Vector; + typedef UrdfVisitor::Vector3 Vector3; typedef Model::FrameIndex FrameIndex; // Parent joint of the current body @@ -115,8 +115,8 @@ namespace pinocchio damping = Vector::Constant(6, 0.); model.addJointAndBody( - UrdfVisitorBase::FLOATING, axis, parentFrameId, jointPlacement, joint->name, Y, - link->name, max_effort, max_velocity, min_config, max_config, friction, damping); + JointType::FLOATING, axis, parentFrameId, jointPlacement, joint->name, Y, link->name, + max_effort, max_velocity, min_config, max_config, friction, damping); break; case ::urdf::Joint::REVOLUTE: @@ -147,18 +147,17 @@ namespace pinocchio friction = Vector::Constant(0, 0.); damping = Vector::Constant(0, 0.); - MimicInfo_ mimic_info( + MimicInfo mimic_info( joint->mimic->joint_name, joint->mimic->multiplier, joint->mimic->offset, axis, - UrdfVisitorBase::REVOLUTE); + JointType::REVOLUTE); model.addJointAndBody( - UrdfVisitorBase::MIMIC, axis, parentFrameId, jointPlacement, joint->name, Y, - link->name, max_effort, max_velocity, min_config, max_config, friction, damping, - mimic_info); + JointType::MIMIC, axis, parentFrameId, jointPlacement, joint->name, Y, link->name, + max_effort, max_velocity, min_config, max_config, friction, damping, mimic_info); } else model.addJointAndBody( - UrdfVisitorBase::REVOLUTE, axis, parentFrameId, jointPlacement, joint->name, Y, + JointType::REVOLUTE, axis, parentFrameId, jointPlacement, joint->name, Y, link->name, max_effort, max_velocity, min_config, max_config, friction, damping); break; @@ -188,7 +187,7 @@ namespace pinocchio } model.addJointAndBody( - UrdfVisitorBase::CONTINUOUS, axis, parentFrameId, jointPlacement, joint->name, Y, + JointType::CONTINUOUS, axis, parentFrameId, jointPlacement, joint->name, Y, link->name, max_effort, max_velocity, min_config, max_config, friction, damping); break; @@ -220,18 +219,17 @@ namespace pinocchio friction = Vector::Constant(0, 0.); damping = Vector::Constant(0, 0.); - MimicInfo_ mimic_info( + MimicInfo mimic_info( joint->mimic->joint_name, joint->mimic->multiplier, joint->mimic->offset, axis, - UrdfVisitorBase::PRISMATIC); + JointType::PRISMATIC); model.addJointAndBody( - UrdfVisitorBase::MIMIC, axis, parentFrameId, jointPlacement, joint->name, Y, - link->name, max_effort, max_velocity, min_config, max_config, friction, damping, - mimic_info); + JointType::MIMIC, axis, parentFrameId, jointPlacement, joint->name, Y, link->name, + max_effort, max_velocity, min_config, max_config, friction, damping, mimic_info); } else model.addJointAndBody( - UrdfVisitorBase::PRISMATIC, axis, parentFrameId, jointPlacement, joint->name, Y, + JointType::PRISMATIC, axis, parentFrameId, jointPlacement, joint->name, Y, link->name, max_effort, max_velocity, min_config, max_config, friction, damping); break; @@ -249,8 +247,8 @@ namespace pinocchio damping = Vector::Constant(3, 0.); model.addJointAndBody( - UrdfVisitorBase::PLANAR, axis, parentFrameId, jointPlacement, joint->name, Y, - link->name, max_effort, max_velocity, min_config, max_config, friction, damping); + JointType::PLANAR, axis, parentFrameId, jointPlacement, joint->name, Y, link->name, + max_effort, max_velocity, min_config, max_config, friction, damping); break; case ::urdf::Joint::FIXED: @@ -300,14 +298,22 @@ namespace pinocchio /// /// \param[in] link The current URDF link. /// \param[in] model The model where the link must be added. + /// \param[in] rootJoint Optional root joint for the model + /// \param[in] model Name for the optional root joint /// void parseRootTree( - const ::urdf::ModelInterface * urdfTree, UrdfVisitorBase & model, const bool mimic) + const ::urdf::ModelInterface * urdfTree, + UrdfVisitor & model, + const boost::optional rootJoint, + const boost::optional rootJointName, + const bool mimic) { model.setName(urdfTree->getName()); ::urdf::LinkConstSharedPtr root_link = urdfTree->getRoot(); - model.addRootJoint(convertFromUrdf(root_link->inertial).cast(), root_link->name); + model.addRootJoint( + convertFromUrdf(root_link->inertial).cast(), root_link->name, rootJoint, + rootJointName); BOOST_FOREACH (::urdf::LinkConstSharedPtr child, root_link->child_links) { @@ -315,11 +321,16 @@ namespace pinocchio } } - void parseRootTree(const std::string & filename, UrdfVisitorBase & model, const bool mimic) + void parseRootTree( + const std::string & filename, + UrdfVisitor & model, + const boost::optional rootJoint, + const boost::optional rootJointName, + const bool mimic) { ::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDFFile(filename); if (urdfTree) - return parseRootTree(urdfTree.get(), model, mimic); + return parseRootTree(urdfTree.get(), model, rootJoint, rootJointName, mimic); else throw std::invalid_argument( "The file " + filename @@ -327,12 +338,16 @@ namespace pinocchio "contain a valid URDF model."); } - void - parseRootTreeFromXML(const std::string & xmlString, UrdfVisitorBase & model, const bool mimic) + void parseRootTreeFromXML( + const std::string & xmlString, + UrdfVisitor & model, + const boost::optional rootJoint, + const boost::optional rootJointName, + const bool mimic) { ::urdf::ModelInterfaceSharedPtr urdfTree = ::urdf::parseURDF(xmlString); if (urdfTree) - return parseRootTree(urdfTree.get(), model, mimic); + return parseRootTree(urdfTree.get(), model, rootJoint, rootJointName, mimic); else throw std::invalid_argument("The XML stream does not contain a valid " "URDF model."); diff --git a/src/visualizers/base-visualizer.cpp b/src/visualizers/base-visualizer.cpp index a437271983..ac44020951 100644 --- a/src/visualizers/base-visualizer.cpp +++ b/src/visualizers/base-visualizer.cpp @@ -32,8 +32,8 @@ namespace pinocchio { if (hasCollisionModel()) { - PINOCCHIO_THROW( - collision_data != nullptr, std::logic_error, + PINOCCHIO_THROW_IF( + collision_data == nullptr, std::logic_error, "A collision model was provided but no pointer to collision GeometryData to borrow."); } else diff --git a/unittest/CMakeLists.txt b/unittest/CMakeLists.txt index 195a918c2a..c2d18a7ac4 100644 --- a/unittest/CMakeLists.txt +++ b/unittest/CMakeLists.txt @@ -1,5 +1,5 @@ # -# Copyright (c) 2015-2024 CNRS INRIA +# Copyright (c) 2015-2025 CNRS INRIA # Copyright (c) 2015 Wandercraft, 86 rue de Paris 91400 Orsay, France. # @@ -17,6 +17,9 @@ function(ADD_TEST_CFLAGS target) endforeach() endfunction() +set(PINOCCHIO_UNIT_TEST_HEADERS ${PROJECT_SOURCE_DIR}/unittest/constraints/init_constraints.hpp + ${PROJECT_SOURCE_DIR}/unittest/constraints/jacobians-checker.hpp) + # Compute flags outside the macro to avoid recomputing it for each tests cxx_flags_by_compiler_frontend(MSVC _USE_MATH_DEFINES OUTPUT TEST_PRIVATE_DEFINITIONS) @@ -51,7 +54,7 @@ function(ADD_PINOCCHIO_UNIT_TEST name) set(PKGS ${unit_test_PACKAGES}) get_cpp_test_name(${name} ${CMAKE_CURRENT_SOURCE_DIR} TEST_NAME) - add_unit_test(${TEST_NAME} ${name}.cpp) + add_unit_test(${TEST_NAME} ${name}.cpp ${PINOCCHIO_UNIT_TEST_HEADERS}) set(MODULE_NAME "${NAME}Test") string(REPLACE "-" "_" MODULE_NAME ${MODULE_NAME}) @@ -74,6 +77,8 @@ function(ADD_PINOCCHIO_UNIT_TEST name) if(NOT unit_test_HEADER_ONLY) target_link_libraries(${TEST_NAME} PUBLIC ${PROJECT_NAME}_default) + else() + target_link_libraries(${TEST_NAME} PUBLIC ${PROJECT_NAME}_headers) endif() if(unit_test_PARSERS OR (unit_test_PARSERS_OPTIONAL AND TARGET ${PROJECT_NAME}_parsers)) @@ -136,7 +141,11 @@ endmacro() find_package(Boost COMPONENTS unit_test_framework) # Header only +add_pinocchio_unit_test(alloca HEADER_ONLY) +add_pinocchio_unit_test(double-entry-container HEADER_ONLY) add_pinocchio_unit_test(macros HEADER_ONLY) +add_pinocchio_unit_test(reference HEADER_ONLY) +add_pinocchio_unit_test(storage HEADER_ONLY) # Math components add_pinocchio_unit_test(eigen-basic-op) @@ -146,12 +155,11 @@ add_pinocchio_unit_test(quaternion) add_pinocchio_unit_test(rpy) add_pinocchio_unit_test(rotation) add_pinocchio_unit_test(vector) +add_pinocchio_unit_test(matrix) +add_pinocchio_unit_test(matrix-inverse) add_pinocchio_unit_test(eigenvalues) add_pinocchio_unit_test(tridiagonal-matrix) -# TOOD This test contains an undefined behavior and is not stable. Reactivte the test when the fix -# is merged. - -# add_pinocchio_unit_test(lanczos-decomposition) +add_pinocchio_unit_test(lanczos-decomposition) add_pinocchio_unit_test(gram-schmidt-orthonormalisation) # Derivatives algo @@ -162,6 +170,13 @@ add_pinocchio_unit_test(aba-derivatives) add_pinocchio_unit_test(centroidal-derivatives) add_pinocchio_unit_test(center-of-mass-derivatives) add_pinocchio_unit_test(constrained-dynamics-derivatives) + +if(BUILD_WITH_SDF_SUPPORT) + add_pinocchio_unit_test(contact-dynamics-derivatives PARSERS) +else() + add_pinocchio_unit_test(contact-dynamics-derivatives) +endif() +add_pinocchio_unit_test(impulse-dynamics-derivatives) add_pinocchio_unit_test(rnea-second-order-derivatives) # Pinocchio features @@ -177,22 +192,28 @@ add_pinocchio_unit_test(com) add_pinocchio_unit_test(joint-jacobian) add_pinocchio_unit_test(cholesky) add_pinocchio_unit_test(constrained-dynamics) +add_pinocchio_unit_test(constraint-variants) add_pinocchio_unit_test(contact-models) +add_pinocchio_unit_test(point-bilateral-constraint) +add_pinocchio_unit_test(point-frictional-constraint) +add_pinocchio_unit_test(weld-constraint) +add_pinocchio_unit_test(joint-frictional-constraint) +add_pinocchio_unit_test(joint-limit-constraint) +add_pinocchio_unit_test(constraint-jacobian) add_pinocchio_unit_test(contact-dynamics) add_pinocchio_unit_test(contact-inverse-dynamics) add_pinocchio_unit_test(closed-loop-dynamics) +add_pinocchio_unit_test(loop-constrained-aba) +add_pinocchio_unit_test(impulse-dynamics) add_pinocchio_unit_test(sample-models COLLISION_OPTIONAL) add_pinocchio_unit_test(kinematics) -# Test for unstable features TODO fix and reactivate these tests in next version -# ADD_PINOCCHIO_UNIT_TEST(delassus) ADD_PINOCCHIO_UNIT_TEST(pv-solver) -add_pinocchio_unit_test(impulse-dynamics-derivatives) -if(BUILD_WITH_SDF_SUPPORT) - add_pinocchio_unit_test(contact-dynamics-derivatives PARSERS) -else() - add_pinocchio_unit_test(contact-dynamics-derivatives) -endif() -add_pinocchio_unit_test(constraint-variants) -add_pinocchio_unit_test(impulse-dynamics) +add_pinocchio_unit_test(delassus) +add_pinocchio_unit_test(delassus-operator-dense) +add_pinocchio_unit_test(delassus-operator-preconditioned) +add_pinocchio_unit_test(delassus-operator-rigid-body) +add_pinocchio_unit_test(preconditioner) +add_pinocchio_unit_test(pv-solver) +add_pinocchio_parallel_unit_test(openmp-exception) add_pinocchio_unit_test( mjcf @@ -267,6 +288,7 @@ add_pinocchio_unit_test(joint-composite) add_pinocchio_unit_test(joint-mimic) add_pinocchio_unit_test(joint-helical) add_pinocchio_unit_test(joint-universal) +add_pinocchio_unit_test(joint-visitors) # Main corpus add_pinocchio_unit_test(model COLLISION_OPTIONAL) @@ -298,6 +320,14 @@ add_pinocchio_unit_test(copy) add_pinocchio_unit_test(contact-cholesky) add_pinocchio_unit_test(classic-acceleration) add_pinocchio_unit_test(coulomb-friction-cone) +add_pinocchio_unit_test(box-set) +add_pinocchio_unit_test(unbounded-set) +add_pinocchio_unit_test(null-set) +add_pinocchio_unit_test(orthant-cone) + +# Solvers +add_pinocchio_unit_test(pgs-solver) +add_pinocchio_unit_test(admm-solver) # Serialization make_directory("${CMAKE_CURRENT_BINARY_DIR}/serialization-data") diff --git a/unittest/admm-solver.cpp b/unittest/admm-solver.cpp new file mode 100644 index 0000000000..13ed912642 --- /dev/null +++ b/unittest/admm-solver.cpp @@ -0,0 +1,1411 @@ +// +// Copyright (c) 2024 INRIA +// + +#include "pinocchio/algorithm/constraints/constraints.hpp" +#include "pinocchio/algorithm/contact-cholesky.hpp" +#include "pinocchio/algorithm/joint-configuration.hpp" +#include "pinocchio/algorithm/contact-jacobian.hpp" +#include "pinocchio/algorithm/admm-solver.hpp" +#include "pinocchio/algorithm/pgs-solver.hpp" +#include "pinocchio/algorithm/aba.hpp" +#include "pinocchio/algorithm/crba.hpp" +#include "pinocchio/algorithm/delassus.hpp" + +#include +#include + +using namespace pinocchio; + +double mu = 1e-4; + +template +struct TestBoxTpl +{ + typedef _ConstraintModel ConstraintModel; + + typedef typename ConstraintModel::ConstraintData ConstraintData; + typedef typename ConstraintModel::ConstraintSet ConstraintSet; + + TestBoxTpl(const Model & model, const std::vector & constraint_models) + : model(model) + , data(model) + , constraint_models(constraint_models) + , v_next(Eigen::VectorXd::Zero(model.nv)) + { + for (const auto & cm : constraint_models) + { + constraint_datas.push_back(cm.createData()); + constraint_sets.push_back(cm.set()); + } + + const Eigen::DenseIndex constraint_size = getTotalConstraintSize(constraint_models); + primal_solution = dual_solution = dual_solution_sparse = Eigen::VectorXd::Zero(constraint_size); + } + + void operator()( + const Eigen::VectorXd & q0, + const Eigen::VectorXd & v0, + const Eigen::VectorXd & tau0, + const Force & fext, + const double dt, + const bool test_warmstart = false) + { + std::vector external_forces(size_t(model.njoints), Force::Zero()); + external_forces[1] = fext; + + const Eigen::VectorXd v_free = + v0 + dt * aba(model, data, q0, v0, tau0, external_forces, Convention::WORLD); + + // Cholesky of the Delassus matrix + crba(model, data, q0, Convention::WORLD); + ContactCholeskyDecomposition chol(model, constraint_models); + chol.resize(model, constraint_models); + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + // std::cout << "chol.getDamping() : " << chol.getDamping().transpose() << std::endl; + + const Eigen::MatrixXd delassus_matrix_plain = chol.getDelassusCholeskyExpression().matrix(); + std::cout << "delassus_matrix_plain: " << delassus_matrix_plain << std::endl; + auto G_expression = chol.getDelassusCholeskyExpression(); + + Eigen::MatrixXd constraint_jacobian(delassus_matrix_plain.rows(), model.nv); + constraint_jacobian.setZero(); + getConstraintsJacobian(model, data, constraint_models, constraint_datas, constraint_jacobian); + + Eigen::VectorXd time_scaling(delassus_matrix_plain.rows()); + internal::getTimeScalingFromAccelerationToConstraints(constraint_models, dt, time_scaling); + const Eigen::VectorXd g = (constraint_jacobian * v_free).cwiseProduct(time_scaling / dt); + + ADMMContactSolverTpl admm_solver(int(delassus_matrix_plain.rows())); + admm_solver.setAbsolutePrecision(1e-13); + admm_solver.setRelativePrecision(1e-14); + admm_solver.setLanczosSize((int)g.size()); + + PGSContactSolver pgs_solver(int(delassus_matrix_plain.rows())); + pgs_solver.setAbsolutePrecision(1e-10); + pgs_solver.setRelativePrecision(1e-14); + + Eigen::VectorXd compliance = Eigen::VectorXd::Zero(g.size()); + G_expression.updateCompliance(compliance); + Eigen::VectorXd mean_inertia = Eigen::VectorXd::Constant(g.size(), data.M.diagonal().trace()); + mean_inertia /= (double)(g.size()); + mean_inertia = mean_inertia.array().sqrt(); + boost::optional> preconditioner_vec(mean_inertia); + boost::optional> primal_solution_constref(primal_solution); + has_converged = admm_solver.solve( + G_expression, g, constraint_models, dt, preconditioner_vec, primal_solution_constref); + primal_solution = admm_solver.getPrimalSolution(); + // std::cout << "primal_solution : " << (primal_solution).transpose() << std::endl; + // std::cout << "g : " << (g).transpose() << std::endl; + // std::cout << "delassus_matrix_plain : " << (delassus_matrix_plain).transpose() << + // std::endl; std::cout << "delassus_matrix_plain * primal_solution : " << + // (delassus_matrix_plain * primal_solution).transpose() << std::endl; std::cout << + // "time_scaling.asDiagonal()* delassus_matrix_plain * primal_solution : " << + // (time_scaling.asDiagonal()*delassus_matrix_plain * primal_solution).transpose() << std::endl; + // std::cout << "time_scaling.asDiagonal()* delassus_matrix_plain * primal_solution + g : " << + // (time_scaling.asDiagonal()*delassus_matrix_plain * primal_solution + g).transpose() << + // std::endl; + + if (test_warmstart) + { + boost::optional> primal_solution_warmstart(primal_solution); + has_converged = + has_converged + && admm_solver.solve( + G_expression, g, constraint_models, dt, preconditioner_vec, primal_solution_warmstart); + primal_solution = admm_solver.getPrimalSolution(); + } + + dual_solution = admm_solver.getDualSolution(); + n_iter = admm_solver.getIterationCount(); + const Eigen::VectorXd tau_ext = constraint_jacobian.transpose() * primal_solution; + + v_next = + v0 + + dt * aba(model, data, q0, v0, (tau0 + tau_ext).eval(), external_forces, Convention::WORLD); + } + + Model model; + Data data; + std::vector constraint_models; + std::vector constraint_datas; + std::vector constraint_sets; + Eigen::VectorXd v_next; + + Eigen::VectorXd primal_solution, dual_solution, dual_solution_sparse; + bool has_converged; + int n_iter; +}; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +Eigen::Vector3d computeFtot(const Eigen::VectorXd & contact_forces) +{ + Eigen::Vector3d f_tot = Eigen::Vector3d::Zero(); + for (int k = 0; k < contact_forces.size() / 3; ++k) + { + f_tot += contact_forces.segment(3 * k, 3); + } + return f_tot; +} + +BOOST_AUTO_TEST_CASE(ball) +{ + Model model; + model.addJoint(0, JointModelFreeFlyer(), SE3::Identity(), "free_flyer"); + + const double ball_dim = 1; + const double ball_mass = 10; + const Inertia ball_inertia = Inertia::FromSphere(ball_mass, ball_dim); + + model.appendBodyToJoint(1, ball_inertia); + + BOOST_CHECK(model.check(model.createData())); + + Eigen::VectorXd q0 = neutral(model); + q0.const_cast_derived()[2] += ball_dim / 2; + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + const Eigen::VectorXd tau0 = Eigen::VectorXd::Zero(model.nv); + + const double dt = 1e-3; + + typedef FrictionalPointConstraintModel ConstraintModel; + typedef TestBoxTpl TestBox; + std::vector constraint_models; + + const double friction_value = 0.4; + { + const SE3 local_placement_ball(SE3::Matrix3::Identity(), SE3::Vector3(0, 0, -ball_dim)); + ConstraintModel cm(model, 0, SE3::Identity(), 1, local_placement_ball); + cm.set() = CoulombFrictionCone(friction_value); + constraint_models.push_back(cm); + } + + // Test static motion with zero external force + { + const Force fext = Force::Zero(); + + TestBox test(model, constraint_models); + test(q0, v0, tau0, fext, dt); + + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(test.dual_solution.isZero(2e-10)); + const Force::Vector3 f_tot_ref = -ball_mass * Model::gravity981 - fext.linear(); + BOOST_CHECK(computeFtot(test.primal_solution).isApprox(f_tot_ref, 1e-8)); + BOOST_CHECK(test.v_next.isZero(2e-10)); + + // Test warmstart + test(q0, v0, tau0, fext, dt, true); + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(test.dual_solution.isZero(2e-10)); + BOOST_CHECK(computeFtot(test.primal_solution).isApprox(f_tot_ref, 1e-8)); + BOOST_CHECK(test.v_next.isZero(2e-10)); + BOOST_CHECK(test.n_iter == 0); + } +} + +void buildStackOfCubesModel( + std::vector masses, + ::pinocchio::Model & model, + std::vector & constraint_models) +{ + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + const int n_cubes = (int)masses.size(); + + for (int i = 0; i < n_cubes; i++) + { + const double box_mass = masses[(std::size_t)i]; + const Inertia box_inertia = Inertia::FromBox(box_mass, box_dims[0], box_dims[1], box_dims[2]); + JointIndex joint_id = + model.addJoint(0, JointModelFreeFlyer(), SE3::Identity(), "free_flyer_" + std::to_string(i)); + model.appendBodyToJoint(joint_id, box_inertia); + } + + const double friction_value = 0.4; + for (int i = 0; i < n_cubes; i++) + { + const SE3 local_placement_box_1( + SE3::Matrix3::Identity(), 0.5 * SE3::Vector3(box_dims[0], box_dims[1], box_dims[2])); + const SE3 local_placement_box_2( + SE3::Matrix3::Identity(), 0.5 * SE3::Vector3(box_dims[0], box_dims[1], -box_dims[2])); + SE3::Matrix3 rot = SE3::Matrix3::Identity(); + for (int j = 0; j < 4; ++j) + { + const SE3 local_placement_1( + SE3::Matrix3::Identity(), rot * local_placement_box_1.translation()); + const SE3 local_placement_2( + SE3::Matrix3::Identity(), rot * local_placement_box_2.translation()); + FrictionalPointConstraintModel cm( + model, (JointIndex)i, local_placement_1, (JointIndex)i + 1, local_placement_2); + cm.set() = CoulombFrictionCone(friction_value); + constraint_models.push_back(cm); + rot = Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ()).toRotationMatrix() * rot; + } + } +} + +BOOST_AUTO_TEST_CASE(box) +{ + Model model; + typedef FrictionalPointConstraintModel ConstraintModel; + typedef TestBoxTpl TestBox; + std::vector constraint_models; + const double box_mass = 1e1; + const std::vector masses = {box_mass}; + + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + buildStackOfCubesModel(masses, model, constraint_models); + + const int num_tests = +#ifdef NDEBUG + 100000 +#else + 100 +#endif + ; + + BOOST_CHECK(model.check(model.createData())); + + Eigen::VectorXd q0 = neutral(model); + q0[2] += box_dims[2] / 2; + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + const Eigen::VectorXd tau0 = Eigen::VectorXd::Zero(model.nv); + + const double dt = 1e-3; + + // Test static motion with zero external force + { + const Force fext = Force::Zero(); + + TestBox test(model, constraint_models); + test(q0, v0, tau0, fext, dt); + + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(test.dual_solution.isZero(2e-10)); + const Force::Vector3 f_tot_ref = -box_mass * Model::gravity981 - fext.linear(); + BOOST_CHECK(computeFtot(test.primal_solution).isApprox(f_tot_ref, 1e-8)); + std::cout << "test.primal_solution: " << test.primal_solution.transpose() << std::endl; + std::cout << "computeFtot(test.primal_solution): " + << computeFtot(test.primal_solution).transpose() << std::endl; + std::cout << "f_tot_ref: " << f_tot_ref.transpose() << std::endl; + BOOST_CHECK(test.v_next.isZero(2e-10)); + } + + const double friction_value = 0.4; + const double f_sliding = friction_value * Model::gravity981.norm() * box_mass; + + // Test static motion with small external force + for (int k = 0; k < num_tests; ++k) + { + const double scaling = 0.9; + Force fext = Force::Zero(); + fext.linear().head<2>().setRandom().normalize(); + fext.linear() *= scaling * f_sliding; + + TestBox test(model, constraint_models); + test(q0, v0, tau0, fext, dt); + + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(test.dual_solution.isZero(1e-8)); + const Force::Vector3 f_tot_ref = -box_mass * Model::gravity981 - fext.linear(); + BOOST_CHECK(computeFtot(test.primal_solution).isApprox(f_tot_ref, 1e-6)); + BOOST_CHECK(test.v_next.isZero(1e-8)); + } + + // Test slidding motion + for (int k = 0; k < num_tests; ++k) + { + const double scaling = 1.1; + Force fext = Force::Zero(); + fext.linear().head<2>().setRandom().normalize(); + fext.linear() *= scaling * f_sliding; + + TestBox test(model, constraint_models); + test(q0, v0, tau0, fext, dt); + + BOOST_CHECK(test.has_converged == true); + const Force::Vector3 f_tot_ref = -box_mass * Model::gravity981 - 1 / scaling * fext.linear(); + BOOST_CHECK(computeFtot(test.primal_solution).isApprox(f_tot_ref, 1e-6)); + BOOST_CHECK( + math::fabs(Motion(test.v_next).linear().norm() - (f_sliding * 0.1 / box_mass * dt)) <= 1e-6); + BOOST_CHECK(Motion(test.v_next).angular().isZero(1e-6)); + } +} + +BOOST_AUTO_TEST_CASE(stack_of_boxes) +{ + const int n_cubes = 10; + const double conditionning = 1e6; + const double mass_factor = std::pow(conditionning, 1. / (n_cubes - 1)); + std::vector masses; + double mass_tot = 0; + for (int i = 0; i < n_cubes; i++) + { + const double box_mass = 1e-3 * std::pow(mass_factor, i); + masses.push_back(box_mass); + mass_tot += box_mass; + } + + Model model; + typedef FrictionalPointConstraintModel ConstraintModel; + typedef TestBoxTpl TestBox; + std::vector constraint_models; + + buildStackOfCubesModel(masses, model, constraint_models); + BOOST_CHECK(model.check(model.createData())); + + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + + Eigen::VectorXd q0 = neutral(model); + for (int i = 0; i < n_cubes; i++) + { + q0[7 * i + 2] = i * box_dims[2]; + q0[7 * i + 2] += box_dims[2] / 2; + } + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + const Eigen::VectorXd tau0 = Eigen::VectorXd::Zero(model.nv); + + const double dt = 1e-3; + + // Test static motion with zero external force + { + const Force fext = Force::Zero(); + + TestBox test(model, constraint_models); + test(q0, v0, tau0, fext, dt); + + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(test.dual_solution.isZero(2e-10)); + const Force::Vector3 f_tot_ref = -mass_tot * Model::gravity981; + BOOST_CHECK(computeFtot(test.primal_solution).head(3).isApprox(f_tot_ref, 1e-8)); + BOOST_CHECK(test.v_next.isZero(2e-10)); + } +} + +BOOST_AUTO_TEST_CASE(bilateral_box) +{ + Model model; + model.addJoint(0, JointModelFreeFlyer(), SE3::Identity(), "free_flyer"); + + const int num_tests = +#ifdef NDEBUG + 100000 +#else + 100 +#endif + ; + + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + const double box_mass = 10; + const Inertia box_inertia = Inertia::FromBox(box_mass, box_dims[0], box_dims[1], box_dims[2]); + + model.appendBodyToJoint(1, box_inertia); + + BOOST_CHECK(model.check(model.createData())); + + Eigen::VectorXd q0 = neutral(model); + q0.const_cast_derived()[2] += box_dims[2] / 2; + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + const Eigen::VectorXd tau0 = Eigen::VectorXd::Zero(model.nv); + + const double dt = 1e-3; + + typedef BilateralPointConstraintModel ConstraintModel; + typedef TestBoxTpl TestBox; + std::vector constraint_models; + + { + const SE3 local_placement_box( + SE3::Matrix3::Identity(), 0.5 * SE3::Vector3(box_dims[0], box_dims[1], -box_dims[2])); + SE3::Matrix3 rot = SE3::Matrix3::Identity(); + for (int i = 0; i < 4; ++i) + { + const SE3 local_placement(SE3::Matrix3::Identity(), rot * local_placement_box.translation()); + ConstraintModel cm(model, 0, SE3::Identity(), 1, local_placement); + constraint_models.push_back(cm); + rot = Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ()).toRotationMatrix() * rot; + } + } + + // Test static motion with zero external force + { + const Force fext = Force::Zero(); + + TestBox test(model, constraint_models); + test(q0, v0, tau0, fext, dt); + + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(test.dual_solution.isZero(2e-10)); + BOOST_CHECK(computeFtot(test.primal_solution).isApprox(-box_mass * Model::gravity981, 1e-8)); + BOOST_CHECK(test.v_next.isZero(2e-10)); + } + + for (int k = 0; k < num_tests; ++k) + { + Force fext = Force::Zero(); + fext.linear().setRandom(); + + TestBox test(model, constraint_models); + test(q0, v0, tau0, fext, dt); + + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(test.dual_solution.isZero(1e-8)); + const Force::Vector3 f_tot_ref = -box_mass * Model::gravity981 - fext.linear(); + BOOST_CHECK(computeFtot(test.primal_solution).isApprox(f_tot_ref, 1e-6)); + BOOST_CHECK(test.v_next.isZero(1e-8)); + } +} + +BOOST_AUTO_TEST_CASE(dry_friction_box) +{ + Model model; + model.addJoint(0, JointModelFreeFlyer(), SE3::Identity(), "free_flyer"); + + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + const double box_mass = 10; + const Inertia box_inertia = Inertia::FromBox(box_mass, box_dims[0], box_dims[1], box_dims[2]); + + model.appendBodyToJoint(1, box_inertia); + model.gravity.setZero(); + Data data(model); + + Eigen::VectorXd q0 = neutral(model); + q0.const_cast_derived()[2] += box_dims[2] / 2; + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + const Eigen::VectorXd tau0 = Eigen::VectorXd::Zero(model.nv); + + const double dt = 1e-3; + + typedef FrictionalJointConstraintModel ConstraintModel; + typedef ConstraintModel::ConstraintData ConstraintData; + typedef ConstraintModel::ConstraintSet ConstraintSet; + std::vector constraint_models; + std::vector constraint_datas; + + ConstraintModel dry_friction_free_flyer(model, ConstraintModel::JointIndexVector(1, 1)); + constraint_models.push_back(dry_friction_free_flyer); + + for (const auto & cm : constraint_models) + constraint_datas.push_back(cm.createData()); + + std::vector constraint_sets; + constraint_sets.push_back( + BoxSet(Eigen::VectorXd::Constant(6, -1.), Eigen::VectorXd::Constant(6, +1.))); + + const auto & box_set = constraint_sets[0]; + constraint_models[0].set() = box_set; + + const Eigen::VectorXd v_free = v0 + dt * aba(model, data, q0, v0, tau0, Convention::WORLD); + + // Cholesky of the Delassus matrix + crba(model, data, q0, Convention::WORLD); + ContactCholeskyDecomposition chol(model, constraint_models); + chol.resize(model, constraint_models); + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + + auto G_expression = chol.getDelassusCholeskyExpression(); + const Eigen::MatrixXd delassus_matrix_plain = chol.getDelassusCholeskyExpression().matrix(); + const auto & G = delassus_matrix_plain; + // std::cout << "G:\n" << delassus_matrix_plain << std::endl; + + Eigen::MatrixXd constraint_jacobian(dry_friction_free_flyer.size(), model.nv); + constraint_jacobian.setZero(); + getConstraintsJacobian(model, data, constraint_models, constraint_datas, constraint_jacobian); + + Eigen::VectorXd time_scaling(delassus_matrix_plain.rows()); + internal::getTimeScalingFromAccelerationToConstraints(constraint_models, dt, time_scaling); + const Eigen::VectorXd g = (constraint_jacobian * v_free).cwiseProduct(time_scaling / dt); + + Eigen::VectorXd compliance = Eigen::VectorXd::Zero(g.size()); + G_expression.updateCompliance(compliance); + boost::optional> preconditioner_vec( + Eigen::VectorXd::Ones(g.size())); + Eigen::VectorXd dual_solution(Eigen::VectorXd::Zero(g.size())); + boost::optional> primal_solution( + Eigen::VectorXd::Zero(g.size())); + ADMMContactSolver admm_solver(int(delassus_matrix_plain.rows())); + admm_solver.setAbsolutePrecision(1e-13); + admm_solver.setRelativePrecision(1e-14); + + const bool has_converged = + admm_solver.solve(G_expression, g, constraint_models, dt, preconditioner_vec, primal_solution); + BOOST_CHECK(has_converged); + + dual_solution = (G * primal_solution.get()).cwiseProduct(time_scaling) + g; + + BOOST_CHECK(std::fabs(primal_solution.get().dot(dual_solution)) <= 1e-8); + BOOST_CHECK(primal_solution.get().isZero()); + + typedef TestBoxTpl TestBox; + + // Test static motion with zero external force + { + TestBox test(model, constraint_models); + test(q0, v0, tau0, Force::Zero(), dt); + + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(test.dual_solution.isZero(2e-10)); + BOOST_CHECK(test.v_next.isZero(2e-10)); + BOOST_CHECK(box_set.isInside(test.primal_solution)); + } + + for (int i = 0; i < 6; ++i) + { + TestBox test(model, constraint_models); + test(q0, v0, tau0 + 2 * Force::Vector6::Unit(i) / dt, Force::Zero(), dt); + + // std::cout << "test.dual_solution: " << test.dual_solution.transpose() << std::endl; + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(!test.primal_solution.isZero(2e-10)); + BOOST_CHECK(!test.v_next.isZero(2e-10)); + BOOST_CHECK(box_set.isInside(test.primal_solution)); + BOOST_CHECK(std::fabs(test.primal_solution[i] - box_set.lb()[i]) < 1e-8); + } + + // Sign reversed + for (int i = 0; i < 6; ++i) + { + TestBox test(model, constraint_models); + test(q0, v0, tau0 - 2 * Force::Vector6::Unit(i) / dt, Force::Zero(), dt); + + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(!test.dual_solution.isZero(2e-10)); + BOOST_CHECK(!test.v_next.isZero(2e-10)); + BOOST_CHECK(box_set.isInside(test.primal_solution)); + BOOST_CHECK(std::fabs(test.primal_solution[i] - box_set.ub()[i]) < 1e-8); + } +} + +BOOST_AUTO_TEST_CASE(joint_limit_slider) +{ + Model model; + model.addJoint(0, JointModelPX(), SE3::Identity(), "slider"); + model.lowerPositionLimit[0] = 0.; + + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + const double box_mass = 10; + const Inertia box_inertia = Inertia::FromBox(box_mass, box_dims[0], box_dims[1], box_dims[2]); + + model.appendBodyToJoint(1, box_inertia); + model.gravity.setZero(); + Data data(model); + + Eigen::VectorXd q0 = Eigen::VectorXd::Zero(model.nq); + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + const Eigen::VectorXd tau_push_against_lower_bound = -Eigen::VectorXd::Ones(model.nv); + + const double dt = 1e-3; + + typedef JointLimitConstraintModel ConstraintModel; + typedef ConstraintModel::ConstraintData ConstraintData; + std::vector constraint_models; + std::vector constraint_datas; + + ConstraintModel joint_limit_constraint_model(model, ConstraintModel::JointIndexVector(1, 1)); + constraint_models.push_back(joint_limit_constraint_model); + + for (const auto & cm : constraint_models) + constraint_datas.push_back(cm.createData()); + + const Eigen::VectorXd v_free_against_lower_bound = + v0 + dt * aba(model, data, q0, v0, tau_push_against_lower_bound, Convention::WORLD); + const Eigen::VectorXd v_free_move_away = + v0 + dt * aba(model, data, q0, v0, -tau_push_against_lower_bound, Convention::WORLD); + + // Cholesky of the Delassus matrix + crba(model, data, q0, Convention::WORLD); + + data.q_in = q0; + auto & cmodel = constraint_models[0]; + auto & cdata = constraint_datas[0]; + cmodel.resize(model, data, cdata); + cmodel.calc(model, data, cdata); + ContactCholeskyDecomposition chol(model, constraint_models); + chol.resize(model, constraint_models); + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + + auto G_expression = chol.getDelassusCholeskyExpression(); + const auto G_plain = G_expression.matrix(); + const Eigen::MatrixXd delassus_matrix_plain = G_expression.matrix(); + + Eigen::MatrixXd constraint_jacobian(cmodel.activeSize(), model.nv); + constraint_jacobian.setZero(); + getConstraintsJacobian(model, data, constraint_models, constraint_datas, constraint_jacobian); + + Eigen::VectorXd time_scaling(delassus_matrix_plain.rows()); + internal::getTimeScalingFromAccelerationToConstraints(constraint_models, dt, time_scaling); + + // External torques push the slider against the lower bound + { + const Eigen::VectorXd g_against_lower_bound = constraint_jacobian * v_free_against_lower_bound; + const Eigen::VectorXd g_tilde_against_lower_bound = + g_against_lower_bound + cdata.constraint_residual / dt; + g_against_lower_bound.const_cast_derived().array() *= time_scaling.array() / dt; + g_tilde_against_lower_bound.const_cast_derived().array() *= time_scaling.array() / dt; + + Eigen::VectorXd dual_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + ADMMContactSolver admm_solver(int(delassus_matrix_plain.rows())); + admm_solver.setAbsolutePrecision(1e-13); + admm_solver.setRelativePrecision(1e-14); + + Eigen::VectorXd compliance = Eigen::VectorXd::Zero(g_tilde_against_lower_bound.size()); + G_expression.updateCompliance(compliance); + boost::optional> preconditioner_vec( + Eigen::VectorXd::Ones(g_tilde_against_lower_bound.size())); + boost::optional> primal_solution_constref(primal_solution); + const bool has_converged = admm_solver.solve( + G_expression, g_tilde_against_lower_bound, constraint_models, dt, preconditioner_vec, + primal_solution_constref); + primal_solution = admm_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + dual_solution = (G_plain * primal_solution).cwiseProduct(time_scaling) + g_against_lower_bound; + Eigen::VectorXd dual_solution2 = admm_solver.getDualSolution(); + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(dual_solution.isZero(1e-6)); + BOOST_CHECK(dual_solution2.isZero(1e-6)); + + BOOST_CHECK((tau_push_against_lower_bound + constraint_jacobian.transpose() * primal_solution) + .isZero(1e-6)); + } + + // External torques push the slider away from the lower bound + { + const Eigen::VectorXd g_move_away = constraint_jacobian * v_free_move_away; + const Eigen::VectorXd g_tilde_move_away = g_move_away + cdata.constraint_residual / dt; + g_move_away.const_cast_derived().array() *= time_scaling.array() / dt; + g_tilde_move_away.const_cast_derived().array() *= time_scaling.array() / dt; + + Eigen::VectorXd dual_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + ADMMContactSolver admm_solver(int(delassus_matrix_plain.rows())); + admm_solver.setAbsolutePrecision(1e-13); + admm_solver.setRelativePrecision(1e-14); + + Eigen::VectorXd compliance = Eigen::VectorXd::Zero(g_tilde_move_away.size()); + G_expression.updateCompliance(compliance); + boost::optional> preconditioner_vec( + Eigen::VectorXd::Ones(g_tilde_move_away.size())); + boost::optional> primal_solution_constref(primal_solution); + const bool has_converged = admm_solver.solve( + G_expression, g_tilde_move_away, constraint_models, dt, preconditioner_vec, + primal_solution_constref); + primal_solution = admm_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + dual_solution = (G_plain * primal_solution).cwiseProduct(time_scaling) + g_move_away; + Eigen::VectorXd dual_solution2 = admm_solver.getDualSolution(); + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(primal_solution.isZero()); + BOOST_CHECK(dual_solution.isApprox(g_move_away)); + } +} + +BOOST_AUTO_TEST_CASE(joint_limit_revolute_xyz) +{ + Model model; + JointIndex joint_id_x = model.addJoint(0, JointModelRX(), SE3::Identity(), "revolute_x"); + JointIndex joint_id_y = model.addJoint(joint_id_x, JointModelRY(), SE3::Identity(), "revolute_y"); + JointIndex joint_id_z = model.addJoint(joint_id_y, JointModelRZ(), SE3::Identity(), "revolute_z"); + + const SE3::Vector3 small_box_dims = SE3::Vector3::Ones() * 1e-3; + const double small_box_mass = 1e-6; + const Inertia small_box_inertia = + Inertia::FromBox(small_box_mass, small_box_dims[0], small_box_dims[1], small_box_dims[2]); + + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + const double box_mass = 10; + const Inertia box_inertia = Inertia::FromBox(box_mass, box_dims[0], box_dims[1], box_dims[2]); + + model.appendBodyToJoint(joint_id_x, small_box_inertia); + model.appendBodyToJoint(joint_id_y, small_box_inertia); + model.appendBodyToJoint(joint_id_z, box_inertia); + model.gravity.setZero(); + model.lowerPositionLimit[0] = 0.; + model.lowerPositionLimit[1] = 0.; + model.lowerPositionLimit[2] = 0.; + Data data(model); + + Eigen::VectorXd q0 = Eigen::VectorXd::Zero(model.nq); + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + const Eigen::VectorXd tau_push_against_lower_bound = -Eigen::VectorXd::Ones(model.nv); + + const double dt = 1e-3; + + typedef JointLimitConstraintModel ConstraintModel; + typedef ConstraintModel::ConstraintData ConstraintData; + std::vector constraint_models; + std::vector constraint_datas; + ConstraintModel::JointIndexVector active_joints = {joint_id_x, joint_id_y, joint_id_z}; + + ConstraintModel joint_limit_constraint_model(model, active_joints); + constraint_models.push_back(joint_limit_constraint_model); + + for (const auto & cm : constraint_models) + constraint_datas.push_back(cm.createData()); + + const Eigen::VectorXd v_free_against_lower_bound = + v0 + dt * aba(model, data, q0, v0, tau_push_against_lower_bound, Convention::WORLD); + const Eigen::VectorXd v_free_move_away = + v0 + dt * aba(model, data, q0, v0, -tau_push_against_lower_bound, Convention::WORLD); + + // Cholesky of the Delassus matrix + crba(model, data, q0, Convention::WORLD); + + data.q_in = q0; + auto & cmodel = constraint_models[0]; + auto & cdata = constraint_datas[0]; + cmodel.resize(model, data, cdata); + cmodel.calc(model, data, cdata); + ContactCholeskyDecomposition chol(model, constraint_models); + chol.resize(model, constraint_models); + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + + auto G_expression = chol.getDelassusCholeskyExpression(); + const auto G_plain = G_expression.matrix(); + const Eigen::MatrixXd delassus_matrix_plain = G_expression.matrix(); + + Eigen::MatrixXd constraint_jacobian(cmodel.activeSize(), model.nv); + constraint_jacobian.setZero(); + getConstraintsJacobian(model, data, constraint_models, constraint_datas, constraint_jacobian); + + Eigen::VectorXd time_scaling(delassus_matrix_plain.rows()); + internal::getTimeScalingFromAccelerationToConstraints(constraint_models, dt, time_scaling); + + // External torques push the slider against the lower bound + { + const Eigen::VectorXd g_against_lower_bound = constraint_jacobian * v_free_against_lower_bound; + const Eigen::VectorXd g_tilde_against_lower_bound = + g_against_lower_bound + cdata.constraint_residual / dt; + g_against_lower_bound.const_cast_derived().array() *= time_scaling.array() / dt; + g_tilde_against_lower_bound.const_cast_derived().array() *= time_scaling.array() / dt; + + Eigen::VectorXd dual_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + ADMMContactSolver admm_solver(int(delassus_matrix_plain.rows())); + admm_solver.setAbsolutePrecision(1e-13); + admm_solver.setRelativePrecision(1e-14); + + Eigen::VectorXd compliance = Eigen::VectorXd::Zero(g_tilde_against_lower_bound.size()); + G_expression.updateCompliance(compliance); + boost::optional> preconditioner_vec( + Eigen::VectorXd::Ones(g_tilde_against_lower_bound.size())); + boost::optional> primal_solution_constref(primal_solution); + const bool has_converged = admm_solver.solve( + G_expression, g_tilde_against_lower_bound, constraint_models, dt, preconditioner_vec, + primal_solution_constref); + primal_solution = admm_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + dual_solution = (G_plain * primal_solution).cwiseProduct(time_scaling) + g_against_lower_bound; + Eigen::VectorXd dual_solution2 = admm_solver.getDualSolution(); + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(dual_solution.isZero(1e-6)); + BOOST_CHECK(dual_solution2.isZero(1e-6)); + + // std::cout << "tau_push_against_lower_bound: " << tau_push_against_lower_bound << std::endl; + // std::cout << "constraint_jacobian.transpose() * primal_solution: " + // << constraint_jacobian.transpose() * primal_solution << std::endl; + // std::cout << "primal_solution: " << primal_solution << std::endl; + + BOOST_CHECK((tau_push_against_lower_bound + constraint_jacobian.transpose() * primal_solution) + .isZero(1e-6)); + } + + // External torques push the slider away from the lower bound + { + const Eigen::VectorXd g_move_away = constraint_jacobian * v_free_move_away; + const Eigen::VectorXd g_tilde_move_away = g_move_away + cdata.constraint_residual / dt; + g_move_away.const_cast_derived().array() *= time_scaling.array() / dt; + g_tilde_move_away.const_cast_derived().array() *= time_scaling.array() / dt; + + Eigen::VectorXd dual_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + ADMMContactSolver admm_solver(int(delassus_matrix_plain.rows())); + admm_solver.setAbsolutePrecision(1e-13); + admm_solver.setRelativePrecision(1e-14); + + Eigen::VectorXd compliance = Eigen::VectorXd::Zero(g_tilde_move_away.size()); + G_expression.updateCompliance(compliance); + boost::optional> preconditioner_vec( + Eigen::VectorXd::Ones(g_tilde_move_away.size())); + boost::optional> primal_solution_constref(primal_solution); + const bool has_converged = admm_solver.solve( + G_expression, g_tilde_move_away, constraint_models, dt, preconditioner_vec, + primal_solution_constref); + primal_solution = admm_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + dual_solution = (G_plain * primal_solution).cwiseProduct(time_scaling) + g_move_away; + Eigen::VectorXd dual_solution2 = admm_solver.getDualSolution(); + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(primal_solution.isZero()); + BOOST_CHECK(dual_solution.isApprox(g_move_away)); + } +} + +BOOST_AUTO_TEST_CASE(joint_limit_slider_xyz) +{ + Model model; + JointIndex joint_id_x = model.addJoint(0, JointModelPX(), SE3::Identity(), "slider_x"); + JointIndex joint_id_y = model.addJoint(joint_id_x, JointModelPY(), SE3::Identity(), "slider_y"); + JointIndex joint_id_z = model.addJoint(joint_id_y, JointModelPZ(), SE3::Identity(), "slider_z"); + + const SE3::Vector3 small_box_dims = SE3::Vector3::Ones() * 1e-3; + const double small_box_mass = 1e-6; + const Inertia small_box_inertia = + Inertia::FromBox(small_box_mass, small_box_dims[0], small_box_dims[1], small_box_dims[2]); + + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + const double box_mass = 10; + const Inertia box_inertia = Inertia::FromBox(box_mass, box_dims[0], box_dims[1], box_dims[2]); + + model.appendBodyToJoint(joint_id_x, small_box_inertia); + model.appendBodyToJoint(joint_id_y, small_box_inertia); + model.appendBodyToJoint(joint_id_z, box_inertia); + model.gravity.setZero(); + model.lowerPositionLimit[0] = 0.; + model.lowerPositionLimit[1] = 0.; + model.lowerPositionLimit[2] = 0.; + Data data(model); + + Eigen::VectorXd q0 = Eigen::VectorXd::Zero(model.nq); + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + const Eigen::VectorXd tau_push_against_lower_bound = -Eigen::VectorXd::Ones(model.nv); + + const double dt = 1e-3; + + typedef JointLimitConstraintModel ConstraintModel; + typedef ConstraintModel::ConstraintData ConstraintData; + std::vector constraint_models; + std::vector constraint_datas; + ConstraintModel::JointIndexVector active_joints = {joint_id_x, joint_id_y, joint_id_z}; + + ConstraintModel joint_limit_constraint_model(model, active_joints); + constraint_models.push_back(joint_limit_constraint_model); + + for (const auto & cm : constraint_models) + constraint_datas.push_back(cm.createData()); + + const Eigen::VectorXd v_free_against_lower_bound = + v0 + dt * aba(model, data, q0, v0, tau_push_against_lower_bound, Convention::WORLD); + const Eigen::VectorXd v_free_move_away = + v0 + dt * aba(model, data, q0, v0, -tau_push_against_lower_bound, Convention::WORLD); + + // Cholesky of the Delassus matrix + crba(model, data, q0, Convention::WORLD); + + data.q_in = q0; + auto & cmodel = constraint_models[0]; + auto & cdata = constraint_datas[0]; + cmodel.resize(model, data, cdata); + cmodel.calc(model, data, cdata); + ContactCholeskyDecomposition chol(model, constraint_models); + chol.resize(model, constraint_models); + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + + auto G_expression = chol.getDelassusCholeskyExpression(); + const auto G_plain = G_expression.matrix(); + const Eigen::MatrixXd delassus_matrix_plain = G_expression.matrix(); + + Eigen::MatrixXd constraint_jacobian(cmodel.activeSize(), model.nv); + constraint_jacobian.setZero(); + getConstraintsJacobian(model, data, constraint_models, constraint_datas, constraint_jacobian); + + Eigen::VectorXd time_scaling(delassus_matrix_plain.rows()); + internal::getTimeScalingFromAccelerationToConstraints(constraint_models, dt, time_scaling); + + // External torques push the slider against the lower bound + { + const Eigen::VectorXd g_against_lower_bound = constraint_jacobian * v_free_against_lower_bound; + const Eigen::VectorXd g_tilde_against_lower_bound = + g_against_lower_bound + cdata.constraint_residual / dt; + g_against_lower_bound.const_cast_derived().array() *= time_scaling.array() / dt; + g_tilde_against_lower_bound.const_cast_derived().array() *= time_scaling.array() / dt; + + Eigen::VectorXd dual_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + ADMMContactSolver admm_solver(int(delassus_matrix_plain.rows())); + admm_solver.setAbsolutePrecision(1e-13); + admm_solver.setRelativePrecision(1e-14); + + Eigen::VectorXd compliance = Eigen::VectorXd::Zero(g_tilde_against_lower_bound.size()); + G_expression.updateCompliance(compliance); + boost::optional> preconditioner_vec( + Eigen::VectorXd::Ones(g_tilde_against_lower_bound.size())); + boost::optional> primal_solution_constref(primal_solution); + const bool has_converged = admm_solver.solve( + G_expression, g_tilde_against_lower_bound, constraint_models, dt, preconditioner_vec, + primal_solution_constref); + primal_solution = admm_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + dual_solution = (G_plain * primal_solution).cwiseProduct(time_scaling) + g_against_lower_bound; + Eigen::VectorXd dual_solution2 = admm_solver.getDualSolution(); + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(dual_solution.isZero(1e-6)); + BOOST_CHECK(dual_solution2.isZero(1e-6)); + + // std::cout << "tau_push_against_lower_bound: " << tau_push_against_lower_bound << std::endl; + // std::cout << "constraint_jacobian.transpose() * primal_solution: " + // << constraint_jacobian.transpose() * primal_solution << std::endl; + // std::cout << "primal_solution: " << primal_solution << std::endl; + + BOOST_CHECK((tau_push_against_lower_bound + constraint_jacobian.transpose() * primal_solution) + .isZero(1e-6)); + } + + // External torques push the slider away from the lower bound + { + const Eigen::VectorXd g_move_away = constraint_jacobian * v_free_move_away; + const Eigen::VectorXd g_tilde_move_away = g_move_away + cdata.constraint_residual / dt; + g_move_away.const_cast_derived().array() *= time_scaling.array() / dt; + g_tilde_move_away.const_cast_derived().array() *= time_scaling.array() / dt; + + Eigen::VectorXd dual_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + ADMMContactSolver admm_solver(int(delassus_matrix_plain.rows())); + admm_solver.setAbsolutePrecision(1e-13); + admm_solver.setRelativePrecision(1e-14); + + Eigen::VectorXd compliance = Eigen::VectorXd::Zero(g_tilde_move_away.size()); + G_expression.updateCompliance(compliance); + boost::optional> preconditioner_vec( + Eigen::VectorXd::Ones(g_tilde_move_away.size())); + boost::optional> primal_solution_constref(primal_solution); + const bool has_converged = admm_solver.solve( + G_expression, g_tilde_move_away, constraint_models, dt, preconditioner_vec, + primal_solution_constref); + primal_solution = admm_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + dual_solution = (G_plain * primal_solution).cwiseProduct(time_scaling) + g_move_away; + Eigen::VectorXd dual_solution2 = admm_solver.getDualSolution(); + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(primal_solution.isZero()); + BOOST_CHECK(dual_solution.isApprox(g_move_away)); + } +} + +BOOST_AUTO_TEST_CASE(joint_limit_translation) +{ + // We test limits for a joint with nq>1 + Model model; + model.addJoint(0, JointModelTranslation(), SE3::Identity(), "translation"); + model.lowerPositionLimit = Eigen::VectorXd::Ones(model.nq) * -10000; + model.lowerPositionLimit[2] = 0; + model.upperPositionLimit = Eigen::VectorXd::Ones(model.nq) * 10000; + + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + const double box_mass = 10; + const Inertia box_inertia = Inertia::FromBox(box_mass, box_dims[0], box_dims[1], box_dims[2]); + + model.appendBodyToJoint(1, box_inertia); + Data data(model); + + Eigen::VectorXd q0 = neutral(model); + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + Eigen::VectorXd tau_gravity = Eigen::VectorXd::Zero(model.nv); + tau_gravity(2) = 9.81 * box_mass; + + const double dt = 1e-3; + + typedef JointLimitConstraintModel ConstraintModel; + typedef ConstraintModel::ConstraintData ConstraintData; + std::vector constraint_models; + std::vector constraint_datas; + + ConstraintModel joint_limit_constraint_model(model, ConstraintModel::JointIndexVector(1, 1)); + constraint_models.push_back(joint_limit_constraint_model); + + for (const auto & cm : constraint_models) + constraint_datas.push_back(cm.createData()); + + const Eigen::VectorXd v_free_against_lower_bound = + v0 + dt * aba(model, data, q0, v0, Eigen::VectorXd::Zero(model.nv), Convention::WORLD); + const Eigen::VectorXd v_free_move_away = + v0 + dt * aba(model, data, q0, v0, tau_gravity, Convention::WORLD); + + // Cholesky of the Delassus matrix + crba(model, data, q0, Convention::WORLD); + + data.q_in = q0; + auto & cmodel = constraint_models[0]; + auto & cdata = constraint_datas[0]; + cmodel.resize(model, data, cdata); + cmodel.calc(model, data, cdata); + ContactCholeskyDecomposition chol(model, constraint_models); + chol.resize(model, constraint_models); + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + + auto G_expression = chol.getDelassusCholeskyExpression(); + const auto G_plain = G_expression.matrix(); + const Eigen::MatrixXd delassus_matrix_plain = G_expression.matrix(); + + Eigen::MatrixXd constraint_jacobian(cmodel.activeSize(), model.nv); + constraint_jacobian.setZero(); + getConstraintsJacobian(model, data, constraint_models, constraint_datas, constraint_jacobian); + + Eigen::VectorXd time_scaling(delassus_matrix_plain.rows()); + internal::getTimeScalingFromAccelerationToConstraints(constraint_models, dt, time_scaling); + + // Gravity pushes the freeflyer against the lower bound + { + const Eigen::VectorXd g_against_lower_bound = constraint_jacobian * v_free_against_lower_bound; + const Eigen::VectorXd g_tilde_against_lower_bound = + g_against_lower_bound + cdata.constraint_residual / dt; + g_against_lower_bound.const_cast_derived().array() *= time_scaling.array() / dt; + g_tilde_against_lower_bound.const_cast_derived().array() *= time_scaling.array() / dt; + + Eigen::VectorXd constraint_velocity = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + ADMMContactSolver admm_solver(int(delassus_matrix_plain.rows())); + admm_solver.setAbsolutePrecision(1e-13); + admm_solver.setRelativePrecision(1e-14); + + Eigen::VectorXd compliance = Eigen::VectorXd::Zero(g_tilde_against_lower_bound.size()); + G_expression.updateCompliance(compliance); + boost::optional> preconditioner_vec( + Eigen::VectorXd::Ones(g_tilde_against_lower_bound.size())); + boost::optional> primal_solution_constref(primal_solution); + const bool has_converged = admm_solver.solve( + G_expression, g_tilde_against_lower_bound, constraint_models, dt, preconditioner_vec, + primal_solution_constref); + primal_solution = admm_solver.getPrimalSolution(); + // std::cout << " admm_solver.getAbsoluteConvergenceResidual(): " << + // admm_solver.getAbsoluteConvergenceResidual() << std::endl; std::cout << " + // admm_solver.getRelativeConvergenceResidual(): " << + // admm_solver.getRelativeConvergenceResidual() << std::endl; + BOOST_CHECK(has_converged); + + constraint_velocity = + G_plain * primal_solution.cwiseProduct(time_scaling) + g_against_lower_bound; + constraint_velocity /= dt; + Eigen::VectorXd dual_solution = admm_solver.getDualSolution(); + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(constraint_velocity.isZero(1e-6)); + BOOST_CHECK( + (dual_solution + - ((G_plain * primal_solution).cwiseProduct(time_scaling) + g_tilde_against_lower_bound)) + .isZero(1e-6)); + + BOOST_CHECK((-tau_gravity + constraint_jacobian.transpose() * primal_solution).isZero(1e-6)); + } + + // External torques compensate the gravity to push the freeflyer away from the lower bound + { + const Eigen::VectorXd g_move_away = constraint_jacobian * v_free_move_away; + const Eigen::VectorXd g_tilde_move_away = g_move_away + cdata.constraint_residual / dt; + g_move_away.const_cast_derived().array() *= time_scaling.array() / dt; + g_tilde_move_away.const_cast_derived().array() *= time_scaling.array() / dt; + + Eigen::VectorXd dual_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + ADMMContactSolver admm_solver(int(delassus_matrix_plain.rows())); + admm_solver.setAbsolutePrecision(1e-13); + admm_solver.setRelativePrecision(1e-14); + + Eigen::VectorXd compliance = Eigen::VectorXd::Zero(g_tilde_move_away.size()); + G_expression.updateCompliance(compliance); + boost::optional> preconditioner_vec( + Eigen::VectorXd::Ones(g_tilde_move_away.size())); + boost::optional> primal_solution_constref(primal_solution); + const bool has_converged = admm_solver.solve( + G_expression, g_tilde_move_away, constraint_models, dt, preconditioner_vec, + primal_solution_constref); + primal_solution = admm_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + dual_solution = (G_plain * primal_solution).cwiseProduct(time_scaling) + g_move_away; + Eigen::VectorXd dual_solution2 = admm_solver.getDualSolution(); + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(primal_solution.isZero()); + BOOST_CHECK(dual_solution.isApprox(g_move_away)); + } +} + +BOOST_AUTO_TEST_CASE(joint_limit_freeflyer) +{ + // We test limits for a joint with nq>1 + Model model; + model.addJoint(0, JointModelFreeFlyer(), SE3::Identity(), "freeflyer"); + model.lowerPositionLimit = Eigen::VectorXd::Ones(model.nq) * -10000; + model.lowerPositionLimit[2] = 0; + model.upperPositionLimit = Eigen::VectorXd::Ones(model.nq) * 10000; + + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + const double box_mass = 10; + const Inertia box_inertia = Inertia::FromBox(box_mass, box_dims[0], box_dims[1], box_dims[2]); + + model.appendBodyToJoint(1, box_inertia); + Data data(model); + + Eigen::VectorXd q0 = neutral(model); + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + Eigen::VectorXd tau_gravity = Eigen::VectorXd::Zero(model.nv); + tau_gravity(2) = 9.81 * box_mass; + + const double dt = 1e-3; + + typedef JointLimitConstraintModel ConstraintModel; + typedef ConstraintModel::ConstraintData ConstraintData; + std::vector constraint_models; + std::vector constraint_datas; + + ConstraintModel joint_limit_constraint_model(model, ConstraintModel::JointIndexVector(1, 1)); + constraint_models.push_back(joint_limit_constraint_model); + + for (const auto & cm : constraint_models) + constraint_datas.push_back(cm.createData()); + + const Eigen::VectorXd v_free_against_lower_bound = + v0 + dt * aba(model, data, q0, v0, Eigen::VectorXd::Zero(model.nv), Convention::WORLD); + const Eigen::VectorXd v_free_move_away = + v0 + dt * aba(model, data, q0, v0, tau_gravity, Convention::WORLD); + + // Cholesky of the Delassus matrix + crba(model, data, q0, Convention::WORLD); + + data.q_in = q0; + auto & cmodel = constraint_models[0]; + auto & cdata = constraint_datas[0]; + cmodel.resize(model, data, cdata); + cmodel.calc(model, data, cdata); + ContactCholeskyDecomposition chol(model, constraint_models); + chol.resize(model, constraint_models); + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + + auto G_expression = chol.getDelassusCholeskyExpression(); + const auto G_plain = G_expression.matrix(); + const Eigen::MatrixXd delassus_matrix_plain = G_expression.matrix(); + + Eigen::MatrixXd constraint_jacobian(cmodel.activeSize(), model.nv); + constraint_jacobian.setZero(); + getConstraintsJacobian(model, data, constraint_models, constraint_datas, constraint_jacobian); + + Eigen::VectorXd time_scaling(delassus_matrix_plain.rows()); + internal::getTimeScalingFromAccelerationToConstraints(constraint_models, dt, time_scaling); + + // Gravity pushes the freeflyer against the lower bound + { + const Eigen::VectorXd g_against_lower_bound = constraint_jacobian * v_free_against_lower_bound; + const Eigen::VectorXd g_tilde_against_lower_bound = + g_against_lower_bound + cdata.constraint_residual / dt; + g_against_lower_bound.const_cast_derived().array() *= time_scaling.array() / dt; + g_tilde_against_lower_bound.const_cast_derived().array() *= time_scaling.array() / dt; + + Eigen::VectorXd constraint_velocity = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + ADMMContactSolver admm_solver(int(delassus_matrix_plain.rows())); + admm_solver.setAbsolutePrecision(1e-13); + admm_solver.setRelativePrecision(1e-14); + + Eigen::VectorXd compliance = Eigen::VectorXd::Zero(g_tilde_against_lower_bound.size()); + G_expression.updateCompliance(compliance); + boost::optional> preconditioner_vec( + Eigen::VectorXd::Ones(g_tilde_against_lower_bound.size())); + boost::optional> primal_solution_constref(primal_solution); + const bool has_converged = admm_solver.solve( + G_expression, g_tilde_against_lower_bound, constraint_models, dt, preconditioner_vec, + primal_solution_constref); + primal_solution = admm_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + constraint_velocity = + G_plain * primal_solution.cwiseProduct(time_scaling) + g_against_lower_bound; + Eigen::VectorXd dual_solution = admm_solver.getDualSolution(); + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(constraint_velocity.isZero(1e-6)); + BOOST_CHECK( + (dual_solution + - (G_plain * primal_solution.cwiseProduct(time_scaling) + g_tilde_against_lower_bound)) + .isZero(1e-6)); + + BOOST_CHECK((-tau_gravity + constraint_jacobian.transpose() * primal_solution).isZero(1e-6)); + } + + // External torques compensate the gravity to push the freeflyer away from the lower bound + { + const Eigen::VectorXd g_move_away = constraint_jacobian * v_free_move_away; + const Eigen::VectorXd g_tilde_move_away = g_move_away + cdata.constraint_residual / dt; + g_move_away.const_cast_derived().array() *= time_scaling.array() / dt; + g_tilde_move_away.const_cast_derived().array() *= time_scaling.array() / dt; + + Eigen::VectorXd dual_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + ADMMContactSolver admm_solver(int(delassus_matrix_plain.rows())); + admm_solver.setAbsolutePrecision(1e-13); + admm_solver.setRelativePrecision(1e-14); + + Eigen::VectorXd compliance = Eigen::VectorXd::Zero(g_tilde_move_away.size()); + G_expression.updateCompliance(compliance); + boost::optional> preconditioner_vec( + Eigen::VectorXd::Ones(g_tilde_move_away.size())); + boost::optional> primal_solution_constref(primal_solution); + const bool has_converged = admm_solver.solve( + G_expression, g_tilde_move_away, constraint_models, dt, preconditioner_vec, + primal_solution_constref); + primal_solution = admm_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + dual_solution = (G_plain * primal_solution).cwiseProduct(time_scaling) + g_move_away; + Eigen::VectorXd dual_solution2 = admm_solver.getDualSolution(); + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(primal_solution.isZero()); + BOOST_CHECK(dual_solution.isApprox(g_move_away)); + } +} + +BOOST_AUTO_TEST_CASE(joint_limit_composite) +{ + // We test limits for a joint with nq>1 + JointModelComposite joint; + joint.addJoint(JointModelRX()); + joint.addJoint(JointModelRY()); + Model model; + model.addJoint(0, joint, SE3::Identity(), "composite"); + model.lowerPositionLimit = Eigen::VectorXd::Ones(model.nq) * -10000; + model.lowerPositionLimit[1] = 0; + model.upperPositionLimit = Eigen::VectorXd::Ones(model.nq) * 10000; + + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + const double box_mass = 10; + const Inertia box_inertia = Inertia::FromBox(box_mass, box_dims[0], box_dims[1], box_dims[2]); + + model.appendBodyToJoint(1, box_inertia); + model.gravity.setZero(); + Data data(model); + + Eigen::VectorXd q0 = Eigen::VectorXd::Zero(model.nq); + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + const Eigen::VectorXd tau_push_against_lower_bound = -Eigen::VectorXd::Ones(model.nv); + + const double dt = 1e-3; + + typedef JointLimitConstraintModel ConstraintModel; + typedef ConstraintModel::ConstraintData ConstraintData; + std::vector constraint_models; + std::vector constraint_datas; + + ConstraintModel joint_limit_constraint_model(model, ConstraintModel::JointIndexVector(1, 1)); + constraint_models.push_back(joint_limit_constraint_model); + + for (const auto & cm : constraint_models) + constraint_datas.push_back(cm.createData()); + + const Eigen::VectorXd v_free_against_lower_bound = + v0 + dt * aba(model, data, q0, v0, tau_push_against_lower_bound, Convention::WORLD); + const Eigen::VectorXd v_free_move_away = + v0 + dt * aba(model, data, q0, v0, -tau_push_against_lower_bound, Convention::WORLD); + + // Cholesky of the Delassus matrix + crba(model, data, q0, Convention::WORLD); + + data.q_in = q0; + auto & cmodel = constraint_models[0]; + auto & cdata = constraint_datas[0]; + cmodel.resize(model, data, cdata); + cmodel.calc(model, data, cdata); + ContactCholeskyDecomposition chol(model, constraint_models); + chol.resize(model, constraint_models); + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + + auto G_expression = chol.getDelassusCholeskyExpression(); + const auto G_plain = G_expression.matrix(); + const Eigen::MatrixXd delassus_matrix_plain = G_expression.matrix(); + + Eigen::MatrixXd constraint_jacobian(cmodel.activeSize(), model.nv); + constraint_jacobian.setZero(); + getConstraintsJacobian(model, data, constraint_models, constraint_datas, constraint_jacobian); + + Eigen::VectorXd time_scaling(delassus_matrix_plain.rows()); + internal::getTimeScalingFromAccelerationToConstraints(constraint_models, dt, time_scaling); + + // External torques push the freeflyer against from the lower bound + { + const Eigen::VectorXd g_against_lower_bound = constraint_jacobian * v_free_against_lower_bound; + const Eigen::VectorXd g_tilde_against_lower_bound = + g_against_lower_bound + cdata.constraint_residual / dt; + g_against_lower_bound.const_cast_derived().array() *= time_scaling.array() / dt; + g_tilde_against_lower_bound.const_cast_derived().array() *= time_scaling.array() / dt; + + Eigen::VectorXd constraint_velocity = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + ADMMContactSolver admm_solver(int(delassus_matrix_plain.rows())); + admm_solver.setAbsolutePrecision(1e-13); + admm_solver.setRelativePrecision(1e-14); + + Eigen::VectorXd compliance = Eigen::VectorXd::Zero(g_tilde_against_lower_bound.size()); + G_expression.updateCompliance(compliance); + boost::optional> preconditioner_vec( + Eigen::VectorXd::Ones(g_tilde_against_lower_bound.size())); + boost::optional> primal_solution_constref(primal_solution); + const bool has_converged = admm_solver.solve( + G_expression, g_tilde_against_lower_bound, constraint_models, dt, preconditioner_vec, + primal_solution_constref); + primal_solution = admm_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + constraint_velocity = + G_plain * primal_solution.cwiseProduct(time_scaling) + g_against_lower_bound; + + Eigen::VectorXd dual_solution = admm_solver.getDualSolution(); + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(std::abs(constraint_velocity[0]) < 1e-6); + BOOST_CHECK( + (dual_solution + - (G_plain * primal_solution.cwiseProduct(time_scaling) + g_tilde_against_lower_bound)) + .isZero(1e-6)); + + BOOST_CHECK( + std::abs( + (tau_push_against_lower_bound + constraint_jacobian.transpose() * primal_solution)(1)) + < 1e-6); + } + + // External torques push the freeflyer away from the lower bound + { + const Eigen::VectorXd g_move_away = constraint_jacobian * v_free_move_away; + const Eigen::VectorXd g_tilde_move_away = g_move_away + cdata.constraint_residual / dt; + g_move_away.const_cast_derived().array() *= time_scaling.array() / dt; + g_tilde_move_away.const_cast_derived().array() *= time_scaling.array() / dt; + + Eigen::VectorXd dual_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + ADMMContactSolver admm_solver(int(delassus_matrix_plain.rows())); + admm_solver.setAbsolutePrecision(1e-13); + admm_solver.setRelativePrecision(1e-14); + + Eigen::VectorXd compliance = Eigen::VectorXd::Zero(g_tilde_move_away.size()); + G_expression.updateCompliance(compliance); + boost::optional> preconditioner_vec( + Eigen::VectorXd::Ones(g_tilde_move_away.size())); + boost::optional> primal_solution_constref(primal_solution); + const bool has_converged = admm_solver.solve( + G_expression, g_tilde_move_away, constraint_models, dt, preconditioner_vec, + primal_solution_constref); + primal_solution = admm_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + dual_solution = (G_plain * primal_solution).cwiseProduct(time_scaling) + g_move_away; + Eigen::VectorXd dual_solution2 = admm_solver.getDualSolution(); + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(primal_solution.isZero()); + BOOST_CHECK(dual_solution.isApprox(g_move_away)); + } +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/all-joints.cpp b/unittest/all-joints.cpp index c1d0802e48..b4e09a8f00 100644 --- a/unittest/all-joints.cpp +++ b/unittest/all-joints.cpp @@ -234,6 +234,23 @@ BOOST_AUTO_TEST_CASE(transform) TestJointModelTransform()(JointModel()); } +struct TestJointModelLieGroup : TestJointModel +{ + template + static void test(const JointModelBase & jmodel) + { + auto lgo = jmodel.template lieGroup(); + BOOST_CHECK(lgo.nq() == jmodel.nq()); + BOOST_CHECK(lgo.nv() == jmodel.nv()); + } +}; + +BOOST_AUTO_TEST_CASE(lie_group) +{ + typedef JointCollectionDefault::JointModelVariant JointModelVariant; + boost::mpl::for_each(TestJointModelLieGroup()); +} + struct TestJointModelCast : TestJointModel { template diff --git a/unittest/alloca.cpp b/unittest/alloca.cpp new file mode 100644 index 0000000000..f0d104d73c --- /dev/null +++ b/unittest/alloca.cpp @@ -0,0 +1,54 @@ +// +// Copyright (c) 2024 INRIA +// + +#include "pinocchio/fwd.hpp" + +#include +#include + +using namespace pinocchio; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +template +typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixLikeInput) + copy(const Eigen::MatrixBase & mat) +{ + typedef typename MatrixLikeInput::Scalar Scalar; + void * alloca_ptr = alloca(size_t(mat.size()) * sizeof(Scalar)); + + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(MatrixLikeInput) MatrixPlain; + typedef Eigen::Map MatrixPlainMap; + MatrixPlainMap alloca_map = + MatrixPlainMap(static_cast(alloca_ptr), mat.rows(), mat.cols()); + + alloca_map = mat; // copy + return MatrixPlain(alloca_map); +} + +BOOST_AUTO_TEST_CASE(copy_eigen_input) +{ + const int num_tests = 1000; + const Eigen::DenseIndex rows = 10, cols = 20; + const Eigen::MatrixXd mat = Eigen::MatrixXd::Random(rows, cols); + + for (int i = 0; i < num_tests; ++i) + { + const auto mat_copy = copy(mat); + BOOST_CHECK(mat_copy == mat); + } +} + +BOOST_AUTO_TEST_CASE(macro) +{ + const Eigen::DenseIndex rows = 10, cols = 20; + typedef Eigen::Map MapType; + MapType map = MapType(PINOCCHIO_EIGEN_MAP_ALLOCA(Eigen::MatrixXd::Scalar, rows, cols)); + map.setZero(); + BOOST_CHECK(map.rows() == rows); + BOOST_CHECK(map.cols() == cols); + BOOST_CHECK(map.isZero(0.)); +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/box-set.cpp b/unittest/box-set.cpp new file mode 100644 index 0000000000..f225b8a782 --- /dev/null +++ b/unittest/box-set.cpp @@ -0,0 +1,85 @@ +// +// Copyright (c) 2024 INRIA +// + +#include +#include "pinocchio/algorithm/constraints/box-set.hpp" + +#include +#include + +using namespace pinocchio; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(test_proj) +{ + const int num_tests = int(1e6); + const int dim = 10; + + const BoxSet box_constraint(-BoxSet::Vector::Ones(dim), BoxSet::Vector::Ones(dim)); + + BOOST_CHECK(box_constraint.dim() == dim); + + BOOST_CHECK(box_constraint.isInside(BoxSet::Vector::Zero(dim))); + BOOST_CHECK(box_constraint.project(BoxSet::Vector::Zero(dim)) == BoxSet::Vector::Zero(dim)); + + for (int k = 0; k < num_tests; ++k) + { + const BoxSet::Vector x = BoxSet::Vector::Random(dim); + + // Cone + const auto proj_x = box_constraint.project(x); + const auto proj_proj_x = box_constraint.project(proj_x); + + BOOST_CHECK(box_constraint.isInside(proj_x, 1e-12)); + BOOST_CHECK(box_constraint.isInside(proj_proj_x, 1e-12)); + BOOST_CHECK(proj_x == proj_proj_x); + if (box_constraint.isInside(x)) + BOOST_CHECK(x == proj_x); + + BOOST_CHECK(fabs((x - proj_x).dot(proj_x)) <= 1e-12); // orthogonal projection + } +} + +BOOST_AUTO_TEST_CASE(test_scaled_proj) +{ + const int num_tests = int(1e6); + const int dim = 10; + + BoxSet box_constraint(-BoxSet::Vector::Ones(dim), BoxSet::Vector::Ones(dim)); + BoxSet::Vector scale = BoxSet::Vector::Random(dim); + scale.array() = + scale.array().max(BoxSet::Vector::Ones(dim).array() * 0.1); // ensure scale is positive + const BoxSet scaled_box_constraint( + -BoxSet::Vector::Ones(dim).cwiseQuotient(scale), + BoxSet::Vector::Ones(dim).cwiseQuotient(scale)); + + BOOST_CHECK(box_constraint.dim() == dim); + + BOOST_CHECK(box_constraint.isInside(BoxSet::Vector::Zero(dim))); + BoxSet::Vector res(dim); + box_constraint.scaledProject(BoxSet::Vector::Zero(dim), scale, res); + BOOST_CHECK(res == BoxSet::Vector::Zero(dim)); + + for (int k = 0; k < num_tests; ++k) + { + const BoxSet::Vector x = BoxSet::Vector::Random(dim); + + // Cone + box_constraint.scaledProject(x, scale, res); + const auto proj_x = res; + box_constraint.scaledProject(proj_x, scale, res); + const auto proj_proj_x = res; + + BOOST_CHECK(scaled_box_constraint.isInside(proj_x, 1e-12)); + BOOST_CHECK(scaled_box_constraint.isInside(proj_proj_x, 1e-12)); + BOOST_CHECK(proj_x == proj_proj_x); + if (scaled_box_constraint.isInside(x)) + BOOST_CHECK(x == proj_x); + + BOOST_CHECK(fabs((x - proj_x).dot(proj_x)) <= 1e-12); // orthogonal projection + } +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/cholesky.cpp b/unittest/cholesky.cpp index ad27d5ed1b..46ad62a6e5 100644 --- a/unittest/cholesky.cpp +++ b/unittest/cholesky.cpp @@ -19,9 +19,6 @@ #include "pinocchio/algorithm/joint-configuration.hpp" #include -#ifdef NDEBUG - #include -#endif #include #include diff --git a/unittest/constrained-dynamics.cpp b/unittest/constrained-dynamics.cpp index 8c07066063..bbd2fea29f 100644 --- a/unittest/constrained-dynamics.cpp +++ b/unittest/constrained-dynamics.cpp @@ -22,46 +22,8 @@ #include #include -#define KP 10 -#define KD 10 - -BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) - -// BOOST_AUTO_TEST_CASE(contact_models) -// { -// using namespace pinocchio; - -// // Check default constructor -// RigidConstraintModel cmodel1; -// BOOST_CHECK(cmodel1.type == CONTACT_UNDEFINED); -// BOOST_CHECK(cmodel1.size() == 0); - -// // Check complete constructor -// const SE3 M(SE3::Random()); -// RigidConstraintModel cmodel2(CONTACT_3D,0,M); -// BOOST_CHECK(cmodel2.type == CONTACT_3D); -// BOOST_CHECK(cmodel2.joint1_id == 0); -// BOOST_CHECK(cmodel2.joint1_placement.isApprox(M)); -// BOOST_CHECK(cmodel2.size() == 3); - -// // Check contructor with two arguments -// RigidConstraintModel cmodel2prime(CONTACT_3D,0); -// BOOST_CHECK(cmodel2prime.type == CONTACT_3D); -// BOOST_CHECK(cmodel2prime.joint1_id == 0); -// BOOST_CHECK(cmodel2prime.joint1_placement.isIdentity()); -// BOOST_CHECK(cmodel2prime.size() == 3); - -// // Check default copy constructor -// RigidConstraintModel cmodel3(cmodel2); -// BOOST_CHECK(cmodel3 == cmodel2); - -// // Check complete constructor 6D -// RigidConstraintModel cmodel4(CONTACT_6D,0); -// BOOST_CHECK(cmodel4.type == CONTACT_6D); -// BOOST_CHECK(cmodel4.joint1_id == 0); -// BOOST_CHECK(cmodel4.joint1_placement.isIdentity()); -// BOOST_CHECK(cmodel4.size() == 6); -// } +#define KP 0 +#define KD 0 /// \brief Computes motions in the world frame pinocchio::Motion computeAcceleration( @@ -113,6 +75,44 @@ pinocchio::Motion computeAcceleration( return res; } +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +// BOOST_AUTO_TEST_CASE(contact_models) +// { +// using namespace pinocchio; + +// // Check default constructor +// RigidConstraintModel cmodel1; +// BOOST_CHECK(cmodel1.type == CONTACT_UNDEFINED); +// BOOST_CHECK(cmodel1.size() == 0); + +// // Check complete constructor +// const SE3 M(SE3::Random()); +// RigidConstraintModel cmodel2(CONTACT_3D,0,M); +// BOOST_CHECK(cmodel2.type == CONTACT_3D); +// BOOST_CHECK(cmodel2.joint1_id == 0); +// BOOST_CHECK(cmodel2.joint1_placement.isApprox(M)); +// BOOST_CHECK(cmodel2.size() == 3); + +// // Check contructor with two arguments +// RigidConstraintModel cmodel2prime(CONTACT_3D,0); +// BOOST_CHECK(cmodel2prime.type == CONTACT_3D); +// BOOST_CHECK(cmodel2prime.joint1_id == 0); +// BOOST_CHECK(cmodel2prime.joint1_placement.isIdentity()); +// BOOST_CHECK(cmodel2prime.size() == 3); + +// // Check default copy constructor +// RigidConstraintModel cmodel3(cmodel2); +// BOOST_CHECK(cmodel3 == cmodel2); + +// // Check complete constructor 6D +// RigidConstraintModel cmodel4(CONTACT_6D,0); +// BOOST_CHECK(cmodel4.type == CONTACT_6D); +// BOOST_CHECK(cmodel4.joint1_id == 0); +// BOOST_CHECK(cmodel4.joint1_placement.isIdentity()); +// BOOST_CHECK(cmodel4.size() == 6); +// } + BOOST_AUTO_TEST_CASE(test_sparse_forward_dynamics_empty) { using namespace Eigen; @@ -548,10 +548,6 @@ BOOST_AUTO_TEST_CASE(test_constraint_dynamics_LOCAL_6D_loop_closure_j1j2) constraint_data.push_back(RigidConstraintData(ci_closure)); constraint_data_fd.push_back(RigidConstraintData(ci_closure)); - Eigen::DenseIndex constraint_dim = 0; - for (size_t k = 0; k < constraint_models.size(); ++k) - constraint_dim += constraint_models[k].size(); - const double mu0 = 0.; ProximalSettings prox_settings(1e-12, mu0, 100); @@ -1055,8 +1051,6 @@ BOOST_AUTO_TEST_CASE(test_correction_CONTACT_6D) log6(contact_datas[0].c1Mc2.act(contact_datas_plus[0].c1Mc2.inverse())) / dt; BOOST_CHECK( contact_RF_velocity_error_fd.isApprox(contact_datas[0].contact_velocity_error, sqrt(dt))); - std::cout << "contact_RF_velocity_error_fd:\n" << contact_RF_velocity_error_fd << std::endl; - std::cout << "contact_velocity_error:\n" << contact_datas[0].contact_velocity_error << std::endl; // Simulation loop { @@ -1389,32 +1383,21 @@ BOOST_AUTO_TEST_CASE(test_sparse_forward_dynamics_in_contact_specifying_joint2id BOOST_CHECK(data.ddq.isApprox(data_ref.ddq)); BOOST_CHECK((J_ref * data.ddq + rhs_ref).isZero()); - std::cout << "data_ref.ddq: " << data_ref.ddq.transpose() << std::endl; - std::cout << "data.ddq: " << data.ddq.transpose() << std::endl; - std::cout << "res: " << (J_ref * data.ddq + rhs_ref).transpose() << std::endl; - std::cout << "res_ref: " << (J_ref * data_ref.ddq + rhs_ref).transpose() << std::endl; - const Motion vel_1_final = ci_RF.joint2_placement.actInv(data.v[ci_RF.joint2_id]); const Motion::Vector3 acc_1_final = ci_RF.joint2_placement.actInv(data.a[ci_RF.joint2_id]).linear() + vel_1_final.angular().cross(vel_1_final.linear()); BOOST_CHECK(acc_1_final.isZero()); - std::cout << "acc_1_final:" << acc_1_final.transpose() << std::endl; - const Motion vel_2_final = ci_LF.joint2_placement.actInv(data.v[ci_LF.joint2_id]); const Motion::Vector3 acc_2_final = ci_LF.joint2_placement.actInv(data.a[ci_LF.joint2_id]).linear() + vel_2_final.angular().cross(vel_2_final.linear()); BOOST_CHECK(acc_2_final.isZero()); - std::cout << "acc_2_final:" << acc_2_final.transpose() << std::endl; - Motion acc_3_final = c1Mc2_3.act(data.a[ci_RA.joint2_id]); BOOST_CHECK(acc_3_final.isZero()); - std::cout << "acc_3_final:\n" << acc_3_final << std::endl; - Eigen::DenseIndex constraint_id = 0; for (size_t k = 0; k < contact_models.size(); ++k) { @@ -1462,8 +1445,6 @@ BOOST_AUTO_TEST_CASE(test_sparse_forward_dynamics_in_contact_specifying_joint2id model, data_bis, q, v, tau, contact_models_bis, contact_datas_bis, prox_settings); BOOST_CHECK(data_bis.ddq.isApprox(data.ddq)); - std::cout << "ddq: " << data_bis.ddq.transpose() << std::endl; - std::cout << "ddq: " << data.ddq.transpose() << std::endl; for (size_t k = 0; k < contact_models.size(); ++k) { @@ -1479,7 +1460,6 @@ BOOST_AUTO_TEST_CASE(test_sparse_forward_dynamics_in_contact_specifying_joint2id BOOST_CHECK(cdata.oMc2.isApprox(cdata_bis.oMc1)); BOOST_CHECK(cdata.c1Mc2.isApprox(cdata_bis.c1Mc2.inverse())); - std::cout << "cdata.c1Mc2:\n" << cdata.c1Mc2 << std::endl; Force contact_force, contact_force_bis; switch (cmodel.reference_frame) { @@ -1516,9 +1496,6 @@ BOOST_AUTO_TEST_CASE(test_sparse_forward_dynamics_in_contact_specifying_joint2id BOOST_CHECK(false); break; } - - std::cout << "contact_force: " << contact_force.toVector().transpose() << std::endl; - std::cout << "contact_force_bis: " << contact_force_bis.toVector().transpose() << std::endl; } } @@ -1734,8 +1711,6 @@ BOOST_AUTO_TEST_CASE(test_contact_ABA_6D) const double mu = prox_settings.mu; contactABA(model, data, q, v, tau, contact_models, contact_datas, prox_settings); - std::cout << "data.ddq: " << data.ddq.transpose() << std::endl; - std::cout << "data_ref.ddq: " << data_ref.ddq.transpose() << std::endl; BOOST_CHECK((J_ref * data.ddq + gamma).isZero()); forwardKinematics(model, data_ref, q, v, 0 * v); diff --git a/unittest/constraint-jacobian.cpp b/unittest/constraint-jacobian.cpp new file mode 100644 index 0000000000..1401b6a76d --- /dev/null +++ b/unittest/constraint-jacobian.cpp @@ -0,0 +1,116 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#include "pinocchio/algorithm/kinematics.hpp" +#include "pinocchio/algorithm/jacobian.hpp" +#include "pinocchio/algorithm/contact-jacobian.hpp" +#include "pinocchio/algorithm/joint-configuration.hpp" +#include "pinocchio/multibody/sample-models.hpp" +#include "pinocchio/algorithm/constraints/constraints.hpp" + +#include + +#include +#include + +using namespace pinocchio; +using namespace Eigen; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(constraint_jacobian_operations) +{ + + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + Data data(model), data_ref(model); + + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); + VectorXd q = randomConfiguration(model); + computeJointJacobians(model, data, q); + computeJointJacobians(model, data_ref, q); + + const std::string RF = "rleg6_joint"; + const std::string LF = "lleg6_joint"; + + // 3D - LOCAL + { + BilateralPointConstraintModel cm_RF_LOCAL(model, model.getJointId(RF), SE3::Random()); + BilateralPointConstraintData cd_RF_LOCAL(cm_RF_LOCAL); + BilateralPointConstraintModel cm_LF_LOCAL(model, model.getJointId(LF), SE3::Random()); + BilateralPointConstraintData cd_LF_LOCAL(cm_LF_LOCAL); + + const std::vector constraints_models{cm_RF_LOCAL, cm_LF_LOCAL}; + std::vector constraints_datas{cd_RF_LOCAL, cd_LF_LOCAL}; + std::vector constraints_datas_ref{cd_RF_LOCAL, cd_LF_LOCAL}; + + const Eigen::DenseIndex m = getTotalConstraintSize(constraints_models); + + Eigen::VectorXd res(model.nv); + const Eigen::VectorXd rhs = Eigen::VectorXd::Random(m); + + evalConstraints(model, data, constraints_models, constraints_datas); + evalConstraintJacobianTransposeMatrixProduct( + model, data, constraints_models, constraints_datas, rhs, res); + + // Check Jacobian + { + Eigen::VectorXd res_ref = Eigen::VectorXd::Zero(model.nv); + Data::MatrixXs J_RF_LOCAL_sparse(3, model.nv); + J_RF_LOCAL_sparse.setZero(); // TODO: change input type when all the API would be refactorized + // with CRTP on contact constraints + getConstraintJacobian(model, data, cm_RF_LOCAL, cd_RF_LOCAL, J_RF_LOCAL_sparse); + res_ref += J_RF_LOCAL_sparse.transpose() * rhs.segment<3>(0); + + Data::MatrixXs J_LF_LOCAL_sparse(3, model.nv); + J_LF_LOCAL_sparse.setZero(); // TODO: change input type when all the API would be refactorized + // with CRTP on contact constraints + getConstraintJacobian(model, data, cm_LF_LOCAL, cd_LF_LOCAL, J_LF_LOCAL_sparse); + res_ref += J_LF_LOCAL_sparse.transpose() * rhs.segment<3>(3); + + BOOST_CHECK(res.isApprox(res_ref)); + } + + // Alternative way to compute the Jacobians + { + Eigen::MatrixXd J_ref(6, model.nv); + J_ref.setZero(); + getConstraintsJacobian(model, data_ref, constraints_models, constraints_datas_ref, J_ref); + const Eigen::VectorXd res_ref = J_ref.transpose() * rhs; + BOOST_CHECK(res.isApprox(res_ref)); + } + + // Check that getConstraintJacobian works with Matrix3Xs + { + using Matrix3Xs = Eigen::Matrix; + Matrix3Xs J_RF_LOCAL_sparse_3xs(3, model.nv); + J_RF_LOCAL_sparse_3xs.setZero(); + getConstraintJacobian(model, data, cm_RF_LOCAL, cd_RF_LOCAL, J_RF_LOCAL_sparse_3xs); + + Data::MatrixXs J_RF_LOCAL_sparse_xs(3, model.nv); + J_RF_LOCAL_sparse_xs.setZero(); + getConstraintJacobian(model, data, cm_RF_LOCAL, cd_RF_LOCAL, J_RF_LOCAL_sparse_xs); + + BOOST_CHECK(J_RF_LOCAL_sparse_3xs.isApprox(J_RF_LOCAL_sparse_xs)); + } + + // Check that getConstraintJacobian works with Matrix6Xs + { + using Matrix6Xs = Eigen::Matrix; + Matrix6Xs J_RF_LOCAL_sparse_6xs(6, model.nv); + J_RF_LOCAL_sparse_6xs.setZero(); + getConstraintJacobian( + model, data, cm_RF_LOCAL, cd_RF_LOCAL, J_RF_LOCAL_sparse_6xs.topRows(3)); + + Data::MatrixXs J_RF_LOCAL_sparse_xs(6, model.nv); + J_RF_LOCAL_sparse_xs.setZero(); + getConstraintJacobian(model, data, cm_RF_LOCAL, cd_RF_LOCAL, J_RF_LOCAL_sparse_xs.topRows(3)); + + BOOST_CHECK(J_RF_LOCAL_sparse_6xs.isApprox(J_RF_LOCAL_sparse_xs)); + } + } +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/constraint-variants.cpp b/unittest/constraint-variants.cpp index 269065b685..c4b8f741eb 100644 --- a/unittest/constraint-variants.cpp +++ b/unittest/constraint-variants.cpp @@ -1,14 +1,13 @@ // -// Copyright (c) 2023 INRIA +// Copyright (c) 2023-2024 INRIA // #include "pinocchio/multibody/data.hpp" #include "pinocchio/algorithm/constraints/constraints.hpp" -#include "pinocchio/algorithm/constraints/constraint-model-generic.hpp" -#include "pinocchio/algorithm/constraints/constraint-data-generic.hpp" -#include "pinocchio/algorithm/contact-info.hpp" #include "pinocchio/multibody/sample-models.hpp" +#include "constraints/init_constraints.hpp" + #include #include @@ -19,16 +18,15 @@ using namespace Eigen; BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) -BOOST_AUTO_TEST_CASE(contact_variants) +BOOST_AUTO_TEST_CASE(constraint_variants) { Model model; buildModels::humanoidRandom(model, true); Data data(model); - const SE3 M(SE3::Random()); - RigidConstraintModel rcm(CONTACT_3D, model, 0, M); - RigidConstraintData rcd(rcm); + FrictionalPointConstraintModel rcm = init_constraint(model); + FrictionalPointConstraintData rcd(rcm); ConstraintModel::ConstraintModelVariant constraint_model_variant = rcm; ConstraintModel constraint_model(rcm); @@ -37,36 +35,106 @@ BOOST_AUTO_TEST_CASE(contact_variants) ConstraintData constraint_data = rcm.createData(); } -BOOST_AUTO_TEST_CASE(contact_visitors) +BOOST_AUTO_TEST_CASE(constraint_visitors) { Model model; buildModels::humanoidRandom(model, true); Data data(model); - const SE3 M(SE3::Random()); - RigidConstraintModel rcm(CONTACT_3D, model, 0, M); - RigidConstraintData rcd(rcm); + FrictionalPointConstraintModel rcm = init_constraint(model); + FrictionalPointConstraintData rcd(rcm); BOOST_CHECK(ConstraintData(rcd) == ConstraintData(rcd)); BOOST_CHECK(ConstraintData(rcd) == rcd); ConstraintModel constraint_model(rcm); + // Test size + { + BOOST_CHECK(constraint_model.size() == rcm.size()); + } + // Test create data visitor - ConstraintData constraint_data = createData(constraint_model); - constraint_data = rcd; + { + FrictionalPointConstraintData rcd(rcm); + ConstraintData constraint_data = visitors::createData(constraint_model); + constraint_data = rcd; + BOOST_CHECK(constraint_data == rcd); + } // Test calc visitor - calc(constraint_model, constraint_data, model, data); - rcm.calc(model, data, rcd); - BOOST_CHECK(rcd == constraint_data); + { + ConstraintData constraint_data1(rcm.createData()); + visitors::calc(constraint_model, model, data, constraint_data1); + rcm.calc(model, data, rcd); + // BOOST_CHECK(rcd == constraint_data1); + ConstraintData constraint_data2(rcm.createData()); + constraint_model.calc(model, data, constraint_data2); + // BOOST_CHECK(rcd == constraint_data2); + } // Test jacobian visitor - Data::MatrixXs jacobian_matrix = Data::Matrix6x::Zero(6, model.nv), - jacobian_matrix_ref = Data::Matrix6x::Zero(6, model.nv); - jacobian(constraint_model, constraint_data, model, data, jacobian_matrix); - rcm.jacobian(model, data, rcd, jacobian_matrix_ref); - BOOST_CHECK(jacobian_matrix == jacobian_matrix_ref); + { + ConstraintData constraint_data(rcm.createData()); + Data::MatrixXs jacobian_matrix1 = Data::MatrixXs::Zero(rcm.size(), model.nv), + jacobian_matrix2 = Data::MatrixXs::Zero(rcm.size(), model.nv), + jacobian_matrix_ref = Data::MatrixXs::Zero(rcm.size(), model.nv); + rcm.jacobian(model, data, rcd, jacobian_matrix_ref); + visitors::jacobian(constraint_model, model, data, constraint_data, jacobian_matrix1); + BOOST_CHECK(jacobian_matrix1 == jacobian_matrix_ref); + constraint_model.jacobian(model, data, constraint_data, jacobian_matrix2); + BOOST_CHECK(jacobian_matrix2 == jacobian_matrix_ref); + } + + // Test getRowActiveIndexes + { + for (Eigen::DenseIndex row_id = 0; row_id < constraint_model.size(); ++row_id) + { + BOOST_CHECK(constraint_model.getRowActiveIndexes(row_id) == rcm.getRowActiveIndexes(row_id)); + } + } + + // Test getRowActivableSparsityPattern + { + for (Eigen::DenseIndex row_id = 0; row_id < constraint_model.size(); ++row_id) + { + BOOST_CHECK( + constraint_model.getRowActivableSparsityPattern(row_id) + == rcm.getRowActivableSparsityPattern(row_id)); + } + } + + // Test jacobianMatrixProduct + { + const Eigen::Index num_cols = 20; + ConstraintData constraint_data(rcm.createData()); + const Data::MatrixXs input_matrix = Data::MatrixXs::Random(model.nv, num_cols); + Data::MatrixXs output_matrix1(rcm.size(), num_cols), output_matrix2(rcm.size(), num_cols), + output_matrix_ref(rcm.size(), num_cols); + rcm.jacobianMatrixProduct(model, data, rcd, input_matrix, output_matrix_ref); + visitors::jacobianMatrixProduct( + constraint_model, model, data, constraint_data, input_matrix, output_matrix1); + BOOST_CHECK(output_matrix1 == output_matrix_ref); + constraint_model.jacobianMatrixProduct( + model, data, constraint_data, input_matrix, output_matrix2); + BOOST_CHECK(output_matrix2 == output_matrix_ref); + } + + // Test jacobianTransposeMatrixProduct + { + const Eigen::Index num_cols = 20; + ConstraintData constraint_data(rcm.createData()); + const Data::MatrixXs input_matrix = Data::MatrixXs::Random(rcm.size(), num_cols); + Data::MatrixXs output_matrix1(model.nv, num_cols), output_matrix2(model.nv, num_cols), + output_matrix_ref(model.nv, num_cols); + rcm.jacobianTransposeMatrixProduct(model, data, rcd, input_matrix, output_matrix_ref); + visitors::jacobianTransposeMatrixProduct( + constraint_model, model, data, constraint_data, input_matrix, output_matrix1); + BOOST_CHECK(output_matrix1 == output_matrix_ref); + constraint_model.jacobianTransposeMatrixProduct( + model, data, constraint_data, input_matrix, output_matrix2); + BOOST_CHECK(output_matrix2 == output_matrix_ref); + } } BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/constraints/init_constraints.hpp b/unittest/constraints/init_constraints.hpp new file mode 100644 index 0000000000..7721ee2a5f --- /dev/null +++ b/unittest/constraints/init_constraints.hpp @@ -0,0 +1,52 @@ +#pragma once + +#include "pinocchio/algorithm/constraints/constraints.hpp" + +namespace pinocchio +{ + + template + struct init_constraint_default + { + template class JointCollectionTpl> + static ConstraintModel run(const ModelTpl & model) + { + return ConstraintModel(model); + } + }; + + template + struct init_constraint_default> + { + typedef RigidConstraintModelTpl ConstraintModel; + + template class JointCollectionTpl> + static ConstraintModel run(const ModelTpl & model) + { + return ConstraintModel(CONTACT_3D, model, 0, SE3::Random()); + } + }; + + template + struct init_constraint_default> + { + typedef FrictionalPointConstraintModelTpl ConstraintModel; + + template class JointCollectionTpl> + static ConstraintModel run(const ModelTpl & model) + { + return ConstraintModel(model, 0, SE3::Random()); + } + }; + + template< + class ConstraintModel, + typename S, + int O, + template class JointCollectionTpl> + ConstraintModel init_constraint(const ModelTpl & model) + { + return init_constraint_default::run(model); + } + +} // namespace pinocchio diff --git a/unittest/constraints/jacobians-checker.hpp b/unittest/constraints/jacobians-checker.hpp new file mode 100644 index 0000000000..6381612181 --- /dev/null +++ b/unittest/constraints/jacobians-checker.hpp @@ -0,0 +1,80 @@ +#pragma once +#include "pinocchio/multibody/model.hpp" +#include "pinocchio/multibody/data.hpp" + +#include "pinocchio/algorithm/constraints/constraints.hpp" +#include "pinocchio/algorithm/contact-jacobian.hpp" + +#include + +namespace pinocchio +{ + + template + void check_jacobians_operations( + const Model & model, + const Data & data, + const ConstraintModelBase & cmodel, + ConstraintDataBase & cdata) + { + Data::MatrixXs J_ref = Data::MatrixXs::Zero(cmodel.size(), model.nv); + getConstraintJacobian(model, data, cmodel, cdata, J_ref); + + // Check Jacobian matrix product +#ifdef NDEBUG + const int num_tests = int(1e4); +#else + const int num_tests = int(1e2); +#endif + + const Eigen::DenseIndex m = 40; + for (int k = 0; k < num_tests; ++k) + { + const Data::MatrixXs mat = Data::MatrixXs::Random(model.nv, m); + Data::MatrixXs res(cmodel.size(), m); + + const Data::MatrixXs mat_transpose = Data::MatrixXs::Random(cmodel.size(), m); + Data::MatrixXs res_transpose(model.nv, m); + + // Set to + cmodel.jacobianMatrixProduct(model, data, cdata.derived(), mat, res); + Data::MatrixXs res_ref = J_ref * mat; + BOOST_CHECK(res.isApprox(res_ref)); + + cmodel.jacobianTransposeMatrixProduct( + model, data, cdata.derived(), mat_transpose, res_transpose); + Data::MatrixXs res_transpose_ref = J_ref.transpose() * mat_transpose; + BOOST_CHECK(res_transpose.isApprox(res_transpose_ref)); + + // Add to + res = res_ref.setRandom(); + cmodel.jacobianMatrixProduct(model, data, cdata.derived(), mat, res, AddTo()); + res_ref += J_ref * mat; + BOOST_CHECK(res.isApprox(res_ref)); + + res_transpose = res_transpose_ref.setRandom(); + cmodel.jacobianTransposeMatrixProduct( + model, data, cdata.derived(), mat_transpose, res_transpose, AddTo()); + res_transpose_ref += J_ref.transpose() * mat_transpose; + BOOST_CHECK(res_transpose.isApprox(res_transpose_ref)); + + // Remove to + res = res_ref.setRandom(); + cmodel.jacobianMatrixProduct(model, data, cdata.derived(), mat, res, RmTo()); + res_ref -= J_ref * mat; + BOOST_CHECK(res.isApprox(res_ref)); + + res_transpose = res_transpose_ref.setRandom(); + cmodel.jacobianTransposeMatrixProduct( + model, data, cdata.derived(), mat_transpose, res_transpose, RmTo()); + res_transpose_ref -= J_ref.transpose() * mat_transpose; + BOOST_CHECK(res_transpose.isApprox(res_transpose_ref)); + } + + { + const auto identity = Eigen::MatrixXd::Identity(model.nv, model.nv); + BOOST_CHECK( + cmodel.jacobianMatrixProduct(model, data, cdata.derived(), identity).isApprox(J_ref)); + } + } +} // namespace pinocchio diff --git a/unittest/contact-cholesky.cpp b/unittest/contact-cholesky.cpp index f1f714fcca..16fff0800b 100644 --- a/unittest/contact-cholesky.cpp +++ b/unittest/contact-cholesky.cpp @@ -1,14 +1,18 @@ // -// Copyright (c) 2019-2022 INRIA +// Copyright (c) 2019-2024 INRIA // +#define PINOCCHIO_EIGEN_CHECK_MALLOC + #include +#include "pinocchio/fwd.hpp" +#include "pinocchio/math/eigenvalues.hpp" #include "pinocchio/algorithm/jacobian.hpp" #include "pinocchio/algorithm/cholesky.hpp" -#include "pinocchio/algorithm/contact-info.hpp" +#include "pinocchio/algorithm/constraints/constraints.hpp" #include "pinocchio/algorithm/crba.hpp" -#include "pinocchio/algorithm/contact-cholesky.hxx" +#include "pinocchio/algorithm/contact-cholesky.hpp" #include "pinocchio/algorithm/joint-configuration.hpp" #include "pinocchio/multibody/sample-models.hpp" @@ -17,6 +21,60 @@ namespace pinocchio { + + template + struct UDUt + { + typedef _Matrix Matrix; + typedef typename Matrix::Scalar Scalar; + enum + { + Options = Matrix::Options + }; + typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix) PlainMatrix; + typedef typename PINOCCHIO_EIGEN_PLAIN_ROW_MAJOR_TYPE(Matrix) RowMatrix; + typedef Eigen::Matrix Vector; + + explicit UDUt(const Matrix & mat) + : U(mat.rows(), mat.cols()) + , D(mat.rows()) + { + assert(mat.rows() == mat.cols()); + U.setZero(); + U.diagonal().setOnes(); + compute(mat); + } + + PlainMatrix matrix() const + { + return U * D.asDiagonal() * U.transpose(); + } + + template + void compute(const Eigen::MatrixBase & mat) + { + assert(mat.rows() == mat.cols()); + U.template triangularView() = mat.template triangularView(); + for (Eigen::DenseIndex k = mat.rows() - 1; k >= 0; --k) + { + for (Eigen::DenseIndex i = k - 1; i >= 0; --i) + { + const Scalar a = U(i, k) / U(k, k); + for (Eigen::DenseIndex j = i; j >= 0; --j) + { + U(j, i) -= U(j, k) * a; + } + U(i, k) = a; + } + } + D = U.diagonal(); + U.diagonal().setOnes(); + } + + RowMatrix U; + Vector D; + }; + namespace cholesky { template @@ -24,23 +82,19 @@ namespace pinocchio : public ContactCholeskyDecompositionTpl { typedef ContactCholeskyDecompositionTpl Base; - typedef typename Base::IndexVector IndexVector; - typedef typename Base::BooleanVector BooleanVector; + using typename Base::BooleanVector; + using typename Base::EigenIndexVector; ContactCholeskyDecompositionAccessorTpl(const Base & other) : Base(other) { } - const IndexVector & getParents_fromRow() const + const EigenIndexVector & getParents_fromRow() const { return this->parents_fromRow; } - const IndexVector & getLastChild() const - { - return this->last_child; - } - const IndexVector & getNvSubtree_fromRow() const + const EigenIndexVector & getNvSubtree_fromRow() const { return this->nv_subtree_fromRow; } @@ -60,6 +114,16 @@ namespace pinocchio BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) +BOOST_AUTO_TEST_CASE(UDUt_solver) +{ + const Eigen::DenseIndex size = 100; + Eigen::MatrixXd mat = Eigen::MatrixXd::Random(size, size); + mat = mat * mat.transpose(); + + pinocchio::UDUt udut(mat); + BOOST_CHECK(udut.matrix().isApprox(mat)); +} + BOOST_AUTO_TEST_CASE(contact_operator_equal) { @@ -117,7 +181,7 @@ BOOST_AUTO_TEST_CASE(contact_cholesky_simple) ContactCholeskyDecomposition contact_chol_decomposition; const PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models_empty; PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas_empty; - contact_chol_decomposition.allocate(model, contact_models_empty); + contact_chol_decomposition.resize(model, contact_models_empty); BOOST_CHECK(contact_chol_decomposition.D.size() == model.nv); BOOST_CHECK(contact_chol_decomposition.Dinv.size() == model.nv); @@ -151,11 +215,6 @@ BOOST_AUTO_TEST_CASE(contact_cholesky_simple) BOOST_CHECK(access.getParents_fromRow()[k] == data.parents_fromRow[(size_t)k]); } - for (Eigen::DenseIndex k = 0; k < model.njoints; ++k) - { - BOOST_CHECK(access.getLastChild()[k] == data.lastChild[(size_t)k]); - } - for (Eigen::DenseIndex k = 0; k < model.nv; ++k) { BOOST_CHECK(access.getNvSubtree_fromRow()[k] == data.nvSubtree_fromRow[(size_t)k]); @@ -322,7 +381,7 @@ BOOST_AUTO_TEST_CASE(contact_cholesky_contact6D_LOCAL) Data data(model); crba(model, data, q, Convention::WORLD); ContactCholeskyDecomposition contact_chol_decomposition; - contact_chol_decomposition.allocate(model, contact_models); + contact_chol_decomposition.resize(model, contact_models); ContactCholeskyDecompositionAccessor access(contact_chol_decomposition); for (Eigen::DenseIndex k = 0; k < model.nv; ++k) @@ -375,6 +434,8 @@ BOOST_AUTO_TEST_CASE(contact_cholesky_contact6D_LOCAL) BOOST_CHECK(osim.isApprox(JMinvJt.inverse())); const MatrixXd rhs = MatrixXd::Random(12, 12); + BOOST_CHECK(contact_chol_decomposition.getDelassusCholeskyExpression().getDamping().isApprox( + Eigen::VectorXd::Zero(12))); const MatrixXd res_delassus = contact_chol_decomposition.getDelassusCholeskyExpression() * rhs; const MatrixXd res_delassus_ref = iosim * rhs; @@ -395,7 +456,7 @@ BOOST_AUTO_TEST_CASE(contact_cholesky_contact6D_LOCAL) BOOST_CHECK(Minv_test.isApprox(data_ref.Minv)); ContactCholeskyDecomposition contact_chol_decomposition_mu; - contact_chol_decomposition_mu.allocate(model, contact_models); + contact_chol_decomposition_mu.resize(model, contact_models); contact_chol_decomposition_mu.compute(model, data, contact_models, contact_datas, 0.); BOOST_CHECK(contact_chol_decomposition_mu.D.isApprox(contact_chol_decomposition.D)); @@ -538,6 +599,18 @@ BOOST_AUTO_TEST_CASE(contact_cholesky_contact6D_LOCAL) MatrixXd mat3 = contact_chol_decomposition.matrix(); BOOST_CHECK(mat3.isApprox(H)); + + // Check memory allocation + { + const auto delassus_chol = contact_chol_decomposition.getDelassusCholeskyExpression(); + PowerIterationAlgoTpl power_iteration(delassus_chol.rows()); + const Eigen::VectorXd rhs = Eigen::VectorXd::Random(delassus_chol.rows()); + Eigen::VectorXd res = Eigen::VectorXd::Random(delassus_chol.rows()); + PINOCCHIO_EIGEN_MALLOC_NOT_ALLOWED(); + res.noalias() = delassus_chol * rhs; + power_iteration.run(delassus_chol); + PINOCCHIO_EIGEN_MALLOC_ALLOWED(); + } } BOOST_AUTO_TEST_CASE(contact_cholesky_contact3D_6D_LOCAL) @@ -609,7 +682,7 @@ BOOST_AUTO_TEST_CASE(contact_cholesky_contact3D_6D_LOCAL) Data data(model); crba(model, data, q, Convention::WORLD); ContactCholeskyDecomposition contact_chol_decomposition; - contact_chol_decomposition.allocate(model, contact_models); + contact_chol_decomposition.resize(model, contact_models); ContactCholeskyDecompositionAccessor access(contact_chol_decomposition); for (Eigen::DenseIndex k = 0; k < model.nv; ++k) @@ -826,7 +899,7 @@ BOOST_AUTO_TEST_CASE(contact_cholesky_contact6D_LOCAL_WORLD_ALIGNED) Data data(model); crba(model, data, q, Convention::WORLD); ContactCholeskyDecomposition contact_chol_decomposition; - contact_chol_decomposition.allocate(model, contact_models); + contact_chol_decomposition.resize(model, contact_models); contact_chol_decomposition.compute(model, data, contact_models, contact_datas); data.M.triangularView() = @@ -941,7 +1014,7 @@ BOOST_AUTO_TEST_CASE(contact_cholesky_contact6D_by_joint_2) Data data(model); crba(model, data, q, Convention::WORLD); ContactCholeskyDecomposition contact_chol_decomposition; - contact_chol_decomposition.allocate(model, contact_models); + contact_chol_decomposition.resize(model, contact_models); contact_chol_decomposition.compute(model, data, contact_models, contact_datas, mu); data.M.triangularView() = @@ -1146,7 +1219,7 @@ BOOST_AUTO_TEST_CASE(contact_cholesky_contact3D_6D_WORLD_by_joint_2) Data data(model); crba(model, data, q, Convention::WORLD); ContactCholeskyDecomposition contact_chol_decomposition; - contact_chol_decomposition.allocate(model, contact_models); + contact_chol_decomposition.resize(model, contact_models); contact_chol_decomposition.compute(model, data, contact_models, contact_datas); @@ -1291,7 +1364,7 @@ BOOST_AUTO_TEST_CASE(loop_contact_cholesky_contact6D) Data data(model); crba(model, data, q, Convention::WORLD); ContactCholeskyDecomposition contact_chol_decomposition; - contact_chol_decomposition.allocate(model, contact_models); + contact_chol_decomposition.resize(model, contact_models); contact_chol_decomposition.compute(model, data, contact_models, contact_datas, mu); Data::MatrixXs H_recomposed = contact_chol_decomposition.matrix(); @@ -1435,7 +1508,7 @@ BOOST_AUTO_TEST_CASE(loop_contact_cholesky_contact_3d) Data data(model); crba(model, data, q, Convention::WORLD); ContactCholeskyDecomposition contact_chol_decomposition; - contact_chol_decomposition.allocate(model, contact_models); + contact_chol_decomposition.resize(model, contact_models); contact_chol_decomposition.compute(model, data, contact_models, contact_datas, mu); BOOST_CHECK(contact_datas[0].c1Mc2.isApprox(_1M2_loop1)); BOOST_CHECK(contact_datas[1].c1Mc2.isApprox(_1M2_loop2)); @@ -1517,12 +1590,16 @@ BOOST_AUTO_TEST_CASE(contact_cholesky_updateDamping) { ContactCholeskyDecomposition contact_chol_decomposition; - contact_chol_decomposition.allocate(model, contact_models); + contact_chol_decomposition.resize(model, contact_models); + contact_chol_decomposition.compute(model, data, contact_models, contact_datas, mu1); + BOOST_CHECK(contact_chol_decomposition.getDamping().isConstant(mu1)); + contact_chol_decomposition.updateDamping(mu2); + BOOST_CHECK(contact_chol_decomposition.getDamping().isConstant(mu2)); ContactCholeskyDecomposition contact_chol_decomposition_ref; - contact_chol_decomposition_ref.allocate(model, contact_models); + contact_chol_decomposition_ref.resize(model, contact_models); contact_chol_decomposition_ref.compute(model, data, contact_models, contact_datas, mu2); BOOST_CHECK(contact_chol_decomposition.D.isApprox(contact_chol_decomposition_ref.D)); @@ -1532,12 +1609,12 @@ BOOST_AUTO_TEST_CASE(contact_cholesky_updateDamping) { ContactCholeskyDecomposition contact_chol_decomposition; - contact_chol_decomposition.allocate(model, contact_models); + contact_chol_decomposition.resize(model, contact_models); contact_chol_decomposition.compute(model, data, contact_models, contact_datas, mu1); contact_chol_decomposition.getDelassusCholeskyExpression().updateDamping(mu2); ContactCholeskyDecomposition contact_chol_decomposition_ref; - contact_chol_decomposition_ref.allocate(model, contact_models); + contact_chol_decomposition_ref.resize(model, contact_models); contact_chol_decomposition_ref.compute(model, data, contact_models, contact_datas, mu2); BOOST_CHECK(contact_chol_decomposition.D.isApprox(contact_chol_decomposition_ref.D)); @@ -1546,4 +1623,488 @@ BOOST_AUTO_TEST_CASE(contact_cholesky_updateDamping) } } +BOOST_AUTO_TEST_CASE(contact_cholesky_joint_frictional_constraint) +{ + using namespace Eigen; + using namespace pinocchio; + + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + + const Eigen::VectorXd q = neutral(model); + + const std::string RF_name = "rleg6_joint"; + const JointIndex RF_id = model.getJointId(RF_name); + + const Model::IndexVector & RF_support = model.supports[RF_id]; + const Model::IndexVector active_joint_ids(RF_support.begin() + 1, RF_support.end()); + + FrictionalJointConstraintModel constraint_model(model, active_joint_ids); + FrictionalJointConstraintData constraint_data(constraint_model); + + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(FrictionalJointConstraintModel) constraint_models; + constraint_models.push_back(constraint_model); + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(FrictionalJointConstraintData) constraint_datas; + constraint_datas.push_back(constraint_data); + + // Build Cholesky decomposition + Data data(model); + crba(model, data, q, Convention::WORLD); + + ContactCholeskyDecomposition contact_chol_decomposition; + contact_chol_decomposition.resize(model, constraint_models); + + // Compute decompositions + const double mu = 1e-10; + contact_chol_decomposition.compute(model, data, constraint_models, constraint_datas, mu); + + const int constraint_dim = constraint_model.size(); + const int total_dim = model.nv + constraint_dim; + Data::MatrixXs H(total_dim, total_dim); + H.setZero(); + H.topLeftCorner(constraint_dim, constraint_dim).diagonal().fill(-mu); + H.bottomRightCorner(model.nv, model.nv) = data.M; + constraint_model.jacobian( + model, data, constraint_data, H.middleRows(0, constraint_dim).rightCols(model.nv)); + + H.triangularView() = H.triangularView().transpose(); + + BOOST_CHECK(contact_chol_decomposition.matrix().isApprox(H)); + BOOST_CHECK(contact_chol_decomposition.matrix().middleRows(6, 6).rightCols(model.nv).isApprox( + H.middleRows(6, 6).rightCols(model.nv))); + + UDUt udut(H); + + BOOST_CHECK(udut.D.isApprox(contact_chol_decomposition.D)); + BOOST_CHECK(udut.U.isApprox(contact_chol_decomposition.U)); +} + +BOOST_AUTO_TEST_CASE(contact_cholesky_model_generic) +{ + using namespace Eigen; + using namespace pinocchio; + + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + pinocchio::Data data_ref(model); + + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); + VectorXd q = randomConfiguration(model); + + const std::string RF_name = "rleg6_joint"; + const std::string LF_name = "lleg6_joint"; + + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConstraintModel) constraint_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConstraintData) constraint_datas; + + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintModel) rigid_constraint_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(BilateralPointConstraintData) rigid_constraint_datas; + + BilateralPointConstraintModel ci_RF( + model, 0, SE3::Identity(), model.getJointId(RF_name), SE3::Identity()); + constraint_models.push_back(ci_RF); + rigid_constraint_models.push_back(ci_RF); + constraint_datas.push_back(BilateralPointConstraintData(ci_RF)); + rigid_constraint_datas.push_back(BilateralPointConstraintData(ci_RF)); + BilateralPointConstraintModel ci_LF( + model, 0, SE3::Identity(), model.getJointId(LF_name), SE3::Identity()); + constraint_models.push_back(ci_LF); + rigid_constraint_models.push_back(ci_LF); + constraint_datas.push_back(BilateralPointConstraintData(ci_LF)); + rigid_constraint_datas.push_back(BilateralPointConstraintData(ci_LF)); + + Data data(model); + crba(model, data, q, Convention::WORLD); + + ContactCholeskyDecomposition contact_chol_decomposition, contact_chol_decomposition_ref; + contact_chol_decomposition.resize(model, constraint_models); + contact_chol_decomposition_ref.resize(model, rigid_constraint_models); + + const double mu = 1e-10; + contact_chol_decomposition.compute(model, data, constraint_models, constraint_datas, mu); + contact_chol_decomposition_ref.compute( + model, data, rigid_constraint_models, rigid_constraint_datas, mu); + + BOOST_CHECK(contact_chol_decomposition.D.isApprox(contact_chol_decomposition_ref.D)); + BOOST_CHECK(contact_chol_decomposition.Dinv.isApprox(contact_chol_decomposition_ref.Dinv)); + BOOST_CHECK(contact_chol_decomposition.U.isApprox(contact_chol_decomposition_ref.U)); +} + +BOOST_AUTO_TEST_CASE(contact_cholesky_dynamic_size) +{ + using namespace Eigen; + using namespace pinocchio; + + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + pinocchio::Data data(model); + + // First, test not activable limits on joints + { + model.lowerPositionLimit.setConstant(-std::numeric_limits::max()); + model.upperPositionLimit.setConstant(std::numeric_limits::max()); + VectorXd q = pinocchio::neutral(model); + data.q_in = q; + + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConstraintModel) constraint_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConstraintData) constraint_datas; + + JointLimitConstraintModel::JointIndexVector joint_indices; + for (int i = 1; i < model.njoints; ++i) + { + joint_indices.push_back((Model::JointIndex)i); + } + model.positionLimitMargin.setZero(); + JointLimitConstraintModel joint_limit_constraint_model(model, joint_indices); + constraint_models.push_back(joint_limit_constraint_model); + // No activable joint limits + BOOST_CHECK(constraint_models[0].size() == 0); + + const std::string RF_name = "rleg6_joint"; + const std::string LF_name = "lleg6_joint"; + + BilateralPointConstraintModel ci_RF( + model, 0, SE3::Identity(), model.getJointId(RF_name), SE3::Identity()); + constraint_models.push_back(ci_RF); + BilateralPointConstraintModel ci_LF( + model, 0, SE3::Identity(), model.getJointId(LF_name), SE3::Identity()); + constraint_models.push_back(ci_LF); + + for (const auto & cm : constraint_models) + constraint_datas.push_back(cm.createData()); + + crba(model, data, q, Convention::WORLD); + + for (std::size_t i = 0; i < constraint_models.size(); ++i) + { + JointLimitConstraintModel * jlcm = + boost::get(&constraint_models[i]); + if (jlcm != nullptr) + { + JointLimitConstraintData * jlcd = + boost::get(&constraint_datas[i]); + jlcm->resize(model, data, *jlcd); + } + constraint_models[i].calc(model, data, constraint_datas[i]); + } + + // No active joint limits + BOOST_CHECK(constraint_models[0].activeSize() == 0); + // Size of bilateral constraints should be 3 + BOOST_CHECK(constraint_models[1].activeSize() == 3); + BOOST_CHECK(constraint_models[2].activeSize() == 3); + + ContactCholeskyDecomposition contact_chol_decomposition, contact_chol_decomposition_ref; + contact_chol_decomposition.resize(model, constraint_models); + + const double mu = 1e-10; + contact_chol_decomposition.compute(model, data, constraint_models, constraint_datas, mu); + + // Only bilateral constraints should be active + BOOST_CHECK(contact_chol_decomposition.constraintDim() == 6); + + // BOOST_CHECK(contact_chol_decomposition.D.isApprox(contact_chol_decomposition_ref.D)); + // BOOST_CHECK(contact_chol_decomposition.Dinv.isApprox(contact_chol_decomposition_ref.Dinv)); + // BOOST_CHECK(contact_chol_decomposition.U.isApprox(contact_chol_decomposition_ref.U)); + } + + // Second, test activable but unactive limits on joints + { + model.lowerPositionLimit.setConstant(-1e4); + model.upperPositionLimit.setConstant(1e4); + VectorXd q = pinocchio::neutral(model); + data.q_in = q; + + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConstraintModel) constraint_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConstraintData) constraint_datas; + + JointLimitConstraintModel::JointIndexVector joint_indices; + for (int i = 1; i < model.njoints; ++i) + { + joint_indices.push_back((Model::JointIndex)i); + } + model.positionLimitMargin.setZero(); + JointLimitConstraintModel joint_limit_constraint_model(model, joint_indices); + constraint_models.push_back(joint_limit_constraint_model); + // Activable joint limits (only the rotation part of the freeflyer is not activable) + BOOST_CHECK(constraint_models[0].size() == 2 * (model.nv - 3)); + + const std::string RF_name = "rleg6_joint"; + const std::string LF_name = "lleg6_joint"; + + BilateralPointConstraintModel ci_RF( + model, 0, SE3::Identity(), model.getJointId(RF_name), SE3::Identity()); + constraint_models.push_back(ci_RF); + BilateralPointConstraintModel ci_LF( + model, 0, SE3::Identity(), model.getJointId(LF_name), SE3::Identity()); + constraint_models.push_back(ci_LF); + + for (const auto & cm : constraint_models) + constraint_datas.push_back(cm.createData()); + + crba(model, data, q, Convention::WORLD); + + for (std::size_t i = 0; i < constraint_models.size(); ++i) + { + JointLimitConstraintModel * jlcm = + boost::get(&constraint_models[i]); + if (jlcm != nullptr) + { + JointLimitConstraintData * jlcd = + boost::get(&constraint_datas[i]); + jlcm->resize(model, data, *jlcd); + } + constraint_models[i].calc(model, data, constraint_datas[i]); + } + + // No active joint limits + BOOST_CHECK(constraint_models[0].activeSize() == 0); + + ContactCholeskyDecomposition contact_chol_decomposition, contact_chol_decomposition_ref; + contact_chol_decomposition.resize(model, constraint_models); + + const double mu = 1e-10; + contact_chol_decomposition.compute(model, data, constraint_models, constraint_datas, mu); + + // Only bilateral constraints should be active + BOOST_CHECK(contact_chol_decomposition.constraintDim() == 6); + + // BOOST_CHECK(contact_chol_decomposition.D.isApprox(contact_chol_decomposition_ref.D)); + // BOOST_CHECK(contact_chol_decomposition.Dinv.isApprox(contact_chol_decomposition_ref.Dinv)); + // BOOST_CHECK(contact_chol_decomposition.U.isApprox(contact_chol_decomposition_ref.U)); + } + + // Third, test only active lower limits on joints + { + model.lowerPositionLimit.setConstant(0); + model.upperPositionLimit.setConstant(1e4); + VectorXd q = pinocchio::neutral(model); + data.q_in = q; + + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConstraintModel) constraint_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConstraintData) constraint_datas; + + JointLimitConstraintModel::JointIndexVector joint_indices; + for (int i = 1; i < model.njoints; ++i) + { + joint_indices.push_back((Model::JointIndex)i); + } + model.positionLimitMargin.setZero(); + JointLimitConstraintModel joint_limit_constraint_model(model, joint_indices); + constraint_models.push_back(joint_limit_constraint_model); + // Activable joint limits (only the rotation part of the freeflyer is not activable) + BOOST_CHECK(constraint_models[0].size() == 2 * (model.nv - 3)); + + const std::string RF_name = "rleg6_joint"; + const std::string LF_name = "lleg6_joint"; + + BilateralPointConstraintModel ci_RF( + model, 0, SE3::Identity(), model.getJointId(RF_name), SE3::Identity()); + constraint_models.push_back(ci_RF); + BilateralPointConstraintModel ci_LF( + model, 0, SE3::Identity(), model.getJointId(LF_name), SE3::Identity()); + constraint_models.push_back(ci_LF); + + for (const auto & cm : constraint_models) + constraint_datas.push_back(cm.createData()); + + crba(model, data, q, Convention::WORLD); + + for (std::size_t i = 0; i < constraint_models.size(); ++i) + { + JointLimitConstraintModel * jlcm = + boost::get(&constraint_models[i]); + if (jlcm != nullptr) + { + JointLimitConstraintData * jlcd = + boost::get(&constraint_datas[i]); + jlcm->resize(model, data, *jlcd); + } + constraint_models[i].calc(model, data, constraint_datas[i]); + } + + // Active joint limits (only the the rotation part of the freeflyer is not active) + BOOST_CHECK(constraint_models[0].activeSize() == (model.nv - 3)); + + ContactCholeskyDecomposition contact_chol_decomposition, contact_chol_decomposition_ref; + contact_chol_decomposition.resize(model, constraint_models); + + const double mu = 1e-10; + contact_chol_decomposition.compute(model, data, constraint_models, constraint_datas, mu); + + // Bilateral constraints and lower limits should be active (except for the rotation part of the + // freeflyer) + BOOST_CHECK(contact_chol_decomposition.constraintDim() == 6 + (model.nv - 3)); + + // BOOST_CHECK(contact_chol_decomposition.D.isApprox(contact_chol_decomposition_ref.D)); + // BOOST_CHECK(contact_chol_decomposition.Dinv.isApprox(contact_chol_decomposition_ref.Dinv)); + // BOOST_CHECK(contact_chol_decomposition.U.isApprox(contact_chol_decomposition_ref.U)); + } +} + +BOOST_AUTO_TEST_CASE(contact_cholesky_model_with_compliance) +{ + using namespace Eigen; + using namespace pinocchio; + + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + pinocchio::Data data_ref(model); + + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); + VectorXd q = randomConfiguration(model); + + const std::string RF_name = "rleg6_joint"; + const std::string LF_name = "lleg6_joint"; + + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConstraintModel) constraint_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(ConstraintData) constraint_datas; + + BilateralPointConstraintModel ci_RF( + model, 0, SE3::Identity(), model.getJointId(RF_name), SE3::Identity()); + ci_RF.compliance() = Eigen::VectorXd::Constant(3, 6e-4); + constraint_models.push_back(ci_RF); + constraint_datas.push_back(BilateralPointConstraintData(ci_RF)); + BilateralPointConstraintModel ci_LF( + model, 0, SE3::Identity(), model.getJointId(LF_name), SE3::Identity()); + ci_LF.compliance() = Eigen::VectorXd::Constant(3, 7e-4); + constraint_models.push_back(ci_LF); + constraint_datas.push_back(BilateralPointConstraintData(ci_LF)); + + Data data(model); + crba(model, data, q, Convention::WORLD); + + ContactCholeskyDecomposition contact_chol_decomposition, contact_chol_decomposition_ref; + contact_chol_decomposition.resize(model, constraint_models); + + const double mu = 1e-10; + contact_chol_decomposition.compute(model, data, constraint_models, constraint_datas, mu); + + auto delassus_chol = contact_chol_decomposition.getDelassusCholeskyExpression(); + + Eigen::VectorXd compliance_vec(6); + compliance_vec.head(3) = Eigen::VectorXd::Constant(3, 6e-4); + compliance_vec.tail(3) = Eigen::VectorXd::Constant(3, 7e-4); + + BOOST_CHECK(delassus_chol.getDamping().isApprox(Eigen::VectorXd::Constant(6, mu))); + BOOST_CHECK(delassus_chol.getCompliance().isApprox(compliance_vec)); + + const double new_mu = 1e-3; + delassus_chol.updateDamping(new_mu); + const double new_compliance = 1e1; + delassus_chol.updateCompliance(new_compliance); + + BOOST_CHECK(delassus_chol.getDamping().isApprox(Eigen::VectorXd::Constant(6, new_mu))); + BOOST_CHECK(delassus_chol.getCompliance().isApprox(Eigen::VectorXd::Constant(6, new_compliance))); +} + +BOOST_AUTO_TEST_CASE(contact_cholesky_check_resize) +{ + using namespace Eigen; + using namespace pinocchio; + using namespace pinocchio::cholesky; + + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + pinocchio::Data data_ref(model); + + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); + VectorXd q = randomConfiguration(model); + + const std::string RF = "rleg6_joint"; + const std::string LF = "lleg6_joint"; + + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) + RigidConstraintModelStdVector; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) + RigidConstraintDataStdVector; + + RigidConstraintModelStdVector contact_models; + RigidConstraintDataStdVector contact_datas; + + { + RigidConstraintModel ci_RF(CONTACT_6D, model, model.getJointId(RF), LOCAL); + contact_models.push_back(ci_RF); + contact_datas.push_back(RigidConstraintData(ci_RF)); + RigidConstraintModel ci_LF(CONTACT_6D, model, model.getJointId(LF), LOCAL); + contact_models.push_back(ci_LF); + contact_datas.push_back(RigidConstraintData(ci_LF)); + } + + Data data(model); + crba(model, data, q, Convention::WORLD); + ContactCholeskyDecomposition contact_chol_decomposition; + contact_chol_decomposition.resize(model, contact_models); + contact_chol_decomposition.compute(model, data, contact_models, contact_datas); + + // Check copy constructor + { + ContactCholeskyDecomposition contact_chol_decomposition_copy(contact_chol_decomposition); + BOOST_CHECK(contact_chol_decomposition_copy.U == contact_chol_decomposition.U); + BOOST_CHECK(contact_chol_decomposition_copy.U.data() != contact_chol_decomposition.U.data()); + BOOST_CHECK(contact_chol_decomposition_copy.D == contact_chol_decomposition.D); + BOOST_CHECK(contact_chol_decomposition_copy.D.data() != contact_chol_decomposition.D.data()); + BOOST_CHECK(contact_chol_decomposition_copy.Dinv == contact_chol_decomposition.Dinv); + BOOST_CHECK( + contact_chol_decomposition_copy.Dinv.data() != contact_chol_decomposition.Dinv.data()); + } + + // Test resize + { + ContactCholeskyDecomposition contact_chol_decomposition_empty(model); + { + RigidConstraintModelStdVector contact_models_empty; + RigidConstraintDataStdVector contact_datas_empty; + contact_chol_decomposition_empty.compute( + model, data, contact_models_empty, contact_datas_empty); + + BOOST_CHECK( + contact_chol_decomposition_empty.U.bottomRightCorner(model.nv, model.nv) + == contact_chol_decomposition.U.bottomRightCorner(model.nv, model.nv)); + BOOST_CHECK( + contact_chol_decomposition_empty.D.tail(model.nv) + == contact_chol_decomposition.D.tail(model.nv)); + BOOST_CHECK( + contact_chol_decomposition_empty.Dinv.tail(model.nv) + == contact_chol_decomposition.Dinv.tail(model.nv)); + } + + contact_chol_decomposition_empty.resize(model, contact_models); + { + RigidConstraintDataStdVector contact_datas; + for (const auto & cmodel : contact_models) + contact_datas.push_back(cmodel.createData()); + + contact_chol_decomposition_empty.compute(model, data, contact_models, contact_datas); + BOOST_CHECK(contact_chol_decomposition_empty.U == contact_chol_decomposition.U); + BOOST_CHECK(contact_chol_decomposition_empty.D == contact_chol_decomposition.D); + BOOST_CHECK(contact_chol_decomposition_empty.Dinv == contact_chol_decomposition.Dinv); + } + + contact_chol_decomposition_empty.resize(model, RigidConstraintModelStdVector()); + { + RigidConstraintModelStdVector contact_models_empty; + RigidConstraintDataStdVector contact_datas_empty; + contact_chol_decomposition_empty.U.triangularView().setZero(); + contact_chol_decomposition_empty.D.setZero(); + contact_chol_decomposition_empty.Dinv.setZero(); + contact_chol_decomposition_empty.compute( + model, data, contact_models_empty, contact_datas_empty); + + BOOST_CHECK( + contact_chol_decomposition_empty.U.bottomRightCorner(model.nv, model.nv) + == contact_chol_decomposition.U.bottomRightCorner(model.nv, model.nv)); + BOOST_CHECK( + contact_chol_decomposition_empty.D.tail(model.nv) + == contact_chol_decomposition.D.tail(model.nv)); + BOOST_CHECK( + contact_chol_decomposition_empty.Dinv.tail(model.nv) + == contact_chol_decomposition.Dinv.tail(model.nv)); + } + } +} + BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/contact-dynamics-derivatives.cpp b/unittest/contact-dynamics-derivatives.cpp index 105e350f84..79800412fd 100644 --- a/unittest/contact-dynamics-derivatives.cpp +++ b/unittest/contact-dynamics-derivatives.cpp @@ -27,8 +27,8 @@ #endif // PINOCCHIO_WITH_SDFORMAT -#define KP 10 -#define KD 10 +#define KP 10. +#define KD 2 * math::sqrt(KP) BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) @@ -374,6 +374,8 @@ BOOST_AUTO_TEST_CASE(test_constraint_dynamics_derivatives_LOCAL_6D_fd) BOOST_CHECK(ddq_partial_dq_fd.isApprox(data.ddq_dq, sqrt(alpha))); BOOST_CHECK(lambda_partial_dq_fd.isApprox(data.dlambda_dq, sqrt(alpha))); + // std::cout << "lambda_partial_dq_fd:\n" << lambda_partial_dq_fd << std::endl; + // std::cout << "data.dlambda_dq:\n" << data.dlambda_dq << std::endl; VectorXd v_plus(v); for (int k = 0; k < model.nv; ++k) diff --git a/unittest/contact-dynamics.cpp b/unittest/contact-dynamics.cpp index 3151cfb368..98ffb43da3 100644 --- a/unittest/contact-dynamics.cpp +++ b/unittest/contact-dynamics.cpp @@ -120,7 +120,7 @@ BOOST_AUTO_TEST_CASE(test_computeKKTMatrix) J.bottomRows<6>() = J_LF; // Check Forward Dynamics - pinocchio::crba(model, data_ref, q, pinocchio::Convention::WORLD); + pinocchio::crba(model, data_ref, q); data_ref.M.triangularView() = data_ref.M.transpose().triangularView(); diff --git a/unittest/contact-inverse-dynamics.cpp b/unittest/contact-inverse-dynamics.cpp index 7901b3e459..3f776bab6f 100644 --- a/unittest/contact-inverse-dynamics.cpp +++ b/unittest/contact-inverse-dynamics.cpp @@ -1,182 +1,184 @@ // -// Copyright (c) 2019-2023 INRIA +// Copyright (c) 2024 INRIA // -#include "pinocchio/algorithm/aba.hpp" -#include "pinocchio/algorithm/rnea.hpp" -#include "pinocchio/algorithm/frames.hpp" -#include "pinocchio/algorithm/jacobian.hpp" -#include "pinocchio/algorithm/centroidal.hpp" -#include "pinocchio/algorithm/kinematics.hpp" -#include "pinocchio/algorithm/contact-info.hpp" -#include "pinocchio/algorithm/compute-all-terms.hpp" -#include "pinocchio/algorithm/constrained-dynamics.hpp" -#include "pinocchio/algorithm/contact-dynamics.hpp" +#include + #include "pinocchio/algorithm/contact-inverse-dynamics.hpp" #include "pinocchio/algorithm/joint-configuration.hpp" -#include "pinocchio/multibody/sample-models.hpp" -#include "pinocchio/utils/timer.hpp" -#include "pinocchio/spatial/classic-acceleration.hpp" -#include +#include "pinocchio/algorithm/constraints/constraints.hpp" +#include "pinocchio/multibody/sample-models.hpp" +#include "pinocchio/algorithm/contact-solver-utils.hpp" #include -#include -#include -#define KP 10 -#define KD 10 +using namespace Eigen; +using namespace pinocchio; +using namespace pinocchio::internal; -BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) +typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(FrictionalPointConstraintModel) + FrictionalPointConstraintModelVector; +typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(FrictionalPointConstraintData) + FrictionalPointConstraintDataVector; -/// \brief Computes motions in the world frame -pinocchio::Motion computeAcceleration( - const pinocchio::Model & model, - pinocchio::Data & data, - const pinocchio::JointIndex & joint_id, - pinocchio::ReferenceFrame reference_frame, - const pinocchio::ContactType type, - const pinocchio::SE3 & placement = pinocchio::SE3::Identity()) +void init(Model & model, FrictionalPointConstraintModelVector & constraint_models) { - PINOCCHIO_UNUSED_VARIABLE(model); - using namespace pinocchio; - Motion res(Motion::Zero()); + pinocchio::buildModels::humanoidRandom(model, true); + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); - const Data::SE3 & oMi = data.oMi[joint_id]; - const Data::SE3 & iMc = placement; - const Data::SE3 oMc = oMi * iMc; + const std::string RF = "rleg6_joint"; + FrictionalPointConstraintModel ci_RF(model, model.getJointId(RF)); + ci_RF.set().mu = 0.4; + constraint_models.push_back(ci_RF); - const Motion ov = oMi.act(data.v[joint_id]); - const Motion oa = oMi.act(data.a[joint_id]); + const std::string LF = "lleg6_joint"; + FrictionalPointConstraintModel ci_LF(model, model.getJointId(LF)); + ci_LF.set().mu = 0.4; + constraint_models.push_back(ci_LF); +} + +FrictionalPointConstraintDataVector +createData(const FrictionalPointConstraintModelVector & constraint_models) +{ + FrictionalPointConstraintDataVector constraint_datas; - switch (reference_frame) + for (const auto & cmodel : constraint_models) { - case WORLD: - if (type == CONTACT_3D) - classicAcceleration(ov, oa, res.linear()); - else - res.linear() = oa.linear(); - res.angular() = oa.angular(); - break; - case LOCAL_WORLD_ALIGNED: - if (type == CONTACT_3D) - res.linear() = oMc.rotation() * classicAcceleration(data.v[joint_id], data.a[joint_id], iMc); - else - res.linear() = oMc.rotation() * (iMc.actInv(data.a[joint_id])).linear(); - res.angular() = oMi.rotation() * data.a[joint_id].angular(); - break; - case LOCAL: - if (type == CONTACT_3D) - classicAcceleration(data.v[joint_id], data.a[joint_id], iMc, res.linear()); - else - res.linear() = (iMc.actInv(data.a[joint_id])).linear(); - res.angular() = iMc.rotation().transpose() * data.a[joint_id].angular(); - break; - default: - break; + constraint_datas.push_back(cmodel.createData()); } - return res; + return constraint_datas; } +template +typename PINOCCHIO_EIGEN_PLAIN_TYPE(VectorLike) abs(const Eigen::MatrixBase & vec) +{ + return Eigen::abs(vec.array()).matrix(); +} + +template +void makeIsotropic( + FrictionalPointConstraintModelVector & constraint_models, + const Eigen::MatrixBase & vec_) +{ + auto & vec = vec_.const_cast_derived(); + + Eigen::Index row_id = 0; + for (const auto & cmodel : constraint_models) + { + const auto csize = cmodel.size(); + + auto vec_seg = vec.segment(row_id, csize); + vec_seg[1] = vec_seg[0]; + + row_id += csize; + } +} + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + BOOST_AUTO_TEST_CASE(test_contact_inverse_dynamics_3D) { - using namespace Eigen; - using namespace pinocchio; +#ifdef NDEBUG + const int num_tests = int(1e4); +#else + const int num_tests = int(1e2); +#endif - pinocchio::Model model; - pinocchio::buildModels::humanoidRandom(model, true); - pinocchio::Data data(model), data_ref(model); + Model model; + FrictionalPointConstraintModelVector constraint_models; - model.lowerPositionLimit.head<3>().fill(-1.); - model.upperPositionLimit.head<3>().fill(1.); + init(model, constraint_models); + const double mu_prox = 1e-4; VectorXd q = randomConfiguration(model); - VectorXd v = VectorXd::Random(model.nv); VectorXd tau = VectorXd::Random(model.nv); - - const std::string RF = "rleg6_joint"; - // const Model::JointIndex RF_id = model.getJointId(RF); - const std::string LF = "lleg6_joint"; - // const Model::JointIndex LF_id = model.getJointId(LF); - - // Contact models and data - typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) - RigidConstraintModelVector; - typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) RigidConstraintDataVector; - typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(CoulombFrictionCone) CoulombFrictionConeVector; - - RigidConstraintModelVector contact_models; - RigidConstraintDataVector contact_datas; - CoulombFrictionConeVector cones; - RigidConstraintModel ci_RF(CONTACT_3D, model, model.getJointId(RF), LOCAL); - contact_models.push_back(ci_RF); - contact_datas.push_back(RigidConstraintData(ci_RF)); - cones.push_back(CoulombFrictionCone(0.4)); - RigidConstraintModel ci_LF(CONTACT_3D, model, model.getJointId(LF), LOCAL); - contact_models.push_back(ci_LF); - contact_datas.push_back(RigidConstraintData(ci_LF)); - cones.push_back(CoulombFrictionCone(0.4)); - - RigidConstraintDataVector contact_datas_ref(contact_datas); + VectorXd a = Eigen::VectorXd::Zero(model.nv); Eigen::DenseIndex constraint_dim = 0; - for (size_t k = 0; k < contact_models.size(); ++k) - constraint_dim += contact_models[k].size(); - - Eigen::MatrixXd J_ref(constraint_dim, model.nv); - J_ref.setZero(); - - double dt = 1e-3; - Eigen::VectorXd R = Eigen::VectorXd::Zero(constraint_dim); - Eigen::VectorXd constraint_correction = Eigen::VectorXd::Zero(constraint_dim); - boost::optional lambda_guess = boost::optional(boost::none); - Eigen::VectorXd a = Eigen::VectorXd::Zero(model.nv); - ProximalSettings prox_settings(1e-12, 1e-6, 1); - initConstraintDynamics(model, data_ref, contact_models); - contactInverseDynamics( - model, data_ref, q, v, a, dt, contact_models, contact_datas, cones, R, constraint_correction, - prox_settings, lambda_guess); - // constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas_ref, - // prox_settings_cd); forwardKinematics(model, data_ref, q, v, v*0); - - // Data::Matrix6x Jtmp = Data::Matrix6x::Zero(6,model.nv); - // getJointJacobian(model,data_ref,ci_RF.joint1_id,ci_RF.reference_frame,Jtmp); - // J_ref.middleRows<3>(0) = Jtmp.middleRows<3>(Motion::LINEAR); - // Jtmp.setZero(); getJointJacobian(model,data_ref,ci_LF.joint1_id,ci_LF.reference_frame,Jtmp); - // J_ref.middleRows<3>(3) = Jtmp.middleRows<3>(Motion::LINEAR); - - // Eigen::VectorXd gamma(constraint_dim); - - // gamma.segment<3>(0) = - // computeAcceleration(model,data_ref,ci_RF.joint1_id,ci_RF.reference_frame,ci_RF.type).linear(); - // gamma.segment<3>(3) = - // computeAcceleration(model,data_ref,ci_LF.joint1_id,ci_LF.reference_frame,ci_LF.type).linear(); - - // BOOST_CHECK((J_ref*data_ref.ddq + gamma).isZero()); - - // Data data_constrained_dyn(model); - - // PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH - // PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_DEPRECECATED_DECLARATIONS - // forwardDynamics(model,data_constrained_dyn,q,v,tau,J_ref,gamma,0.); - // PINOCCHIO_COMPILER_DIAGNOSTIC_POP - - // BOOST_CHECK((J_ref*data_constrained_dyn.ddq + gamma).isZero()); - - // ProximalSettings prox_settings; - // prox_settings.max_iter = 10; - // prox_settings.mu = 1e8; - // contactABA(model, data, q, v, tau, contact_models, contact_datas, prox_settings); - - // BOOST_CHECK((J_ref*data.ddq + gamma).isZero()); - - // // Call the algorithm a second time - // Data data2(model); - // ProximalSettings prox_settings2; - // contactABA(model, data2, q, v, tau, contact_models, contact_datas, prox_settings2); - - // BOOST_CHECK(prox_settings2.iter == 0); + for (const auto & cmodel : constraint_models) + { + constraint_dim += cmodel.size(); + } + + BOOST_CHECK(constraint_dim > 0); + + for (int n = 0; n < num_tests; ++n) + { + Eigen::VectorXd R = abs(Eigen::VectorXd::Random(constraint_dim)) + + Eigen::VectorXd::Constant(constraint_dim, 1e-10); + makeIsotropic(constraint_models, R); + + Eigen::Index constraint_index = 0; + for (auto & cmodel : constraint_models) + { + cmodel.compliance() = R.segment(constraint_index, cmodel.size()); + constraint_index += cmodel.size(); + } + + ProximalSettings prox_settings(1e-12, 1e-12, /*mu = */ 0, 100); + + const Eigen::VectorXd x_positive = abs(Eigen::VectorXd::Random(constraint_dim)); + const Eigen::VectorXd x_in_cone = Eigen::VectorXd::Zero(constraint_dim); + + computeConeProjection(constraint_models, x_positive, x_in_cone); + + const Eigen::VectorXd constraint_velocity_ref = -(R.asDiagonal() * x_in_cone).eval(); + const Eigen::VectorXd sigma_ref = (constraint_velocity_ref + R.asDiagonal() * x_in_cone); + BOOST_CHECK(sigma_ref.isZero()); + + Eigen::VectorXd x_sol = Eigen::VectorXd::Zero(constraint_dim); + + bool has_converged = computeInverseDynamicsConstraintForces( + constraint_models, constraint_velocity_ref, x_sol, prox_settings, /*solve_ncp = */ false); + BOOST_CHECK(has_converged); + + Eigen::VectorXd sigma = constraint_velocity_ref + R.asDiagonal() * x_sol; + + Eigen::VectorXd sigma_correction(sigma); + computeDeSaxeCorrection(constraint_models, sigma, sigma_correction); + sigma += sigma_correction; + + BOOST_CHECK(sigma.isZero(1e-8)); + Eigen::VectorXd sigma_projected(sigma); + computeDualConeProjection(constraint_models, sigma, sigma_projected); + BOOST_CHECK((sigma_projected - sigma).lpNorm() <= 1e-10); + } + + // test with mu_prox > 0 + for (int n = 0; n < num_tests; ++n) + { + const Eigen::VectorXd R_zero = Eigen::VectorXd::Zero(constraint_dim); + for (auto & cmodel : constraint_models) + { + cmodel.compliance().setZero(); + } + + ProximalSettings prox_settings(1e-12, 1e-12, mu_prox, 200); + + const Eigen::VectorXd constraint_velocity = Eigen::VectorXd::Random(constraint_dim); + Eigen::VectorXd constraint_velocity_projected(constraint_velocity); + computeDualConeProjection( + constraint_models, constraint_velocity, constraint_velocity_projected); + + Eigen::VectorXd x_sol = Eigen::VectorXd::Zero(constraint_dim); + bool has_converged = computeInverseDynamicsConstraintForces( + constraint_models, constraint_velocity_projected, x_sol, prox_settings, + /*solve_ncp = */ false); + BOOST_CHECK(has_converged); + + Eigen::VectorXd x_sol_projected(x_sol); + computeConeProjection(constraint_models, x_sol, x_sol_projected); + BOOST_CHECK((x_sol_projected - x_sol).lpNorm() <= 1e-10); + + BOOST_CHECK(std::abs(constraint_velocity_projected.dot(x_sol)) <= 1e-10); + } +} + +BOOST_AUTO_TEST_CASE(test_contact_whole_body_inverse_dynamics_3D) +{ } BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/contact-models.cpp b/unittest/contact-models.cpp index 2244d9333b..c3f8711686 100644 --- a/unittest/contact-models.cpp +++ b/unittest/contact-models.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2019-2021 INRIA +// Copyright (c) 2019-2024 INRIA // #include "pinocchio/algorithm/aba.hpp" @@ -88,26 +88,48 @@ void check_A1_and_A2( const RigidConstraintModel & cmodel, RigidConstraintData & cdata) { - const RigidConstraintModel::Matrix36 A1 = cmodel.getA1(cdata); - const RigidConstraintModel::Matrix36 A1_ref = cdata.oMc1.toActionMatrixInverse().topRows<3>(); + const RigidConstraintModel::Matrix36 A1_world = cmodel.getA1(cdata, WorldFrameTag()); + const RigidConstraintModel::Matrix36 A1_world_ref = + cdata.oMc1.toActionMatrixInverse().topRows<3>(); - BOOST_CHECK(A1.isApprox(A1_ref)); + BOOST_CHECK(A1_world.isApprox(A1_world_ref)); - const RigidConstraintModel::Matrix36 A2 = cmodel.getA2(cdata); - const RigidConstraintModel::Matrix36 A2_ref = + const RigidConstraintModel::Matrix36 A2_world = cmodel.getA2(cdata, WorldFrameTag()); + const RigidConstraintModel::Matrix36 A2_world_ref = -cdata.c1Mc2.rotation() * cdata.oMc2.toActionMatrixInverse().topRows<3>(); - BOOST_CHECK(A2.isApprox(A2_ref)); + BOOST_CHECK(A2_world.isApprox(A2_world_ref)); - // Check Jacobian + const RigidConstraintModel::Matrix36 A1_local = cmodel.getA1(cdata, LocalFrameTag()); + const RigidConstraintModel::Matrix36 A1_local_ref = + cmodel.joint1_placement.toActionMatrixInverse().topRows<3>(); + + BOOST_CHECK(A1_local.isApprox(A1_local_ref)); + + const RigidConstraintModel::Matrix36 A2_local = cmodel.getA2(cdata, LocalFrameTag()); + const RigidConstraintModel::Matrix36 A2_local_ref = + -cdata.c1Mc2.rotation() * cmodel.joint2_placement.toActionMatrixInverse().topRows<3>(); + + BOOST_CHECK(A2_local.isApprox(A2_local_ref)); + + // Check Jacobians Data::MatrixXs J_ref(3, model.nv); J_ref.setZero(); getConstraintJacobian(model, data, cmodel, cdata, J_ref); - const Data::Matrix6x J1 = getJointJacobian(model, data, cmodel.joint1_id, WORLD); - const Data::Matrix6x J2 = getJointJacobian(model, data, cmodel.joint2_id, WORLD); - const Data::Matrix3x J = A1 * J1 + A2 * J2; - BOOST_CHECK(J.isApprox(J_ref)); + // World + const Data::Matrix6x J1_world = getJointJacobian(model, data, cmodel.joint1_id, WORLD); + const Data::Matrix6x J2_world = getJointJacobian(model, data, cmodel.joint2_id, WORLD); + const Data::Matrix3x J_world = A1_world * J1_world + A2_world * J2_world; + + BOOST_CHECK(J_world.isApprox(J_ref)); + + // Local + const Data::Matrix6x J1_local = getJointJacobian(model, data, cmodel.joint1_id, LOCAL); + const Data::Matrix6x J2_local = getJointJacobian(model, data, cmodel.joint2_id, LOCAL); + const Data::Matrix3x J_local = A1_local * J1_local + A2_local * J2_local; + + BOOST_CHECK(J_local.isApprox(J_ref)); // Check Jacobian matrix product const Eigen::DenseIndex m = 40; @@ -122,6 +144,50 @@ void check_A1_and_A2( BOOST_CHECK(res.isApprox(res_ref)); } +BOOST_AUTO_TEST_CASE(constraint3D_basic_operations) +{ + const pinocchio::Model model; + const pinocchio::Data data(model); + RigidConstraintModel cm(CONTACT_3D, model, 0, SE3::Random(), LOCAL); + RigidConstraintData cd(cm); + cm.calc(model, data, cd); + + const pinocchio::SE3 placement = cm.joint1_placement; + + { + const Eigen::Vector3d diagonal_inertia(1, 2, 3); + + const pinocchio::SE3::Matrix6 spatial_inertia = + cm.computeConstraintSpatialInertia(placement, diagonal_inertia); + BOOST_CHECK(spatial_inertia.transpose().isApprox(spatial_inertia)); // check symmetric matrix + + const auto A1 = cm.getA1(cd, LocalFrameTag()); + const pinocchio::SE3::Matrix6 spatial_inertia_ref = + A1.transpose() * diagonal_inertia.asDiagonal() * A1; + + BOOST_CHECK(spatial_inertia.isApprox(spatial_inertia_ref)); + } + + // Scalar + { + const double constant_value = 10; + const Eigen::Vector3d diagonal_inertia = Eigen::Vector3d::Constant(constant_value); + + const pinocchio::SE3::Matrix6 spatial_inertia = + cm.computeConstraintSpatialInertia(placement, diagonal_inertia); + BOOST_CHECK(spatial_inertia.transpose().isApprox(spatial_inertia)); // check symmetric matrix + + const auto A1 = cm.getA1(cd, LocalFrameTag()); + const pinocchio::SE3::Matrix6 spatial_inertia_ref = + A1.transpose() * diagonal_inertia.asDiagonal() * A1; + + BOOST_CHECK(spatial_inertia.isApprox(spatial_inertia_ref)); + + const Inertia spatial_inertia_ref2(constant_value, placement.translation(), Symmetric3::Zero()); + BOOST_CHECK(spatial_inertia.isApprox(spatial_inertia_ref2.matrix())); + } +} + BOOST_AUTO_TEST_CASE(contact_models_sparsity_and_jacobians) { @@ -174,7 +240,8 @@ BOOST_AUTO_TEST_CASE(contact_models_sparsity_and_jacobians) for (DenseIndex k = 0; k < model.nv; ++k) { - BOOST_CHECK(J_clm_LOCAL.col(k).isZero() != within(k, clm_RF_LF_LOCAL.colwise_span_indexes)); + if (!within(k, clm_RF_LF_LOCAL.colwise_span_indexes)) + BOOST_CHECK(J_clm_LOCAL.col(k).isZero()); } // Check Jacobian @@ -246,7 +313,8 @@ BOOST_AUTO_TEST_CASE(contact_models_sparsity_and_jacobians) for (DenseIndex k = 0; k < model.nv; ++k) { - BOOST_CHECK(J_clm_LWA.col(k).isZero() != within(k, clm_RF_LF_LWA.colwise_span_indexes)); + if (!within(k, clm_RF_LF_LWA.colwise_span_indexes)) + BOOST_CHECK(J_clm_LWA.col(k).isZero()); } // Check Jacobian diff --git a/unittest/coulomb-friction-cone.cpp b/unittest/coulomb-friction-cone.cpp index 45c55e672d..daef9c52f1 100644 --- a/unittest/coulomb-friction-cone.cpp +++ b/unittest/coulomb-friction-cone.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2022 INRIA +// Copyright (c) 2022-2024 INRIA // #include @@ -12,6 +12,12 @@ using namespace pinocchio; BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) +Eigen::Vector3d positiveRandomScaling() +{ + const Eigen::Vector2d random_vec = Eigen::abs(Eigen::Vector2d::Random().array()); + return Eigen::Vector3d(random_vec[0], random_vec[0], random_vec[1]); +} + BOOST_AUTO_TEST_CASE(test_proj) { const int num_tests = int(1e5); @@ -72,4 +78,50 @@ BOOST_AUTO_TEST_CASE(test_proj) } } +BOOST_AUTO_TEST_CASE(test_weighted_projection) +{ + const int num_tests = int(1e4); + const double mu = 1; + + const CoulombFrictionCone cone(mu); + + // Test with idendity scaling + { + const auto Ones4d = Eigen::Vector3d::Ones(); + for (int k = 0; k < num_tests; ++k) + { + const Eigen::Vector3d x = Eigen::Vector3d::Random(); + const Eigen::Vector3d proj_x = cone.weightedProject(x, Ones4d); + const Eigen::Vector3d proj_x_ref = cone.project(x); + + BOOST_CHECK(proj_x.isApprox(proj_x_ref)); + } + } + + // Test with any positive scaling + { + for (int k = 0; k < num_tests; ++k) + { + const Eigen::Vector3d scaling = positiveRandomScaling() + Eigen::Vector3d::Constant(1e-8); + BOOST_CHECK((scaling.array() > 0).all()); + + const Eigen::Vector3d scaling_sqrt = Eigen::sqrt(scaling.array()); + const Eigen::Vector3d scaling_sqrt_inv = Eigen::inverse(scaling_sqrt.array()); + + const Eigen::Vector3d x = Eigen::Vector3d::Random(); + const Eigen::Vector3d proj_x = cone.weightedProject(x, scaling); + + const double mu_scale = math::sqrt(scaling[0] / scaling[2]) * mu; + const CoulombFrictionCone cone_scale(mu_scale); + const Eigen::Vector3d x_scale = scaling_sqrt.asDiagonal() * x; + const Eigen::Vector3d proj_x_ref_scale = cone_scale.project(x_scale); + const Eigen::Vector3d proj_x_ref = scaling_sqrt_inv.array() * proj_x_ref_scale.array(); + + // std::cout << "proj_x: " << proj_x.transpose() << std::endl; + // std::cout << "proj_x_ref: " << proj_x_ref.transpose() << std::endl; + BOOST_CHECK(proj_x.isApprox(proj_x_ref)); + } + } +} + BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/cppad/joints.cpp b/unittest/cppad/joints.cpp index 28f53678db..fd302cae64 100644 --- a/unittest/cppad/joints.cpp +++ b/unittest/cppad/joints.cpp @@ -134,17 +134,6 @@ struct TestADOnJoints test(jmodel); } - template - void operator()(const pinocchio::JointModelHelicalUnalignedTpl &) const - { - typedef pinocchio::JointModelHelicalUnalignedTpl JointModel; - typedef typename JointModel::Vector3 Vector3; - JointModel jmodel(Vector3::Random().normalized()); - jmodel.setIndexes(0, 0, 0); - - test(jmodel); - } - template void operator()(const pinocchio::JointModelRevoluteUnalignedTpl &) const { diff --git a/unittest/data.cpp b/unittest/data.cpp index f3c5c343b9..6bfb7b18a9 100644 --- a/unittest/data.cpp +++ b/unittest/data.cpp @@ -82,7 +82,7 @@ BOOST_AUTO_TEST_CASE(test_data_mimic_idx_vExtended_to_idx_v_fromRow) Data data_mimic(model_mimic); Data data_full(model_full); - for (size_t joint_id = 1; joint_id < model_mimic.njoints; joint_id++) + for (JointIndex joint_id = 1; joint_id < JointIndex(model_mimic.njoints); joint_id++) { const int idx_vj = model_mimic.joints[joint_id].idx_v(); const int idx_vExtended_j = model_mimic.joints[joint_id].idx_vExtended(); @@ -108,20 +108,21 @@ BOOST_AUTO_TEST_CASE(test_data_mimic_mimic_parents_fromRow) Data data_mimic(model_mimic); - for (size_t joint_id = 1; joint_id < model_mimic.njoints; joint_id++) + for (JointIndex joint_id = 1; joint_id < JointIndex(model_mimic.njoints); joint_id++) { const int idx_vExtended_j = model_mimic.joints[joint_id].idx_vExtended(); const int nvExtended_j = model_mimic.joints[joint_id].nvExtended(); // If the parent from row is not the universe, it should be either mimic or non mimic - not // both - const bool parent_is_universe = (data_mimic.parents_fromRow[idx_vExtended_j] == -1); + const bool parent_is_universe = + (data_mimic.parents_fromRow[JointIndex(idx_vExtended_j)] == -1); const bool parent_is_mimic = - (data_mimic.mimic_parents_fromRow[idx_vExtended_j] - == data_mimic.parents_fromRow[idx_vExtended_j]); + (data_mimic.mimic_parents_fromRow[JointIndex(idx_vExtended_j)] + == data_mimic.parents_fromRow[JointIndex(idx_vExtended_j)]); const bool parent_is_not_mimic = - (data_mimic.non_mimic_parents_fromRow[idx_vExtended_j] - == data_mimic.parents_fromRow[idx_vExtended_j]); + (data_mimic.non_mimic_parents_fromRow[JointIndex(idx_vExtended_j)] + == data_mimic.parents_fromRow[JointIndex(idx_vExtended_j)]); BOOST_CHECK(parent_is_universe || (parent_is_mimic != parent_is_not_mimic)); for (int v = 1; v < nvExtended_j; v++) diff --git a/unittest/delassus-operator-dense.cpp b/unittest/delassus-operator-dense.cpp new file mode 100644 index 0000000000..9eb507e11c --- /dev/null +++ b/unittest/delassus-operator-dense.cpp @@ -0,0 +1,194 @@ +// +// Copyright (c) 2024 INRIA +// + +#define PINOCCHIO_EIGEN_CHECK_MALLOC + +#include + +#include // to avoid C99 warnings + +#include +#include + +#include +#include +#include +#include +#include +#include + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +using namespace pinocchio; + +BOOST_AUTO_TEST_CASE(test_memory_allocation) +{ + const Eigen::DenseIndex mat_size = 100; + const Eigen::MatrixXd mat_ = Eigen::MatrixXd::Random(mat_size, mat_size); + const Eigen::MatrixXd symmetric_mat = mat_.transpose() * mat_; + + BOOST_CHECK(isSymmetric(symmetric_mat)); + + DelassusOperatorDense delassus(symmetric_mat); + + Eigen::VectorXd res(mat_size); + const Eigen::VectorXd rhs = Eigen::VectorXd::Random(mat_size); + res = delassus * rhs; + BOOST_CHECK(res.isApprox((symmetric_mat * rhs).eval())); + + PowerIterationAlgoTpl power_iteration(mat_size); + + // Check memory allocations + Eigen::internal::set_is_malloc_allowed(false); + res = delassus * rhs; + (delassus * rhs).evalTo(res); + res.noalias() = symmetric_mat * rhs; + res.noalias() = delassus * rhs; + evalTo(symmetric_mat * rhs, res); + power_iteration.run(delassus); + power_iteration.run(symmetric_mat); + Eigen::internal::set_is_malloc_allowed(true); +} + +BOOST_AUTO_TEST_CASE(test_cholesky_expression_to_dense) +{ + // create model + Model model; + buildModels::manipulator(model); + model.lowerPositionLimit.setConstant(-1.0); + model.upperPositionLimit.setConstant(1.0); + model.lowerDryFrictionLimit.setConstant(-1.0); + model.upperDryFrictionLimit.setConstant(1.0); + Data data(model); + + // setup data + Eigen::VectorXd q0 = ::pinocchio::neutral(model); + Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + Eigen::VectorXd tau = Eigen::VectorXd::Zero(model.nv); + data.q_in = q0; + aba(model, data, q0, v0, tau, Convention::WORLD); + crba(model, data, q0, Convention::WORLD); + + // create constraints + std::vector constraint_models; + std::vector constraint_datas; + + FrictionalJointConstraintModel::JointIndexVector active_friction_idxs; + FrictionalJointConstraintModel::JointIndexVector active_limit_idxs; + for (size_t i = 1; i < model.joints.size(); ++i) + { + const Model::JointModel & joint = model.joints[i]; + active_friction_idxs.push_back(joint.id()); + active_limit_idxs.push_back(joint.id()); + } + FrictionalJointConstraintModel joints_friction(model, active_friction_idxs); + constraint_models.push_back(joints_friction); + constraint_datas.push_back(joints_friction.createData()); + // + JointLimitConstraintModel joints_limit(model, active_limit_idxs); + constraint_models.push_back(joints_limit); + constraint_datas.push_back(joints_limit.createData()); + + for (size_t i = 0; i < constraint_models.size(); ++i) + { + const ConstraintModel & cmodel = constraint_models[i]; + ConstraintData & cdata = constraint_datas[i]; + cmodel.calc(model, data, cdata); + } + + // compute delassus + ContactCholeskyDecomposition chol(model, constraint_models); + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + + // check dense method + DelassusOperatorDense delassus_operator_dense = chol.getDelassusCholeskyExpression().dense(); + Eigen::MatrixXd true_delassus_dense = chol.getDelassusCholeskyExpression().matrix(); + Eigen::VectorXd true_compliance = chol.getDelassusCholeskyExpression().getCompliance(); + Eigen::VectorXd true_damping = chol.getDelassusCholeskyExpression().getDamping(); + true_delassus_dense -= true_damping.asDiagonal(); + true_delassus_dense -= true_compliance.asDiagonal(); + DelassusOperatorDense true_delassus_operator_dense(true_delassus_dense); + true_delassus_operator_dense.updateCompliance(true_compliance); + true_delassus_operator_dense.updateDamping(true_damping); + + BOOST_CHECK(delassus_operator_dense == true_delassus_operator_dense); + + // check dense constructor from expression + DelassusOperatorDense delassus_operator_dense2(chol.getDelassusCholeskyExpression()); + + BOOST_CHECK(delassus_operator_dense2 == true_delassus_operator_dense); +} + +BOOST_AUTO_TEST_CASE(delassus_dense_compliant) +{ + const Eigen::DenseIndex mat_size = 50; + const Eigen::MatrixXd mat = Eigen::MatrixXd::Random(mat_size, mat_size); + const Eigen::MatrixXd symmetric_mat = mat.transpose() * mat; + const Eigen::VectorXd compliance = 1e-1 * Eigen::VectorXd::Ones(mat_size); + const Eigen::MatrixXd compliance_matrix = compliance.asDiagonal(); + const Eigen::MatrixXd compliant_matrix = symmetric_mat + compliance_matrix; + + BOOST_CHECK(isSymmetric(symmetric_mat)); + BOOST_CHECK(isSymmetric(compliant_matrix)); + + DelassusOperatorDense delassus(symmetric_mat); + delassus.updateCompliance(compliance); + BOOST_CHECK(delassus.getCompliance().isApprox(compliance)); + + Eigen::VectorXd res(mat_size); + const Eigen::VectorXd rhs = Eigen::VectorXd::Random(mat_size); + + // Checking matrix() method + BOOST_CHECK(compliant_matrix.isApprox(delassus.matrix())); + + // Checking apply on the right + delassus.applyOnTheRight(rhs, res); + BOOST_CHECK(res.isApprox((compliant_matrix * rhs).eval())); + + // Checking solved + Eigen::VectorXd damping_vec = 5e-3 * Eigen::VectorXd::Ones(mat_size); + Eigen::MatrixXd damping = damping_vec.asDiagonal(); + delassus.updateDamping(damping_vec); + BOOST_CHECK(delassus.getDamping().isApprox(damping_vec)); + delassus.solve(rhs, res); + const Eigen::MatrixXd compliant_matrix_inv = (compliant_matrix + damping).inverse(); + Eigen::VectorXd res_solve = compliant_matrix_inv * rhs; + BOOST_CHECK(res.isApprox(res_solve)); + + // Checking undampedMatrix() method + BOOST_CHECK(compliant_matrix.isApprox(delassus.undampedMatrix())); + + // Checking solveInPlace + delassus.solveInPlace(rhs); + BOOST_CHECK(rhs.isApprox(res_solve)); + + // Checking updateDamping + const double new_damping = 1e-3; + const Eigen::MatrixXd damped_compliant_matrix = + compliant_matrix + new_damping * Eigen::MatrixXd::Identity(mat_size, mat_size); + delassus.updateDamping(new_damping); + BOOST_CHECK(delassus.getDamping().isApprox(Eigen::VectorXd::Constant(mat_size, new_damping))); + delassus.applyOnTheRight(rhs, res); + Eigen::VectorXd res_apply = damped_compliant_matrix * rhs; + BOOST_CHECK(res.isApprox(res_apply)); + + // Checking updateCompliance + const double new_compliance = 4e-3; + const Eigen::MatrixXd new_compliance_matrix = + Eigen::VectorXd::Constant(mat_size, new_compliance).asDiagonal(); + const Eigen::MatrixXd new_compliant_matrix = symmetric_mat + new_compliance_matrix; + delassus.updateCompliance(new_compliance); + BOOST_CHECK( + delassus.getCompliance().isApprox(Eigen::VectorXd::Constant(mat_size, new_compliance))); + const Eigen::MatrixXd new_damped_compliant_matrix = + new_compliant_matrix + new_damping * Eigen::MatrixXd::Identity(mat_size, mat_size); + delassus.updateDamping(new_damping); + BOOST_CHECK(delassus.getDamping().isApprox(Eigen::VectorXd::Constant(mat_size, new_damping))); + delassus.applyOnTheRight(rhs, res); + Eigen::VectorXd new_res_apply = new_damped_compliant_matrix * rhs; + BOOST_CHECK(new_damped_compliant_matrix.isApprox(delassus.matrix())); + BOOST_CHECK(res.isApprox(new_res_apply)); +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/delassus-operator-preconditioned.cpp b/unittest/delassus-operator-preconditioned.cpp new file mode 100644 index 0000000000..a6dd0b7921 --- /dev/null +++ b/unittest/delassus-operator-preconditioned.cpp @@ -0,0 +1,90 @@ +#define PINOCCHIO_EIGEN_CHECK_MALLOC +#include + +#include // to avoid C99 warnings + +#include +#include + +#include +#include +#include "pinocchio/algorithm/diagonal-preconditioner.hpp" +#include + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +using namespace pinocchio; + +BOOST_AUTO_TEST_CASE(delassus_dense_preconditioned) +{ + const Eigen::DenseIndex mat_size = 3; + const Eigen::MatrixXd mat = Eigen::MatrixXd::Random(mat_size, mat_size); + const Eigen::MatrixXd symmetric_mat = mat.transpose() * mat; + const Eigen::VectorXd diag_vec = 1e-1 * Eigen::VectorXd::Ones(mat_size); + const Eigen::MatrixXd preconditioner_matrix = diag_vec.asDiagonal(); + const Eigen::MatrixXd preconditioned_matrix = + preconditioner_matrix * symmetric_mat * preconditioner_matrix; + + BOOST_CHECK(isSymmetric(symmetric_mat)); + BOOST_CHECK(isSymmetric(preconditioned_matrix)); + + DelassusOperatorDense delassus(symmetric_mat); + DiagonalPreconditionerTpl diag_preconditioner(diag_vec); + DelassusOperatorPreconditionedTpl< + DelassusOperatorDense, DiagonalPreconditionerTpl> + delassus_preconditioned(delassus, diag_preconditioner); + + Eigen::VectorXd res(mat_size); + const Eigen::VectorXd rhs = Eigen::VectorXd::Random(mat_size); + + // Checking matrix() method + BOOST_CHECK(preconditioned_matrix.isApprox(delassus_preconditioned.matrix())); + + // Checking apply on the right + delassus_preconditioned.applyOnTheRight(rhs, res); + BOOST_CHECK(res.isApprox((preconditioned_matrix * rhs).eval())); + + // Checking solved + Eigen::VectorXd damping_vec = 5e-3 * Eigen::VectorXd::Ones(mat_size); + Eigen::MatrixXd damping = damping_vec.asDiagonal(); + delassus_preconditioned.updateDamping(damping_vec); + delassus_preconditioned.solve(rhs, res); + const Eigen::MatrixXd preconditioned_matrix_inv = (preconditioned_matrix + damping).inverse(); + Eigen::VectorXd res_solve = preconditioned_matrix_inv * rhs; + BOOST_CHECK(res.isApprox(res_solve)); + + // Checking solveInPlace + delassus_preconditioned.solveInPlace(rhs); + BOOST_CHECK(rhs.isApprox(res_solve)); + + // Checking updateDamping + double new_damping = 1e-3; + const Eigen::MatrixXd damped_preconditioned_matrix = + preconditioned_matrix + new_damping * Eigen::MatrixXd::Identity(mat_size, mat_size); + delassus_preconditioned.updateDamping(new_damping); + delassus_preconditioned.applyOnTheRight(rhs, res); + Eigen::VectorXd res_apply = damped_preconditioned_matrix * rhs; + BOOST_CHECK(res.isApprox(res_apply)); + + // Checking updateCompliance + const double new_compliance = 3e-3; + delassus.updateDamping(0.); + delassus.updateCompliance(new_compliance); + DelassusOperatorPreconditionedTpl< + DelassusOperatorDense, DiagonalPreconditionerTpl> + delassus_preconditioned2(delassus, diag_preconditioner); + const Eigen::MatrixXd preconditioned_compliant_matrix = + preconditioner_matrix + * (symmetric_mat + new_compliance * Eigen::MatrixXd::Identity(mat_size, mat_size)) + * preconditioner_matrix; + new_damping = 8e-3; + const Eigen::MatrixXd damped_preconditioned_compliant_matrix = + preconditioned_compliant_matrix + new_damping * Eigen::MatrixXd::Identity(mat_size, mat_size); + delassus_preconditioned2.updateDamping(new_damping); + BOOST_CHECK(damped_preconditioned_compliant_matrix.isApprox(delassus_preconditioned2.matrix())); + delassus_preconditioned2.applyOnTheRight(rhs, res); + Eigen::VectorXd res_apply2 = damped_preconditioned_compliant_matrix * rhs; + BOOST_CHECK(res.isApprox(res_apply2)); +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/delassus-operator-rigid-body.cpp b/unittest/delassus-operator-rigid-body.cpp new file mode 100644 index 0000000000..c97050d4ed --- /dev/null +++ b/unittest/delassus-operator-rigid-body.cpp @@ -0,0 +1,1220 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#include +#include +#include + +#include "pinocchio/context.hpp" +#include "pinocchio/algorithm/cholesky.hpp" +#include "pinocchio/algorithm/constraints/constraints.hpp" +#include "pinocchio/algorithm/contact-dynamics.hpp" +#include "pinocchio/algorithm/contact-jacobian.hpp" +#include "pinocchio/algorithm/contact-cholesky.hpp" +#include "pinocchio/algorithm/joint-configuration.hpp" + +#include "pinocchio/multibody/sample-models.hpp" +#include "pinocchio/algorithm/delassus-operator-rigid-body.hpp" +#include "pinocchio/algorithm/aba.hpp" +#include "pinocchio/algorithm/crba.hpp" +#include "pinocchio/algorithm/loop-constrained-aba.hpp" +#include "pinocchio/algorithm/constraints/utils.hpp" +#include "pinocchio/algorithm/proximal.hpp" + +#include +#include + +using namespace pinocchio; +using namespace Eigen; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(default_constructor_shared_ptr) +{ + typedef FrictionalPointConstraintModelTpl ConstraintModel; + typedef DelassusOperatorRigidBodySystemsTpl< + double, 0, JointCollectionDefaultTpl, ConstraintModel, std::shared_ptr> + DelassusOperatorRigidBodySharedPtr; + typedef typename DelassusOperatorRigidBodySharedPtr::ConstraintModelVector ConstraintModelVector; + typedef typename DelassusOperatorRigidBodySharedPtr::ConstraintDataVector ConstraintDataVector; + + std::shared_ptr model_shared_ptr = std::make_shared(); + Model * model_ptr = model_shared_ptr.get(); + Model & model = *model_ptr; + buildModels::humanoidRandom(model, true); + + std::shared_ptr data_shared_ptr = std::make_shared(model); + Data * data_ptr = data_shared_ptr.get(); + // Data & data = *data_ptr; + + std::shared_ptr constraint_models_shared_ptr = + std::make_shared(); + ConstraintModelVector * constraint_models_ptr = constraint_models_shared_ptr.get(); + std::shared_ptr constraint_datas_shared_ptr = + std::make_shared(); + ConstraintDataVector * constraint_datas_ptr = constraint_datas_shared_ptr.get(); + + DelassusOperatorRigidBodySharedPtr delassus_operator( + model_shared_ptr, data_shared_ptr, constraint_models_shared_ptr, constraint_datas_shared_ptr); + + BOOST_CHECK(delassus_operator.size() == 0); + BOOST_CHECK(&delassus_operator.model() == model_ptr); + BOOST_CHECK(&delassus_operator.data() == data_ptr); + BOOST_CHECK(&delassus_operator.constraint_models() == constraint_models_ptr); + BOOST_CHECK(&delassus_operator.constraint_datas() == constraint_datas_ptr); +} + +BOOST_AUTO_TEST_CASE(default_constructor_reference_wrapper) +{ + typedef FrictionalPointConstraintModelTpl ConstraintModel; + typedef DelassusOperatorRigidBodySystemsTpl< + double, 0, JointCollectionDefaultTpl, ConstraintModel, std::reference_wrapper> + DelassusOperatorRigidBodyReferenceWrapper; + typedef + typename DelassusOperatorRigidBodyReferenceWrapper::ConstraintModelVector ConstraintModelVector; + typedef + typename DelassusOperatorRigidBodyReferenceWrapper::ConstraintDataVector ConstraintDataVector; + + Model model; + std::reference_wrapper model_ref = model; + buildModels::humanoidRandom(model, true); + + Data data(model); + std::reference_wrapper data_ref = data; + + ConstraintModelVector constraint_models; + std::reference_wrapper constraint_models_ref = constraint_models; + ConstraintDataVector constraint_datas; + auto constraint_datas_ref = helper::make_ref(constraint_datas); + + DelassusOperatorRigidBodyReferenceWrapper delassus_operator( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref); + + BOOST_CHECK(delassus_operator.size() == 0); + BOOST_CHECK(&delassus_operator.model() == &model); + BOOST_CHECK(&delassus_operator.data() == &data); + BOOST_CHECK(&delassus_operator.constraint_models() == &constraint_models); + BOOST_CHECK(&delassus_operator.constraint_datas() == &constraint_datas); +} + +BOOST_AUTO_TEST_CASE(general_test_weld_constraint_model) +{ + typedef WeldConstraintModelTpl ConstraintModel; + typedef DelassusOperatorRigidBodySystemsTpl< + double, 0, JointCollectionDefaultTpl, ConstraintModel, std::reference_wrapper> + DelassusOperatorRigidBodyReferenceWrapper; + typedef + typename DelassusOperatorRigidBodyReferenceWrapper::ConstraintModelVector ConstraintModelVector; + typedef + typename DelassusOperatorRigidBodyReferenceWrapper::ConstraintDataVector ConstraintDataVector; + + Model model; + std::reference_wrapper model_ref = model; + buildModels::humanoidRandom(model, true); + model.gravity.setZero(); + const Eigen::VectorXd q_neutral = neutral(model); + const Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv); + const Eigen::VectorXd tau = Eigen::VectorXd::Random(model.nv); + + const std::string RF = "rleg6_joint"; + const std::string LF = "lleg6_joint"; + + Data data(model), data_gt(model), data_aba(model); + std::reference_wrapper data_ref = data; + + ConstraintModelVector constraint_models; + ConstraintDataVector constraint_datas; + const ConstraintModel cm_RF_LF_LOCAL( + model, model.getJointId(RF), SE3::Random(), model.getJointId(LF), SE3::Random()); + + constraint_models.push_back(cm_RF_LF_LOCAL); + constraint_datas.push_back(cm_RF_LF_LOCAL.createData()); + const ConstraintModel cm_LF_LOCAL(model, model.getJointId(LF), SE3::Random()); + constraint_models.push_back(cm_LF_LOCAL); + constraint_datas.push_back(cm_LF_LOCAL.createData()); + + // ConstraintDataVector constraint_datas_gt = constraint_datas; + // + std::reference_wrapper constraint_models_ref = constraint_models; + std::reference_wrapper constraint_datas_ref = constraint_datas; + + const double damping_value = 1e-4; + + const double mu_inv = damping_value; + const double mu = 1. / mu_inv; + + // Test operator * + { + DelassusOperatorRigidBodyReferenceWrapper delassus_operator( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, damping_value); + delassus_operator.updateDamping(mu_inv); + delassus_operator.updateCompliance(0); + BOOST_CHECK(delassus_operator.isDirty()); + delassus_operator.compute(q_neutral); + BOOST_CHECK(!delassus_operator.isDirty()); + + const Eigen::VectorXd rhs = Eigen::VectorXd::Random(delassus_operator.size()); + Eigen::VectorXd res(delassus_operator.size()); + + delassus_operator.applyOnTheRight(rhs, res); + + // Eval J Minv Jt + auto Minv_gt = computeMinverse(model, data_gt, q_neutral); + make_symmetric(Minv_gt); + BOOST_CHECK(Minv_gt.isApprox(Minv_gt.transpose())); + + auto M_gt = crba(model, data_gt, q_neutral, Convention::WORLD); + make_symmetric(M_gt); + + ConstraintDataVector constraint_datas_gt = createData(constraint_models); + Eigen::MatrixXd constraints_jacobian_gt(delassus_operator.size(), model.nv); + constraints_jacobian_gt.setZero(); + evalConstraints(model, data_gt, constraint_models, constraint_datas_gt); + getConstraintsJacobian( + model, data_gt, constraint_models, constraint_datas_gt, constraints_jacobian_gt); + + const Eigen::MatrixXd delassus_dense_gt_undamped = + constraints_jacobian_gt * Minv_gt * constraints_jacobian_gt.transpose(); + const Eigen::MatrixXd delassus_dense_gt = + delassus_dense_gt_undamped + Eigen::MatrixXd(delassus_operator.getDamping().asDiagonal()); + + Eigen::VectorXd tau_constraints = Eigen::VectorXd::Zero(model.nv); + evalConstraintJacobianTransposeMatrixProduct( + model, data_gt, constraint_models, constraint_datas_gt, rhs, tau_constraints); + const Eigen::VectorXd Jt_rhs_gt = constraints_jacobian_gt.transpose() * rhs; + BOOST_CHECK(tau_constraints.isApprox(Jt_rhs_gt)); + + std::vector fext_gt(size_t(model.njoints), Force::Zero()); + mapConstraintForcesToJointForces( + model, data_aba, constraint_models, constraint_datas_gt, rhs, fext_gt, LocalFrameTag()); + auto fext_gt_copy = fext_gt; + + aba( + model, data_aba, q_neutral, Eigen::VectorXd::Zero(model.nv), 0 * tau_constraints, fext_gt, + Convention::LOCAL); + + Eigen::VectorXd tau_constraints_ref = Eigen::VectorXd::Zero(model.nv); + for (JointIndex joint_id = JointIndex(model.njoints) - 1; joint_id >= 1; --joint_id) + { + const auto parent_id = model.parents[joint_id]; + const auto & jmodel = model.joints[joint_id]; + const auto & jdata = data_aba.joints[joint_id]; + const auto joint_nv = jmodel.nv(); + const auto joint_idx_v = jmodel.idx_v(); + + tau_constraints_ref.segment(joint_idx_v, joint_nv) = + jdata.S().matrix().transpose() * fext_gt_copy[joint_id].toVector(); + + fext_gt_copy[parent_id] += data_aba.liMi[joint_id].act(fext_gt_copy[joint_id]); + } + BOOST_CHECK(tau_constraints_ref.isApprox(Jt_rhs_gt)); + + for (Model::JointIndex joint_id = 1; joint_id < Model::JointIndex(model.njoints); ++joint_id) + { + BOOST_CHECK(data.joints[joint_id].S().isApprox(data_aba.joints[joint_id].S())); + BOOST_CHECK(data.joints[joint_id].U().isApprox(data_aba.joints[joint_id].U())); + BOOST_CHECK(data.joints[joint_id].Dinv().isApprox(data_aba.joints[joint_id].Dinv())); + BOOST_CHECK(data.joints[joint_id].UDinv().isApprox(data_aba.joints[joint_id].UDinv())); + BOOST_CHECK(data.liMi[joint_id].isApprox(data_aba.liMi[joint_id])); + BOOST_CHECK(data.Yaba[joint_id].isApprox(data_aba.Yaba[joint_id])); + } + BOOST_CHECK(delassus_operator.getCustomData().u.isApprox(data_aba.u)); + + const Eigen::VectorXd Minv_Jt_rhs_gt = Minv_gt * Jt_rhs_gt; + BOOST_CHECK(delassus_operator.getCustomData().ddq.isApprox(Minv_Jt_rhs_gt)); + + const auto res_gt = (delassus_dense_gt * rhs).eval(); + BOOST_CHECK(res.isApprox(res_gt)); + + // Multiple call and operator * + { + for (int i = 0; i < 100; ++i) + { + Eigen::VectorXd res(delassus_operator.size()); + delassus_operator.applyOnTheRight(rhs, res); + BOOST_CHECK(res.isApprox(res_gt)); + + const Eigen::VectorXd res2 = delassus_operator * rhs; + BOOST_CHECK(res2 == res); // Should be exactly the same + BOOST_CHECK(res2.isApprox(res_gt)); + } + } + } // End: Test operator * + + // Test second call consistency + { + // Data data(model); + // std::reference_wrapper data_ref = data; + DelassusOperatorRigidBodyReferenceWrapper delassus_operator( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, damping_value); + delassus_operator.updateDamping(mu_inv); + delassus_operator.updateCompliance(0); + delassus_operator.compute(q_neutral); + + Data data2(model); + std::reference_wrapper data2_ref = data2; + + ConstraintDataVector constraint_datas2 = createData(constraint_models_ref.get()); + std::reference_wrapper constraint_datas2_ref = constraint_datas2; + + DelassusOperatorRigidBodyReferenceWrapper delassus_operator2( + model_ref, data2_ref, constraint_models_ref, constraint_datas2_ref, damping_value); + delassus_operator2.updateDamping(mu_inv); + delassus_operator2.updateCompliance(0); + delassus_operator2.compute(q_neutral); + + // Check consistency between a fresh and dirty data + { + BOOST_CHECK(!delassus_operator.isDirty()); + BOOST_CHECK(!delassus_operator2.isDirty()); + BOOST_CHECK(delassus_operator.getDamping() == delassus_operator2.getDamping()); + BOOST_CHECK(delassus_operator.getCompliance() == delassus_operator2.getCompliance()); + + BOOST_CHECK(data.oMi == data2.oMi); + BOOST_CHECK(data.liMi == data2.liMi); + BOOST_CHECK(data.J == data2.J); + BOOST_CHECK(data.Yaba == data2.Yaba); + BOOST_CHECK(data.elimination_order == data2.elimination_order); + BOOST_CHECK(data.constraints_supported_dim == data2.constraints_supported_dim); + BOOST_CHECK(data.neighbour_links == data2.neighbour_links); + BOOST_CHECK((data.joint_cross_coupling.keys() == data2.joint_cross_coupling.keys()).all()); + + for (JointIndex joint_id = 1; joint_id < JointIndex(model.njoints); ++joint_id) + { + BOOST_CHECK(data.joints[joint_id].S() == data2.joints[joint_id].S()); + BOOST_CHECK(data.joints[joint_id].U() == data2.joints[joint_id].U()); + BOOST_CHECK(data.joints[joint_id].Dinv() == data2.joints[joint_id].Dinv()); + BOOST_CHECK(data.joints[joint_id].UDinv() == data2.joints[joint_id].UDinv()); + + BOOST_CHECK(data.joints_augmented[joint_id].S() == data2.joints_augmented[joint_id].S()); + BOOST_CHECK(data.joints_augmented[joint_id].U() == data2.joints_augmented[joint_id].U()); + BOOST_CHECK( + data.joints_augmented[joint_id].Dinv() == data2.joints_augmented[joint_id].Dinv()); + BOOST_CHECK( + data.joints_augmented[joint_id].UDinv() == data2.joints_augmented[joint_id].UDinv()); + + BOOST_CHECK(data.oYaba_augmented[joint_id] == data2.oYaba_augmented[joint_id]); + } + } + } + + // Test solveInPlace + { + // Data data(model); + // std::reference_wrapper data_ref = data; + DelassusOperatorRigidBodyReferenceWrapper delassus_operator( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, damping_value); + delassus_operator.updateDamping(mu_inv); + delassus_operator.updateCompliance(0); + delassus_operator.compute(q_neutral); + + Data data_crba(model); + Eigen::MatrixXd M = crba(model, data_crba, q_neutral, Convention::WORLD); + make_symmetric(M); + + auto constraint_datas_crba = createData(constraint_models); + const auto Jc = + getConstraintsJacobian(model, data_crba, constraint_models, constraint_datas_crba); + + const Eigen::MatrixXd M_augmented = M + mu * Jc.transpose() * Jc; + const Eigen::MatrixXd M_augmented_inv = M_augmented.inverse(); + + const Eigen::VectorXd rhs = Eigen::VectorXd::Unit(model.nv, 0); + Eigen::VectorXd res = rhs; + + const Eigen::VectorXd col_ref = M_augmented_inv * rhs; + delassus_operator.getAugmentedMassMatrixOperator().solveInPlace(res); + BOOST_CHECK(res.isApprox(col_ref, 1e-10)); + + for (Eigen::DenseIndex col_id = 0; col_id < model.nv; ++col_id) + { + const Eigen::VectorXd rhs = Eigen::VectorXd::Unit(model.nv, col_id); + const auto res_ref = (M_augmented_inv * rhs).eval(); + + Eigen::VectorXd res = rhs; + delassus_operator.getAugmentedMassMatrixOperator().solveInPlace(res); + BOOST_CHECK(res.isApprox(res_ref, 1e-10)); + } + + // Test Delassus inverse + const auto delassus_size = delassus_operator.size(); + const Eigen::MatrixXd M_inv = M.inverse(); + const Eigen::MatrixXd delassus_dense = + Jc * M_inv * Jc.transpose() + + mu_inv * Eigen::MatrixXd::Identity(delassus_size, delassus_size); + const Eigen::MatrixXd delassus_dense_inv = delassus_dense.inverse(); + + for (Eigen::DenseIndex col_id = 0; col_id < delassus_size; ++col_id) + { + const Eigen::VectorXd rhs = Eigen::VectorXd::Unit(delassus_size, col_id); + const auto res_ref = (delassus_dense_inv * rhs).eval(); + + Eigen::VectorXd res = rhs; + delassus_operator.solveInPlace(res); + BOOST_CHECK(res.isApprox(res_ref, 1e-10)); + } + } + + // Test updateDamping + { + Data data(model); + std::reference_wrapper data_ref = data; + + auto constraint_datas = createData(constraint_models); + std::reference_wrapper constraint_datas_ref = constraint_datas; + + DelassusOperatorRigidBodyReferenceWrapper delassus_operator( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, damping_value); + delassus_operator.compute(q_neutral); + + Data data2(model); + std::reference_wrapper data2_ref = data2; + auto constraint_datas2 = createData(constraint_models); + std::reference_wrapper constraint_datas2_ref = constraint_datas2; + + const double new_damping_value = 1e-6; + // const double new_mu = 1. / new_damping_value; + DelassusOperatorRigidBodyReferenceWrapper delassus_operator2( + model_ref, data2_ref, constraint_models_ref, constraint_datas2_ref, new_damping_value); + BOOST_CHECK(delassus_operator2.isDirty()); + delassus_operator2.compute(q_neutral); + BOOST_CHECK(!delassus_operator2.isDirty()); + + BOOST_CHECK(!delassus_operator.isDirty()); + delassus_operator.updateDamping(new_damping_value); + BOOST_CHECK(delassus_operator.isDirty()); + delassus_operator.compute(true); + BOOST_CHECK(!delassus_operator.isDirty()); + + BOOST_CHECK(delassus_operator.getDamping() == delassus_operator2.getDamping()); + BOOST_CHECK(delassus_operator.getCompliance() == delassus_operator2.getCompliance()); + + BOOST_CHECK(data.J == data2.J); + BOOST_CHECK(data.elimination_order == data2.elimination_order); + for (JointIndex joint_id = 1; joint_id < JointIndex(model.njoints); ++joint_id) + { + BOOST_CHECK(data.oMi[joint_id] == data2.oMi[joint_id]); + BOOST_CHECK(data.liMi[joint_id] == data2.liMi[joint_id]); + + BOOST_CHECK(data.Yaba[joint_id] == data2.Yaba[joint_id]); + BOOST_CHECK(data.joints[joint_id].StU() == data2.joints[joint_id].StU()); + BOOST_CHECK(data.joints[joint_id].Dinv() == data2.joints[joint_id].Dinv()); + BOOST_CHECK(data.joints[joint_id].UDinv() == data2.joints[joint_id].UDinv()); + + BOOST_CHECK(data.oYaba_augmented[joint_id] == data2.oYaba_augmented[joint_id]); + BOOST_CHECK(data.joints_augmented[joint_id].StU() == data2.joints_augmented[joint_id].StU()); + BOOST_CHECK( + data.joints_augmented[joint_id].Dinv() == data2.joints_augmented[joint_id].Dinv()); + BOOST_CHECK( + data.joints_augmented[joint_id].UDinv() == data2.joints_augmented[joint_id].UDinv()); + } + + Data data_crba(model); + Eigen::MatrixXd M = crba(model, data_crba, q_neutral, Convention::WORLD); + make_symmetric(M); + + auto constraint_datas_crba = createData(constraint_models); + const auto Jc = + getConstraintsJacobian(model, data_crba, constraint_models, constraint_datas_crba); + + const auto delassus_size = delassus_operator.size(); + const Eigen::MatrixXd M_inv = M.inverse(); + const Eigen::MatrixXd delassus_dense = + Jc * M_inv * Jc.transpose() + + new_damping_value * Eigen::MatrixXd::Identity(delassus_size, delassus_size); + const Eigen::MatrixXd delassus_dense_inv = delassus_dense.inverse(); + + for (Eigen::DenseIndex col_id = 0; col_id < delassus_size; ++col_id) + { + const Eigen::VectorXd rhs = Eigen::VectorXd::Unit(delassus_size, col_id); + const auto res_ref = (delassus_dense_inv * rhs).eval(); + + Eigen::VectorXd res = rhs; + delassus_operator.solveInPlace(res); + BOOST_CHECK(res.isApprox(res_ref, 1e-8)); + + Eigen::VectorXd res2 = rhs; + delassus_operator2.solveInPlace(res2); + BOOST_CHECK(res2.isApprox(res_ref, 1e-8)); + + BOOST_CHECK(res.isApprox(res2)); + } + } + + // Compare with lcaba + // { + // Data data_lcaba(model); + // RigidConstraintModel rcm( + // CONTACT_6D, model, cm_RF_LOCAL.joint1_id, cm_RF_LOCAL.joint1_placement, + // cm_RF_LOCAL.joint2_id, cm_RF_LOCAL.joint2_placement, + // // cm_RF_LOCAL.joint2_id, cm_RF_LOCAL.joint2_placement, + // // cm_RF_LOCAL.joint1_id, cm_RF_LOCAL.joint1_placement, + // LOCAL); + // + // std::vector rcm_vector; + // rcm_vector.push_back(rcm); + // std::vector rcd_vector; + // rcd_vector.push_back(rcm.createData()); + // + // const auto & rcd = rcd_vector[0]; + // + // computeJointMinimalOrdering(model, data_lcaba, rcm_vector); + // ProximalSettings prox_settings(1e-14, min_damping_value, 1); + // lcaba(model, data_lcaba, q_neutral, v, tau, rcm_vector, rcd_vector, prox_settings); + // + // BOOST_CHECK(data_lcaba.elimination_order == data.elimination_order); + // + // + // + // + // // for(JointIndex joint_id = 1; joint_id < JointIndex(model.njoints); ++joint_id) + // // { + // // BOOST_CHECK(data.oMi[joint_id].isApprox(data_lcaba.oMi[joint_id])); + // // BOOST_CHECK(data.liMi[joint_id].isApprox(data_lcaba.liMi[joint_id])); + // // std::cout << "oYaba_aug[" << joint_id << "]:\n" << data.oYaba_augmented[joint_id] << + // // std::endl; std::cout << "oYaba_aug_lcaba[" << joint_id << "]:\n" << + // // data_lcaba.oYaba_augmented[joint_id] << std::endl; + // // } + // // std::cout << "elimination ordering: "; + // // for(const auto val: data_lcaba.elimination_order) + // // std::cout << val << ", "; + // std::cout << std::endl; + // std::cout << "---------" << std::endl; + // + // std::cout << "---------" << std::endl; + // + // std::cout << "oYaba_aug[" << joint1_id << "]:\n" + // << data.oYaba_augmented[joint1_id] << std::endl; + // std::cout << "oYaba_aug_lcaba[" << joint1_id << "]:\n" + // << data_lcaba.oYaba_augmented[joint1_id] << std::endl; + // + // std::cout << "---------" << std::endl; + // + // std::cout << "oYaba_aug[" << joint2_id << "]:\n" + // << data.oYaba_augmented[joint2_id] << std::endl; + // std::cout << "oYaba_aug_lcaba[" << joint2_id << "]:\n" + // << data_lcaba.oYaba_augmented[joint2_id] << std::endl; + // } +} + +BOOST_AUTO_TEST_CASE(general_test_frictional_point_constraint_model) +{ + typedef FrictionalPointConstraintModelTpl ConstraintModel; + typedef DelassusOperatorRigidBodySystemsTpl< + double, 0, JointCollectionDefaultTpl, ConstraintModel, std::reference_wrapper> + DelassusOperatorRigidBodyReferenceWrapper; + typedef + typename DelassusOperatorRigidBodyReferenceWrapper::ConstraintModelVector ConstraintModelVector; + typedef + typename DelassusOperatorRigidBodyReferenceWrapper::ConstraintDataVector ConstraintDataVector; + + Model model; + std::reference_wrapper model_ref = model; + buildModels::humanoidRandom(model, true); + model.gravity.setZero(); + const Eigen::VectorXd q_neutral = neutral(model); + const Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv); + const Eigen::VectorXd tau = Eigen::VectorXd::Random(model.nv); + + const std::string RF = "rleg6_joint"; + const std::string LF = "lleg6_joint"; + + Data data(model), data_gt(model), data_aba(model); + std::reference_wrapper data_ref = data; + // const ConstraintModel cm_RF_LOCAL(model, model.getJointId(RF), SE3::Random()); + // const ConstraintModel cm_RF_LOCAL(model, 0, SE3::Identity(), model.getJointId(RF), + // SE3::Random()); + + ConstraintModelVector constraint_models; + ConstraintDataVector constraint_datas; + + const ConstraintModel cm_LF_RF_LOCAL( + model, model.getJointId(LF), SE3::Random(), model.getJointId(RF), SE3::Random()); + constraint_models.push_back(cm_LF_RF_LOCAL); + constraint_datas.push_back(cm_LF_RF_LOCAL.createData()); + + const ConstraintModel cm_LF_LOCAL(model, model.getJointId(LF), SE3::Random()); + constraint_models.push_back(cm_LF_LOCAL); + constraint_datas.push_back(cm_LF_LOCAL.createData()); + + const ConstraintModel cm_RF_LOCAL(model, model.getJointId(RF), SE3::Random()); + constraint_models.push_back(cm_RF_LOCAL); + constraint_datas.push_back(cm_RF_LOCAL.createData()); + + ConstraintDataVector constraint_datas_gt = constraint_datas; + + std::reference_wrapper constraint_models_ref = constraint_models; + std::reference_wrapper constraint_datas_ref = constraint_datas; + + const double min_damping_value = 1e-4; + + DelassusOperatorRigidBodyReferenceWrapper delassus_operator( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, min_damping_value); + // Eval J Minv Jt + auto Minv_gt = computeMinverse(model, data_gt, q_neutral); + make_symmetric(Minv_gt); + BOOST_CHECK(Minv_gt.isApprox(Minv_gt.transpose())); + + auto M_gt = crba(model, data_gt, q_neutral); + make_symmetric(M_gt); + + Eigen::MatrixXd constraints_jacobian_gt(delassus_operator.size(), model.nv); + constraints_jacobian_gt.setZero(); + evalConstraints(model, data_gt, constraint_models, constraint_datas_gt); + getConstraintsJacobian( + model, data_gt, constraint_models, constraint_datas_gt, constraints_jacobian_gt); + + const Eigen::MatrixXd delassus_dense_gt_undamped = + constraints_jacobian_gt * Minv_gt * constraints_jacobian_gt.transpose(); + const Eigen::MatrixXd delassus_dense_gt = + delassus_dense_gt_undamped + Eigen::MatrixXd(delassus_operator.getDamping().asDiagonal()); + + // Test Jacobian transpose operator + { + const Eigen::VectorXd rhs = Eigen::VectorXd::Random(delassus_operator.size()); + + computeJointJacobians(model, data, q_neutral); + for (Model::JointIndex joint_id = 1; joint_id < Model::JointIndex(model.njoints); ++joint_id) + { + BOOST_CHECK(data.joints[joint_id].S().isApprox(data_gt.joints[joint_id].S())); + BOOST_CHECK(data.liMi[joint_id].isApprox(data_gt.liMi[joint_id])); + BOOST_CHECK(data.oMi[joint_id].isApprox(data_gt.oMi[joint_id])); + } + + const Eigen::VectorXd Jt_rhs_gt = constraints_jacobian_gt.transpose() * rhs; + Eigen::VectorXd Jt_rhs(model.nv); + + evalConstraints(model, data, constraint_models, constraint_datas); + evalConstraintJacobianTransposeMatrixProduct( + model, data, constraint_models, constraint_datas, rhs, Jt_rhs); + + BOOST_CHECK(Jt_rhs.isApprox(Jt_rhs_gt)); + }; + + // Test operator * + { + const Eigen::VectorXd rhs = Eigen::VectorXd::Random(delassus_operator.size()); + Eigen::VectorXd res(delassus_operator.size()); + + delassus_operator.compute(q_neutral); + delassus_operator.applyOnTheRight(rhs, res); + + // Eval Jt*rhs vs internal computations. This test is useful to check intermediate computation. + // Eigen::VectorXd Jt_rhs(model.nv); + // evalConstraintJacobianTransposeMatrixProduct(model,data,constraint_models,constraint_datas,rhs,Jt_rhs); + // BOOST_CHECK(delassus_operator.getCustomData().u.isApprox(Jt_rhs)); + // + // std::cout << "delassus_operator.getCustomData().u: " << + // delassus_operator.getCustomData().u.transpose() << std::endl; std::cout << "Jt_rhs: " << + // Jt_rhs.transpose() << std::endl; const Eigen::VectorXd Jt_rhs_gt = + // constraints_jacobian_gt.transpose() * rhs; + // BOOST_CHECK(delassus_operator.getCustomData().u.isApprox(Jt_rhs_gt)); + // + // pinocchio::container::aligned_vector joint_forces_gt( + // size_t(model.njoints), Data::Force::Zero()); + // mapConstraintForcesToJointForces( + // model, data_gt, constraint_models, constraint_datas_gt, rhs, joint_forces_gt); + + Eigen::VectorXd tau_constraints = Eigen::VectorXd::Zero(model.nv); + evalConstraintJacobianTransposeMatrixProduct( + model, data_gt, constraint_models, constraint_datas_gt, rhs, tau_constraints); + const Eigen::VectorXd Jt_rhs_gt = constraints_jacobian_gt.transpose() * rhs; + BOOST_CHECK(tau_constraints.isApprox(Jt_rhs_gt)); + + aba( + model, data_aba, q_neutral, Eigen::VectorXd::Zero(model.nv), tau_constraints, + Convention::LOCAL); + + for (Model::JointIndex joint_id = 1; joint_id < Model::JointIndex(model.njoints); ++joint_id) + { + // const CustomData & custom_data = delassus_operator.getCustomData(); + BOOST_CHECK(data.joints[joint_id].S().isApprox(data_aba.joints[joint_id].S())); + BOOST_CHECK(data.liMi[joint_id].isApprox(data_aba.liMi[joint_id])); + // BOOST_CHECK(custom_data.oMi[joint_id].isApprox(data_aba.oMi[joint_id])); // + // minimal::ABA does not compute this quantity + BOOST_CHECK(data.Yaba[joint_id].isApprox(data_aba.Yaba[joint_id])); + } + BOOST_CHECK(delassus_operator.getCustomData().u.isApprox(data_aba.u)); + + // std::cout << "delassus_operator.getCustomData().u: " << + // delassus_operator.getCustomData().u.transpose() << std::endl; std::cout << "data_aba.u: " + // << data_aba.u.transpose() << std::endl; + // + const Eigen::VectorXd Minv_Jt_rhs_gt = Minv_gt * Jt_rhs_gt; + // + // // std::cout << "Minv_Jt_rhs: " << delassus_operator.getCustomData().ddq.transpose() << + // // std::endl; std::cout << "Minv_Jt_rhs_gt: " << Minv_Jt_rhs_gt.transpose() << + // std::endl; + // + BOOST_CHECK(delassus_operator.getCustomData().ddq.isApprox(Minv_Jt_rhs_gt)); + // + const auto res_gt = (delassus_dense_gt * rhs).eval(); + BOOST_CHECK(res.isApprox(res_gt)); + // + // // std::cout << "res: " << res.transpose() << std::endl; + // // std::cout << "res_gt: " << res_gt.transpose() << std::endl; + // + // Multiple call and operator * + { + for (int i = 0; i < 100; ++i) + { + Eigen::VectorXd res(delassus_operator.size()); + delassus_operator.applyOnTheRight(rhs, res); + BOOST_CHECK(res.isApprox(res_gt)); + + const Eigen::VectorXd res2 = delassus_operator * rhs; + BOOST_CHECK(res2 == res); // Should be exactly the same + BOOST_CHECK(res2.isApprox(res_gt)); + } + } + } // End: Test operator * + + // Update damping + { + const Eigen::VectorXd rhs = Eigen::VectorXd::Random(delassus_operator.size()); + const double mu = 1; + delassus_operator.updateDamping(mu); + BOOST_CHECK(delassus_operator.getDamping().isApproxToConstant(mu)); + + Eigen::VectorXd res_damped(delassus_operator.size()); + delassus_operator.applyOnTheRight(rhs, res_damped); + const auto res_gt_damped = + ((delassus_dense_gt_undamped + + mu * Eigen::MatrixXd::Identity(delassus_operator.size(), delassus_operator.size())) + * rhs) + .eval(); + BOOST_CHECK(res_damped.isApprox(res_gt_damped)); + } + + // Update compliance + { + const Eigen::VectorXd rhs = Eigen::VectorXd::Random(delassus_operator.size()); + const double compliance = 3e-2; + const double mu = 1; + delassus_operator.updateDamping(mu); + delassus_operator.updateCompliance(compliance); + // BOOST_CHECK(delassus_operator.getCompliance().isApproxToConstant(compliance)); + + Eigen::VectorXd res_damped(delassus_operator.size()); + delassus_operator.applyOnTheRight(rhs, res_damped); + const auto res_gt_damped = + ((delassus_dense_gt_undamped + + compliance * Eigen::MatrixXd::Identity(delassus_operator.size(), delassus_operator.size()) + + mu * Eigen::MatrixXd::Identity(delassus_operator.size(), delassus_operator.size())) + * rhs) + .eval(); + BOOST_CHECK(res_damped.isApprox(res_gt_damped)); + } + + // Test solveInPlace + { + // const Eigen::VectorXd rhs = Eigen::VectorXd::Random(delassus_operator.size()); + const Eigen::VectorXd rhs = Eigen::VectorXd::Unit(model.nv, 0); + Eigen::VectorXd res = rhs; + + const double mu_inv = min_damping_value; + const double mu = 1. / mu_inv; + + Data data(model); + std::reference_wrapper data_ref = data; + + DelassusOperatorRigidBodyReferenceWrapper delassus_operator( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, min_damping_value); + delassus_operator.updateDamping(mu_inv); + delassus_operator.updateCompliance(0); + delassus_operator.compute(q_neutral); + delassus_operator.getAugmentedMassMatrixOperator().solveInPlace(res); + + // Check elimination_order + const auto & elimination_order = data.elimination_order; + for (auto it = elimination_order.begin(); it != elimination_order.end(); ++it) + { + const auto joint_id = *it; + const auto & joint_support = model.supports[joint_id]; + for (const auto supporting_joint : joint_support) + { + bool is_after = + std::find(it, elimination_order.end(), supporting_joint) != elimination_order.end(); + BOOST_CHECK(is_after || supporting_joint == 0); + } + } + + Data data_crba(model); + Eigen::MatrixXd M = crba(model, data_crba, q_neutral, Convention::WORLD); + make_symmetric(M); + + auto constraint_datas_crba = createData(constraint_models); + const auto Jc = + getConstraintsJacobian(model, data_crba, constraint_models, constraint_datas_crba); + + const Eigen::MatrixXd M_augmented = M + mu * Jc.transpose() * Jc; + const Eigen::MatrixXd M_augmented_inv = M_augmented.inverse(); + const Eigen::VectorXd col_ref = M_augmented_inv * rhs; + + BOOST_CHECK(res.isApprox(col_ref, 1e-10)); + + for (Eigen::DenseIndex col_id = 0; col_id < model.nv; ++col_id) + { + const Eigen::VectorXd rhs = Eigen::VectorXd::Unit(model.nv, col_id); + const auto res_ref = (M_augmented_inv * rhs).eval(); + + Eigen::VectorXd res = rhs; + delassus_operator.getAugmentedMassMatrixOperator().solveInPlace(res); + BOOST_CHECK(res.isApprox(res_ref, 1e-10)); + } + + // Test Delassus inverse + const auto delassus_size = delassus_operator.size(); + const Eigen::MatrixXd M_inv = M.inverse(); + const Eigen::MatrixXd delassus_dense = + Jc * M_inv * Jc.transpose() + + mu_inv * Eigen::MatrixXd::Identity(delassus_size, delassus_size); + const Eigen::MatrixXd delassus_dense_inv = delassus_dense.inverse(); + + for (Eigen::DenseIndex col_id = 0; col_id < delassus_size; ++col_id) + { + const Eigen::VectorXd rhs = Eigen::VectorXd::Unit(delassus_size, col_id); + const auto res_ref = (delassus_dense_inv * rhs).eval(); + + Eigen::VectorXd res = rhs; + delassus_operator.solveInPlace(res); + BOOST_CHECK(res.isApprox(res_ref, 1e-10)); + } + + // + // const Eigen::VectorXd res_gt = delassus_dense_gt.llt().solve(rhs); + // + // BOOST_CHECK(res.isApprox(res_gt)); + // std::cout << "res:\n" << res.transpose() << std::endl; + // std::cout << "res_gt:\n" << res_gt.transpose() << std::endl; + // + // // Check accuracy + // + // const double min_damping_value_sqrt = math::sqrt(min_damping_value); + // const double min_damping_value_sqrt_inv = 1. / min_damping_value_sqrt; + // const Eigen::MatrixXd scaled_matrix = + // Eigen::MatrixXd::Identity(model.nv, model.nv) * min_damping_value_sqrt; + // const Eigen::MatrixXd scaled_matrix_inv = + // Eigen::MatrixXd::Identity(delassus_operator.size(), delassus_operator.size()) + // * min_damping_value_sqrt_inv; + // const Eigen::MatrixXd M_gt_scaled = scaled_matrix * M_gt * scaled_matrix; + // std::cout << "M_gt_scaled:\n" << M_gt_scaled << std::endl; + // std::cout << "M_gt:\n" << M_gt << std::endl; + // const Eigen::MatrixXd M_gt_scaled_plus_Jt_J = + // M_gt_scaled + constraints_jacobian_gt.transpose() * constraints_jacobian_gt; + // const Eigen::MatrixXd M_gt_scaled_plus_Jt_J_inv = M_gt_scaled_plus_Jt_J.inverse(); + // const Eigen::MatrixXd damped_delassus_inverse_woodbury = + // 1. / min_damping_value + // * Eigen::MatrixXd::Identity(delassus_operator.size(), delassus_operator.size()) + // - scaled_matrix_inv + // * (constraints_jacobian_gt * M_gt_scaled_plus_Jt_J * + // constraints_jacobian_gt.transpose()) + // .eval() + // * scaled_matrix_inv; + // + // const Eigen::VectorXd res_gt_woodbury = damped_delassus_inverse_woodbury * rhs; + // + // std::cout << "res: " << res.transpose() << std::endl; + // std::cout << "res_gt: " << res_gt.transpose() << std::endl; + // std::cout << "res_gt_woodbury: " << res_gt_woodbury.transpose() << std::endl; + // std::cout << "res - res_gt: " << (res - res_gt).norm() << std::endl; + } +} + +template< + template class Holder, + typename Scalar, + typename ConstraintModelVector, + typename ConstraintDataVector, + typename GeneralizedCondigurationVector> +void test_apply_on_the_right( + const Holder & model_ref, + Holder & data_ref, + const Holder & constraint_models_ref, + const Holder & constraint_datas_ref, + const Eigen::MatrixBase & q_neutral, + const Scalar damping_value) +{ + typedef typename ConstraintModelVector::value_type ConstraintModel; + typedef DelassusOperatorRigidBodySystemsTpl< + double, 0, JointCollectionDefaultTpl, ConstraintModel, std::reference_wrapper> + DelassusOperatorRigidBodyReferenceWrapper; + + const Model & model = model_ref; + Data & data = data_ref; + const ConstraintModelVector & constraint_models = constraint_models_ref; + + Data data_gt(model), data_aba(model); + DelassusOperatorRigidBodyReferenceWrapper delassus_operator( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, damping_value); + delassus_operator.updateDamping(damping_value); + delassus_operator.updateCompliance(0); + delassus_operator.compute(q_neutral); + + const Eigen::VectorXd rhs = Eigen::VectorXd::Random(delassus_operator.size()); + Eigen::VectorXd res(delassus_operator.size()); + + delassus_operator.applyOnTheRight(rhs, res); + + // Eval J Minv Jt + auto Minv_gt = computeMinverse(model, data_gt, q_neutral); + make_symmetric(Minv_gt); + BOOST_CHECK(Minv_gt.isApprox(Minv_gt.transpose())); + + auto M_gt = crba(model, data_gt, q_neutral); + make_symmetric(M_gt); + + ConstraintDataVector constraint_datas_gt = createData(constraint_models); + Eigen::MatrixXd constraints_jacobian_gt(delassus_operator.size(), model.nv); + constraints_jacobian_gt.setZero(); + evalConstraints(model, data_gt, constraint_models, constraint_datas_gt); + getConstraintsJacobian( + model, data_gt, constraint_models, constraint_datas_gt, constraints_jacobian_gt); + + const Eigen::MatrixXd delassus_dense_gt_undamped = + constraints_jacobian_gt * Minv_gt * constraints_jacobian_gt.transpose(); + const Eigen::MatrixXd delassus_dense_gt = + delassus_dense_gt_undamped + Eigen::MatrixXd(delassus_operator.getDamping().asDiagonal()); + + Eigen::VectorXd tau_constraints = Eigen::VectorXd::Zero(model.nv); + evalConstraintJacobianTransposeMatrixProduct( + model, data_gt, constraint_models, constraint_datas_gt, rhs, tau_constraints); + const Eigen::VectorXd Jt_rhs_gt = constraints_jacobian_gt.transpose() * rhs; + BOOST_CHECK(tau_constraints.isApprox(Jt_rhs_gt)); + + aba( + model, data_aba, q_neutral, Eigen::VectorXd::Zero(model.nv), tau_constraints, + Convention::LOCAL); + + for (Model::JointIndex joint_id = 1; joint_id < Model::JointIndex(model.njoints); ++joint_id) + { + BOOST_CHECK(data.joints[joint_id].S().isApprox(data_aba.joints[joint_id].S())); + BOOST_CHECK(data.liMi[joint_id].isApprox(data_aba.liMi[joint_id])); + BOOST_CHECK(data.Yaba[joint_id].isApprox(data_aba.Yaba[joint_id])); + } + BOOST_CHECK(delassus_operator.getCustomData().u.isApprox(data_aba.u)); + + const Eigen::VectorXd Minv_Jt_rhs_gt = Minv_gt * Jt_rhs_gt; + BOOST_CHECK(delassus_operator.getCustomData().ddq.isApprox(Minv_Jt_rhs_gt)); + + const auto res_gt = (delassus_dense_gt * rhs).eval(); + BOOST_CHECK(res.isApprox(res_gt)); + + // Multiple call and operator * + { + for (int i = 0; i < 100; ++i) + { + Eigen::VectorXd res(delassus_operator.size()); + delassus_operator.applyOnTheRight(rhs, res); + BOOST_CHECK(res.isApprox(res_gt)); + + const Eigen::VectorXd res2 = delassus_operator * rhs; + BOOST_CHECK(res2 == res); // Should be exactly the same + BOOST_CHECK(res2.isApprox(res_gt)); + } + } +} + +template< + template class Holder, + typename Scalar, + typename ConstraintModelVector, + typename ConstraintDataVector, + typename GeneralizedCondigurationVector> +void test_solve_in_place( + const Holder & model_ref, + Holder & data_ref, + const Holder & constraint_models_ref, + const Holder & constraint_datas_ref, + const Eigen::MatrixBase & q_neutral, + const Scalar damping_value) +{ + typedef typename ConstraintModelVector::value_type ConstraintModel; + typedef DelassusOperatorRigidBodySystemsTpl< + double, 0, JointCollectionDefaultTpl, ConstraintModel, std::reference_wrapper> + DelassusOperatorRigidBodyReferenceWrapper; + + const Model & model = model_ref; + Data & data = data_ref; + const ConstraintModelVector & constraint_models = constraint_models_ref; + + // Data data(model); + // std::reference_wrapper data_ref = data; + DelassusOperatorRigidBodyReferenceWrapper delassus_operator( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, damping_value); + delassus_operator.updateDamping(damping_value); + delassus_operator.updateCompliance(0); + delassus_operator.compute(q_neutral); + + Data data_crba(model); + Eigen::MatrixXd M = crba(model, data_crba, q_neutral, Convention::WORLD); + make_symmetric(M); + + auto constraint_datas_crba = createData(constraint_models); + const auto Jc = + getConstraintsJacobian(model, data_crba, constraint_models, constraint_datas_crba); + + const Scalar mu = Scalar(1) / damping_value; + const Eigen::MatrixXd muJcTJc = mu * Jc.transpose() * Jc; + const Eigen::MatrixXd M_augmented = M + muJcTJc; + const Eigen::MatrixXd M_augmented_inv = M_augmented.inverse(); + + const Eigen::VectorXd rhs = Eigen::VectorXd::Unit(model.nv, 0); + Eigen::VectorXd res = rhs; + + const Eigen::VectorXd col_ref = M_augmented_inv * rhs; + delassus_operator.getAugmentedMassMatrixOperator().solveInPlace(res); + BOOST_CHECK(res.isApprox(col_ref, 1e-10)); + + for (Eigen::DenseIndex col_id = 0; col_id < model.nv; ++col_id) + { + const Eigen::VectorXd rhs = Eigen::VectorXd::Unit(model.nv, col_id); + const auto res_ref = (M_augmented_inv * rhs).eval(); + + Eigen::VectorXd res = rhs; + delassus_operator.getAugmentedMassMatrixOperator().solveInPlace(res); + BOOST_CHECK(res.isApprox(res_ref, 1e-10)); + } + + // Test Delassus inverse + const auto delassus_size = delassus_operator.size(); + const Eigen::MatrixXd M_inv = M.inverse(); + const Eigen::MatrixXd delassus_dense = + Jc * M_inv * Jc.transpose() + + damping_value * Eigen::MatrixXd::Identity(delassus_size, delassus_size); + const Eigen::MatrixXd delassus_dense_inv = delassus_dense.inverse(); + + for (Eigen::DenseIndex col_id = 0; col_id < delassus_size; ++col_id) + { + const Eigen::VectorXd rhs = Eigen::VectorXd::Unit(delassus_size, col_id); + const auto res_ref = (delassus_dense_inv * rhs).eval(); + + Eigen::VectorXd res = rhs; + delassus_operator.solveInPlace(res); + BOOST_CHECK(res.isApprox(res_ref, 1e-10)); + } +} + +BOOST_AUTO_TEST_CASE(general_test_joint_frictional_constraint) +{ + typedef FrictionalJointConstraintModelTpl ConstraintModel; + typedef DelassusOperatorRigidBodySystemsTpl< + double, 0, JointCollectionDefaultTpl, ConstraintModel, std::reference_wrapper> + DelassusOperatorRigidBodyReferenceWrapper; + typedef DelassusOperatorRigidBodyReferenceWrapper::CustomData CustomData; + typedef + typename DelassusOperatorRigidBodyReferenceWrapper::ConstraintModelVector ConstraintModelVector; + typedef + typename DelassusOperatorRigidBodyReferenceWrapper::ConstraintDataVector ConstraintDataVector; + + Model model; + std::reference_wrapper model_ref = model; + + buildModels::humanoidRandom(model, true); + + const Eigen::VectorXd q_neutral = neutral(model); + const Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv); + const Eigen::VectorXd tau = Eigen::VectorXd::Random(model.nv); + + Data data(model), data_gt(model), data_aba(model); + std::reference_wrapper data_ref = data; + + ConstraintModelVector constraint_models; + ConstraintDataVector constraint_datas; + + const std::string RF_name = "rleg6_joint"; + const JointIndex RF_id = model.getJointId(RF_name); + + const Model::IndexVector & RF_support = model.supports[RF_id]; + const Model::IndexVector active_joint_ids(RF_support.begin() + 1, RF_support.end()); + + FrictionalJointConstraintModel constraint_model(model, active_joint_ids); + + constraint_models.push_back(constraint_model); + constraint_datas.push_back(constraint_model.createData()); + std::reference_wrapper constraint_models_ref = constraint_models; + std::reference_wrapper constraint_datas_ref = constraint_datas; + + const double damping_value = 1e-4; + + const double mu_inv = damping_value; + const double mu = 1. / mu_inv; + + // Test operator * + { + test_apply_on_the_right( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, q_neutral, damping_value); + } // End: Test operator * + + // Test solveInPlace + { + test_solve_in_place( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, q_neutral, damping_value); + } +} + +BOOST_AUTO_TEST_CASE(general_test_constraint_generic) +{ + typedef FrictionalJointConstraintModelTpl FrictionalJointConstraintModel; + typedef DelassusOperatorRigidBodySystemsTpl< + double, 0, JointCollectionDefaultTpl, ConstraintModel, std::reference_wrapper> + DelassusOperatorRigidBodyReferenceWrapper; + typedef DelassusOperatorRigidBodyReferenceWrapper::CustomData CustomData; + typedef + typename DelassusOperatorRigidBodyReferenceWrapper::ConstraintModelVector ConstraintModelVector; + typedef + typename DelassusOperatorRigidBodyReferenceWrapper::ConstraintDataVector ConstraintDataVector; + + Model model; + std::reference_wrapper model_ref = model; + + buildModels::humanoidRandom(model, true); + + const Eigen::VectorXd q_neutral = neutral(model); + const Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv); + const Eigen::VectorXd tau = Eigen::VectorXd::Random(model.nv); + + Data data(model), data_gt(model), data_aba(model); + std::reference_wrapper data_ref = data; + + ConstraintModelVector constraint_models; + ConstraintDataVector constraint_datas; + + const std::string RF_name = "rleg6_joint"; + const JointIndex RF_id = model.getJointId(RF_name); + + const Model::IndexVector & RF_support = model.supports[RF_id]; + const Model::IndexVector active_joint_ids(RF_support.begin() + 1, RF_support.end()); + + FrictionalJointConstraintModel constraint_model(model, active_joint_ids); + + constraint_models.push_back(constraint_model); + constraint_datas.push_back(constraint_model.createData()); + std::reference_wrapper constraint_models_ref = constraint_models; + std::reference_wrapper constraint_datas_ref = constraint_datas; + + const double damping_value = 1e-4; + + // Test operator * + { + test_apply_on_the_right( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, q_neutral, damping_value); + } // End: Test operator * + + // Test solveInPlace + { + test_solve_in_place( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, q_neutral, damping_value); + } +} + +BOOST_AUTO_TEST_CASE(general_test_no_constraints) +{ + typedef FrictionalPointConstraintModelTpl ConstraintModel; + typedef DelassusOperatorRigidBodySystemsTpl< + double, 0, JointCollectionDefaultTpl, ConstraintModel, std::reference_wrapper> + DelassusOperatorRigidBodyReferenceWrapper; + typedef + typename DelassusOperatorRigidBodyReferenceWrapper::ConstraintModelVector ConstraintModelVector; + typedef + typename DelassusOperatorRigidBodyReferenceWrapper::ConstraintDataVector ConstraintDataVector; + + Model model; + std::reference_wrapper model_ref = model; + buildModels::humanoidRandom(model, true); + model.gravity.setZero(); + + const Eigen::VectorXd q_neutral = neutral(model); + const Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv); + const Eigen::VectorXd tau = Eigen::VectorXd::Random(model.nv); + + Data data(model), data_gt(model), data_aba(model); + std::reference_wrapper data_ref = data; + + ConstraintModelVector constraint_models; + ConstraintDataVector constraint_datas; + + ConstraintDataVector constraint_datas_gt = constraint_datas; + + std::reference_wrapper constraint_models_ref = constraint_models; + std::reference_wrapper constraint_datas_ref = constraint_datas; + + const double min_damping_value = 1e-4; + + DelassusOperatorRigidBodyReferenceWrapper delassus_operator( + model_ref, data_ref, constraint_models_ref, constraint_datas_ref, min_damping_value); + + // Test solveInPlace + { + const Eigen::DenseIndex col_id = 7; + const Eigen::VectorXd rhs = Eigen::VectorXd::Unit(model.nv, col_id); + Eigen::VectorXd res = rhs; + + const double mu_inv = min_damping_value; + const double mu = 1. / mu_inv; + + delassus_operator.updateDamping(mu); + delassus_operator.updateCompliance(0); + delassus_operator.compute(q_neutral); + + delassus_operator.getAugmentedMassMatrixOperator().solveInPlace(res); + + Data data_crba(model); + Eigen::MatrixXd M = crba(model, data_crba, q_neutral, Convention::WORLD); + make_symmetric(M); + const Eigen::MatrixXd M_inv = M.inverse(); + BOOST_CHECK(data.J.isApprox(data_crba.J)); + + Data data_aba(model); + const auto res_ref = + aba(model, data_aba, q_neutral, Eigen::VectorXd::Zero(model.nv), rhs, Convention::WORLD); + + BOOST_CHECK(data.J.isApprox(data_aba.J)); + for (Model::JointIndex joint_id = 1; joint_id < Model::JointIndex(model.njoints); ++joint_id) + { + BOOST_CHECK(data.liMi[joint_id].isApprox(data_aba.liMi[joint_id])); + BOOST_CHECK(data.oMi[joint_id].isApprox(data_aba.oMi[joint_id])); + BOOST_CHECK(data.oYaba_augmented[joint_id].isApprox(data_aba.oYaba[joint_id])); + + BOOST_CHECK(data.joints_augmented[joint_id].U().isApprox(data_aba.joints[joint_id].U())); + BOOST_CHECK( + data.joints_augmented[joint_id].Dinv().isApprox(data_aba.joints[joint_id].Dinv())); + BOOST_CHECK( + data.joints_augmented[joint_id].UDinv().isApprox(data_aba.joints[joint_id].UDinv())); + } + + BOOST_CHECK(res.isApprox(M_inv.col(col_id))); + BOOST_CHECK(res.isApprox(res_ref)); + + for (Eigen::DenseIndex col_id = 0; col_id < model.nv; ++col_id) + { + const Eigen::VectorXd rhs = Eigen::VectorXd::Unit(model.nv, col_id); + const auto res_ref = + aba(model, data_aba, q_neutral, Eigen::VectorXd::Zero(model.nv), rhs, Convention::WORLD); + const auto res_ref2 = (M_inv * rhs).eval(); + BOOST_CHECK(res_ref.isApprox(res_ref2)); + + Eigen::VectorXd res = rhs; + delassus_operator.getAugmentedMassMatrixOperator().solveInPlace(res); + BOOST_CHECK(res.isApprox(res_ref)); + BOOST_CHECK(res.isApprox(res_ref2)); + } + + // Check elimination_order + const auto & elimination_order = data.elimination_order; + for (auto it = elimination_order.begin(); it != elimination_order.end(); ++it) + { + const auto joint_id = *it; + const auto & joint_support = model.supports[joint_id]; + for (const auto support_joint : joint_support) + { + bool is_after = + std::find(it, elimination_order.end(), support_joint) != elimination_order.end(); + BOOST_CHECK(is_after || support_joint == 0); + } + } + } +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/delassus.cpp b/unittest/delassus.cpp index 2509c6b212..8c26cd2b70 100644 --- a/unittest/delassus.cpp +++ b/unittest/delassus.cpp @@ -20,23 +20,19 @@ namespace pinocchio : public ContactCholeskyDecompositionTpl { typedef ContactCholeskyDecompositionTpl Base; - typedef typename Base::IndexVector IndexVector; - typedef typename Base::BooleanVector BooleanVector; + using typename Base::BooleanVector; + using typename Base::EigenIndexVector; ContactCholeskyDecompositionAccessorTpl(const Base & other) : Base(other) { } - const IndexVector & getParents_fromRow() const + const EigenIndexVector & getParents_fromRow() const { return this->parents_fromRow; } - const IndexVector & getLastChild() const - { - return this->last_child; - } - const IndexVector & getNvSubtree_fromRow() const + const EigenIndexVector & getNvSubtree_fromRow() const { return this->nv_subtree_fromRow; } diff --git a/unittest/double-entry-container.cpp b/unittest/double-entry-container.cpp new file mode 100644 index 0000000000..7143037922 --- /dev/null +++ b/unittest/double-entry-container.cpp @@ -0,0 +1,117 @@ +// +// Copyright (c) 2025 INRIA +// + +#include "pinocchio/container/double-entry-container.hpp" + +#include +#include +#include + +using namespace pinocchio; +typedef Eigen::Matrix Matrix6; +typedef Eigen::aligned_allocator Allocator; + +typedef container::DoubleEntryContainer Container; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(test_all) +{ + const Eigen::Index nrows = 20, ncols = 20; + + Container container(nrows, ncols); + BOOST_CHECK(container.size() == 0); + BOOST_CHECK(container.rows() == nrows); + BOOST_CHECK(container.cols() == ncols); + BOOST_CHECK(container.begin() == container.end()); + + container.reserve(size_t(nrows)); + BOOST_CHECK(container.values().capacity() == size_t(nrows)); + + // Fill diagonal with random values + for (Eigen::Index id = 0; id < nrows; id++) + { + const bool res = container.insert(id, id, Matrix6::Constant(double(id))); + BOOST_CHECK(res); + BOOST_CHECK(container.size() == size_t(id + 1)); + } + + for (Eigen::Index id = 0; id < nrows; id++) + { + const bool res = container.insert(id, id, Matrix6::Constant(double(id))); + BOOST_CHECK(!res); + BOOST_CHECK(container.size() == size_t(nrows)); + } + + { + const Eigen::VectorXi linear_range = Eigen::VectorXi::LinSpaced(nrows, 0, nrows - 1); + BOOST_CHECK(container.keys().matrix().diagonal() == linear_range.cast()); + } + + // Set diagonal and check + container.fill(Matrix6::Identity()); + for (auto val : container) + BOOST_CHECK(val == Matrix6::Identity()); + + // Check method find + for (Eigen::Index row_id = 0; row_id < nrows; row_id++) + { + for (Eigen::Index col_id = 0; col_id < ncols; col_id++) + { + if (row_id == col_id) + BOOST_CHECK(*container.find(row_id, col_id) == Matrix6::Identity()); + else + BOOST_CHECK(container.find(row_id, col_id) == container.end()); + } + } + + const Container copy(container); + BOOST_CHECK(container == copy); + + // No change + for (Eigen::Index id = 0; id < nrows; id++) + { + container[{id, id}].setIdentity(); + } + BOOST_CHECK(container == copy); + + // Change values + for (Eigen::Index id = 0; id < nrows; id++) + { + container[{id, id}].setZero(); + BOOST_CHECK((container[{id, id}] == Matrix6::Zero())); + } + BOOST_CHECK(container != copy); + + // Restore values + for (Eigen::Index id = 0; id < nrows; id++) + { + container[{id, id}].setIdentity(); + } + BOOST_CHECK(container == copy); + + // Apply + container.apply([](Matrix6 & v) { v.setZero(); }); + container.apply([](const Matrix6 & v) { BOOST_CHECK(v.isZero(0)); }); + BOOST_CHECK(container != copy); + + container.apply([](Matrix6 & v) { v.setIdentity(); }); + BOOST_CHECK(container == copy); + + // Remove elt (4,4) + BOOST_CHECK(!container.remove(3, 4)); + BOOST_CHECK(container == copy); + BOOST_CHECK(container.find(4, 4) != container.end()); + BOOST_CHECK(container.remove(4, 4)); + BOOST_CHECK(container != copy); + BOOST_CHECK(container.size() == size_t(nrows - 1)); + BOOST_CHECK(container.find(4, 4) == container.end()); + + // Check operator[] insertion + container[{4, 4}] = Matrix6::Identity(); + BOOST_CHECK(container.keys()(4, 4) == long(nrows - 1)); + BOOST_CHECK(container != copy); +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/eigen-basic-op.cpp b/unittest/eigen-basic-op.cpp index ecccdad788..f24a24e06c 100644 --- a/unittest/eigen-basic-op.cpp +++ b/unittest/eigen-basic-op.cpp @@ -1,11 +1,12 @@ // -// Copyright (c) 2019 INRIA +// Copyright (c) 2019-2025 INRIA // #include "pinocchio/multibody/model.hpp" - -#include #include "pinocchio/math/matrix.hpp" +#include "pinocchio/math/eigen-helpers.hpp" + +#include "pinocchio/utils/std-vector.hpp" #include #include @@ -44,4 +45,47 @@ BOOST_AUTO_TEST_CASE(test_matrix_scalar_product) BOOST_CHECK(res.eval() == M); } +BOOST_AUTO_TEST_CASE(test_eigen_helpers) +{ + using namespace pinocchio; + using namespace Eigen; + const Eigen::DenseIndex m = 20, n = 100; + + MatrixXd M(MatrixXd::Ones(m, n)); + + setZero(M); + BOOST_CHECK(M.isZero(0)); + setOnes(M); + BOOST_CHECK(M.isOnes(0)); + setIdentity(M); + BOOST_CHECK(M.isIdentity(0)); +} + +BOOST_AUTO_TEST_CASE(test_eigen_helpers_on_std_vector) +{ + using namespace pinocchio; + using namespace Eigen; + const Eigen::DenseIndex m = 20, n = 100; + + std::vector vec(10, MatrixXd::Ones(m, n)); + + apply_for_each(vec, setZero); + for (const auto & val : vec) + { + BOOST_CHECK(val.isZero(0)); + } + + apply_for_each(vec, setOnes); + for (const auto & val : vec) + { + BOOST_CHECK(val.isOnes(0)); + } + + apply_for_each(vec, setIdentity); + for (const auto & val : vec) + { + BOOST_CHECK(val.isIdentity(0)); + } +} + BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/explog.cpp b/unittest/explog.cpp index 129285f471..d63f2256e1 100644 --- a/unittest/explog.cpp +++ b/unittest/explog.cpp @@ -78,7 +78,6 @@ BOOST_AUTO_TEST_CASE(renorm_rotation) SE3::Matrix3 R_normed; SE3::Matrix3 Id(SE3::Matrix3::Identity()); SE3::Vector3 vals; - double tr0, tr; const size_t num_tries = 20; for (size_t i = 0; i < num_tries; i++) @@ -88,10 +87,6 @@ BOOST_AUTO_TEST_CASE(renorm_rotation) R1 = M1.rotation(); R_normed = pinocchio::renormalize_rotation_matrix(R1); BOOST_CHECK((R_normed.transpose() * R_normed).isApprox(Id)); - tr0 = R1.trace(); - - tr = R_normed.trace(); - vals = 2. * R_normed.diagonal().array() - tr + 1.; } } diff --git a/unittest/finite-differences.cpp b/unittest/finite-differences.cpp index 9b3958ef41..4377b023bf 100644 --- a/unittest/finite-differences.cpp +++ b/unittest/finite-differences.cpp @@ -141,7 +141,6 @@ struct init> static JointModel run() { - typedef typename JointModel::Vector3 Vector3; JointModel jmodel(XAxis::vector(), YAxis::vector()); jmodel.setIndexes(0, 0, 0); diff --git a/unittest/fusion.cpp b/unittest/fusion.cpp index d9b7ea473c..264e0b6950 100644 --- a/unittest/fusion.cpp +++ b/unittest/fusion.cpp @@ -12,7 +12,6 @@ #include #include "pinocchio/tools/timer.hpp" -#include #include #include diff --git a/unittest/gram-schmidt-orthonormalisation.cpp b/unittest/gram-schmidt-orthonormalisation.cpp index d15698aaae..e89d2f511f 100644 --- a/unittest/gram-schmidt-orthonormalisation.cpp +++ b/unittest/gram-schmidt-orthonormalisation.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2024 INRIA +// Copyright (c) 2024-2025 INRIA // #include @@ -16,7 +16,7 @@ BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) using namespace pinocchio; -BOOST_AUTO_TEST_CASE(test_random_matrix) +BOOST_AUTO_TEST_CASE(test_orthogonalization) { for (size_t i = 0; i < 100; ++i) { @@ -28,10 +28,32 @@ BOOST_AUTO_TEST_CASE(test_random_matrix) for (size_t k = 0; k < 1000; ++k) { const Eigen::VectorXd random_vec = Eigen::VectorXd::Random(size); - orthonormalisation(basis.leftCols(10), random_vec); + orthogonalization(basis.leftCols(10), random_vec); BOOST_CHECK((basis.leftCols(10).transpose() * random_vec).isZero()); } } } +BOOST_AUTO_TEST_CASE(test_orthonormalization) +{ + const size_t num_tests = +#ifdef NDEBUG + 10000 +#else + 100 +#endif + ; + for (size_t i = 0; i < num_tests; ++i) + { + const Eigen::DenseIndex size = 100; + const double prec = size * size * Eigen::NumTraits::dummy_precision(); + const Eigen::MatrixXd random_mat = Eigen::MatrixXd::Random(size, size); + const Eigen::MatrixXd mat = random_mat + Eigen::MatrixXd::Identity(size, size); + + BOOST_CHECK(!isOrthonormal(mat, prec)); + orthonormalization(mat); + BOOST_CHECK(isOrthonormal(mat, prec)); + } +} + BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/joint-configurations.cpp b/unittest/joint-configurations.cpp index 135395016f..53898a4a4e 100644 --- a/unittest/joint-configurations.cpp +++ b/unittest/joint-configurations.cpp @@ -52,6 +52,7 @@ BOOST_AUTO_TEST_CASE(interpolate_test) Eigen::VectorXd q01_1 = interpolate(model, q0, q1, 1.0); BOOST_CHECK_MESSAGE(isSameConfiguration(model, q01_1, q1), "interpolation: q01_1 != q1"); + Eigen::VectorXd q01_1_bis; } BOOST_AUTO_TEST_CASE(diff_integration_test) @@ -59,15 +60,17 @@ BOOST_AUTO_TEST_CASE(diff_integration_test) Model model; buildAllJointsModel(model); - std::vector qs(2); - std::vector vs(2); - std::vector results(2, Eigen::MatrixXd::Zero(model.nv, model.nv)); + std::vector qs(3); + std::vector vs(3); + std::vector results(3, Eigen::MatrixXd::Zero(model.nv, model.nv)); std::vector results_fd(2, Eigen::MatrixXd::Zero(model.nv, model.nv)); qs[0] = Eigen::VectorXd::Ones(model.nq); + qs[2] = Eigen::VectorXd::Ones(model.nq); normalize(model, qs[0]); vs[0] = Eigen::VectorXd::Zero(model.nv); + vs[2] = Eigen::VectorXd::Zero(model.nv); vs[1] = Eigen::VectorXd::Ones(model.nv); dIntegrate(model, qs[0], vs[0], results[0], ARG0); @@ -114,6 +117,116 @@ BOOST_AUTO_TEST_CASE(diff_integration_test) BOOST_CHECK(results[1].isApprox(results_fd[1], sqrt(eps))); } +BOOST_AUTO_TEST_CASE(tangent_map_test) +{ + Model model; + buildAllJointsModel(model); + + Eigen::VectorXd q(Eigen::VectorXd::Random(model.nq)); + normalize(model, q); + Eigen::VectorXd q_plus(Eigen::VectorXd::Zero(model.nq)); + Eigen::VectorXd v(Eigen::VectorXd::Zero(model.nv)); + + std::vector TMs(5, Eigen::MatrixXd::Zero(model.nq, model.nv)); + + Eigen::MatrixXd TMc(Eigen::MatrixXd::Zero(model.nq, MAX_JOINT_NV)); + + tangentMap(model, q, TMs[0]); + tangentMapProduct(model, q, Eigen::MatrixXd::Identity(model.nv, model.nv), TMs[1]); + tangentMapTransposeProduct( + model, q, Eigen::MatrixXd::Identity(model.nq, model.nq), TMs[2].transpose()); + + typedef typename Model::JointIndex JointIndex; + std::vector joint_selection; + for (JointIndex i = 1; i < (JointIndex)model.njoints; ++i) + { + joint_selection.push_back(i); + } + compactTangentMap(model, joint_selection, q, TMc); + std::vector nvs; + nvs.reserve(static_cast(model.nq)); + std::vector idx_vs; + idx_vs.reserve(static_cast(model.nq)); + + indexvInfo(model, joint_selection, nvs, idx_vs); + size_t k_s; + for (Eigen::DenseIndex k = 0; k < model.nq; ++k) + { + k_s = static_cast(k); + TMs[3].block(k, idx_vs[k_s], 1, nvs[k_s]) = TMc.block(k, 0, 1, nvs[k_s]); + } + + const double eps = 1e-8; + for (Eigen::DenseIndex k = 0; k < model.nv; ++k) + { + v[k] = eps; + + q_plus = integrate(model, q, v); + TMs[4].col(k) = (q_plus - q) / eps; + + v[k] = 0; + } + + BOOST_CHECK(TMs[0].isApprox(TMs[1], 1e-8)); + BOOST_CHECK(TMs[0].isApprox(TMs[2], 1e-8)); + BOOST_CHECK(TMs[0].isApprox(TMs[3], 1e-8)); + BOOST_CHECK(TMs[0].isApprox(TMs[4], sqrt(eps))); +} + +BOOST_AUTO_TEST_CASE(lie_group_test) +{ + Model model; + buildAllJointsModel(model); + + typedef + typename LieGroupMap::template operationProduct::type + LGO; + + LGO lgo1; + lieGroup(model, lgo1); + + LGO lgo2 = lieGroup(model); + + LGO lgo3; + typedef typename Model::JointIndex JointIndex; + for (JointIndex i = 1; i < (JointIndex)model.njoints; ++i) + { + lgo3 *= model.joints[i].template lieGroup(); + } + + BOOST_CHECK(lgo1 == lgo2); + BOOST_CHECK(lgo1 == lgo3); +} + +BOOST_AUTO_TEST_CASE(lie_group_vs_algo_test) +{ + Model model; + buildAllJointsModel(model); + + typedef + typename LieGroupMap::template operationProduct::type + LGO; + + LGO lgo; + lieGroup(model, lgo); + + Eigen::VectorXd q(randomConfiguration( + model, -1 * Eigen::VectorXd::Ones(model.nq), Eigen::VectorXd::Ones(model.nq))); + Eigen::VectorXd q2(randomConfiguration( + model, -1 * Eigen::VectorXd::Ones(model.nq), Eigen::VectorXd::Ones(model.nq))); + Eigen::VectorXd v(Eigen::VectorXd::Zero(model.nv)); + + std::vector q_ps(2, Eigen::VectorXd::Zero(model.nq)); + integrate(model, q, v, q_ps[0]); + lgo.integrate(q, v, q_ps[1]); + BOOST_CHECK(q_ps[0].isApprox(q_ps[1], 1e-8)); + + std::vector v_ds(2, Eigen::VectorXd::Zero(model.nv)); + difference(model, q, q2, v_ds[0]); + lgo.difference(q, q2, v_ds[1]); + BOOST_CHECK(v_ds[0].isApprox(v_ds[1], 1e-8)); +} + BOOST_AUTO_TEST_CASE(diff_difference_test) { Model model; @@ -296,7 +409,7 @@ BOOST_AUTO_TEST_CASE(integrate_difference_test) Eigen::VectorXd qdot(Eigen::VectorXd::Random(model.nv)); BOOST_CHECK_MESSAGE( - isSameConfiguration(model, integrate(model, q0, difference(model, q0, q1)), q1), + isSameConfiguration(model, integrate(model, q0, difference(model, q0, q1)), q1, 1e-5), "Integrate (difference) - wrong results"); BOOST_CHECK_MESSAGE( diff --git a/unittest/joint-frictional-constraint.cpp b/unittest/joint-frictional-constraint.cpp new file mode 100644 index 0000000000..9d0505f5e0 --- /dev/null +++ b/unittest/joint-frictional-constraint.cpp @@ -0,0 +1,278 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#include "pinocchio/algorithm/kinematics.hpp" +#include "pinocchio/algorithm/jacobian.hpp" +#include "pinocchio/algorithm/constraints/joint-frictional-constraint.hpp" +#include "pinocchio/algorithm/joint-configuration.hpp" +#include "pinocchio/multibody/sample-models.hpp" + +#include + +// Helpers +#include "constraints/jacobians-checker.hpp" + +#include +#include + +using namespace pinocchio; +typedef FrictionalJointConstraintModel::EigenIndexVector EigenIndexVector; +typedef FrictionalJointConstraintModel::BooleanVector BooleanVector; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(constraint_empty_constructor) +{ + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + + const Data data(model); + + const Model::IndexVector empty_active_joint_ids; + + FrictionalJointConstraintModel constraint(model, empty_active_joint_ids); +} + +BOOST_AUTO_TEST_CASE(constraint_constructor) +{ + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + + const Data data(model); + const auto & parents_fromRow = data.parents_fromRow; + + const std::string RF_name = "rleg6_joint"; + const JointIndex RF_id = model.getJointId(RF_name); + + const Model::IndexVector & RF_support = model.supports[RF_id]; + const Model::IndexVector active_joint_ids(RF_support.begin() + 1, RF_support.end()); + + FrictionalJointConstraintModel constraint(model, active_joint_ids); + // FrictionalJointConstraintData constraint_data = constraint.createData(); + + // Check size + { + int total_size = 0; + for (const JointIndex joint_id : active_joint_ids) + { + total_size += model.joints[joint_id].nv(); + } + BOOST_CHECK(constraint.size() == total_size); + BOOST_CHECK(constraint.getActiveDofs().size() == size_t(total_size)); + } + + // Check sparsity pattern + { + const EigenIndexVector & active_dofs = constraint.getActiveDofs(); + for (size_t row_id = 0; row_id < size_t(constraint.size()); ++row_id) + { + const Eigen::DenseIndex dof_id = active_dofs[row_id]; + const BooleanVector & row_sparsity_pattern = + constraint.getRowActivableSparsityPattern(Eigen::DenseIndex(row_id)); + const EigenIndexVector & row_active_indexes = + constraint.getRowActiveIndexes(Eigen::DenseIndex(row_id)); + + // Check that the rest of the indexes greater than dof_id are not active. + BOOST_CHECK((row_sparsity_pattern.tail(model.nv - 1 - dof_id).array() == false).all()); + + Eigen::DenseIndex id = dof_id; + while (parents_fromRow[size_t(id)] > -1) + { + BOOST_CHECK(row_sparsity_pattern[id] == true); + id = parents_fromRow[size_t(id)]; + } + + for (const Eigen::DenseIndex active_id : row_active_indexes) + { + BOOST_CHECK(row_sparsity_pattern[active_id] == true); + } + } + } +} + +BOOST_AUTO_TEST_CASE(cast) +{ + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + + const Eigen::VectorXd q = neutral(model); + + const Data data(model); + + const std::string RF_name = "rleg6_joint"; + const JointIndex RF_id = model.getJointId(RF_name); + + const Model::IndexVector & RF_support = model.supports[RF_id]; + const Model::IndexVector active_joint_ids(RF_support.begin() + 1, RF_support.end()); + + FrictionalJointConstraintModel cm(model, active_joint_ids); + + const auto cm_cast_double = cm.cast(); + BOOST_CHECK(cm_cast_double == cm); + + const auto cm_cast_long_double = cm.cast(); + BOOST_CHECK(cm_cast_long_double.cast() == cm); +} + +BOOST_AUTO_TEST_CASE(constraint_jacobian) +{ + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + + const Eigen::VectorXd q = neutral(model); + + const Data data(model); + + const std::string RF_name = "rleg6_joint"; + const JointIndex RF_id = model.getJointId(RF_name); + + const Model::IndexVector & RF_support = model.supports[RF_id]; + const Model::IndexVector active_joint_ids(RF_support.begin() + 1, RF_support.end()); + + FrictionalJointConstraintModel constraint_model(model, active_joint_ids); + FrictionalJointConstraintData constraint_data(constraint_model); + + Eigen::MatrixXd jacobian_matrix(constraint_model.size(), model.nv); + constraint_model.jacobian(model, data, constraint_data, jacobian_matrix); + + const EigenIndexVector & active_dofs = constraint_model.getActiveDofs(); + for (Eigen::DenseIndex row_id = 0; row_id < constraint_model.size(); ++row_id) + { + const Eigen::DenseIndex dof_id = active_dofs[size_t(row_id)]; + BOOST_CHECK(jacobian_matrix.row(row_id).sum() == 1.); + BOOST_CHECK(jacobian_matrix(row_id, dof_id) == 1.); + BOOST_CHECK( + (dof_id - 1) > 0 ? (jacobian_matrix.row(row_id).head(dof_id - 1).array() == 0).all() : true); + BOOST_CHECK( + (model.nv - dof_id - 1) > 0 + ? (jacobian_matrix.row(row_id).tail(model.nv - dof_id - 1).array() == 0).all() + : true); + } + + check_jacobians_operations(model, data, constraint_model, constraint_data); +} + +BOOST_AUTO_TEST_CASE(constraint_coupling_inertia) +{ + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + + const Eigen::VectorXd q = neutral(model); + + Data data(model); + computeJointJacobians(model, data, q); + + const std::string RF_name = "rleg6_joint"; + const JointIndex RF_id = model.getJointId(RF_name); + + const Model::IndexVector & RF_support = model.supports[RF_id]; + const Model::IndexVector active_joint_ids(RF_support.begin() + 1, RF_support.end()); + + FrictionalJointConstraintModel constraint_model(model, active_joint_ids); + FrictionalJointConstraintData constraint_data(constraint_model); + + constraint_model.calc(model, data, constraint_data); + const Eigen::VectorXd diagonal_inertia = + Eigen::VectorXd::Random(constraint_model.size()).array().square(); + constraint_model.appendCouplingConstraintInertias( + model, data, constraint_data, diagonal_inertia, WorldFrameTag()); + + Eigen::Index row_id = 0; + + for (const auto joint_id : active_joint_ids) + { + // std::cout << "joint_id: " << joint_id << std::endl; + + const auto & jmodel = model.joints[joint_id]; + const auto jmodel_nv = jmodel.nv(); + const auto jmodel_idx_v = jmodel.idx_v(); + + const auto diagonal_inertia_segment = diagonal_inertia.segment(row_id, jmodel_nv); + + BOOST_CHECK( + diagonal_inertia_segment == data.joint_apparent_inertia.segment(jmodel_idx_v, jmodel_nv)); + + row_id += jmodel_nv; + // std::cout << "----" << std::endl; + } + + Eigen::MatrixXd jacobian_matrix(constraint_model.size(), model.nv); + constraint_model.jacobian(model, data, constraint_data, jacobian_matrix); + + const Eigen::MatrixXd joint_space_constraint_inertia = + jacobian_matrix.transpose() * diagonal_inertia.asDiagonal() * jacobian_matrix; + + BOOST_CHECK(joint_space_constraint_inertia.isApprox( + Eigen::MatrixXd(data.joint_apparent_inertia.asDiagonal()))); +} + +BOOST_AUTO_TEST_CASE(check_maps) +{ + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + Data data(model), data_ref(model); + + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); + + const std::string RF_name = "rleg6_joint"; + const JointIndex RF_id = model.getJointId(RF_name); + + const Model::IndexVector & RF_support = model.supports[RF_id]; + const Model::IndexVector active_joint_ids(RF_support.begin() + 1, RF_support.end()); + + FrictionalJointConstraintModel constraint_model(model, active_joint_ids); + FrictionalJointConstraintData constraint_data(constraint_model), + constraint_data_ref(constraint_model); + + const Eigen::VectorXd q = neutral(model); + computeJointJacobians(model, data, q); + constraint_model.calc(model, data, constraint_data); + computeJointJacobians(model, data_ref, q); + constraint_model.calc(model, data_ref, constraint_data_ref); + + const auto constraint_jacobian_ref = + constraint_model.jacobian(model, data_ref, constraint_data_ref); + + // Test mapConstraintForcesToJointTorques + { + const Eigen::VectorXd constraint_forces = + Eigen::VectorXd::Random(constraint_model.activeSize()); + + Eigen::VectorXd joint_torques_ref = Eigen::VectorXd::Zero(model.nv); + joint_torques_ref = constraint_jacobian_ref.transpose() * constraint_forces; + + Eigen::VectorXd joint_torques_ref2 = Eigen::VectorXd::Zero(model.nv); + constraint_model.jacobianTransposeMatrixProduct( + model, data_ref, constraint_data_ref, constraint_forces, joint_torques_ref2, SetTo()); + + Eigen::VectorXd joint_torques = Eigen::VectorXd::Zero(model.nv); + constraint_model.mapConstraintForceToJointTorques( + model, data_ref, constraint_data, constraint_forces, joint_torques); + + BOOST_CHECK(joint_torques.isApprox(joint_torques_ref)); + BOOST_CHECK(joint_torques.isApprox(joint_torques_ref2)); + } + + // Test mapJointMotionsToConstraintMotions + { + const Eigen::VectorXd joint_motions = Eigen::VectorXd::Random(model.nv); + + Eigen::VectorXd constraint_motions_ref = Eigen::VectorXd::Zero(constraint_model.activeSize()); + constraint_motions_ref = constraint_jacobian_ref * joint_motions; + + Eigen::VectorXd constraint_motions_ref2 = Eigen::VectorXd::Zero(constraint_model.activeSize()); + constraint_model.jacobianMatrixProduct( + model, data_ref, constraint_data_ref, joint_motions, constraint_motions_ref2, SetTo()); + + Eigen::VectorXd constraint_motions = -Eigen::VectorXd::Ones(constraint_model.activeSize()); + constraint_model.mapJointMotionsToConstraintMotion( + model, data_ref, constraint_data, joint_motions, constraint_motions); + + BOOST_CHECK(constraint_motions.isApprox(constraint_motions_ref)); + BOOST_CHECK(constraint_motions.isApprox(constraint_motions_ref2)); + } +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/joint-generic.cpp b/unittest/joint-generic.cpp index 1f993b7bb7..ae3f9aad94 100644 --- a/unittest/joint-generic.cpp +++ b/unittest/joint-generic.cpp @@ -47,6 +47,10 @@ void test_joint_methods( BOOST_CHECK(jma == jmodel); BOOST_CHECK(jma.hasSameIndexes(jmodel)); + typedef typename LieGroupMap::template operationProduct< + typename JointModel::Scalar, JointModel::Options>::type PV; + BOOST_CHECK(PV(jmodel.template lieGroup()) == jma.template lieGroup()); + pinocchio::JointData jda(jdata.derived()); BOOST_CHECK(jda == jdata); BOOST_CHECK(jdata == jda); @@ -242,7 +246,6 @@ struct init> static JointModel run() { - typedef typename JointModel::Vector3 Vector3; JointModel jmodel(XAxis::vector(), YAxis::vector()); jmodel.setIndexes(0, 0, 0); @@ -352,7 +355,7 @@ namespace pinocchio typedef Eigen::Matrix ConfigVector_t; typedef Eigen::Matrix TangentVector_t; - typedef boost::mpl::false_ is_mimicable_t; + typedef std::false_type is_mimicable_t; }; template class JointCollectionTpl> diff --git a/unittest/joint-limit-constraint.cpp b/unittest/joint-limit-constraint.cpp new file mode 100644 index 0000000000..9740f77559 --- /dev/null +++ b/unittest/joint-limit-constraint.cpp @@ -0,0 +1,398 @@ +// +// Copyright (c) 2024 INRIA +// + +#include "utils/model-generator.hpp" +#include "pinocchio/algorithm/kinematics.hpp" +#include "pinocchio/algorithm/constraints/joint-limit-constraint.hpp" +#include "pinocchio/algorithm/joint-configuration.hpp" +#include "pinocchio/multibody/sample-models.hpp" + +// Helpers +#include "constraints/jacobians-checker.hpp" + +#include + +#include +#include + +using namespace pinocchio; +typedef JointLimitConstraintModel::EigenIndexVector EigenIndexVector; +typedef JointLimitConstraintModel::BooleanVector BooleanVector; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(constraint_empty_constructor) +{ + Model model; + buildAllJointsModel(model); + + const Data data(model); + + const Model::IndexVector empty_activable_joint_ids; + + JointLimitConstraintModel constraint(model, empty_activable_joint_ids); +} + +BOOST_AUTO_TEST_CASE(constraint_constructor_with_infinite_bounds) +{ + Model model; + buildAllJointsModel(model); + + model.lowerPositionLimit.fill(-std::numeric_limits::max()); + model.upperPositionLimit.fill(+std::numeric_limits::max()); + + const Data data(model); + + const std::string ee_name = "translation_joint"; + const JointIndex ee_id = model.getJointId(ee_name); + + const Model::IndexVector & ee_support = model.supports[ee_id]; + const Model::IndexVector activable_joint_ids(ee_support.begin() + 1, ee_support.end()); + JointLimitConstraintModel constraint(model, activable_joint_ids); + + BOOST_CHECK(constraint.size() == 0); +} + +BOOST_AUTO_TEST_CASE(constraint_constructor) +{ + Model model; + buildAllJointsModel(model); + + Data data(model); + const auto & parents_fromRow = data.parents_fromRow; + + const std::string ee_name = "translation_joint"; + const JointIndex ee_id = model.getJointId(ee_name); + + const Model::IndexVector & ee_support = model.supports[ee_id]; + const Model::IndexVector activable_joint_ids(ee_support.begin() + 1, ee_support.end()); + + for (const JointIndex joint_id : activable_joint_ids) + { + const auto & jmodel = model.joints[joint_id]; + std::cout << "joint type: " << jmodel.shortname() << std::endl; + } + JointLimitConstraintModel constraint(model, activable_joint_ids); + + // Check size + { + int total_size = 0; + for (const JointIndex joint_id : activable_joint_ids) + { + const auto & jmodel = model.joints[joint_id]; + const int idx_q = jmodel.idx_q(); + const int nq = jmodel.nq(); + const auto has_configuration_limit = jmodel.hasConfigurationLimit(); + for (int k = 0; k < nq; ++k) + { + const int index_q = idx_q + k; + if (has_configuration_limit[k]) + { + if (model.lowerPositionLimit[index_q] != -std::numeric_limits::max()) + total_size++; + if (model.upperPositionLimit[index_q] != +std::numeric_limits::max()) + total_size++; + } + } + } + BOOST_CHECK(constraint.size() == total_size); + } + + // we set the margin to infinity so all limits are taken into account in what follows. + model.positionLimitMargin = + Eigen::VectorXd::Constant(model.nq, std::numeric_limits::max()); + constraint = JointLimitConstraintModel(model, activable_joint_ids); + JointLimitConstraintData constraint_data(constraint); + const Eigen::VectorXd q0 = randomConfiguration(model); + data.q_in = q0; + constraint.resize(model, data, constraint_data); + constraint.calc(model, data, constraint_data); + + // Check projection on force sets + { + const Eigen::DenseIndex nb_lower_active_dofs = Eigen::DenseIndex(constraint.lowerActiveSize()); + const Eigen::DenseIndex nb_upper_active_dofs = Eigen::DenseIndex(constraint.upperActiveSize()); + + const Eigen::DenseIndex total_active_dofs = nb_lower_active_dofs + nb_upper_active_dofs; + + const int num_projections = int(1e6); + for (int k = 0; k < num_projections; ++k) + { + const Eigen::VectorXd f = Eigen::VectorXd::Random(total_active_dofs); + const Eigen::VectorXd f_proj = constraint.set().project(f); + + BOOST_CHECK((f_proj.head(nb_lower_active_dofs).array() <= 0).all()); + BOOST_CHECK((f_proj.tail(nb_lower_active_dofs).array() >= 0).all()); + } + } +} + +BOOST_AUTO_TEST_CASE(cast) +{ + Model model; + buildAllJointsModel(model); + + const Data data(model); + + const std::string ee_name = "translation_joint"; + const JointIndex ee_id = model.getJointId(ee_name); + + const Model::IndexVector & ee_support = model.supports[ee_id]; + const Model::IndexVector active_joint_ids(ee_support.begin() + 1, ee_support.end()); + JointLimitConstraintModel cm(model, active_joint_ids); + + const auto cm_cast_double = cm.cast(); + BOOST_CHECK(cm_cast_double == cm); + + const auto cm_cast_long_double = cm.cast(); + BOOST_CHECK(cm_cast_long_double.cast() == cm); +} + +BOOST_AUTO_TEST_CASE(constraint_jacobian) +{ + Model model; + buildAllJointsModel(model); + + Data data(model); + + const std::string ee_name = "translation_joint"; + const JointIndex ee_id = model.getJointId(ee_name); + + const Model::IndexVector & ee_support = model.supports[ee_id]; + const Model::IndexVector activable_joint_ids(ee_support.begin() + 1, ee_support.end()); + + // we set the margin to infinity so all limits are taken into account in what follows. + model.positionLimitMargin = + Eigen::VectorXd::Constant(model.nq, std::numeric_limits::max()); + + JointLimitConstraintModel constraint_model(model, activable_joint_ids); + JointLimitConstraintData constraint_data(constraint_model); + + // Check against finite differences on the drift of the constraint + const double eps_fd = 1e-8; + for (int i = 0; i < 1e4; ++i) + { + const Eigen::VectorXd q0 = randomConfiguration(model); + data.q_in = q0; + constraint_model.resize(model, data, constraint_data); + constraint_model.calc(model, data, constraint_data); + + Eigen::MatrixXd jacobian_matrix(constraint_model.activeSize(), model.nv); + constraint_model.jacobian(model, data, constraint_data, jacobian_matrix); + Data data_fd(model); + JointLimitConstraintData constraint_data_fd(constraint_model); + Eigen::MatrixXd jacobian_matrix_fd(constraint_model.activeSize(), model.nv); + + for (Eigen::DenseIndex k = 0; k < model.nv; ++k) + { + Eigen::VectorXd v_eps = Eigen::VectorXd::Zero(model.nv); + v_eps[k] = eps_fd; + const Eigen::VectorXd q_plus = integrate(model, q0, v_eps); + data_fd.q_in = q_plus; + + constraint_model.resize(model, data_fd, constraint_data_fd); + constraint_model.calc(model, data_fd, constraint_data_fd); + + jacobian_matrix_fd.col(k) = + (constraint_data_fd.constraint_residual - constraint_data.constraint_residual) / eps_fd; + } + + BOOST_CHECK(jacobian_matrix.isApprox(jacobian_matrix_fd, math::sqrt(eps_fd))); + } + + check_jacobians_operations(model, data, constraint_model, constraint_data); +} + +BOOST_AUTO_TEST_CASE(dynamic_constraint_residual) +{ + Model model; + buildAllJointsModel(model); + + model.gravity.setZero(); + model.lowerPositionLimit.fill(0.); + const Eigen::VectorXd qmin(Eigen::VectorXd::Zero(model.nq)); + const Eigen::VectorXd qmax(Eigen::VectorXd::Ones(model.nq)); + // We deactivate the upper limits + model.upperPositionLimit.fill(std::numeric_limits::max()); + model.positionLimitMargin = Eigen::VectorXd::Constant(model.nq, .5); + + Data data(model); + + int total_size = 0; + Model::IndexVector activable_joint_ids; + for (Model::JointIndex i = 1; i < (Model::JointIndex)model.njoints; ++i) + { + activable_joint_ids.push_back(i); + + const auto & jmodel = model.joints[i]; + const int nq = jmodel.nq(); + const auto has_configuration_limit = jmodel.hasConfigurationLimit(); + for (int k = 0; k < nq; ++k) + { + if (has_configuration_limit[size_t(k)]) + total_size++; + } + } + + JointLimitConstraintModel constraint_model(model, activable_joint_ids); + BOOST_CHECK(constraint_model.size() == total_size); + JointLimitConstraintData constraint_data(constraint_model); + + for (int i = 0; i < 1e4; ++i) + { + const Eigen::VectorXd q0 = randomConfiguration(model, qmin, qmax); + std::size_t active_size = 0; + std::vector active_indexes; + Eigen::VectorXd activable_residual(constraint_model.size()); + + int set_idx = 0; + for (Model::JointIndex i = 1; i < (Model::JointIndex)model.njoints; ++i) + { + const auto & jmodel = model.joints[i]; + const int idx_q = jmodel.idx_q(); + const int nq = jmodel.nq(); + + const auto has_configuration_limit = jmodel.hasConfigurationLimit(); + for (int k = 0; k < nq; ++k) + { + if (!has_configuration_limit[size_t(k)]) + continue; + const int q_index = idx_q + k; + activable_residual(set_idx) = -(q0(q_index) - model.lowerPositionLimit[q_index]); + if (-activable_residual(set_idx) < model.positionLimitMargin[q_index]) + { + active_size++; + active_indexes.push_back((std::size_t)set_idx); + } + set_idx++; + } + } + BOOST_CHECK(constraint_model.size() == set_idx); + + Eigen::VectorXd residual(active_size); + for (std::size_t j = 0; j < active_size; j++) + { + residual((Eigen::Index)j) = activable_residual((Eigen::Index)active_indexes[j]); + } + + data.q_in = q0; + constraint_model.resize(model, data, constraint_data); + constraint_model.calc(model, data, constraint_data); + BOOST_CHECK((int)active_size == constraint_model.activeSize()); + BOOST_CHECK((int)active_size == constraint_data.constraint_residual.size()); + BOOST_CHECK(constraint_data.constraint_residual.isApprox(residual)); + BOOST_CHECK(constraint_data.activable_constraint_residual.isApprox(activable_residual)); + BOOST_CHECK(active_indexes == constraint_model.getActiveSetIndexes()); + } +} + +BOOST_AUTO_TEST_CASE(dynamic_constraint_jacobian) +{ + Model model; + buildAllJointsModel(model); + + model.gravity.setZero(); + model.lowerPositionLimit.fill(0.); + const Eigen::VectorXd qmin(Eigen::VectorXd::Zero(model.nq)); + const Eigen::VectorXd qmax(Eigen::VectorXd::Ones(model.nq)); + // We deactivate the upper limits + model.upperPositionLimit.fill(std::numeric_limits::max()); + model.positionLimitMargin = Eigen::VectorXd::Constant(model.nq, .5); + + Data data(model); + + int total_size = 0; + Model::IndexVector activable_joint_ids; + for (Model::JointIndex i = 1; i < (Model::JointIndex)model.njoints; ++i) + { + activable_joint_ids.push_back(i); + + const auto & jmodel = model.joints[i]; + const int nq = jmodel.nq(); + const auto has_configuration_limit = jmodel.hasConfigurationLimit(); + for (int k = 0; k < nq; ++k) + { + if (has_configuration_limit[size_t(k)]) + total_size++; + } + } + + JointLimitConstraintModel constraint_model(model, activable_joint_ids); + BOOST_CHECK(constraint_model.size() == total_size); + JointLimitConstraintData constraint_data(constraint_model); + + const double eps_fd = 1e-8; + for (int i = 0; i < 1e4; ++i) + { + const Eigen::VectorXd q0 = randomConfiguration(model, qmin, qmax); + int active_size = 0; + std::vector active_indexes; + Eigen::VectorXd activable_residual(constraint_model.size()); + + int set_idx = 0; + for (Model::JointIndex i = 1; i < (Model::JointIndex)model.njoints; ++i) + { + const auto & jmodel = model.joints[i]; + const int idx_q = jmodel.idx_q(); + const int nq = jmodel.nq(); + + const auto has_configuration_limit = jmodel.hasConfigurationLimit(); + for (int k = 0; k < nq; ++k) + { + if (!has_configuration_limit[size_t(k)]) + continue; + const int q_index = idx_q + k; + activable_residual(set_idx) = -(q0(q_index) - model.lowerPositionLimit[q_index]); + if (-activable_residual(set_idx) < model.positionLimitMargin[q_index]) + { + active_size++; + active_indexes.push_back((std::size_t)set_idx); + } + set_idx++; + } + } + BOOST_CHECK(constraint_model.size() == set_idx); + + data.q_in = q0; + constraint_model.resize(model, data, constraint_data); + constraint_model.calc(model, data, constraint_data); + + std::vector active_set_indexes = constraint_model.getActiveSetIndexes(); + BOOST_CHECK(active_size == constraint_model.activeSize()); + BOOST_CHECK(active_size == constraint_data.constraint_residual.size()); + + Eigen::MatrixXd jacobian_matrix(constraint_model.activeSize(), model.nv); + constraint_model.jacobian(model, data, constraint_data, jacobian_matrix); + + Data data_fd(model); + JointLimitConstraintData constraint_data_fd(constraint_model); + Eigen::MatrixXd jacobian_matrix_fd(constraint_model.activeSize(), model.nv); + + bool ok_to_check = true; + for (Eigen::DenseIndex k = 0; k < model.nv; ++k) + { + Eigen::VectorXd v_eps = Eigen::VectorXd::Zero(model.nv); + v_eps[k] = eps_fd; + const Eigen::VectorXd q_plus = integrate(model, q0, v_eps); + data_fd.q_in = q_plus; + constraint_model.resize(model, data_fd, constraint_data_fd); + constraint_model.calc(model, data_fd, constraint_data_fd); + bool same_active_set = active_set_indexes == constraint_model.getActiveSetIndexes(); + // if the active set is identical we can check the jacobian + if (!same_active_set) + { + ok_to_check = false; + continue; + } + jacobian_matrix_fd.col(k) = + (constraint_data_fd.constraint_residual - constraint_data.constraint_residual) / eps_fd; + BOOST_CHECK(jacobian_matrix.col(k).isApprox(jacobian_matrix_fd.col(k), math::sqrt(eps_fd))); + } + + if (ok_to_check) + BOOST_CHECK(jacobian_matrix.isApprox(jacobian_matrix_fd, math::sqrt(eps_fd))); + } +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/joint-universal.cpp b/unittest/joint-universal.cpp index 260432f675..b5b0f94c59 100644 --- a/unittest/joint-universal.cpp +++ b/unittest/joint-universal.cpp @@ -124,7 +124,6 @@ BOOST_AUTO_TEST_CASE(vsRXRY) BOOST_AUTO_TEST_CASE(vsRandomAxis) { typedef SE3::Vector3 Vector3; - typedef SE3::Matrix3 Matrix3; Vector3 axis1; axis1 << 0., 0., 1.; diff --git a/unittest/joint-visitors.cpp b/unittest/joint-visitors.cpp new file mode 100644 index 0000000000..886a9ed9be --- /dev/null +++ b/unittest/joint-visitors.cpp @@ -0,0 +1,32 @@ +// +// Copyright (c) 2024 INRIA +// + +#include "pinocchio/multibody/model.hpp" +#include "pinocchio/multibody/data.hpp" +#include "pinocchio/multibody/joint/joint-basic-visitors.hpp" +#include "pinocchio/multibody/joint/joint-generic.hpp" + +#include + +#include +#include + +namespace bf = boost::fusion; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(test_check_joint_type) +{ + using namespace pinocchio; + + const JointModel jmodel_rx = JointModelRX(); + const JointModel jmodel_px = JointModelPX(); + + typedef boost::mpl::vector JointModelSequence; + + BOOST_CHECK(check_joint_type_within_sequence(jmodel_rx) == true); + BOOST_CHECK(check_joint_type_within_sequence(jmodel_px) == false); +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/kinematics-derivatives.cpp b/unittest/kinematics-derivatives.cpp index 9caa2b5a35..df306d2eda 100644 --- a/unittest/kinematics-derivatives.cpp +++ b/unittest/kinematics-derivatives.cpp @@ -1,5 +1,6 @@ // -// Copyright (c) 2017-2020 CNRS INRIA +// Copyright (c) 2017-2020 CNRS +// Copyright (c) 2018-2024 INRIA // #include @@ -68,7 +69,7 @@ BOOST_AUTO_TEST_CASE(test_kinematics_derivatives_velocity) VectorXd v(VectorXd::Random(model.nv)); VectorXd a(VectorXd::Random(model.nv)); - computeForwardKinematicsDerivatives(model, data, q, v, a); + computeForwardKinematicsDerivatives(model, data, q, v); const Model::JointIndex jointId = model.existJointName("rarm2_joint") ? model.getJointId("rarm2_joint") diff --git a/unittest/kinematics.cpp b/unittest/kinematics.cpp index db21b9c3c0..185afcbdd7 100644 --- a/unittest/kinematics.cpp +++ b/unittest/kinematics.cpp @@ -361,7 +361,7 @@ BOOST_AUTO_TEST_CASE(test_kinematics_mimic) pinocchio::Data dataFKRed(model_mimic); pinocchio::forwardKinematics(model_mimic, dataFKRed, q, v, a); - for (int i = 0; i < model_full.njoints; i++) + for (pinocchio::JointIndex i = 0; i < pinocchio::JointIndex(model_full.njoints); i++) { BOOST_CHECK(dataFKRed.oMi[i].isApprox(dataFKFull.oMi[i])); BOOST_CHECK(dataFKRed.liMi[i].isApprox(dataFKFull.liMi[i])); diff --git a/unittest/lanczos-decomposition.cpp b/unittest/lanczos-decomposition.cpp index 8820eea701..b9cb5190c5 100644 --- a/unittest/lanczos-decomposition.cpp +++ b/unittest/lanczos-decomposition.cpp @@ -1,10 +1,15 @@ // -// Copyright (c) 2024 INRIA +// Copyright (c) 2024-2025 INRIA // #include -#include +#include "pinocchio/math/lanczos-decomposition.hpp" +#include "pinocchio/algorithm/delassus-operator-dense.hpp" +#include "pinocchio/algorithm/contact-cholesky.hpp" +#include "pinocchio/algorithm/crba.hpp" +#include "pinocchio/algorithm/diagonal-preconditioner.hpp" +#include "pinocchio/algorithm/delassus-operator-preconditioned.hpp" #include // to avoid C99 warnings @@ -15,6 +20,25 @@ BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) using namespace pinocchio; +int line; +#define SET_LINE line = __LINE__ + 1 +#define PINOCCHIO_CHECK(cond) BOOST_CHECK_MESSAGE(cond, "from line " << line << ": " #cond) +#define PINOCCHIO_CHECK_EQUAL(a, b) \ + BOOST_CHECK_MESSAGE( \ + (a) == (b), "from line " << line << ": " #a "[" << (a) << "] != " #b "[" << (b) << "].") + +BOOST_AUTO_TEST_CASE(test_basic_constructor) +{ + const Eigen::DenseIndex mat_size = 20; + const Eigen::DenseIndex decomposition_size = 10; + + typedef LanczosDecompositionTpl LanczosDecomposition; + LanczosDecomposition lanczos_decomposition(mat_size, decomposition_size); + + BOOST_CHECK(lanczos_decomposition.size() == mat_size); + BOOST_CHECK(lanczos_decomposition.decompositionSize() == decomposition_size); +} + BOOST_AUTO_TEST_CASE(test_identity) { const Eigen::DenseIndex mat_size = 20; @@ -26,10 +50,7 @@ BOOST_AUTO_TEST_CASE(test_identity) const auto residual = lanczos_decomposition.computeDecompositionResidual(identity_matrix); BOOST_CHECK(residual.isZero()); - BOOST_CHECK(lanczos_decomposition.rank() == 1); - BOOST_CHECK((lanczos_decomposition.Qs().transpose() * lanczos_decomposition.Qs()) - .topLeftCorner(lanczos_decomposition.rank(), lanczos_decomposition.rank()) - .isIdentity()); + BOOST_CHECK((lanczos_decomposition.Qs().transpose() * lanczos_decomposition.Qs()).isIdentity()); } BOOST_AUTO_TEST_CASE(test_diagonal_matrix) @@ -49,10 +70,32 @@ BOOST_AUTO_TEST_CASE(test_diagonal_matrix) BOOST_CHECK(math::fabs(lanczos_decomposition.Qs().col(col_id).norm() - 1.) <= 1e-12); } - BOOST_CHECK(lanczos_decomposition.rank() == lanczos_decomposition.Ts().cols()); BOOST_CHECK((lanczos_decomposition.Qs().transpose() * lanczos_decomposition.Qs()).isIdentity()); } +void checkDecomposition( + const LanczosDecompositionTpl & lanczos_decomposition, + const Eigen::MatrixXd & matrix) +{ + const auto residual = lanczos_decomposition.computeDecompositionResidual(matrix); + + const auto & Ts = lanczos_decomposition.Ts(); + const auto & Qs = lanczos_decomposition.Qs(); + const Eigen::MatrixXd residual_bis = matrix * Qs - Qs * Ts.matrix(); + const Eigen::MatrixXd residual_tierce = Qs.transpose() * matrix * Qs - Ts.matrix(); + const Eigen::MatrixXd residual_fourth = matrix - Qs * Ts.matrix() * Qs.transpose(); + PINOCCHIO_CHECK(residual.isZero(1e-10)); + + const auto size = lanczos_decomposition.decompositionSize(); + + for (Eigen::DenseIndex col_id = 0; col_id < size; ++col_id) + { + PINOCCHIO_CHECK(math::fabs(lanczos_decomposition.Qs().col(col_id).norm() - 1.) <= 1e-12); + } + + PINOCCHIO_CHECK((Qs.transpose() * Qs).isIdentity()); +} + BOOST_AUTO_TEST_CASE(test_random) { typedef LanczosDecompositionTpl LanczosDecomposition; @@ -65,22 +108,221 @@ BOOST_AUTO_TEST_CASE(test_random) LanczosDecomposition lanczos_decomposition(matrix, 10); - const auto residual = lanczos_decomposition.computeDecompositionResidual(matrix); + SET_LINE; + checkDecomposition(lanczos_decomposition, matrix); + } +} - const auto & Ts = lanczos_decomposition.Ts(); - const auto & Qs = lanczos_decomposition.Qs(); - const Eigen::MatrixXd residual_bis = matrix * Qs - Qs * Ts.matrix(); - const Eigen::MatrixXd residual_tierce = Qs.transpose() * matrix * Qs - Ts.matrix(); - const Eigen::MatrixXd residual_fourth = matrix - Qs * Ts.matrix() * Qs.transpose(); - BOOST_CHECK(residual.isZero()); +BOOST_AUTO_TEST_CASE(test_low_rank) +{ + typedef LanczosDecompositionTpl LanczosDecomposition; + const Eigen::DenseIndex mat_size = 20; + Eigen::MatrixXd A = Eigen::MatrixXd::Identity(mat_size, mat_size); + A.row(mat_size - 1).setZero(); + A.col(mat_size - 1).setZero(); - for (Eigen::DenseIndex col_id = 0; col_id < lanczos_decomposition.Ts().cols(); ++col_id) + LanczosDecomposition lanczos_decomposition_10(A, 10); + SET_LINE; + checkDecomposition(lanczos_decomposition_10, A); +} + +BOOST_AUTO_TEST_CASE(test_delassus) +{ + typedef LanczosDecompositionTpl LanczosDecomposition; + const Eigen::DenseIndex mat_size = 20; + + for (int it = 0; it < 1000; ++it) + { + const Eigen::MatrixXd A = Eigen::MatrixXd::Random(mat_size, mat_size); + const Eigen::MatrixXd matrix = A.transpose() * A; + + DelassusOperatorDense delassus(matrix); + + LanczosDecomposition lanczos_decomposition(delassus, 10); + + SET_LINE; + checkDecomposition(lanczos_decomposition, matrix); + } +} + +void buildStackOfCubeModel( + std::vector masses, + ::pinocchio::Model & model, + std::vector & constraint_models) +{ + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + const int n_cubes = (int)masses.size(); + + for (int i = 0; i < n_cubes; i++) + { + const double box_mass = masses[(std::size_t)i]; + const Inertia box_inertia = Inertia::FromBox(box_mass, box_dims[0], box_dims[1], box_dims[2]); + JointIndex joint_id = + model.addJoint(0, JointModelFreeFlyer(), SE3::Identity(), "free_flyer_" + std::to_string(i)); + model.appendBodyToJoint(joint_id, box_inertia); + } + + const double friction_value = 0.4; + for (int i = 0; i < n_cubes; i++) + { + const SE3 local_placement_box_1( + SE3::Matrix3::Identity(), 0.5 * SE3::Vector3(box_dims[0], box_dims[1], box_dims[2])); + const SE3 local_placement_box_2( + SE3::Matrix3::Identity(), 0.5 * SE3::Vector3(box_dims[0], box_dims[1], -box_dims[2])); + SE3::Matrix3 rot = SE3::Matrix3::Identity(); + for (int j = 0; j < 4; ++j) { - BOOST_CHECK(math::fabs(lanczos_decomposition.Qs().col(col_id).norm() - 1.) <= 1e-12); + const SE3 local_placement_1( + SE3::Matrix3::Identity(), rot * local_placement_box_1.translation()); + const SE3 local_placement_2( + SE3::Matrix3::Identity(), rot * local_placement_box_2.translation()); + FrictionalPointConstraintModel cm( + model, (JointIndex)i, local_placement_1, (JointIndex)i + 1, local_placement_2); + cm.set() = CoulombFrictionCone(friction_value); + constraint_models.push_back(cm); + rot = Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ()).toRotationMatrix() * rot; } - // Check orthonormality - BOOST_CHECK(lanczos_decomposition.rank() == lanczos_decomposition.Ts().cols()); - BOOST_CHECK((lanczos_decomposition.Qs().transpose() * lanczos_decomposition.Qs()).isIdentity()); + } +} + +BOOST_AUTO_TEST_CASE(test_delassus_cube) +{ + typedef LanczosDecompositionTpl LanczosDecomposition; + ::pinocchio::Model model; + typedef FrictionalPointConstraintModel ConstraintModel; + typedef typename ConstraintModel::ConstraintData ConstraintData; + std::vector constraint_models; + + const double box_mass = 10; + std::vector masses = {box_mass}; + + buildStackOfCubeModel(masses, model, constraint_models); + + BOOST_CHECK(model.check(model.createData())); + + Data data(model); + + Eigen::VectorXd q0 = neutral(model); + + crba(model, data, q0, Convention::WORLD); + ContactCholeskyDecomposition chol(model, constraint_models); + std::vector constraint_datas; + for (const auto & cm : constraint_models) + { + constraint_datas.push_back(cm.createData()); + } + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + + const Eigen::MatrixXd delassus_matrix_plain = chol.getDelassusCholeskyExpression().matrix(true); + auto G_expression = chol.getDelassusCholeskyExpression(); + + BOOST_CHECK(delassus_matrix_plain.isApprox(delassus_matrix_plain.transpose(), 0)); + + // Eigen::SelfAdjointEigenSolver eigensolver(delassus_matrix_plain); + // std::cout << "The eigenvalues of delassus_matrix_plain are:\n" << + // eigensolver.eigenvalues().transpose() << std::endl; + + for (int decomposition_size = 3; decomposition_size <= delassus_matrix_plain.rows(); + ++decomposition_size) + { + LanczosDecomposition lanczos_decomposition(G_expression, decomposition_size); + SET_LINE; + checkDecomposition(lanczos_decomposition, delassus_matrix_plain); + } + + // { + // LanczosDecomposition lanczos_decomposition(G_expression, 7); + // SET_LINE; + // checkDecomposition(lanczos_decomposition, delassus_matrix_plain); + // } + + Eigen::VectorXd mean_inertia = + Eigen::VectorXd::Constant(delassus_matrix_plain.rows(), data.M.diagonal().trace()); + mean_inertia /= (double)delassus_matrix_plain.rows(); + mean_inertia = mean_inertia.array().sqrt(); + typedef DiagonalPreconditionerTpl Preconditionner; + Preconditionner diag_preconditioner(mean_inertia); + DelassusOperatorPreconditionedTpl< + DelassusCholeskyExpressionTpl, Preconditionner> + delassus_preconditioned(G_expression, diag_preconditioner); + + const Eigen::MatrixXd delassus_preconditioned_matrix_plain = delassus_preconditioned.matrix(true); + + for (int decomposition_size = 3; decomposition_size <= delassus_matrix_plain.rows(); + ++decomposition_size) + { + LanczosDecomposition lanczos_decomposition(delassus_preconditioned, decomposition_size); + SET_LINE; + checkDecomposition(lanczos_decomposition, delassus_preconditioned_matrix_plain); + } +} + +BOOST_AUTO_TEST_CASE(test_delassus_light_cube) +{ + typedef LanczosDecompositionTpl LanczosDecomposition; + ::pinocchio::Model model; + typedef FrictionalPointConstraintModel ConstraintModel; + typedef typename ConstraintModel::ConstraintData ConstraintData; + std::vector constraint_models; + + const double box_mass = 1e-3; + std::vector masses = {box_mass}; + + buildStackOfCubeModel(masses, model, constraint_models); + + BOOST_CHECK(model.check(model.createData())); + + Data data(model); + + Eigen::VectorXd q0 = neutral(model); + + crba(model, data, q0, Convention::WORLD); + ContactCholeskyDecomposition chol(model, constraint_models); + std::vector constraint_datas; + for (const auto & cm : constraint_models) + { + constraint_datas.push_back(cm.createData()); + } + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + + const Eigen::MatrixXd delassus_matrix_plain = chol.getDelassusCholeskyExpression().matrix(true); + auto G_expression = chol.getDelassusCholeskyExpression(); + + BOOST_CHECK(delassus_matrix_plain.isApprox(delassus_matrix_plain.transpose(), 0)); + + for (int decomposition_size = 3; decomposition_size <= 6; ++decomposition_size) + { + LanczosDecomposition lanczos_decomposition(G_expression, decomposition_size); + SET_LINE; + checkDecomposition(lanczos_decomposition, delassus_matrix_plain); + } +} + +BOOST_AUTO_TEST_CASE(test_delassus_preconditioned) +{ + typedef LanczosDecompositionTpl LanczosDecomposition; + const Eigen::DenseIndex mat_size = 20; + + for (int it = 0; it < 1000; ++it) + { + const Eigen::MatrixXd A = Eigen::MatrixXd::Random(mat_size, mat_size); + const Eigen::MatrixXd matrix = A.transpose() * A; + + Eigen::VectorXd diag_vec = Eigen::VectorXd::Constant(mat_size, 1e-6); + Eigen::MatrixXd preconditioner_diag = diag_vec.asDiagonal(); + const Eigen::MatrixXd matrix_preconditioned = + preconditioner_diag * matrix * preconditioner_diag; + + DelassusOperatorDense delassus(matrix); + typedef DiagonalPreconditionerTpl Preconditionner; + Preconditionner diag_preconditioner(diag_vec); + DelassusOperatorPreconditionedTpl + delassus_preconditioned(delassus, diag_preconditioner); + + LanczosDecomposition lanczos_decomposition(delassus_preconditioned, 10); + + SET_LINE; + checkDecomposition(lanczos_decomposition, matrix_preconditioned); } } diff --git a/unittest/liegroups.cpp b/unittest/liegroups.cpp index 3249470680..0e1b23ca02 100644 --- a/unittest/liegroups.cpp +++ b/unittest/liegroups.cpp @@ -567,6 +567,100 @@ struct LieGroup_JintegrateCoeffWise } }; +template +struct LieGroup_TangentMap +{ + template + void operator()(const T) const + { + typedef typename T::ConfigVector_t ConfigVector_t; + typedef typename T::TangentVector_t TangentVector_t; + typedef typename T::JacobianMatrix_t JacobianMatrix_t; + typedef typename T::TangentMapMatrix_t TangentMapMatrix_t; + typedef typename T::Scalar Scalar; + + T lg; + ConfigVector_t q = lg.random(); + TangentVector_t v, dq, dv; + ConfigVector_t dI_eucl, dq_ps; + + if (around_identity) + v.setZero(); + else + v.setRandom(); + + dv.setZero(); + dq.setZero(); + dv.setZero(); + dq_ps.setZero(); + + ConfigVector_t q_p_v = lg.integrate(q, v); + + PINOCCHIO_COMPILER_DIAGNOSTIC_PUSH + PINOCCHIO_COMPILER_DIAGNOSTIC_IGNORED_MAYBE_UNINITIALIZED + JacobianMatrix_t Jq, Jv; + lg.dIntegrate_dq(q, v, Jq); + lg.dIntegrate_dv(q, v, Jv); + + TangentMapMatrix_t TM_q_p_v, Jq_eucl, Jv_eucl, Jq_eucl_p, Jv_eucl_p; + lg.tangentMap(q_p_v, TM_q_p_v); + Jq_eucl = TM_q_p_v * Jq; + Jv_eucl = TM_q_p_v * Jv; + lg.tangentMapProduct(q_p_v, Jq, Jq_eucl_p); + lg.tangentMapProduct(q_p_v, Jv, Jv_eucl_p); + PINOCCHIO_COMPILER_DIAGNOSTIC_POP + + EIGEN_VECTOR_IS_APPROX(Jq_eucl_p, Jq_eucl, 1e-6); + EIGEN_VECTOR_IS_APPROX(Jv_eucl_p, Jv_eucl, 1e-6); + + const Scalar eps = 1e-6; + for (int i = 0; i < v.size(); ++i) + { + dq[i] = dv[i] = eps; + + // wrt q + ConfigVector_t q_dq = lg.integrate(q, dq); + ConfigVector_t q_dq_p_v = lg.integrate(q_dq, v); + + ConfigVector_t Jq_eucl_col = Jq_eucl.col(i); + ConfigVector_t Jq_eucl_fd = (q_dq_p_v - q_p_v) / eps; + EIGEN_VECTOR_IS_APPROX(Jq_eucl_col, Jq_eucl_fd, 1e-2); + + // wrt v + ConfigVector_t q_p_v_dv = lg.integrate(q, (v + dv).eval()); + + ConfigVector_t Jv_eucl_col = Jv_eucl.col(i); + ConfigVector_t Jv_eucl_fd = (q_p_v_dv - q_p_v) / eps; + EIGEN_VECTOR_IS_APPROX(Jv_eucl_col, Jv_eucl_fd, 1e-2); + + dq[i] = dv[i] = 0; + } + for (int i = 0; i < v.size(); ++i) + { + dv[i] = Scalar(1.); + + // wrt q + ConfigVector_t manual_prod = TM_q_p_v * dv; + ConfigVector_t prod; + lg.tangentMapProduct(q_p_v, dv, prod); + EIGEN_VECTOR_IS_APPROX(prod, manual_prod, 1e-6); + + dv[i] = Scalar(0.); + } + for (int i = 0; i < q.size(); ++i) + { + dq_ps[i] = Scalar(1.); + + TangentVector_t manual_co_prod = TM_q_p_v.transpose() * dq_ps; + TangentVector_t co_prod; + lg.tangentMapTransposeProduct(q_p_v, dq_ps, co_prod); + EIGEN_VECTOR_IS_APPROX(co_prod, manual_co_prod, 1e-6); + + dq_ps[i] = Scalar(0.); + } + } +}; + BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) BOOST_AUTO_TEST_CASE(test_all) @@ -725,6 +819,34 @@ BOOST_AUTO_TEST_CASE(JintegrateCoeffWise) } } +BOOST_AUTO_TEST_CASE(tangentMap) +{ + typedef double Scalar; + enum + { + Options = 0 + }; + + typedef boost::mpl::vector< + VectorSpaceOperationTpl<1, Scalar, Options>, VectorSpaceOperationTpl<2, Scalar, Options>, + SpecialOrthogonalOperationTpl<2, Scalar, Options>, + SpecialOrthogonalOperationTpl<3, Scalar, Options>, + SpecialEuclideanOperationTpl<2, Scalar, Options>, + SpecialEuclideanOperationTpl<3, Scalar, Options>, + CartesianProductOperation< + VectorSpaceOperationTpl<2, Scalar, Options>, + SpecialOrthogonalOperationTpl<2, Scalar, Options>>, + CartesianProductOperation< + VectorSpaceOperationTpl<3, Scalar, Options>, + SpecialOrthogonalOperationTpl<3, Scalar, Options>>> + Types; + for (int i = 0; i < 20; ++i) + { + boost::mpl::for_each(LieGroup_TangentMap()); + boost::mpl::for_each(LieGroup_TangentMap()); + } +} + BOOST_AUTO_TEST_CASE(test_vector_space) { typedef VectorSpaceOperationTpl<3, double> VSO_t; diff --git a/unittest/loop-constrained-aba.cpp b/unittest/loop-constrained-aba.cpp new file mode 100644 index 0000000000..caf6a6cf31 --- /dev/null +++ b/unittest/loop-constrained-aba.cpp @@ -0,0 +1,886 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#include + +#include "pinocchio/algorithm/frames.hpp" +#include "pinocchio/algorithm/jacobian.hpp" +#include "pinocchio/algorithm/contact-info.hpp" +#include "pinocchio/algorithm/proximal.hpp" +#include "pinocchio/algorithm/constrained-dynamics.hpp" +#include "pinocchio/algorithm/contact-dynamics.hpp" +#include "pinocchio/algorithm/joint-configuration.hpp" +#include "pinocchio/multibody/sample-models.hpp" +#include "pinocchio/spatial/classic-acceleration.hpp" +#include "pinocchio/algorithm/loop-constrained-aba.hpp" + +#include +#include + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +using namespace pinocchio; +using namespace Eigen; + +void build_trident_model(Model & model) +{ + + Inertia I1 = Inertia::Random(); + Inertia I2 = Inertia::Random(); + model.gravity.linear() = model.gravity981; + + JointModel branch_connector = JointModelRX(); + + JointIndex joint0 = model.addJoint(0, JointModelFreeFlyer(), SE3::Random(), "joint0"); + model.appendBodyToJoint(joint0, I1, SE3::Random()); + + int num_children = 10; + + JointIndex parent_id; + std::string joint_name; + JointIndex mid_chain_joint; + + JointIndex joint1 = model.addJoint(joint0, branch_connector, SE3::Random(), "joint1"); + parent_id = joint1; + model.appendBodyToJoint(joint1, I1, SE3::Random()); + for (int k = 1; k <= num_children; ++k) + { + joint_name = "joint1" + std::to_string(k); + parent_id = model.addJoint(parent_id, JointModelRX(), SE3::Random(), joint_name); + model.appendBodyToJoint(parent_id, Inertia::Random(), SE3::Random()); + + if (k == 3) + mid_chain_joint = parent_id; + } + + JointIndex joint2 = model.addJoint(mid_chain_joint, branch_connector, SE3::Random(), "joint2"); + parent_id = joint2; + model.appendBodyToJoint(joint2, I2, SE3::Random()); + for (int k = 1; k <= num_children; ++k) + { + joint_name = "joint2" + std::to_string(k); + parent_id = model.addJoint(parent_id, JointModelRX(), SE3::Random(), joint_name); + model.appendBodyToJoint(parent_id, Inertia::Random(), SE3::Random()); + + if (k == 3) + mid_chain_joint = parent_id; + } + + JointIndex joint3 = model.addJoint(mid_chain_joint, branch_connector, SE3::Random(), "joint3"); + parent_id = joint3; + model.appendBodyToJoint(joint3, Inertia::Random(), SE3::Random()); + for (int k = 1; k <= num_children; ++k) + { + joint_name = "joint3" + std::to_string(k); + parent_id = model.addJoint(parent_id, JointModelRX(), SE3::Random(), joint_name); + model.appendBodyToJoint(parent_id, Inertia::Random(), SE3::Random()); + } + + model.lowerPositionLimit.fill(-5.); + model.upperPositionLimit.fill(5.); +} + +BOOST_AUTO_TEST_CASE(test_6D_unconstrained) +{ + Model model; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + const double mu0 = 1e-3; + ProximalSettings prox_settings_ref(1e-14, mu0, 1); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-10)); +} + +BOOST_AUTO_TEST_CASE(test_6D_descendants) +{ + Model model; + + build_trident_model(model); + // model.gravity.setZero(); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint12"), model.getJointId("joint17"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + + const double mu0 = 1e-5; + ProximalSettings prox_settings_ref(1e-14, mu0, 100); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + + std::cout << "data_ref.ddq: " << data_ref.ddq.transpose() << std::endl; + std::cout << "data.ddq: " << data.ddq.transpose() << std::endl; + std::cout << "|| data_ref.ddq - data.ddq ||: " << (data_ref.ddq - data.ddq).norm() << std::endl; + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-8)); +} + +BOOST_AUTO_TEST_CASE(test_6D_descendants_reversed) +{ + Model model; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) ConstraintModelVector; + typedef PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) ConstraintDataVector; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + ConstraintModelVector contact_models, contact_models_reversed; + ConstraintDataVector contact_datas, contact_datas_ref, contact_datas_reversed, + contact_datas_reversed_ref; + + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint12"), model.getJointId("joint17"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + contact_datas_ref.push_back(rcm1.createData()); + + const double mu0 = 1e-5; + ProximalSettings prox_settings_ref(1e-14, mu0, 100); + ProximalSettings prox_settings(prox_settings_ref), prox_settings_reversed(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + + std::cout << "prox_settings_ref.iter: " << prox_settings_ref.iter << std::endl; + std::cout << "prox_settings.iter: " << prox_settings.iter << std::endl; + std::cout << "data_ref.ddq: " << data_ref.ddq.transpose() << std::endl; + std::cout << "data.ddq: " << data.ddq.transpose() << std::endl; + std::cout << "|| data_ref.ddq - data.ddq ||: " << (data_ref.ddq - data.ddq).norm() << std::endl; + std::cout << "---" << std::endl; + + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-8)); + + // Check reversed + + Data data_reversed(model); + RigidConstraintModel rcm1_reversed = RigidConstraintModel( + CONTACT_6D, model, rcm1.joint2_id, rcm1.joint2_placement, rcm1.joint1_id, rcm1.joint1_placement, + LOCAL); + contact_models_reversed.push_back(rcm1_reversed); + contact_datas_reversed.push_back(rcm1_reversed.createData()); + contact_datas_reversed_ref.push_back(rcm1_reversed.createData()); + + initConstraintDynamics(model, data_ref, contact_models_reversed); + constraintDynamics( + model, data_ref, q, v, tau, contact_models_reversed, contact_datas_reversed_ref, + prox_settings_ref); + + computeJointMinimalOrdering(model, data_reversed, contact_models_reversed); + lcaba( + model, data_reversed, q, v, tau, contact_models_reversed, contact_datas_reversed, + prox_settings_reversed); + + std::cout << "prox_settings_ref.iter: " << prox_settings_ref.iter << std::endl; + std::cout << "prox_settings_reversed.iter: " << prox_settings_reversed.iter << std::endl; + std::cout << "data_reversed.ddq: " << data_reversed.ddq.transpose() << std::endl; + std::cout << "data_ref.ddq: " << data_ref.ddq.transpose() << std::endl; + std::cout << "data.ddq: " << data.ddq.transpose() << std::endl; + std::cout << "|| data_reversed.ddq - data.ddq ||: " << (data_reversed.ddq - data.ddq).norm() + << std::endl; + + BOOST_CHECK(data_reversed.ddq.isApprox(data.ddq, 1e-8)); + BOOST_CHECK(data_ref.ddq.isApprox(data_reversed.ddq, 1e-8)); + + // Check + for (JointIndex j = 1; j < size_t(model.njoints); ++j) + { + if (data.constraints_supported_dim[j] == 0) + BOOST_CHECK(data.neighbour_links[j].size() == 0); + } +} + +BOOST_AUTO_TEST_CASE(test_12D_descendants_redundant_reversed) +{ + Model model; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint12"), model.getJointId("joint27"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + + RigidConstraintModel rcm2 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint17"), model.getJointId("joint12"), LOCAL); + rcm2.joint1_placement.setRandom(); + rcm2.joint2_placement.setRandom(); + contact_models.push_back(rcm2); + contact_datas.push_back(rcm2.createData()); + + const double mu0 = 1e-3; + ProximalSettings prox_settings_ref(1e-12, mu0, 3); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-10)); +} + +BOOST_AUTO_TEST_CASE(test_6D_different_branches) +{ + Model model; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint210"), model.getJointId("joint38"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + + const double mu0 = 1e-3; + ProximalSettings prox_settings_ref(1e-12, mu0, 3); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-10)); +} + +BOOST_AUTO_TEST_CASE(test_12D_coupled_loop_common_link) +{ + Model model; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = pinocchio::randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint210"), model.getJointId("joint38"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + + RigidConstraintModel rcm2 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint38"), model.getJointId("joint18"), LOCAL); + rcm2.joint1_placement.setRandom(); + rcm2.joint2_placement.setRandom(); + contact_models.push_back(rcm2); + contact_datas.push_back(rcm2.createData()); + + const double mu0 = 1e-1; + ProximalSettings prox_settings_ref(1e-12, mu0, 3); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-10)); +} + +BOOST_AUTO_TEST_CASE(test_24D_coupling_with_double_ground) +{ + Model model; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = pinocchio::randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint1"), model.getJointId("joint14"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + + RigidConstraintModel rcm2 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint1"), model.getJointId("joint24"), LOCAL); + rcm2.joint1_placement.setRandom(); + rcm2.joint2_placement.setRandom(); + contact_models.push_back(rcm2); + contact_datas.push_back(rcm2.createData()); + + RigidConstraintModel rcm3 = + RigidConstraintModel(CONTACT_6D, model, model.getJointId("joint24"), LOCAL); + rcm3.joint1_placement.setRandom(); + rcm3.joint2_placement.setRandom(); + contact_models.push_back(rcm3); + contact_datas.push_back(rcm3.createData()); + + RigidConstraintModel rcm4 = + RigidConstraintModel(CONTACT_6D, model, model.getJointId("joint14"), LOCAL); + rcm4.joint1_placement.setRandom(); + rcm4.joint2_placement.setRandom(); + contact_models.push_back(rcm4); + contact_datas.push_back(rcm4.createData()); + + const double mu0 = 1e-1; + ProximalSettings prox_settings_ref(1e-12, mu0, 3); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-10)); +} + +BOOST_AUTO_TEST_CASE(test_6D_consecutive_links) +{ + Model model; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint14"), model.getJointId("joint15"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + + const double mu0 = 1e-3; + ProximalSettings prox_settings_ref(1e-12, mu0, 3); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-10)); +} + +BOOST_AUTO_TEST_CASE(test_12D_coupled_on_a_chain) +{ + Model model; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint12"), model.getJointId("joint19"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + + RigidConstraintModel rcm2 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint14"), model.getJointId("joint18"), LOCAL); + rcm2.joint1_placement.setRandom(); + rcm2.joint2_placement.setRandom(); + contact_models.push_back(rcm2); + contact_datas.push_back(rcm2.createData()); + + const double mu0 = 1e-3; + ProximalSettings prox_settings_ref(1e-12, mu0, 3); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-10)); +} + +BOOST_AUTO_TEST_CASE(test_12D_cross_coupled_on_a_chain) +{ + Model model; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint12"), model.getJointId("joint19"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + + RigidConstraintModel rcm2 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint14"), model.getJointId("joint18"), LOCAL); + rcm2.joint1_placement.setRandom(); + rcm2.joint2_placement.setRandom(); + contact_models.push_back(rcm2); + contact_datas.push_back(rcm2.createData()); + + const double mu0 = 1e-3; + ProximalSettings prox_settings_ref(1e-12, mu0, 3); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-10)); +} + +BOOST_AUTO_TEST_CASE(test_24D_cross_coupling) +{ + Model model; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint11"), model.getJointId("joint39"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + + RigidConstraintModel rcm2 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint21"), model.getJointId("joint38"), LOCAL); + rcm2.joint1_placement.setRandom(); + rcm2.joint2_placement.setRandom(); + contact_models.push_back(rcm2); + contact_datas.push_back(rcm2.createData()); + + RigidConstraintModel rcm3 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint19"), model.getJointId("joint29"), LOCAL); + rcm3.joint1_placement.setRandom(); + rcm3.joint2_placement.setRandom(); + contact_models.push_back(rcm3); + contact_datas.push_back(rcm3.createData()); + + RigidConstraintModel rcm4 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint29"), model.getJointId("joint39"), LOCAL); + rcm4.joint1_placement.setRandom(); + rcm4.joint2_placement.setRandom(); + contact_models.push_back(rcm4); + contact_datas.push_back(rcm4.createData()); + + const double mu0 = 1e-3; + ProximalSettings prox_settings_ref(1e-12, mu0, 3); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-10)); +} + +BOOST_AUTO_TEST_CASE(test_6D_cons_baumgarte) +{ + Model model; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = + RigidConstraintModel(CONTACT_6D, model, model.getJointId("joint11"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + rcm1.corrector.Kd.setIdentity(); + rcm1.corrector.Kp.setIdentity(); + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + + RigidConstraintModel rcm2 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint21"), model.getJointId("joint38"), LOCAL); + rcm2.joint1_placement.setRandom(); + rcm2.joint2_placement.setRandom(); + rcm2.corrector.Kd.setIdentity(); + rcm2.corrector.Kp.setIdentity(); + contact_models.push_back(rcm2); + contact_datas.push_back(rcm2.createData()); + + RigidConstraintModel rcm3 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint19"), model.getJointId("joint29"), LOCAL); + rcm3.joint1_placement.setRandom(); + rcm3.joint2_placement.setRandom(); + rcm3.corrector.Kd.setIdentity(); + rcm3.corrector.Kp.setIdentity(); + contact_models.push_back(rcm3); + contact_datas.push_back(rcm3.createData()); + + RigidConstraintModel rcm4 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint29"), model.getJointId("joint39"), LOCAL); + rcm4.joint1_placement.setRandom(); + rcm4.joint2_placement.setRandom(); + rcm4.corrector.Kd.setIdentity(); + rcm4.corrector.Kp.setIdentity(); + contact_models.push_back(rcm4); + contact_datas.push_back(rcm4.createData()); + + const double mu0 = 1e-3; + ProximalSettings prox_settings_ref(1e-12, mu0, 3); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-10)); +} + +BOOST_AUTO_TEST_CASE(test_3D_cons_baumgarte) +{ + Model model; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = + RigidConstraintModel(CONTACT_3D, model, model.getJointId("joint11"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + rcm1.corrector.Kd.setIdentity(); + rcm1.corrector.Kp.setIdentity(); + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + + RigidConstraintModel rcm2 = RigidConstraintModel( + CONTACT_3D, model, model.getJointId("joint21"), model.getJointId("joint38"), LOCAL); + rcm2.joint1_placement.setRandom(); + rcm2.joint2_placement.setRandom(); + rcm2.corrector.Kd.setIdentity(); + rcm2.corrector.Kp.setIdentity(); + contact_models.push_back(rcm2); + contact_datas.push_back(rcm2.createData()); + + RigidConstraintModel rcm3 = RigidConstraintModel( + CONTACT_3D, model, model.getJointId("joint19"), model.getJointId("joint29"), LOCAL); + rcm3.joint1_placement.setRandom(); + rcm3.joint2_placement.setRandom(); + rcm3.corrector.Kd.setIdentity(); + rcm3.corrector.Kp.setIdentity(); + contact_models.push_back(rcm3); + contact_datas.push_back(rcm3.createData()); + + RigidConstraintModel rcm4 = RigidConstraintModel( + CONTACT_3D, model, model.getJointId("joint29"), model.getJointId("joint39"), LOCAL); + rcm4.joint1_placement.setRandom(); + rcm4.joint2_placement.setRandom(); + rcm4.corrector.Kd.setIdentity(); + rcm4.corrector.Kp.setIdentity(); + contact_models.push_back(rcm4); + contact_datas.push_back(rcm4.createData()); + + const double mu0 = 1e-3; + ProximalSettings prox_settings_ref(1e-12, mu0, 3); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-10)); +} + +BOOST_AUTO_TEST_CASE(test_loop_con_and_ground_con) +{ + Model model; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint12"), model.getJointId("joint17"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + + RigidConstraintModel rcm2 = + RigidConstraintModel(CONTACT_6D, model, model.getJointId("joint14"), LOCAL); + rcm2.joint1_placement.setRandom(); + + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + + contact_models.push_back(rcm2); + contact_datas.push_back(rcm2.createData()); + + const double mu0 = 1e-1; + ProximalSettings prox_settings_ref(1e-12, mu0, 3); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-10)); +} + +BOOST_AUTO_TEST_CASE(test_loop_con_and_ground_con3D) +{ + Model model; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint12"), model.getJointId("joint17"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + + RigidConstraintModel rcm2 = + RigidConstraintModel(CONTACT_3D, model, model.getJointId("joint24"), LOCAL); + rcm2.joint1_placement.setRandom(); + + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + + contact_models.push_back(rcm2); + contact_datas.push_back(rcm2.createData()); + + const double mu0 = 1e-1; + ProximalSettings prox_settings_ref(1e-12, mu0, 3); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-10)); +} + +BOOST_AUTO_TEST_CASE(test_loop_con3D_ground_con3D) +{ + Model model; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = RigidConstraintModel( + CONTACT_3D, model, model.getJointId("joint12"), model.getJointId("joint17"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + + RigidConstraintModel rcm2 = + RigidConstraintModel(CONTACT_3D, model, model.getJointId("joint24"), LOCAL); + rcm2.joint1_placement.setRandom(); + + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + + contact_models.push_back(rcm2); + contact_datas.push_back(rcm2.createData()); + + const double mu0 = 1e-1; + ProximalSettings prox_settings_ref(1e-12, mu0, 3); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-10)); +} + +BOOST_AUTO_TEST_CASE(test_coupled_3D_6D_loops) +{ + Model model; + + build_trident_model(model); + Data data(model), data_ref(model); + + // Contact models and data + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(RigidConstraintData) contact_datas; + + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + const VectorXd tau = VectorXd::Random(model.nv); + + RigidConstraintModel rcm1 = RigidConstraintModel( + CONTACT_3D, model, model.getJointId("joint12"), model.getJointId("joint27"), LOCAL); + rcm1.joint1_placement.setRandom(); + rcm1.joint2_placement.setRandom(); + + RigidConstraintModel rcm2 = RigidConstraintModel( + CONTACT_6D, model, model.getJointId("joint24"), model.getJointId("joint11"), LOCAL); + rcm2.joint1_placement.setRandom(); + rcm2.joint2_placement.setRandom(); + + contact_models.push_back(rcm1); + contact_datas.push_back(rcm1.createData()); + + contact_models.push_back(rcm2); + contact_datas.push_back(rcm2.createData()); + + const double mu0 = 1e-1; + ProximalSettings prox_settings_ref(1e-12, mu0, 3); + ProximalSettings prox_settings(prox_settings_ref); + + initConstraintDynamics(model, data_ref, contact_models); + constraintDynamics(model, data_ref, q, v, tau, contact_models, contact_datas, prox_settings_ref); + + computeJointMinimalOrdering(model, data, contact_models); + lcaba(model, data, q, v, tau, contact_models, contact_datas, prox_settings); + + BOOST_CHECK(data_ref.ddq.isApprox(data.ddq, 1e-10)); +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/macros.cpp b/unittest/macros.cpp index eef23da63f..f4b7e7738f 100644 --- a/unittest/macros.cpp +++ b/unittest/macros.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2021 CNRS INRIA +// Copyright (c) 2021-2024 CNRS INRIA // #include "pinocchio/macros.hpp" @@ -31,14 +31,37 @@ void function_2(std::vector v, size_t size) BOOST_AUTO_TEST_CASE(test_check_arguments) { - expected_msg = "wrong argument size: expected 2, got 3\n" - "hint: v.size() is different from size\n"; - BOOST_CHECK_EXCEPTION( - function_1(std::vector(3), 2), std::invalid_argument, check_exception_msg); - expected_msg = "wrong argument size: expected 2, got 3\n" - "hint: custom message with stream\n"; - BOOST_CHECK_EXCEPTION( - function_2(std::vector(3), 2), std::invalid_argument, check_exception_msg); + { + BOOST_CHECK_THROW(function_1(std::vector(3), 2), std::invalid_argument); + try + { + function_1(std::vector(3), 2); + } + catch (std::invalid_argument & e) + { + const std::string message(e.what()); + + expected_msg = "wrong argument size: expected 2, got 3\n" + "hint: v.size() is different from size\n"; + BOOST_CHECK(message.find(expected_msg) != std::string::npos); + } + } + + { + BOOST_CHECK_THROW(function_2(std::vector(3), 2), std::invalid_argument); + try + { + function_2(std::vector(3), 2); + } + catch (std::invalid_argument & e) + { + const std::string message(e.what()); + + expected_msg = "wrong argument size: expected 2, got 3\n" + "hint: custom message with stream\n"; + BOOST_CHECK(message.find(expected_msg) != std::string::npos); + } + } } BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/matrix-inverse.cpp b/unittest/matrix-inverse.cpp new file mode 100644 index 0000000000..3ac61ea4ef --- /dev/null +++ b/unittest/matrix-inverse.cpp @@ -0,0 +1,117 @@ +// +// Copyright (c) 2025 INRIA +// + +#include + +#include +#include + +#include // to avoid C99 warnings + +#include +#include + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +using namespace pinocchio; + +template +using MatrixTpl = Eigen::Matrix; + +using DynamicMatrix = MatrixTpl; + +#ifndef NDEBUG +const int N = int(1e3); +#else +const int N = int(1e4); +#endif + +template +void test_generated_inverse_impl() +{ + std::cout << "size: " << size << std::endl; + typedef MatrixTpl Matrix; + for (int i = 0; i < N; ++i) + { + Matrix mat = Matrix::Random(); + mat = mat.transpose() * mat + 1e-8 * Matrix::Identity(); + make_symmetric(mat); + BOOST_CHECK(is_symmetric(mat, 0)); + + if (!(mat.determinant() > 1e-3)) + { + i--; + continue; + } + + Matrix res = Matrix::Zero(); + matrix_inversion_code_generated(mat, res); + BOOST_CHECK((res * mat).isIdentity(1e-8)); + BOOST_CHECK(mat.inverse().isApprox(res, 1e-8)); + } +} + +BOOST_AUTO_TEST_CASE(test_generated_inverse) +{ + test_generated_inverse_impl<1>(); + test_generated_inverse_impl<2>(); + test_generated_inverse_impl<3>(); + test_generated_inverse_impl<4>(); + test_generated_inverse_impl<5>(); + test_generated_inverse_impl<6>(); + test_generated_inverse_impl<7>(); + test_generated_inverse_impl<8>(); + test_generated_inverse_impl<9>(); + test_generated_inverse_impl<10>(); + test_generated_inverse_impl<11>(); + test_generated_inverse_impl<12>(); +} + +template +void test_matrix_inverse_on_dynamic_matrix_impl() +{ + std::cout << "size: " << size << std::endl; + typedef DynamicMatrix Matrix; + for (int i = 0; i < N; ++i) + { + Matrix mat = Matrix::Random(size, size); + mat = mat.transpose() * mat + 1e-8 * Matrix::Identity(size, size); + make_symmetric(mat); + BOOST_CHECK(is_symmetric(mat, 0)); + + if (!(mat.determinant() > 1e-3)) + { + i--; + continue; + } + + Matrix res = Matrix::Zero(size, size); + matrix_inversion(mat, res); + BOOST_CHECK((res * mat).isIdentity(1e-8)); + BOOST_CHECK(mat.inverse().isApprox(res, 1e-8)); + + // Direct call to the method + Matrix res2 = Matrix::Zero(size, size); + pinocchio::internal::MatrixInversionDynamicMatrixImpl::run(mat, res2); + BOOST_CHECK(res2 == res); + } +} + +BOOST_AUTO_TEST_CASE(test_matrix_inverse_on_dynamic_matrix) +{ + test_matrix_inverse_on_dynamic_matrix_impl<1>(); + test_matrix_inverse_on_dynamic_matrix_impl<2>(); + test_matrix_inverse_on_dynamic_matrix_impl<3>(); + test_matrix_inverse_on_dynamic_matrix_impl<4>(); + test_matrix_inverse_on_dynamic_matrix_impl<5>(); + test_matrix_inverse_on_dynamic_matrix_impl<6>(); + test_matrix_inverse_on_dynamic_matrix_impl<7>(); + test_matrix_inverse_on_dynamic_matrix_impl<8>(); + test_matrix_inverse_on_dynamic_matrix_impl<9>(); + test_matrix_inverse_on_dynamic_matrix_impl<10>(); + test_matrix_inverse_on_dynamic_matrix_impl<11>(); + test_matrix_inverse_on_dynamic_matrix_impl<12>(); +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/matrix.cpp b/unittest/matrix.cpp new file mode 100644 index 0000000000..99fdd1ef42 --- /dev/null +++ b/unittest/matrix.cpp @@ -0,0 +1,72 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#include + +#include // to avoid C99 warnings + +#include +#include + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +using namespace pinocchio; + +BOOST_AUTO_TEST_CASE(test_isSymmetric) +{ + srand(0); + + typedef Eigen::MatrixXd Matrix; + +#ifdef NDEBUG + const int max_test = 1e3; + const int max_size = 200; +#else + const int max_test = 1e2; + const int max_size = 100; +#endif + for (int i = 0; i < max_test; ++i) + { + const Eigen::DenseIndex rows = rand() % max_size + 3; // random row number + const Eigen::DenseIndex cols = rand() % max_size + 3; // random col number + + const Matrix random_matrix = Matrix::Random(rows, cols); + Matrix symmetric_matrix = random_matrix.transpose() * random_matrix; + BOOST_CHECK(isSymmetric(symmetric_matrix)); + + symmetric_matrix.coeffRef(1, 0) += 2.; + BOOST_CHECK(!isSymmetric(symmetric_matrix)); + + // Specific check for the Zero matrix + BOOST_CHECK(isSymmetric(Matrix::Zero(rows, rows))); + // Specific check for the Identity matrix + BOOST_CHECK(isSymmetric(Matrix::Identity(rows, rows))); + } +} + +BOOST_AUTO_TEST_CASE(test_enforceSymmetry) +{ + srand(0); + + typedef Eigen::MatrixXd Matrix; + +#ifdef NDEBUG + const int max_test = 1e3; + const int max_size = 200; +#else + const int max_test = 1e2; + const int max_size = 100; +#endif + for (int i = 0; i < max_test; ++i) + { + const Eigen::DenseIndex rows = rand() % max_size + 3; // random row number + + Matrix random_matrix = Matrix::Random(rows, rows); + BOOST_CHECK(!isSymmetric(random_matrix)); + enforceSymmetry(random_matrix); + BOOST_CHECK(isSymmetric(random_matrix, 0)); + } +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/mjcf.cpp b/unittest/mjcf.cpp index 972adc637d..9341faf8a9 100644 --- a/unittest/mjcf.cpp +++ b/unittest/mjcf.cpp @@ -19,6 +19,8 @@ #include #include +typedef ::pinocchio::mjcf::details::MjcfVisitor MjcfVisitor; + namespace { @@ -113,7 +115,7 @@ BOOST_AUTO_TEST_CASE(convert_inertia_fullinertia) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model; - MjcfGraph::UrdfVisitor visitor(model); + MjcfVisitor visitor(model); MjcfGraph graph(visitor, "fakeMjcf"); @@ -147,7 +149,7 @@ BOOST_AUTO_TEST_CASE(convert_inertia_diaginertia) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model; - MjcfGraph::UrdfVisitor visitor(model); + MjcfVisitor visitor(model); MjcfGraph graph(visitor, "fakeMjcf"); @@ -197,7 +199,7 @@ BOOST_AUTO_TEST_CASE(geoms_construction) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model_m; - MjcfGraph::UrdfVisitor visitor(model_m); + MjcfVisitor visitor(model_m); MjcfGraph graph(visitor, "fakeMjcf"); graph.parseGraphFromXML(namefile.name()); @@ -288,7 +290,7 @@ BOOST_AUTO_TEST_CASE(inertia_from_geom) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model_m; - MjcfGraph::UrdfVisitor visitor(model_m); + MjcfVisitor visitor(model_m); MjcfGraph graph(visitor, "fakeMjcf"); graph.parseGraphFromXML(namefile.name()); @@ -330,7 +332,7 @@ BOOST_AUTO_TEST_CASE(convert_orientation) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model; - MjcfGraph::UrdfVisitor visitor(model); + MjcfVisitor visitor(model); MjcfGraph graph(visitor, "fakeMjcf"); @@ -384,7 +386,7 @@ BOOST_AUTO_TEST_CASE(merge_default) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model; - MjcfGraph::UrdfVisitor visitor(model); + MjcfVisitor visitor(model); MjcfGraph graph(visitor, "fakeMjcf"); graph.parseDefault(ptr.get_child("default"), ptr, "default"); @@ -453,11 +455,13 @@ BOOST_AUTO_TEST_CASE(parse_default_class) typedef pinocchio::SE3::Vector3 Vector3; typedef pinocchio::SE3::Matrix3 Matrix3; - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::BilateralPointConstraintModel) + constraint_models; std::string filename = PINOCCHIO_MODEL_DIR + std::string("/../unittest/models/test_mjcf.xml"); pinocchio::Model model_m; - pinocchio::mjcf::buildModel(filename, model_m, contact_models); + pinocchio::mjcf::buildModel(filename, model_m); + pinocchio::mjcf::buildConstraintModelsFromXML(filename, model_m, constraint_models); std::string file_u = PINOCCHIO_MODEL_DIR + std::string("/../unittest/models/test_mjcf.urdf"); pinocchio::Model model_u; @@ -502,7 +506,7 @@ BOOST_AUTO_TEST_CASE(parse_dirs_no_strippath) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model_m; - MjcfGraph::UrdfVisitor visitor(model_m); + MjcfVisitor visitor(model_m); MjcfGraph graph(visitor, "/fakeMjcf/fake.xml"); graph.parseGraphFromXML(namefile.name()); @@ -539,7 +543,7 @@ BOOST_AUTO_TEST_CASE(parse_dirs_strippath) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model_m; - MjcfGraph::UrdfVisitor visitor(model_m); + MjcfVisitor visitor(model_m); MjcfGraph graph(visitor, "/fakeMjcf/fake.xml"); graph.parseGraphFromXML(namefile.name()); @@ -571,7 +575,7 @@ BOOST_AUTO_TEST_CASE(parse_RX) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model_m, modelRX; - MjcfGraph::UrdfVisitor visitor(model_m); + MjcfVisitor visitor(model_m); MjcfGraph graph(visitor, "fakeMjcf"); graph.parseGraphFromXML(namefile.name()); @@ -608,7 +612,7 @@ BOOST_AUTO_TEST_CASE(parse_PX) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model_m, modelPX; - MjcfGraph::UrdfVisitor visitor(model_m); + MjcfVisitor visitor(model_m); MjcfGraph graph(visitor, "fakeMjcf"); graph.parseGraphFromXML(namefile.name()); @@ -645,7 +649,7 @@ BOOST_AUTO_TEST_CASE(parse_Sphere) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model_m, modelS; - MjcfGraph::UrdfVisitor visitor(model_m); + MjcfVisitor visitor(model_m); MjcfGraph graph(visitor, "fakeMjcf"); graph.parseGraphFromXML(namefile.name()); @@ -682,7 +686,7 @@ BOOST_AUTO_TEST_CASE(parse_Free) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model_m, modelF; - MjcfGraph::UrdfVisitor visitor(model_m); + MjcfVisitor visitor(model_m); MjcfGraph graph(visitor, "fakeMjcf"); graph.parseGraphFromXML(namefile.name()); @@ -720,7 +724,7 @@ BOOST_AUTO_TEST_CASE(parse_composite_RXRY) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model_m, modelRXRY; - MjcfGraph::UrdfVisitor visitor(model_m); + MjcfVisitor visitor(model_m); MjcfGraph graph(visitor, "fakeMjcf"); graph.parseGraphFromXML(namefile.name()); @@ -762,7 +766,7 @@ BOOST_AUTO_TEST_CASE(parse_composite_PXPY) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model_m, modelPXPY; - MjcfGraph::UrdfVisitor visitor(model_m); + MjcfVisitor visitor(model_m); MjcfGraph graph(visitor, "fakeMjcf"); graph.parseGraphFromXML(namefile.name()); @@ -804,7 +808,7 @@ BOOST_AUTO_TEST_CASE(parse_composite_PXRY) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model_m, modelPXRY; - MjcfGraph::UrdfVisitor visitor(model_m); + MjcfVisitor visitor(model_m); MjcfGraph graph(visitor, "fakeMjcf"); graph.parseGraphFromXML(namefile.name()); @@ -846,7 +850,7 @@ BOOST_AUTO_TEST_CASE(parse_composite_PXSphere) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model_m, modelPXSphere; - MjcfGraph::UrdfVisitor visitor(model_m); + MjcfVisitor visitor(model_m); MjcfGraph graph(visitor, "fakeMjcf"); graph.parseGraphFromXML(namefile.name()); @@ -938,6 +942,55 @@ BOOST_AUTO_TEST_CASE(adding_keyframes) Eigen::VectorXd vect_ref(model_m.nq); vect_ref << 0, 0, 0.596, 0, 0.154359, 0, 0.988015, 0, 0.154359, 0, 0.988015; + ::pinocchio::normalize(model_m, vect_ref); + + BOOST_CHECK(vect_model.size() == vect_ref.size()); + BOOST_CHECK(vect_model == vect_ref); +} + +// Test laoding a model with a spherical joint and verify that keyframe is valid +BOOST_AUTO_TEST_CASE(adding_keyframes_with_ref_and_freejoint) +{ + std::istringstream xmlData(R"( + + + + + + + + + + + + + + + + + + + + + )"); + + auto namefile = createTempFile(xmlData); + + pinocchio::Model model_m; + pinocchio::mjcf::buildModel(namefile.name(), model_m); + + Eigen::Vector3d freejoint_trans_test = Eigen::Vector3d::Zero(); + Eigen::Vector3d freejoint_trans = model_m.jointPlacements[1].translation(); + BOOST_CHECK(freejoint_trans_test == freejoint_trans); + + Eigen::VectorXd vect_model = model_m.referenceConfigurations.at("test"); + + Eigen::VectorXd vect_ref(model_m.nq); + vect_ref << 0, 0, 0.596, 0, 0.154359, 0, 0.988015, 0, 0.154359, 0, 0.988015; + ::pinocchio::normalize(model_m, vect_ref); BOOST_CHECK(vect_model.size() == vect_ref.size()); BOOST_CHECK(vect_model == vect_ref); @@ -978,9 +1031,6 @@ BOOST_AUTO_TEST_CASE(joint_and_inertias) BOOST_AUTO_TEST_CASE(armature) { - typedef pinocchio::SE3::Vector3 Vector3; - typedef pinocchio::SE3::Matrix3 Matrix3; - std::istringstream xmlData(R"( @@ -1004,7 +1054,7 @@ BOOST_AUTO_TEST_CASE(armature) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model_m; - MjcfGraph::UrdfVisitor visitor(model_m); + MjcfVisitor visitor(model_m); MjcfGraph graph(visitor, "fakeMjcf"); graph.parseGraphFromXML(namefile.name()); @@ -1013,7 +1063,7 @@ BOOST_AUTO_TEST_CASE(armature) Eigen::VectorXd armature_real(model_m.nv); armature_real << 1.3, 2.4, 0.4, 1, 1, 1; - for (size_t i = 0; i < size_t(model_m.nv); i++) + for (Eigen::DenseIndex i = 0; i < model_m.nv; i++) BOOST_CHECK_EQUAL(model_m.armature[i], armature_real[i]); } @@ -1045,7 +1095,7 @@ BOOST_AUTO_TEST_CASE(reference_positions) Eigen::VectorXd vect_model = model_m.referenceConfigurations.at("test"); Eigen::VectorXd vect_ref(model_m.nq); - vect_ref << 0.66, 0.4; + vect_ref << 0.8, 0.5; BOOST_CHECK(vect_model.size() == vect_ref.size()); BOOST_CHECK(vect_model == vect_ref); @@ -1138,6 +1188,140 @@ BOOST_AUTO_TEST_CASE(build_model_no_root_joint) BOOST_CHECK_EQUAL(model_m.nq, 29); } +double degreesToRadian(double degrees) +{ + return degrees * (M_PI / 180.0); +} + +BOOST_AUTO_TEST_CASE(slide_joint_limits) +{ + std::istringstream xmlData(R"( + + + + + + + + + )"); + + auto namefile = createTempFile(xmlData); + + pinocchio::Model model_m; + pinocchio::mjcf::buildModel(namefile.name(), model_m); + + Eigen::VectorXd lower_position_limit(model_m.lowerPositionLimit); + lower_position_limit << -degreesToRadian(16.34); + Eigen::VectorXd upper_position_limit(model_m.upperPositionLimit); + upper_position_limit << degreesToRadian(17.2); + Eigen::VectorXd position_limit_margin(model_m.positionLimitMargin); + position_limit_margin << degreesToRadian(1.2345); + Eigen::VectorXd min_dry_friction(model_m.lowerDryFrictionLimit); + min_dry_friction << -11.6; + Eigen::VectorXd max_dry_friction(model_m.upperDryFrictionLimit); + max_dry_friction << 11.6; + Eigen::VectorXd min_effort(model_m.lowerEffortLimit); + min_effort << 1.5; + Eigen::VectorXd max_effort(model_m.upperEffortLimit); + max_effort << 4.8; + + BOOST_CHECK(lower_position_limit == model_m.lowerPositionLimit); + BOOST_CHECK(upper_position_limit == model_m.upperPositionLimit); + BOOST_CHECK(position_limit_margin == model_m.positionLimitMargin); + BOOST_CHECK(min_dry_friction == model_m.lowerDryFrictionLimit); + BOOST_CHECK(max_dry_friction == model_m.upperDryFrictionLimit); + BOOST_CHECK(min_effort == model_m.lowerEffortLimit); + BOOST_CHECK(max_effort == model_m.upperEffortLimit); +} + +BOOST_AUTO_TEST_CASE(hinge_joint_limits) +{ + std::istringstream xmlData(R"( + + + + + + + + + )"); + + auto namefile = createTempFile(xmlData); + + pinocchio::Model model_m; + pinocchio::mjcf::buildModel(namefile.name(), model_m); + + Eigen::VectorXd lower_position_limit(model_m.lowerPositionLimit); + lower_position_limit << -degreesToRadian(16.34); + Eigen::VectorXd upper_position_limit(model_m.upperPositionLimit); + upper_position_limit << degreesToRadian(17.2); + Eigen::VectorXd position_limit_margin(model_m.positionLimitMargin); + position_limit_margin << degreesToRadian(1.2345); + Eigen::VectorXd min_dry_friction(model_m.lowerDryFrictionLimit); + min_dry_friction << -11.6; + Eigen::VectorXd max_dry_friction(model_m.upperDryFrictionLimit); + max_dry_friction << 11.6; + Eigen::VectorXd min_effort(model_m.lowerEffortLimit); + min_effort << 1.5; + Eigen::VectorXd max_effort(model_m.upperEffortLimit); + max_effort << 4.8; + + BOOST_CHECK(lower_position_limit == model_m.lowerPositionLimit); + BOOST_CHECK(upper_position_limit == model_m.upperPositionLimit); + BOOST_CHECK(position_limit_margin == model_m.positionLimitMargin); + BOOST_CHECK(min_dry_friction == model_m.lowerDryFrictionLimit); + BOOST_CHECK(max_dry_friction == model_m.upperDryFrictionLimit); + BOOST_CHECK(min_effort == model_m.lowerEffortLimit); + BOOST_CHECK(max_effort == model_m.upperEffortLimit); +} + +BOOST_AUTO_TEST_CASE(hinge_and_slide_joints_limits) +{ + std::istringstream xmlData(R"( + + + + + + + + + + + + )"); + + auto namefile = createTempFile(xmlData); + + pinocchio::Model model_m; + pinocchio::mjcf::buildModel(namefile.name(), model_m); + + Eigen::VectorXd lower_position_limit(model_m.lowerPositionLimit); + lower_position_limit << -degreesToRadian(16.34), -degreesToRadian(18.32); + Eigen::VectorXd upper_position_limit(model_m.upperPositionLimit); + upper_position_limit << degreesToRadian(17.2), degreesToRadian(19.1); + Eigen::VectorXd position_limit_margin(model_m.positionLimitMargin); + position_limit_margin << degreesToRadian(1.2345), degreesToRadian(2.3366); + Eigen::VectorXd min_dry_friction(model_m.lowerDryFrictionLimit); + min_dry_friction << -11.6, -0.17; + Eigen::VectorXd max_dry_friction(model_m.upperDryFrictionLimit); + max_dry_friction << 11.6, 0.17; + Eigen::VectorXd min_effort(model_m.lowerEffortLimit); + min_effort << 1.5, -6.87; + Eigen::VectorXd max_effort(model_m.upperEffortLimit); + max_effort << 4.8, -4.8; + + BOOST_CHECK(lower_position_limit == model_m.lowerPositionLimit); + BOOST_CHECK(upper_position_limit == model_m.upperPositionLimit); + BOOST_CHECK(position_limit_margin == model_m.positionLimitMargin); + BOOST_CHECK(min_dry_friction == model_m.lowerDryFrictionLimit); + BOOST_CHECK(max_dry_friction == model_m.upperDryFrictionLimit); + BOOST_CHECK(min_effort == model_m.lowerEffortLimit); + BOOST_CHECK(max_effort == model_m.upperEffortLimit); +} + BOOST_AUTO_TEST_CASE(build_model_with_root_joint_name) { const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.xml"); @@ -1159,7 +1343,6 @@ BOOST_AUTO_TEST_CASE(build_model_with_root_joint_name) BOOST_AUTO_TEST_CASE(compare_to_urdf) { using namespace pinocchio; - typedef typename pinocchio::Model::ConfigVectorMap ConfigVectorMap; const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.xml"); @@ -1187,22 +1370,11 @@ BOOST_AUTO_TEST_CASE(compare_to_urdf) BOOST_CHECK(model_urdf.idx_vs == model_m.idx_vs); BOOST_CHECK(model_urdf.nvs == model_m.nvs); - typename ConfigVectorMap::const_iterator it = model_m.referenceConfigurations.begin(); - typename ConfigVectorMap::const_iterator it_model_urdf = - model_urdf.referenceConfigurations.begin(); - for (long k = 0; k < (long)model_m.referenceConfigurations.size(); ++k) - { - std::advance(it, k); - std::advance(it_model_urdf, k); - BOOST_CHECK(it->second.size() == it_model_urdf->second.size()); - BOOST_CHECK(it->second == it_model_urdf->second); - } - BOOST_CHECK(model_urdf.armature.size() == model_m.armature.size()); BOOST_CHECK(model_urdf.armature == model_m.armature); - BOOST_CHECK(model_urdf.friction.size() == model_m.friction.size()); - BOOST_CHECK(model_urdf.friction == model_m.friction); + BOOST_CHECK(model_urdf.upperDryFrictionLimit.size() == model_m.upperDryFrictionLimit.size()); + BOOST_CHECK(model_urdf.upperDryFrictionLimit == model_m.upperDryFrictionLimit); BOOST_CHECK(model_urdf.damping.size() == model_m.damping.size()); @@ -1216,8 +1388,8 @@ BOOST_AUTO_TEST_CASE(compare_to_urdf) BOOST_CHECK(model_urdf.rotorGearRatio == model_m.rotorGearRatio); - BOOST_CHECK(model_urdf.effortLimit.size() == model_m.effortLimit.size()); - BOOST_CHECK(model_urdf.effortLimit == model_m.effortLimit); + BOOST_CHECK(model_urdf.upperEffortLimit.size() == model_m.upperEffortLimit.size()); + BOOST_CHECK(model_urdf.upperEffortLimit == model_m.upperEffortLimit); // Cannot test velocity limit since it does not exist in mjcf BOOST_CHECK(model_urdf.lowerPositionLimit.size() == model_m.lowerPositionLimit.size()); @@ -1312,24 +1484,37 @@ BOOST_AUTO_TEST_CASE(test_geometry_parsing) BOOST_AUTO_TEST_CASE(test_contact_parsing) { - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintModel) contact_models; + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::BilateralPointConstraintModel) + constraint_models; std::string filename = PINOCCHIO_MODEL_DIR + std::string("/../unittest/models/closed_chain.xml"); pinocchio::Model model; - pinocchio::mjcf::buildModel(filename, model, contact_models); + pinocchio::mjcf::buildModel(filename, model); + pinocchio::mjcf::buildConstraintModelsFromXML(filename, model, constraint_models); + + BOOST_CHECK_EQUAL(constraint_models.size(), 4); - BOOST_CHECK_EQUAL(contact_models.size(), 4); + // We check that we have correctly parsed the values contained in the XML file BOOST_CHECK_EQUAL( - contact_models[0].joint1_placement.translation(), pinocchio::SE3::Vector3(0.50120, 0, 0)); + constraint_models[0].joint1_placement.translation(), pinocchio::SE3::Vector3(0.50120, 0, 0)); BOOST_CHECK_EQUAL( - contact_models[1].joint1_placement.translation(), pinocchio::SE3::Vector3(0.35012, 0, 0)); + constraint_models[1].joint1_placement.translation(), pinocchio::SE3::Vector3(0.35012, 0, 0)); BOOST_CHECK_EQUAL( - contact_models[2].joint1_placement.translation(), pinocchio::SE3::Vector3(0.50120, 0, 0)); + constraint_models[2].joint1_placement.translation(), pinocchio::SE3::Vector3(0.50120, 0, 0)); BOOST_CHECK_EQUAL( - contact_models[3].joint1_placement.translation(), pinocchio::SE3::Vector3(0.35012, 0, 0)); - for (const auto & cm : contact_models) + constraint_models[3].joint1_placement.translation(), pinocchio::SE3::Vector3(0.35012, 0, 0)); + + // Next, we check if the other constraint placement has been computed correctly. + // If a bilateral constraint has been constructed well, then the origin of the constraint + // placements, expressed in the world frame, should match + const Eigen::VectorXd q0 = model.referenceConfigurations["qpos0"]; + pinocchio::Data data(model); + pinocchio::forwardKinematics(model, data, q0); + for (const auto & cm : constraint_models) { - BOOST_CHECK(cm.joint2_placement.isApprox(cm.joint1_placement.inverse())); + const pinocchio::SE3 oMc1 = data.oMi[cm.joint1_id] * cm.joint1_placement; + const pinocchio::SE3 oMc2 = data.oMi[cm.joint2_id] * cm.joint2_placement; + BOOST_CHECK(oMc1.translation().isApprox(oMc2.translation())); } } @@ -1349,7 +1534,7 @@ BOOST_AUTO_TEST_CASE(test_default_eulerseq) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model_m; - MjcfGraph::UrdfVisitor visitor(model_m); + MjcfVisitor visitor(model_m); MjcfGraph graph(visitor, "fakeMjcf"); graph.parseGraphFromXML(namefile.name()); @@ -1385,7 +1570,7 @@ BOOST_AUTO_TEST_CASE(parse_mesh_with_vertices) typedef ::pinocchio::mjcf::details::MjcfGraph MjcfGraph; pinocchio::Model model_m; - MjcfGraph::UrdfVisitor visitor(model_m); + MjcfVisitor visitor(model_m); MjcfGraph graph(visitor, "/fakeMjcf/fake.xml"); graph.parseGraphFromXML(namefile.name()); @@ -1420,15 +1605,70 @@ BOOST_AUTO_TEST_CASE(test_get_unknown_size_vector_from_stream) Eigen::VectorXd expected2(6); expected2 << 1, 2, 3, 4, 5, 6; BOOST_CHECK(v2 == expected2); +} + +BOOST_AUTO_TEST_CASE(load_hopper) +{ + std::istringstream xmlData(R"( + + + + + + + + )"); + + auto namefile = createTempFile(xmlData); + + pinocchio::Model model_m; + pinocchio::GeometryModel geomModel_m; + pinocchio::mjcf::buildModel(namefile.name(), model_m); + // std::cout << "model_m: " << model_m << std::endl; + pinocchio::mjcf::buildGeom(model_m, namefile.name(), pinocchio::COLLISION, geomModel_m); + // std::cout << "geomModel_m: " << geomModel_m << std::endl; - const auto v3 = pinocchio::mjcf::details::internal::getUnknownSizeVectorFromStream(R"(1 2 3 - 4 5 6 - 7 8 9 - )"); - BOOST_CHECK(v3.size() == 9); - Eigen::VectorXd expected3(9); - expected3 << 1, 2, 3, 4, 5, 6, 7, 8, 9; - BOOST_CHECK(v3 == expected3); + BOOST_CHECK_EQUAL(model_m.nq, 6); } BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/model.cpp b/unittest/model.cpp index 2f5dbc07d3..70b0fe3ef4 100644 --- a/unittest/model.cpp +++ b/unittest/model.cpp @@ -1,5 +1,5 @@ // -// Copyright (c) 2016-2022 CNRS INRIA +// Copyright (c) 2016-2024 CNRS INRIA // #include "pinocchio/multibody/data.hpp" @@ -166,6 +166,70 @@ BOOST_AUTO_TEST_CASE(cast) BOOST_CHECK(model2 == model.cast()); } +// This is the minimal collection to build the `buildModels::manipulator` model +template +struct ManipulatorJointCollectionNoThrow +{ + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + + // Joint Revolute + typedef ::pinocchio::JointModelRevoluteTpl JointModelRX; + typedef ::pinocchio::JointModelRevoluteTpl JointModelRY; + typedef ::pinocchio::JointModelRevoluteTpl JointModelRZ; + + typedef boost::variant JointModelVariant; + + // Joint Revolute + typedef ::pinocchio::JointDataRevoluteTpl JointDataRX; + typedef ::pinocchio::JointDataRevoluteTpl JointDataRY; + typedef ::pinocchio::JointDataRevoluteTpl JointDataRZ; + + typedef boost::variant JointDataVariant; +}; + +template +struct ManipulatorJointCollectionThrow +{ + typedef _Scalar Scalar; + enum + { + Options = _Options + }; + + // Joint Revolute + typedef ::pinocchio::JointModelRevoluteTpl JointModelRX; + typedef ::pinocchio::JointModelRevoluteTpl JointModelRY; + + typedef boost::variant JointModelVariant; + + // Joint Revolute + typedef ::pinocchio::JointDataRevoluteTpl JointDataRX; + typedef ::pinocchio::JointDataRevoluteTpl JointDataRY; + + typedef boost::variant JointDataVariant; +}; + +BOOST_AUTO_TEST_CASE(cast_collection) +{ + typedef ::pinocchio::ModelTpl Model; + typedef ::pinocchio::ModelTpl MinimalModelNoThrow; + typedef ::pinocchio::ModelTpl MinimalModelThrow; + + Model model_full; + buildModels::manipulator(model_full); + + Model model_full_copy(model_full); + BOOST_CHECK(model_full == model_full_copy); + + BOOST_CHECK_NO_THROW({ MinimalModelNoThrow model_no_throw = model_full; }); + + BOOST_CHECK_THROW({ MinimalModelThrow model_throw = model_full; }, std::invalid_argument); +} + BOOST_AUTO_TEST_CASE(test_std_vector_of_Model) { Model model; diff --git a/unittest/models/closed_chain.xml b/unittest/models/closed_chain.xml index ab8bcabb0a..832e1f9e11 100644 --- a/unittest/models/closed_chain.xml +++ b/unittest/models/closed_chain.xml @@ -9,7 +9,7 @@ - + @@ -173,4 +173,12 @@ + + + + + diff --git a/unittest/null-set.cpp b/unittest/null-set.cpp new file mode 100644 index 0000000000..a1746741de --- /dev/null +++ b/unittest/null-set.cpp @@ -0,0 +1,47 @@ +// +// Copyright (c) 2025 INRIA +// + +#include "pinocchio/algorithm/constraints/null-set.hpp" + +#include +#include + +using namespace pinocchio; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(test_proj) +{ + const int num_tests = int(1000); + const int dim = 10; + + const NullSet set(dim); + + BOOST_CHECK(set.dim() == dim); + + BOOST_CHECK(set.isInside(NullSet::Vector::Zero(dim))); + BOOST_CHECK(!set.isInside(NullSet::Vector::Ones(dim))); + BOOST_CHECK(set.project(NullSet::Vector::Zero(dim)) == NullSet::Vector::Zero(dim)); + BOOST_CHECK(set.project(NullSet::Vector::Ones(dim)) == NullSet::Vector::Zero(dim)); + + for (int k = 0; k < num_tests; ++k) + { + const NullSet::Vector x = NullSet::Vector::Random(dim); + if (!x.isZero()) + BOOST_CHECK(!set.isInside(x)); + + const auto proj_x = set.project(x); + const auto proj_proj_x = set.project(proj_x); + + BOOST_CHECK(set.isInside(proj_x, 1e-12)); + BOOST_CHECK(set.isInside(proj_proj_x, 1e-12)); + BOOST_CHECK(proj_x == proj_proj_x); + if (set.isInside(x)) + BOOST_CHECK(x == proj_x); + + BOOST_CHECK(fabs((x - proj_x).dot(proj_x)) <= 1e-12); // orthogonal projection + } +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/openmp-exception.cpp b/unittest/openmp-exception.cpp new file mode 100644 index 0000000000..a67da1e022 --- /dev/null +++ b/unittest/openmp-exception.cpp @@ -0,0 +1,69 @@ +// +// Copyright (c) 2024 INRIA +// + +#include +#include +#include + +#include "pinocchio/utils/openmp.hpp" + +#include +#include + +using namespace pinocchio; + +template +void throw_if_equal_values(const T value, const T ref_value) +{ + if (value == ref_value) + { + std::stringstream message; + message << value << " is equal to " << ref_value; + throw std::logic_error(message.str()); + } +} + +template +void run_parallel_loop(const int n, OpenMPException & openmp_exception, Parameters... params) +{ +#pragma omp parallel for + for (int i = 0; i < n; i++) + { + if (openmp_exception.hasThrown()) + continue; + openmp_exception.run(&throw_if_equal_values, i, params...); + } + + openmp_exception.rethrowException(); +} + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(test_openmp_exception_catch) +{ + + const int num_threads = omp_get_num_threads(); + omp_set_num_threads(num_threads); + { + OpenMPException openmp_exception; + try + { + run_parallel_loop(10000, openmp_exception, 20); + } + catch (...) + { + } + } + + { + OpenMPException openmp_exception; + BOOST_CHECK_THROW(run_parallel_loop(10000, openmp_exception, 20), std::logic_error); + } + { + OpenMPException openmp_exception; + BOOST_CHECK_NO_THROW(run_parallel_loop(10000, openmp_exception, 10001)); + } +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/orthant-cone.cpp b/unittest/orthant-cone.cpp new file mode 100644 index 0000000000..0fdcc5b7d7 --- /dev/null +++ b/unittest/orthant-cone.cpp @@ -0,0 +1,103 @@ +// +// Copyright (c) 2024 INRIA +// + +#include +#include "pinocchio/algorithm/constraints/orthant-cone.hpp" + +#include +#include + +using namespace pinocchio; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +template +void common_test(const int num_tests, const int dim) +{ + + const Orthant orthant(dim); + typedef typename Orthant::Vector Vector; + + BOOST_CHECK(orthant.dim() == dim); + + BOOST_CHECK(orthant.isInside(Vector::Zero(dim))); + BOOST_CHECK(orthant.project(Vector::Zero(dim)) == Vector::Zero(dim)); + BOOST_CHECK(orthant.dual() == orthant); + + for (int k = 0; k < num_tests; ++k) + { + const Vector x = Vector::Random(dim); + + // Cone + const auto proj_x = orthant.project(x); + const auto proj_proj_x = orthant.project(proj_x); + + BOOST_CHECK(orthant.isInside(proj_x, 1e-12)); + BOOST_CHECK(orthant.isInside(proj_proj_x, 1e-12)); + BOOST_CHECK(proj_x == proj_proj_x); + if (orthant.isInside(x)) + BOOST_CHECK(x == proj_x); + + BOOST_CHECK(fabs((x - proj_x).dot(proj_x)) <= 1e-12); // orthogonal projection + } +} + +BOOST_AUTO_TEST_CASE(test_positive_orthant) +{ + const int num_tests = int(1e6); + const int dim = 10; + + common_test(num_tests, dim); + + const PositiveOrthantCone positive_orthant(dim); + typedef PositiveOrthantCone::Vector Vector; + + for (int k = 0; k < num_tests; ++k) + { + const Vector x = Vector::Random(dim); + const Vector x_proj = positive_orthant.project(x); + + BOOST_CHECK((x_proj.array() >= 0).all()); + } +} + +BOOST_AUTO_TEST_CASE(test_negative_orthant) +{ + const int num_tests = int(1e6); + const int dim = 10; + + common_test(num_tests, dim); + + const NegativeOrthantCone negative_orthant(dim); + typedef NegativeOrthantCone::Vector Vector; + + for (int k = 0; k < num_tests; ++k) + { + const Vector x = Vector::Random(dim); + const Vector x_proj = negative_orthant.project(x); + + BOOST_CHECK((x_proj.array() <= 0).all()); + } +} + +BOOST_AUTO_TEST_CASE(test_decomposition) +{ + const int num_tests = int(1e6); + const int dim = 10; + + const NegativeOrthantCone negative_orthant(dim); + const PositiveOrthantCone positive_orthant(dim); + typedef NegativeOrthantCone::Vector Vector; + + for (int k = 0; k < num_tests; ++k) + { + const Vector x = Vector::Random(dim); + const Vector x_proj_neg = negative_orthant.project(x); + const Vector x_proj_pos = positive_orthant.project(x); + + BOOST_CHECK(x == (x_proj_neg + x_proj_pos)); + } +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/pgs-solver.cpp b/unittest/pgs-solver.cpp new file mode 100644 index 0000000000..f2c14a3625 --- /dev/null +++ b/unittest/pgs-solver.cpp @@ -0,0 +1,723 @@ +// +// Copyright (c) 2024 INRIA +// + +#include "pinocchio/algorithm/constraints/constraints.hpp" +#include "pinocchio/algorithm/contact-cholesky.hpp" +#include "pinocchio/algorithm/joint-configuration.hpp" +#include "pinocchio/algorithm/contact-jacobian.hpp" +#include "pinocchio/algorithm/delassus-operator-dense.hpp" +#include "pinocchio/algorithm/pgs-solver.hpp" +#include "pinocchio/algorithm/aba.hpp" +#include "pinocchio/algorithm/crba.hpp" +#include "pinocchio/multibody/sample-models.hpp" + +#include +#include + +using namespace pinocchio; + +double mu = 1e-4; + +#define EIGEN_VECTOR_IS_APPROX(Va, Vb, precision) \ + BOOST_CHECK_MESSAGE( \ + ((Va) - (Vb)).isZero(precision), \ + "check " #Va ".isApprox(" #Vb ") failed at precision " \ + << precision << ". (" #Va " - " #Vb ").norm() = " << ((Va) - (Vb)).norm() << " [\n" \ + << (Va).transpose() << "\n!=\n" \ + << (Vb).transpose() << "\n]") + +template +struct TestBoxTpl +{ + typedef _ConstraintModel ConstraintModel; + + typedef typename ConstraintModel::ConstraintData ConstraintData; + + TestBoxTpl(const Model & model, const std::vector & constraint_models) + : model(model) + , data(model) + , constraint_models(constraint_models) + , v_next(Eigen::VectorXd::Zero(model.nv)) + { + for (const auto & cm : constraint_models) + { + constraint_datas.push_back(cm.createData()); + } + + const Eigen::DenseIndex constraint_size = getTotalConstraintSize(constraint_models); + dual_solution = primal_solution = primal_solution_sparse = + Eigen::VectorXd::Zero(constraint_size); + } + + void operator()( + const Eigen::VectorXd & q0, + const Eigen::VectorXd & v0, + const Eigen::VectorXd & tau0, + const Force & fext, + const double dt) + { + std::vector external_forces(size_t(model.njoints), Force::Zero()); + external_forces[1] = fext; + + const Eigen::VectorXd v_free = + dt * aba(model, data, q0, v0, tau0, external_forces, Convention::WORLD); + + // Cholesky of the Delassus matrix + crba(model, data, q0, Convention::WORLD); + ContactCholeskyDecomposition chol(model, constraint_models); + chol.resize(model, constraint_models); + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + + const Eigen::MatrixXd delassus_matrix_plain = chol.getDelassusCholeskyExpression().matrix(); + const auto & G = delassus_matrix_plain; + const DelassusOperatorDense delassus(G); + // std::cout << "G:\n" << delassus_matrix_plain << std::endl; + + Eigen::MatrixXd constraint_jacobian(delassus_matrix_plain.rows(), model.nv); + constraint_jacobian.setZero(); + getConstraintsJacobian(model, data, constraint_models, constraint_datas, constraint_jacobian); + + Eigen::VectorXd time_scaling(delassus_matrix_plain.rows()); + internal::getTimeScalingFromAccelerationToConstraints(constraint_models, dt, time_scaling); + + const Eigen::VectorXd g = (constraint_jacobian * v_free).cwiseProduct(time_scaling / dt); + // std::cout << "g: " << g.transpose() << std::endl; + + PGSContactSolver pgs_solver(int(delassus_matrix_plain.rows())); + pgs_solver.setAbsolutePrecision(1e-13); + pgs_solver.setRelativePrecision(1e-14); + pgs_solver.setMaxIterations(1000); + has_converged = pgs_solver.solve( + delassus, g, constraint_models, dt, + boost::make_optional((Eigen::Ref)primal_solution)); + primal_solution = pgs_solver.getPrimalSolution(); + + // // Check with sparse view too + // { + // PGSContactSolver pgs_solver_sparse(int(delassus_matrix_plain.rows())); + // const Eigen::SparseMatrix G_sparse = + // delassus_matrix_plain.matrix().sparseView(); + // pgs_solver_sparse.setAbsolutePrecision(1e-10); + // pgs_solver_sparse.setRelativePrecision(1e-14); + // bool has_converged_sparse = + // pgs_solver_sparse.solve(G_sparse, g, constraint_sets, dual_solution_sparse); + // BOOST_CHECK(has_converged_sparse); + // BOOST_CHECK(pgs_solver_sparse.getSolution().isApprox(pgs_solver.getSolution())); + // } + + // std::cout << "x_sol: " << x_sol.transpose() << std::endl; + + // dual_solution = G * primal_solution + g; + dual_solution = pgs_solver.getDualSolution(); + // std::cout << "constraint_velocity: " << constraint_velocity.transpose() << std::endl; + + const Eigen::VectorXd tau_ext = constraint_jacobian.transpose() * primal_solution; + + v_next = + v0 + + dt * aba(model, data, q0, v0, (tau0 + tau_ext).eval(), external_forces, Convention::WORLD); + } + + Model model; + Data data; + std::vector constraint_models; + std::vector constraint_datas; + Eigen::VectorXd v_next; + + Eigen::VectorXd primal_solution, primal_solution_sparse, dual_solution, dual_solution_sparse; + bool has_converged; +}; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +Eigen::Vector3d computeFtot(const Eigen::VectorXd & contact_forces) +{ + Eigen::Vector3d f_tot = Eigen::Vector3d::Zero(); + for (int k = 0; k < contact_forces.size() / 3; ++k) + { + f_tot += contact_forces.segment(3 * k, 3); + } + return f_tot; +} + +BOOST_AUTO_TEST_CASE(box) +{ + Model model; + model.addJoint(0, JointModelFreeFlyer(), SE3::Identity(), "free_flyer"); + + const int num_tests = +#ifdef NDEBUG + 100000 +#else + 100 +#endif + ; + + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + const double box_mass = 10; + const Inertia box_inertia = Inertia::FromBox(box_mass, box_dims[0], box_dims[1], box_dims[2]); + + model.appendBodyToJoint(1, box_inertia); + + BOOST_CHECK(model.check(model.createData())); + + Eigen::VectorXd q0 = neutral(model); + q0.const_cast_derived()[2] += box_dims[2] / 2; + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + const Eigen::VectorXd tau0 = Eigen::VectorXd::Zero(model.nv); + + const double dt = 1e-3; + + typedef FrictionalPointConstraintModel ConstraintModel; + typedef TestBoxTpl TestBox; + std::vector constraint_models; + + const double friction_value = 0.4; + { + const SE3 local_placement_box( + SE3::Matrix3::Identity(), 0.5 * SE3::Vector3(box_dims[0], box_dims[1], -box_dims[2])); + SE3::Matrix3 rot = SE3::Matrix3::Identity(); + for (int i = 0; i < 4; ++i) + { + const SE3 local_placement(SE3::Matrix3::Identity(), rot * local_placement_box.translation()); + ConstraintModel cm(model, 0, SE3::Identity(), 1, local_placement); + cm.set() = CoulombFrictionCone(friction_value); + constraint_models.push_back(cm); + rot = Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ()).toRotationMatrix() * rot; + } + } + + for (const auto & cm : constraint_models) + { + BOOST_CHECK(cm.size() == 3); + } + + // Test static motion with zero external force + { + const Force fext = Force::Zero(); + + TestBox test(model, constraint_models); + test(q0, v0, tau0, fext, dt); + + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(test.dual_solution.isZero(2e-10)); + BOOST_CHECK(computeFtot(test.primal_solution).isApprox(-box_mass * Model::gravity981, 1e-8)); + BOOST_CHECK(test.v_next.isZero(2e-10)); + } + + const double f_sliding = friction_value * Model::gravity981.norm() * box_mass; + + // Test static motion with small external force + for (int k = 0; k < num_tests; ++k) + { + const double scaling = 0.9; + Force fext = Force::Zero(); + fext.linear().head<2>().setRandom().normalize(); + fext.linear() *= scaling * f_sliding; + + TestBox test(model, constraint_models); + test(q0, v0, tau0, fext, dt); + + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(test.dual_solution.isZero(1e-7)); + const Force::Vector3 f_tot_ref = (-box_mass * Model::gravity981 - fext.linear()); + BOOST_CHECK(computeFtot(test.primal_solution).isApprox(f_tot_ref, 1e-6)); + BOOST_CHECK(test.v_next.isZero(1e-8)); + } + + // Test slidding motion + for (int k = 0; k < num_tests; ++k) + { + const double scaling = 1.1; + Force fext = Force::Zero(); + fext.linear().head<2>().setRandom().normalize(); + fext.linear() *= scaling * f_sliding; + + TestBox test(model, constraint_models); + test(q0, v0, tau0, fext, dt); + + BOOST_CHECK(test.has_converged == true); + const Force::Vector3 f_tot_ref = (-box_mass * Model::gravity981 - 1 / scaling * fext.linear()); + BOOST_CHECK(computeFtot(test.primal_solution).isApprox(f_tot_ref, 1e-6)); + BOOST_CHECK( + math::fabs(Motion(test.v_next).linear().norm() - (f_sliding * 0.1 / box_mass) * dt) <= 1e-6); + BOOST_CHECK(Motion(test.v_next).angular().isZero(1e-6)); + } +} + +BOOST_AUTO_TEST_CASE(bilateral_box) +{ + Model model; + model.addJoint(0, JointModelFreeFlyer(), SE3::Identity(), "free_flyer"); + + const int num_tests = +#ifdef NDEBUG + 100000 +#else + 100 +#endif + ; + + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + const double box_mass = 10; + const Inertia box_inertia = Inertia::FromBox(box_mass, box_dims[0], box_dims[1], box_dims[2]); + + model.appendBodyToJoint(1, box_inertia); + + BOOST_CHECK(model.check(model.createData())); + + Eigen::VectorXd q0 = neutral(model); + q0.const_cast_derived()[2] += box_dims[2] / 2; + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + const Eigen::VectorXd tau0 = Eigen::VectorXd::Zero(model.nv); + + const double dt = 1e-3; + + typedef BilateralPointConstraintModel ConstraintModel; + typedef TestBoxTpl TestBox; + std::vector constraint_models; + + { + const SE3 local_placement_box( + SE3::Matrix3::Identity(), 0.5 * SE3::Vector3(box_dims[0], box_dims[1], -box_dims[2])); + SE3::Matrix3 rot = SE3::Matrix3::Identity(); + for (int i = 0; i < 4; ++i) + { + const SE3 local_placement(SE3::Matrix3::Identity(), rot * local_placement_box.translation()); + ConstraintModel cm(model, 0, SE3::Identity(), 1, local_placement); + constraint_models.push_back(cm); + rot = Eigen::AngleAxisd(M_PI / 2, Eigen::Vector3d::UnitZ()).toRotationMatrix() * rot; + } + } + + // Test static motion with zero external force + { + const Force fext = Force::Zero(); + + TestBox test(model, constraint_models); + test(q0, v0, tau0, fext, dt); + + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(test.dual_solution.isZero(2e-10)); + BOOST_CHECK(computeFtot(test.primal_solution).isApprox(-box_mass * Model::gravity981, 1e-8)); + BOOST_CHECK(test.v_next.isZero(2e-10)); + } + + for (int k = 0; k < num_tests; ++k) + { + Force fext = Force::Zero(); + fext.linear().setRandom(); + + TestBox test(model, constraint_models); + test(q0, v0, tau0, fext, dt); + + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(test.dual_solution.isZero(1e-8)); + const Force::Vector3 f_tot_ref = (-box_mass * Model::gravity981 - fext.linear()); + BOOST_CHECK(computeFtot(test.primal_solution).isApprox(f_tot_ref, 1e-6)); + BOOST_CHECK(test.v_next.isZero(1e-8)); + } +} + +BOOST_AUTO_TEST_CASE(bilateral_humanoid) +{ + Model model; + buildModels::humanoid(model); + + Eigen::VectorXd q0 = neutral(model); + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + const Eigen::VectorXd tau0 = Eigen::VectorXd::Zero(model.nv); + + const double dt = 1e-3; + + typedef BilateralPointConstraintModel ConstraintModel; + typedef TestBoxTpl TestBox; + std::vector constraint_models; + + Data data(model); + pinocchio::forwardKinematics(model, data, q0); + const JointIndex joint1_id = 0; + const GeomIndex joint2_id = 14; + assert((int)joint2_id < model.njoints); + assert(model.nvs[joint2_id] == 1); // make sure its a bilaterable joint + const SE3 Mc = data.oMi[joint2_id]; + const SE3 joint1_placement = Mc; + const SE3 joint2_placement = SE3::Identity(); + + ConstraintModel cm(model, joint1_id, joint1_placement, joint2_id, joint2_placement); + constraint_models.push_back(cm); + + // Test static motion with zero external force -> locked joint should not move + { + const Force fext = Force::Zero(); + + TestBox test(model, constraint_models); + test(q0, v0, tau0, fext, dt); + Eigen::VectorXd q_next = integrate(model, q0, test.v_next * dt); + + BOOST_CHECK(test.has_converged == true); + Eigen::VectorXd v_wrist_expected = Eigen::VectorXd::Zero(model.nvs[joint2_id]); + EIGEN_VECTOR_IS_APPROX( + test.v_next.segment(model.idx_vs[joint2_id], model.nvs[joint2_id]), // + v_wrist_expected, // + 1e-6); + pinocchio::forwardKinematics(model, data, q_next); + EIGEN_VECTOR_IS_APPROX( + Mc.translation(), + data.oMi[joint2_id].translation(), // + 1e-6); + } +} + +BOOST_AUTO_TEST_CASE(dry_friction_box) +{ + Model model; + model.addJoint(0, JointModelFreeFlyer(), SE3::Identity(), "free_flyer"); + + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + const double box_mass = 10; + const Inertia box_inertia = Inertia::FromBox(box_mass, box_dims[0], box_dims[1], box_dims[2]); + + model.appendBodyToJoint(1, box_inertia); + model.gravity.setZero(); + Data data(model); + + Eigen::VectorXd q0 = neutral(model); + q0.const_cast_derived()[2] += box_dims[2] / 2; + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + const Eigen::VectorXd tau0 = Eigen::VectorXd::Zero(model.nv); + + const double dt = 1e-3; + + typedef FrictionalJointConstraintModel ConstraintModel; + typedef ConstraintModel::ConstraintData ConstraintData; + typedef BoxSet ConstraintSet; + typedef TestBoxTpl TestBox; + std::vector constraint_models; + std::vector constraint_datas; + + ConstraintModel dry_friction_free_flyer(model, ConstraintModel::JointIndexVector(1, 1)); + constraint_models.push_back(dry_friction_free_flyer); + + for (const auto & cm : constraint_models) + constraint_datas.push_back(cm.createData()); + + std::vector constraint_sets; + constraint_sets.push_back( + BoxSet(Eigen::VectorXd::Constant(6, -1.), Eigen::VectorXd::Constant(6, +1.))); + + const auto & box_set = constraint_sets[0]; + constraint_models[0].set() = box_set; + + const Eigen::VectorXd v_free = dt * aba(model, data, q0, v0, tau0, Convention::WORLD); + + // Cholesky of the Delassus matrix + crba(model, data, q0, Convention::WORLD); + ContactCholeskyDecomposition chol(model, constraint_models); + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + + const Eigen::MatrixXd delassus_matrix_plain = chol.getDelassusCholeskyExpression().matrix(); + const auto & G = delassus_matrix_plain; + const DelassusOperatorDense delassus(G); + // std::cout << "G:\n" << delassus_matrix_plain << std::endl; + + Eigen::MatrixXd constraint_jacobian(dry_friction_free_flyer.size(), model.nv); + constraint_jacobian.setZero(); + getConstraintsJacobian(model, data, constraint_models, constraint_datas, constraint_jacobian); + + const Eigen::VectorXd g = constraint_jacobian * v_free; + + Eigen::VectorXd dual_solution = Eigen::VectorXd::Zero(g.size()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(g.size()); + PGSContactSolver pgs_solver(int(delassus_matrix_plain.rows())); + pgs_solver.setAbsolutePrecision(1e-13); + pgs_solver.setRelativePrecision(1e-14); + const bool has_converged = pgs_solver.solve( + delassus, g, constraint_models, dt, + boost::make_optional((Eigen::Ref)primal_solution)); + primal_solution = pgs_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + dual_solution = G * primal_solution + g; + Eigen::VectorXd dual_solution2 = pgs_solver.getDualSolution(); + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(dual_solution.isZero()); + BOOST_CHECK(dual_solution2.isZero()); + + // Test static motion with zero external force + { + TestBox test(model, constraint_models); + test(q0, v0, tau0, Force::Zero(), dt); + + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(test.dual_solution.isZero(2e-10)); + BOOST_CHECK(test.v_next.isZero(2e-10)); + BOOST_CHECK(box_set.isInside(test.primal_solution)); + } + + for (int i = 0; i < 6; ++i) + { + TestBox test(model, constraint_models); + test(q0, v0, tau0 + 2 * Force::Vector6::Unit(i) / dt, Force::Zero(), dt); + + // std::cout << "test.dual_solution: " << test.dual_solution.transpose() << std::endl; + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(!test.primal_solution.isZero(2e-10)); + BOOST_CHECK(!test.v_next.isZero(2e-10)); + BOOST_CHECK(box_set.isInside(test.primal_solution)); + BOOST_CHECK(std::fabs(test.primal_solution[i] - box_set.lb()[i]) < 1e-8); + } + + // Sign reversed + for (int i = 0; i < 6; ++i) + { + TestBox test(model, constraint_models); + test(q0, v0, tau0 - 2 * Force::Vector6::Unit(i) / dt, Force::Zero(), dt); + + BOOST_CHECK(test.has_converged == true); + BOOST_CHECK(!test.dual_solution.isZero(2e-10)); + BOOST_CHECK(!test.v_next.isZero(2e-10)); + BOOST_CHECK(box_set.isInside(test.primal_solution)); + BOOST_CHECK(std::fabs(test.primal_solution[i] - box_set.ub()[i]) < 1e-8); + } +} + +BOOST_AUTO_TEST_CASE(joint_limit_slider) +{ + Model model; + model.addJoint(0, JointModelPX(), SE3::Identity(), "slider"); + model.lowerPositionLimit[0] = 0.; + + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + const double box_mass = 10; + const Inertia box_inertia = Inertia::FromBox(box_mass, box_dims[0], box_dims[1], box_dims[2]); + + model.appendBodyToJoint(1, box_inertia); + model.gravity.setZero(); + Data data(model); + + Eigen::VectorXd q0 = Eigen::VectorXd::Zero(model.nq); + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + const Eigen::VectorXd tau_push_against_lower_bound = -Eigen::VectorXd::Ones(model.nv); + + const double dt = 1e-3; + + typedef JointLimitConstraintModel ConstraintModel; + typedef ConstraintModel::ConstraintData ConstraintData; + std::vector constraint_models; + std::vector constraint_datas; + + ConstraintModel joint_limit_constraint_model(model, ConstraintModel::JointIndexVector(1, 1)); + constraint_models.push_back(joint_limit_constraint_model); + + for (const auto & cm : constraint_models) + constraint_datas.push_back(cm.createData()); + + const Eigen::VectorXd v_free_against_lower_bound = + dt * aba(model, data, q0, v0, tau_push_against_lower_bound, Convention::WORLD); + const Eigen::VectorXd v_free_move_away = + dt * aba(model, data, q0, v0, -tau_push_against_lower_bound, Convention::WORLD); + + // Cholesky of the Delassus matrix + crba(model, data, q0, Convention::WORLD); + + data.q_in = q0; + auto & cmodel = constraint_models[0]; + auto & cdata = constraint_datas[0]; + cmodel.resize(model, data, cdata); + cmodel.calc(model, data, cdata); + ContactCholeskyDecomposition chol(model, constraint_models); + chol.resize(model, constraint_models); + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + + const Eigen::MatrixXd delassus_matrix_plain = chol.getDelassusCholeskyExpression().matrix(); + const auto & G = delassus_matrix_plain; + const DelassusOperatorDense delassus(G); + + Eigen::MatrixXd constraint_jacobian(cmodel.activeSize(), model.nv); + constraint_jacobian.setZero(); + getConstraintsJacobian(model, data, constraint_models, constraint_datas, constraint_jacobian); + + // External torques push the slider against the lower bound + { + const Eigen::VectorXd g_against_lower_bound = + constraint_jacobian * v_free_against_lower_bound * dt; + const Eigen::VectorXd g_tilde_against_lower_bound = + g_against_lower_bound + cdata.constraint_residual; + + Eigen::VectorXd dual_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + PGSContactSolver pgs_solver(int(delassus_matrix_plain.rows())); + pgs_solver.setAbsolutePrecision(1e-13); + pgs_solver.setRelativePrecision(1e-14); + const bool has_converged = pgs_solver.solve( + delassus, g_tilde_against_lower_bound, constraint_models, dt, + boost::make_optional((Eigen::Ref)primal_solution)); + primal_solution = pgs_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + dual_solution = G * primal_solution * dt * dt + g_tilde_against_lower_bound; + Eigen::VectorXd dual_solution2 = pgs_solver.getDualSolution(); + + // std::cout << "primal_solution: " << primal_solution.transpose() << std::endl; + // std::cout << "constraint_jacobian.transpose() * primal_solution: " << + // (constraint_jacobian.transpose() * primal_solution).transpose() << std::endl; std::cout << + // "dual_solution: " << dual_solution.transpose() << std::endl; std::cout << "dual_solution2: + // " << dual_solution2.transpose() << std::endl; + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(dual_solution.isZero()); + BOOST_CHECK(dual_solution2.isZero()); + + BOOST_CHECK((tau_push_against_lower_bound + constraint_jacobian.transpose() * primal_solution) + .isZero(1e-8)); + } + + // External torques push the slider away from the lower bound + { + const Eigen::VectorXd g_move_away = constraint_jacobian * v_free_move_away * dt; + const Eigen::VectorXd g_tilde_move_away = g_move_away + cdata.constraint_residual; + + Eigen::VectorXd dual_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + PGSContactSolver pgs_solver(int(delassus_matrix_plain.rows())); + pgs_solver.setAbsolutePrecision(1e-13); + pgs_solver.setRelativePrecision(1e-14); + const bool has_converged = pgs_solver.solve( + delassus, g_tilde_move_away, constraint_models, dt, + boost::make_optional((Eigen::Ref)primal_solution)); + primal_solution = pgs_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + dual_solution = G * primal_solution * dt * dt + g_tilde_move_away; + Eigen::VectorXd dual_solution2 = pgs_solver.getDualSolution(); + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(primal_solution.isZero()); + BOOST_CHECK(dual_solution.isApprox(g_tilde_move_away)); + BOOST_CHECK(dual_solution2.isApprox(g_tilde_move_away)); + } +} + +BOOST_AUTO_TEST_CASE(joint_limit_translation) +{ + Model model; + model.addJoint(0, JointModelTranslation(), SE3::Identity(), "slider"); + model.lowerPositionLimit[0] = 0.; + model.lowerPositionLimit[1] = 0.; + model.lowerPositionLimit[2] = 0.; + + const SE3::Vector3 box_dims = SE3::Vector3::Ones(); + const double box_mass = 10; + const Inertia box_inertia = Inertia::FromBox(box_mass, box_dims[0], box_dims[1], box_dims[2]); + + model.appendBodyToJoint(1, box_inertia); + model.gravity.setZero(); + Data data(model); + + Eigen::VectorXd q0 = Eigen::VectorXd::Zero(model.nq); + const Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + const Eigen::VectorXd tau_push_against_lower_bound = -Eigen::VectorXd::Ones(model.nv); + + const double dt = 1e-3; + + typedef JointLimitConstraintModel ConstraintModel; + typedef ConstraintModel::ConstraintData ConstraintData; + std::vector constraint_models; + std::vector constraint_datas; + + ConstraintModel joint_limit_constraint_model(model, ConstraintModel::JointIndexVector(1, 1)); + constraint_models.push_back(joint_limit_constraint_model); + + for (const auto & cm : constraint_models) + constraint_datas.push_back(cm.createData()); + + const Eigen::VectorXd v_free_against_lower_bound = + dt * aba(model, data, q0, v0, tau_push_against_lower_bound, Convention::WORLD); + const Eigen::VectorXd v_free_move_away = + dt * aba(model, data, q0, v0, -tau_push_against_lower_bound, Convention::WORLD); + + // Cholesky of the Delassus matrix + crba(model, data, q0, Convention::WORLD); + + data.q_in = q0; + auto & cmodel = constraint_models[0]; + auto & cdata = constraint_datas[0]; + cmodel.resize(model, data, cdata); + cmodel.calc(model, data, cdata); + ContactCholeskyDecomposition chol(model, constraint_models); + chol.resize(model, constraint_models); + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + + const Eigen::MatrixXd delassus_matrix_plain = chol.getDelassusCholeskyExpression().matrix(); + const auto & G = delassus_matrix_plain; + const DelassusOperatorDense delassus(G); + + Eigen::MatrixXd constraint_jacobian(cmodel.activeSize(), model.nv); + constraint_jacobian.setZero(); + getConstraintsJacobian(model, data, constraint_models, constraint_datas, constraint_jacobian); + + // External torques push the slider against the lower bound + { + const Eigen::VectorXd g_against_lower_bound = + constraint_jacobian * v_free_against_lower_bound * dt; + const Eigen::VectorXd g_tilde_against_lower_bound = + g_against_lower_bound + cdata.constraint_residual; + + Eigen::VectorXd dual_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + PGSContactSolver pgs_solver(int(delassus_matrix_plain.rows())); + pgs_solver.setAbsolutePrecision(1e-13); + pgs_solver.setRelativePrecision(1e-14); + const bool has_converged = pgs_solver.solve( + delassus, g_tilde_against_lower_bound, constraint_models, dt, + boost::make_optional((Eigen::Ref)primal_solution)); + primal_solution = pgs_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + dual_solution = G * primal_solution * dt * dt + g_tilde_against_lower_bound; + Eigen::VectorXd dual_solution2 = pgs_solver.getDualSolution(); + + // std::cout << "primal_solution: " << primal_solution.transpose() << std::endl; + // std::cout << "constraint_jacobian.transpose() * primal_solution: " << + // (constraint_jacobian.transpose() * primal_solution).transpose() << std::endl; std::cout << + // "dual_solution: " << dual_solution.transpose() << std::endl; std::cout << "dual_solution2: + // " << dual_solution2.transpose() << std::endl; + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(dual_solution.isZero()); + BOOST_CHECK(dual_solution2.isZero()); + + BOOST_CHECK((tau_push_against_lower_bound + constraint_jacobian.transpose() * primal_solution) + .isZero(1e-8)); + } + + // External torques push the slider away from the lower bound + { + const Eigen::VectorXd g_move_away = constraint_jacobian * v_free_move_away * dt; + const Eigen::VectorXd g_tilde_move_away = g_move_away + cdata.constraint_residual; + + Eigen::VectorXd dual_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + Eigen::VectorXd primal_solution = Eigen::VectorXd::Zero(cmodel.activeSize()); + PGSContactSolver pgs_solver(int(delassus_matrix_plain.rows())); + pgs_solver.setAbsolutePrecision(1e-13); + pgs_solver.setRelativePrecision(1e-14); + const bool has_converged = pgs_solver.solve( + delassus, g_tilde_move_away, constraint_models, dt, + boost::make_optional((Eigen::Ref)primal_solution)); + primal_solution = pgs_solver.getPrimalSolution(); + BOOST_CHECK(has_converged); + + dual_solution = G * primal_solution * dt * dt + g_tilde_move_away; + Eigen::VectorXd dual_solution2 = pgs_solver.getDualSolution(); + + BOOST_CHECK(std::fabs(primal_solution.dot(dual_solution)) <= 1e-8); + BOOST_CHECK(primal_solution.isZero()); + BOOST_CHECK(dual_solution.isApprox(g_tilde_move_away)); + BOOST_CHECK(dual_solution2.isApprox(g_tilde_move_away)); + } +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/point-bilateral-constraint.cpp b/unittest/point-bilateral-constraint.cpp new file mode 100644 index 0000000000..2a4365a20c --- /dev/null +++ b/unittest/point-bilateral-constraint.cpp @@ -0,0 +1,542 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#include "pinocchio/algorithm/aba.hpp" +#include "pinocchio/algorithm/rnea.hpp" +#include "pinocchio/algorithm/jacobian.hpp" +#include "pinocchio/algorithm/kinematics.hpp" +#include "pinocchio/algorithm/crba.hpp" +#include "pinocchio/algorithm/frames.hpp" +#include "pinocchio/algorithm/contact-info.hpp" +#include "pinocchio/algorithm/contact-cholesky.hpp" +#include "pinocchio/algorithm/contact-jacobian.hpp" +#include "pinocchio/algorithm/joint-configuration.hpp" +#include "pinocchio/multibody/sample-models.hpp" +#include "pinocchio/utils/timer.hpp" +#include "pinocchio/spatial/classic-acceleration.hpp" +#include "pinocchio/algorithm/constraints/point-bilateral-constraint.hpp" + +// Helpers +#include "constraints/jacobians-checker.hpp" + +#include + +#include +#include + +using namespace pinocchio; +using namespace Eigen; + +template +bool within(const T & elt, const std::vector & vec) +{ + typename std::vector::const_iterator it; + + it = std::find(vec.begin(), vec.end(), elt); + if (it != vec.end()) + return true; + else + return false; +} + +template +bool within(const typename Matrix::Scalar & elt, const Eigen::MatrixBase & mat) +{ + for (DenseIndex i = 0; i < mat.rows(); ++i) + for (DenseIndex j = 0; j < mat.rows(); ++j) + { + if (elt == mat(i, j)) + return true; + } + + return false; +} + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(basic_constructor) +{ + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + + // Check complete constructor + const SE3 M(SE3::Random()); + BilateralPointConstraintModel cmodel2(model, 0, M); + BOOST_CHECK(cmodel2.joint1_id == 0); + BOOST_CHECK(cmodel2.joint1_placement == M); + BOOST_CHECK(cmodel2.size() == 3); + + // Check contructor with two arguments + BilateralPointConstraintModel cmodel2prime(model, 0); + BOOST_CHECK(cmodel2prime.joint1_id == 0); + BOOST_CHECK(cmodel2prime.joint1_placement.isIdentity(0.)); + BOOST_CHECK(cmodel2prime.size() == 3); + + // Check default copy constructor + BilateralPointConstraintModel cmodel3(cmodel2); + BOOST_CHECK(cmodel3 == cmodel2); +} + +void check_A1_and_A2( + const Model & model, + const Data & data, + const BilateralPointConstraintModel & cmodel, + BilateralPointConstraintData & cdata) +{ + const BilateralPointConstraintModel::Matrix36 A1_world = cmodel.getA1(cdata, WorldFrameTag()); + BilateralPointConstraintModel::Matrix36 A1_world_ref = + -cdata.oMc1.toActionMatrixInverse().topRows<3>(); + A1_world_ref.rightCols<3>() += + skew(cdata.constraint_position_error) * cdata.oMc1.rotation().transpose(); + + BOOST_CHECK(A1_world.isApprox(A1_world_ref)); + + const BilateralPointConstraintModel::Matrix36 A2_world = cmodel.getA2(cdata, WorldFrameTag()); + const BilateralPointConstraintModel::Matrix36 A2_world_ref = + cdata.c1Mc2.rotation() * cdata.oMc2.toActionMatrixInverse().topRows<3>(); + + BOOST_CHECK(A2_world.isApprox(A2_world_ref)); + + const BilateralPointConstraintModel::Matrix36 A1_local = cmodel.getA1(cdata, LocalFrameTag()); + BilateralPointConstraintModel::Matrix36 A1_local_ref = + -cmodel.joint1_placement.toActionMatrixInverse().topRows<3>(); + A1_local_ref.rightCols<3>() += + skew(cdata.constraint_position_error) * cmodel.joint1_placement.rotation().transpose(); + + BOOST_CHECK(A1_local.isApprox(A1_local_ref)); + + const BilateralPointConstraintModel::Matrix36 A2_local = cmodel.getA2(cdata, LocalFrameTag()); + const BilateralPointConstraintModel::Matrix36 A2_local_ref = + cdata.c1Mc2.rotation() * cmodel.joint2_placement.toActionMatrixInverse().topRows<3>(); + + BOOST_CHECK(A2_local.isApprox(A2_local_ref)); + + // Check Jacobians + Data::MatrixXs J_ref(3, model.nv); + J_ref.setZero(); + getConstraintJacobian(model, data, cmodel, cdata, J_ref); + + // World + const Data::Matrix6x J1_world = getJointJacobian(model, data, cmodel.joint1_id, WORLD); + const Data::Matrix6x J2_world = getJointJacobian(model, data, cmodel.joint2_id, WORLD); + const Data::Matrix3x J_world = A1_world * J1_world + A2_world * J2_world; + + BOOST_CHECK(J_world.isApprox(J_ref)); + + // Local + const Data::Matrix6x J1_local = getJointJacobian(model, data, cmodel.joint1_id, LOCAL); + const Data::Matrix6x J2_local = getJointJacobian(model, data, cmodel.joint2_id, LOCAL); + const Data::Matrix3x J_local = A1_local * J1_local + A2_local * J2_local; + + BOOST_CHECK(J_local.isApprox(J_ref)); +} + +BOOST_AUTO_TEST_CASE(constraint3D_basic_operations) +{ + const pinocchio::Model model; + const pinocchio::Data data(model); + BilateralPointConstraintModel cm(model, 0, SE3::Random()); + BilateralPointConstraintData cd(cm); + cm.calc(model, data, cd); + + const pinocchio::SE3 placement = cm.joint1_placement; + pinocchio::SE3 placement_with_correction = placement; + placement_with_correction.translation() += placement.rotation() * cd.constraint_position_error; + + { + const Eigen::Vector3d diagonal_inertia(1, 2, 3); + + const pinocchio::SE3::Matrix6 spatial_inertia = + cm.computeConstraintSpatialInertia(placement_with_correction, diagonal_inertia); + BOOST_CHECK(spatial_inertia.transpose().isApprox(spatial_inertia)); // check symmetric matrix + + const auto A1 = cm.getA1(cd, LocalFrameTag()); + const pinocchio::SE3::Matrix6 spatial_inertia_ref = + A1.transpose() * diagonal_inertia.asDiagonal() * A1; + + BOOST_CHECK(spatial_inertia.isApprox(spatial_inertia_ref)); + } + + // Scalar + { + const double constant_value = 10; + const Eigen::Vector3d diagonal_inertia = Eigen::Vector3d::Constant(constant_value); + + const pinocchio::SE3::Matrix6 spatial_inertia = + cm.computeConstraintSpatialInertia(placement_with_correction, diagonal_inertia); + BOOST_CHECK(spatial_inertia.transpose().isApprox(spatial_inertia)); // check symmetric matrix + + const auto A1 = cm.getA1(cd, LocalFrameTag()); + const pinocchio::SE3::Matrix6 spatial_inertia_ref = + A1.transpose() * diagonal_inertia.asDiagonal() * A1; + + BOOST_CHECK(spatial_inertia.isApprox(spatial_inertia_ref)); + + const Inertia spatial_inertia_ref2( + constant_value, placement_with_correction.translation(), Symmetric3::Zero()); + BOOST_CHECK(spatial_inertia.isApprox(spatial_inertia_ref2.matrix())); + } +} + +template +Eigen::MatrixXd compute_jacobian_fd( + const Model & model, + const BilateralPointConstraintModel & cmodel, + const Eigen::MatrixBase & q, + const double eps) +{ + Data data_fd(model), data(model); + BilateralPointConstraintData cdata(cmodel), cdata_fd(cmodel); + + Eigen::MatrixXd res(3, model.nv); + res.setZero(); + + forwardKinematics(model, data, q), + + cmodel.calc(model, data, cdata); + Eigen::VectorXd v_plus(model.nv); + v_plus.setZero(); + + for (int i = 0; i < model.nv; ++i) + { + v_plus[i] = eps; + const auto q_plus = integrate(model, q, v_plus); + forwardKinematics(model, data_fd, q_plus), + + cmodel.calc(model, data_fd, cdata_fd); + + res.col(i) = (cdata_fd.constraint_position_error - cdata.constraint_position_error) / eps; + + v_plus[i] = 0; + } + + return res; +} + +Vector3d computeConstraintError( + const Model & model, const Data & data, const BilateralPointConstraintModel & cm) +{ + PINOCCHIO_UNUSED_VARIABLE(model); + + const SE3 oMc1 = data.oMi[cm.joint1_id] * cm.joint1_placement; + const SE3 oMc2 = data.oMi[cm.joint2_id] * cm.joint2_placement; + + const Vector3d error_world_frame = oMc2.translation() - oMc1.translation(); + const Vector3d error_local_frame1 = oMc1.rotation().transpose() * error_world_frame; + + return error_local_frame1; +} + +BOOST_AUTO_TEST_CASE(contact_models_sparsity_and_jacobians) +{ + + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + Data data(model); + + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); + VectorXd q = randomConfiguration(model); + VectorXd v = VectorXd::Random(model.nv); + VectorXd a = VectorXd::Random(model.nv); + + forwardKinematics(model, data, q, v); + computeJointJacobians(model, data, q); + + const std::string RF = "rleg6_joint"; + const std::string LF = "lleg6_joint"; + const double eps_fd = 1e-8; + + const BilateralPointConstraintModel cm_RF(model, model.getJointId(RF), SE3::Random()); + const BilateralPointConstraintModel cm_LF(model, model.getJointId(LF), SE3::Random()); + const BilateralPointConstraintModel clm_RF_LF( + model, cm_RF.joint1_id, cm_RF.joint1_placement, cm_LF.joint1_id, cm_LF.joint1_placement); + + // Check errors values + { + Data data(model); + + BilateralPointConstraintData cd_RF(cm_RF); + BilateralPointConstraintData cd_LF(cm_LF); + BilateralPointConstraintData cld_RF_LF(clm_RF_LF); + + forwardKinematics(model, data, q); + + cm_RF.calc(model, data, cd_RF); + const Vector3d position_error_RF_ref = computeConstraintError(model, data, cm_RF); + BOOST_CHECK(cd_RF.constraint_position_error.isApprox(position_error_RF_ref)); + + cm_LF.calc(model, data, cd_LF); + const Vector3d position_error_LF_ref = computeConstraintError(model, data, cm_LF); + BOOST_CHECK(cd_LF.constraint_position_error.isApprox(position_error_LF_ref)); + + clm_RF_LF.calc(model, data, cld_RF_LF); + const Vector3d position_error_RF_LF_ref = computeConstraintError(model, data, clm_RF_LF); + BOOST_CHECK(cld_RF_LF.constraint_position_error.isApprox(position_error_RF_LF_ref)); + } + { + forwardKinematics(model, data, q, v, a); + + BilateralPointConstraintData cd_RF(cm_RF); + cm_RF.calc(model, data, cd_RF); + BilateralPointConstraintData cd_LF(cm_LF); + cm_LF.calc(model, data, cd_LF); + BilateralPointConstraintData cld_RF_LF(clm_RF_LF); + clm_RF_LF.calc(model, data, cld_RF_LF); + + Data::Matrix6x J6_RF_LOCAL(6, model.nv); + J6_RF_LOCAL.setZero(); + getFrameJacobian(model, data, cm_RF.joint1_id, cm_RF.joint1_placement, LOCAL, J6_RF_LOCAL); + Data::Matrix3x J_RF_LOCAL(3, model.nv); + J_RF_LOCAL = -J6_RF_LOCAL.middleRows<3>(SE3::LINEAR); + J_RF_LOCAL += cross(cd_RF.constraint_position_error, J6_RF_LOCAL.middleRows<3>(SE3::ANGULAR)); + + Data::Matrix6x J6_LF_LOCAL(6, model.nv); + J6_LF_LOCAL.setZero(); + getFrameJacobian(model, data, cm_LF.joint1_id, cm_LF.joint1_placement, LOCAL, J6_LF_LOCAL); + Data::Matrix3x J_LF_LOCAL(3, model.nv); + J_LF_LOCAL = -J6_LF_LOCAL.middleRows<3>(SE3::LINEAR); + J_LF_LOCAL += cross(cd_LF.constraint_position_error, J6_LF_LOCAL.middleRows<3>(SE3::ANGULAR)); + + for (DenseIndex k = 0; k < model.nv; ++k) + { + BOOST_CHECK( + J_RF_LOCAL.middleRows<3>(SE3::LINEAR).col(k).isZero() != cm_RF.colwise_joint1_sparsity[k]); + BOOST_CHECK( + J_LF_LOCAL.middleRows<3>(SE3::LINEAR).col(k).isZero() != cm_LF.colwise_joint1_sparsity[k]); + } + BOOST_CHECK(cm_RF.colwise_joint2_sparsity.isZero()); + BOOST_CHECK(cm_LF.colwise_joint2_sparsity.isZero()); + + const SE3 oMc1 = data.oMi[clm_RF_LF.joint1_id] * clm_RF_LF.joint1_placement; + const SE3 oMc2 = data.oMi[clm_RF_LF.joint2_id] * clm_RF_LF.joint2_placement; + const SE3 c1Mc2 = oMc1.actInv(oMc2); + Data::Matrix3x J_clm_LOCAL = c1Mc2.rotation() * J6_LF_LOCAL.middleRows<3>(SE3::LINEAR) + - J6_RF_LOCAL.middleRows<3>(SE3::LINEAR); + J_clm_LOCAL += + cross(cld_RF_LF.constraint_position_error, J6_RF_LOCAL.middleRows<3>(SE3::ANGULAR)); + + for (DenseIndex k = 0; k < model.nv; ++k) + { + BOOST_CHECK(J_clm_LOCAL.col(k).isZero(0) != within(k, clm_RF_LF.colwise_span_indexes)); + } + + // Check Jacobian vs sparse Jacobian computation + Data::MatrixXs J_RF_sparse(3, model.nv); + J_RF_sparse.setZero(); // TODO: change input type when all the API would be refactorized + // with CRTP on contact constraints + getConstraintJacobian(model, data, cm_RF, cd_RF, J_RF_sparse); + BOOST_CHECK(J_RF_LOCAL.isApprox(J_RF_sparse)); + + const auto J_RF_fd = compute_jacobian_fd(model, cm_RF, q, eps_fd); + BOOST_CHECK(J_RF_sparse.isApprox(J_RF_fd, sqrt(eps_fd))); + + Data::MatrixXs J_LF_sparse(3, model.nv); + J_LF_sparse.setZero(); // TODO: change input type when all the API would be refactorized + // with CRTP on contact constraints + getConstraintJacobian(model, data, cm_LF, cd_LF, J_LF_sparse); + BOOST_CHECK(J_LF_LOCAL.middleRows<3>(SE3::LINEAR).isApprox(J_LF_sparse)); + + const auto J_LF_fd = compute_jacobian_fd(model, cm_LF, q, eps_fd); + BOOST_CHECK(J_LF_sparse.isApprox(J_LF_fd, sqrt(eps_fd))); + + Data::MatrixXs J_clm_sparse(3, model.nv); + J_clm_sparse.setZero(); // TODO: change input type when all the API would be refactorized + // with CRTP on contact constraints + getConstraintJacobian(model, data, clm_RF_LF, cld_RF_LF, J_clm_sparse); + BOOST_CHECK(J_clm_LOCAL.isApprox(J_clm_sparse)); + + const auto J_clm_fd = compute_jacobian_fd(model, clm_RF_LF, q, eps_fd); + BOOST_CHECK(J_clm_sparse.isApprox(J_clm_fd, sqrt(eps_fd))); + + // Check velocity and acceleration + { + const double dt = eps_fd; + BilateralPointConstraintData cd_RF(cm_RF), cd_RF_plus(cm_RF); + cm_RF.calc(model, data, cd_RF); + + Data data_plus(model); + const VectorXd v_plus = v + a * dt; + const VectorXd q_plus = integrate(model, q, v_plus * dt); + forwardKinematics(model, data_plus, q_plus, v_plus); + + { + BilateralPointConstraintData cd_RF(cm_RF), cd_RF_plus(cm_RF); + cm_RF.calc(model, data, cd_RF); + BOOST_CHECK(cd_RF.constraint_velocity_error.isApprox(J_RF_sparse * v)); + + cm_RF.calc(model, data_plus, cd_RF_plus); + const Vector3d constraint_velocity_error_fd = + (cd_RF_plus.constraint_position_error - cd_RF.constraint_position_error) / dt; + BOOST_CHECK( + cd_RF.constraint_velocity_error.isApprox(constraint_velocity_error_fd, sqrt(dt))); + + const Vector3d constraint_acceleration_error_fd = + (cd_RF_plus.constraint_velocity_error - cd_RF.constraint_velocity_error) / dt; + BOOST_CHECK( + cd_RF.constraint_acceleration_error.isApprox(constraint_acceleration_error_fd, sqrt(dt))); + } + + { + BilateralPointConstraintData cd_LF(cm_LF), cd_LF_plus(cm_LF); + cm_LF.calc(model, data, cd_LF); + BOOST_CHECK(cd_LF.constraint_velocity_error.isApprox(J_LF_sparse * v)); + + cm_LF.calc(model, data_plus, cd_LF_plus); + const Vector3d constraint_velocity_error_fd = + (cd_LF_plus.constraint_position_error - cd_LF.constraint_position_error) / dt; + BOOST_CHECK( + cd_LF.constraint_velocity_error.isApprox(constraint_velocity_error_fd, sqrt(dt))); + + const Vector3d constraint_acceleration_error_fd = + (cd_LF_plus.constraint_velocity_error - cd_LF.constraint_velocity_error) / dt; + BOOST_CHECK( + cd_LF.constraint_acceleration_error.isApprox(constraint_acceleration_error_fd, sqrt(dt))); + } + + { + BilateralPointConstraintData cld_RF_LF(clm_RF_LF), cld_RF_LF_plus(clm_RF_LF); + clm_RF_LF.calc(model, data, cld_RF_LF); + BOOST_CHECK(cld_RF_LF.constraint_velocity_error.isApprox(J_clm_sparse * v)); + + clm_RF_LF.calc(model, data_plus, cld_RF_LF_plus); + const Vector3d constraint_velocity_error_fd = + (cld_RF_LF_plus.constraint_position_error - cld_RF_LF.constraint_position_error) / dt; + BOOST_CHECK( + cld_RF_LF.constraint_velocity_error.isApprox(constraint_velocity_error_fd, sqrt(dt))); + + const Vector3d constraint_acceleration_error_fd = + (cld_RF_LF_plus.constraint_velocity_error - cld_RF_LF.constraint_velocity_error) / dt; + BOOST_CHECK(cld_RF_LF.constraint_acceleration_error.isApprox( + constraint_acceleration_error_fd, sqrt(dt))); + } + } + + check_A1_and_A2(model, data, cm_RF, cd_RF); + check_jacobians_operations(model, data, cm_RF, cd_RF); + + check_A1_and_A2(model, data, cm_LF, cd_LF); + check_jacobians_operations(model, data, cm_LF, cd_LF); + + check_A1_and_A2(model, data, clm_RF_LF, cld_RF_LF); + check_jacobians_operations(model, data, clm_RF_LF, cld_RF_LF); + + // Check acceleration contributions + { + Data data(model), data_zero_acc(model); + forwardKinematics(model, data, q, v, a); + computeJointJacobians(model, data, q); + forwardKinematics(model, data_zero_acc, q, v, VectorXd::Zero(model.nv)); + + // RF + BilateralPointConstraintData cd_RF(cm_RF), cd_RF_zero_acc(cm_RF); + cm_RF.calc(model, data, cd_RF); + cm_RF.calc(model, data_zero_acc, cd_RF_zero_acc); + + Data::MatrixXs J_RF_sparse(3, model.nv); + J_RF_sparse.setZero(); + cm_RF.jacobian(model, data, cd_RF, J_RF_sparse); + + BOOST_CHECK((J_RF_sparse * a + cd_RF_zero_acc.constraint_acceleration_error) + .isApprox(cd_RF.constraint_acceleration_error)); + + // LF + BilateralPointConstraintData cd_LF(cm_LF), cd_LF_zero_acc(cm_LF); + cm_LF.calc(model, data, cd_LF); + cm_LF.calc(model, data_zero_acc, cd_LF_zero_acc); + + Data::MatrixXs J_LF_sparse(3, model.nv); + J_LF_sparse.setZero(); + cm_LF.jacobian(model, data, cd_LF, J_LF_sparse); + + BOOST_CHECK((J_LF_sparse * a + cd_LF_zero_acc.constraint_acceleration_error) + .isApprox(cd_LF.constraint_acceleration_error)); + + // Close loop + BilateralPointConstraintData cld_RF_LF(clm_RF_LF), cld_RF_LF_zero_acc(clm_RF_LF); + clm_RF_LF.calc(model, data, cld_RF_LF); + clm_RF_LF.calc(model, data_zero_acc, cld_RF_LF_zero_acc); + + Data::MatrixXs J_clm_sparse(3, model.nv); + J_clm_sparse.setZero(); + clm_RF_LF.jacobian(model, data, cld_RF_LF, J_clm_sparse); + + BOOST_CHECK((J_clm_sparse * a + cld_RF_LF_zero_acc.constraint_acceleration_error) + .isApprox(cld_RF_LF.constraint_acceleration_error)); + } + } +} + +BOOST_AUTO_TEST_CASE(cast) +{ + + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + + const std::string RF = "rleg6_joint"; + + const BilateralPointConstraintModel cm_RF(model, model.getJointId(RF), SE3::Random()); + const auto cm_RF_cast_double = cm_RF.cast(); + BOOST_CHECK(cm_RF_cast_double == cm_RF); + + const auto cm_RF_cast_long_double = cm_RF.cast(); + BOOST_CHECK(cm_RF_cast_long_double.cast() == cm_RF); +} + +BOOST_AUTO_TEST_CASE(cholesky) +{ + + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + Data data(model), data_ref(model); + + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); + VectorXd q = randomConfiguration(model); + VectorXd v = VectorXd::Random(model.nv); + VectorXd a = VectorXd::Random(model.nv); + + crba(model, data, q, Convention::WORLD); + + const std::string RF = "rleg6_joint"; + const std::string LF = "lleg6_joint"; + + const BilateralPointConstraintModel cm_RF(model, model.getJointId(RF), SE3::Random()); + const BilateralPointConstraintModel cm_LF(model, model.getJointId(LF), SE3::Random()); + const BilateralPointConstraintModel clm_RF_LF( + model, cm_RF.joint1_id, cm_RF.joint1_placement, cm_LF.joint1_id, cm_LF.joint1_placement); + + std::vector constraint_models; + constraint_models.push_back(cm_RF); + constraint_models.push_back(cm_LF); + constraint_models.push_back(clm_RF_LF); + + std::vector constraint_datas, constraint_datas_ref; + for (const auto & cm : constraint_models) + { + constraint_datas.push_back(cm.createData()); + constraint_datas_ref.push_back(cm.createData()); + } + + const double mu = 1e-10; + ContactCholeskyDecomposition cholesky(model, constraint_models); + cholesky.compute(model, data, constraint_models, constraint_datas, mu); + + crba(model, data_ref, q, Convention::WORLD); + make_symmetric(data_ref.M); + const auto total_size = getTotalConstraintSize(constraint_models); + Eigen::MatrixXd J_constraints(total_size, model.nv); + J_constraints.setZero(); + getConstraintsJacobian(model, data_ref, constraint_models, constraint_datas, J_constraints); + + Eigen::MatrixXd H_ref = Eigen::MatrixXd::Zero(total_size + model.nv, total_size + model.nv); + H_ref.topLeftCorner(total_size, total_size).diagonal().fill(-mu); + H_ref.bottomRightCorner(model.nv, model.nv) = data_ref.M; + H_ref.topRightCorner(total_size, model.nv) = J_constraints; + H_ref.bottomLeftCorner(model.nv, total_size) = J_constraints.transpose(); + + BOOST_CHECK(cholesky.matrix().isApprox(H_ref)); +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/point-frictional-constraint.cpp b/unittest/point-frictional-constraint.cpp new file mode 100644 index 0000000000..531ff9464f --- /dev/null +++ b/unittest/point-frictional-constraint.cpp @@ -0,0 +1,817 @@ +// +// Copyright (c) 2024-2025 INRIA +// + +#include "pinocchio/algorithm/aba.hpp" +#include "pinocchio/algorithm/rnea.hpp" +#include "pinocchio/algorithm/jacobian.hpp" +#include "pinocchio/algorithm/kinematics.hpp" +#include "pinocchio/algorithm/crba.hpp" +#include "pinocchio/algorithm/frames.hpp" +#include "pinocchio/algorithm/contact-info.hpp" +#include "pinocchio/algorithm/contact-cholesky.hpp" +#include "pinocchio/algorithm/contact-jacobian.hpp" +#include "pinocchio/algorithm/joint-configuration.hpp" +#include "pinocchio/multibody/sample-models.hpp" +#include "pinocchio/utils/timer.hpp" +#include "pinocchio/spatial/classic-acceleration.hpp" +#include "pinocchio/algorithm/constraints/point-bilateral-constraint.hpp" + +// Helpers +#include "constraints/jacobians-checker.hpp" + +#include + +#include +#include + +using namespace pinocchio; +using namespace Eigen; + +template +bool within(const T & elt, const std::vector & vec) +{ + typename std::vector::const_iterator it; + + it = std::find(vec.begin(), vec.end(), elt); + if (it != vec.end()) + return true; + else + return false; +} + +template +bool within(const typename Matrix::Scalar & elt, const Eigen::MatrixBase & mat) +{ + for (DenseIndex i = 0; i < mat.rows(); ++i) + for (DenseIndex j = 0; j < mat.rows(); ++j) + { + if (elt == mat(i, j)) + return true; + } + + return false; +} + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(basic_constructor) +{ + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + + // Check complete constructor + const SE3 M(SE3::Random()); + BilateralPointConstraintModel cmodel2(model, 0, M); + BOOST_CHECK(cmodel2.joint1_id == 0); + BOOST_CHECK(cmodel2.joint1_placement == M); + BOOST_CHECK(cmodel2.size() == 3); + + // Check contructor with two arguments + BilateralPointConstraintModel cmodel2prime(model, 0); + BOOST_CHECK(cmodel2prime.joint1_id == 0); + BOOST_CHECK(cmodel2prime.joint1_placement.isIdentity(0.)); + BOOST_CHECK(cmodel2prime.size() == 3); + + // Check default copy constructor + BilateralPointConstraintModel cmodel3(cmodel2); + BOOST_CHECK(cmodel3 == cmodel2); +} + +void check_A1_and_A2( + const Model & model, + const Data & data, + const BilateralPointConstraintModel & cmodel, + BilateralPointConstraintData & cdata) +{ + const BilateralPointConstraintModel::Matrix36 A1_world = cmodel.getA1(cdata, WorldFrameTag()); + BilateralPointConstraintModel::Matrix36 A1_world_ref = + -cdata.oMc1.toActionMatrixInverse().topRows<3>(); + A1_world_ref.rightCols<3>() += + skew(cdata.constraint_position_error) * cdata.oMc1.rotation().transpose(); + + BOOST_CHECK(A1_world.isApprox(A1_world_ref)); + + const BilateralPointConstraintModel::Matrix36 A2_world = cmodel.getA2(cdata, WorldFrameTag()); + const BilateralPointConstraintModel::Matrix36 A2_world_ref = + cdata.c1Mc2.rotation() * cdata.oMc2.toActionMatrixInverse().topRows<3>(); + + BOOST_CHECK(A2_world.isApprox(A2_world_ref)); + + const BilateralPointConstraintModel::Matrix36 A1_local = cmodel.getA1(cdata, LocalFrameTag()); + BilateralPointConstraintModel::Matrix36 A1_local_ref = + -cmodel.joint1_placement.toActionMatrixInverse().topRows<3>(); + A1_local_ref.rightCols<3>() += + skew(cdata.constraint_position_error) * cmodel.joint1_placement.rotation().transpose(); + + BOOST_CHECK(A1_local.isApprox(A1_local_ref)); + + const BilateralPointConstraintModel::Matrix36 A2_local = cmodel.getA2(cdata, LocalFrameTag()); + const BilateralPointConstraintModel::Matrix36 A2_local_ref = + cdata.c1Mc2.rotation() * cmodel.joint2_placement.toActionMatrixInverse().topRows<3>(); + + BOOST_CHECK(A2_local.isApprox(A2_local_ref)); + + // Check Jacobians + Data::MatrixXs J_ref(3, model.nv); + J_ref.setZero(); + getConstraintJacobian(model, data, cmodel, cdata, J_ref); + + // World + const Data::Matrix6x J1_world = getJointJacobian(model, data, cmodel.joint1_id, WORLD); + const Data::Matrix6x J2_world = getJointJacobian(model, data, cmodel.joint2_id, WORLD); + const Data::Matrix3x J_world = A1_world * J1_world + A2_world * J2_world; + + BOOST_CHECK(J_world.isApprox(J_ref)); + + // Local + const Data::Matrix6x J1_local = getJointJacobian(model, data, cmodel.joint1_id, LOCAL); + const Data::Matrix6x J2_local = getJointJacobian(model, data, cmodel.joint2_id, LOCAL); + const Data::Matrix3x J_local = A1_local * J1_local + A2_local * J2_local; + + BOOST_CHECK(J_local.isApprox(J_ref)); + + // Check Jacobian matrix product + const Eigen::DenseIndex m = 40; + const Data::MatrixXs mat = Data::MatrixXs::Random(model.nv, m); + + Data::MatrixXs res(cmodel.size(), m); + res.setZero(); + cmodel.jacobianMatrixProduct(model, data, cdata, mat, res); + + const Data::MatrixXs res_ref = J_ref * mat; + + BOOST_CHECK(res.isApprox(res_ref)); +} + +BOOST_AUTO_TEST_CASE(constraint3D_basic_operations) +{ + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + Data data(model), data_ref(model); + + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); + const VectorXd q = randomConfiguration(model); + + crba(model, data, q, Convention::WORLD); + + const std::string RF_name = "rleg6_joint"; + const std::string LF_name = "lleg6_joint"; + + BilateralPointConstraintModel cm( + model, model.getJointId(RF_name), SE3::Random(), model.getJointId(LF_name), SE3::Random()); + BilateralPointConstraintData cd(cm); + cm.calc(model, data, cd); + + // Vector LOCAL + { + const pinocchio::SE3 placement_local = cm.joint1_placement; + pinocchio::SE3 placement_local_with_correction = placement_local; + placement_local_with_correction.translation() += + placement_local.rotation() * cd.constraint_position_error; + + const Eigen::Vector3d diagonal_inertia(1, 2, 3); + + const pinocchio::SE3::Matrix6 spatial_inertia_join1 = + cm.computeConstraintSpatialInertia(placement_local_with_correction, diagonal_inertia); + BOOST_CHECK( + spatial_inertia_join1.transpose().isApprox(spatial_inertia_join1)); // check symmetric matrix + + const auto A1 = cm.getA1(cd, LocalFrameTag()); + BOOST_CHECK(A1.isApprox(cd.A1_local)); + const Inertia::Matrix6 I11_ref = A1.transpose() * diagonal_inertia.asDiagonal() * A1; + + BOOST_CHECK(spatial_inertia_join1.isApprox(I11_ref)); + + const auto A2 = cm.getA2(cd, LocalFrameTag()); + BOOST_CHECK(A2.isApprox(cd.A2_local)); + const Inertia::Matrix6 I22_ref = A2.transpose() * diagonal_inertia.asDiagonal() * A2; + + const Inertia::Matrix6 I12_ref = A1.transpose() * diagonal_inertia.asDiagonal() * A2; + + Inertia::Matrix6 I11 = -Inertia::Matrix6::Ones(), I12 = -Inertia::Matrix6::Ones(), + I22 = -Inertia::Matrix6::Ones(); + + cm.computeConstraintInertias(cd, diagonal_inertia, I11, I12, I22, LocalFrameTag()); + BOOST_CHECK(I11.isApprox(I11_ref)); + BOOST_CHECK(I12.isApprox(I12_ref)); + BOOST_CHECK(I22.isApprox(I22_ref)); + + // Check against scalar signature + const double constant_inertia_value = 10; + const Eigen::Vector3d diagonal_inertia_scalar = + Eigen::Vector3d::Constant(constant_inertia_value); + Inertia::Matrix6 I11_scalar = -Inertia::Matrix6::Ones(), I12_scalar = -Inertia::Matrix6::Ones(), + I22_scalar = -Inertia::Matrix6::Ones(); + + cm.computeConstraintInertias(cd, diagonal_inertia_scalar, I11, I12, I22, LocalFrameTag()); + cm.computeConstraintInertias( + cd, constant_inertia_value, I11_scalar, I12_scalar, I22_scalar, LocalFrameTag()); + BOOST_CHECK(I11 == I11_scalar); + BOOST_CHECK(I12 == I12_scalar); + BOOST_CHECK(I22 == I22_scalar); + } + + // Vector WORLD + { + const Eigen::Vector3d diagonal_inertia(1, 2, 3); + + const pinocchio::SE3 placement_world = cd.oMc1; + pinocchio::SE3 placement_world_with_correction = placement_world; + placement_world_with_correction.translation() += + placement_world.rotation() * cd.constraint_position_error; + + const pinocchio::SE3::Matrix6 spatial_inertia_join1 = + cm.computeConstraintSpatialInertia(placement_world_with_correction, diagonal_inertia); + BOOST_CHECK( + spatial_inertia_join1.transpose().isApprox(spatial_inertia_join1)); // check symmetric matrix + + const auto A1 = cm.getA1(cd, WorldFrameTag()); + const Inertia::Matrix6 I11_ref = A1.transpose() * diagonal_inertia.asDiagonal() * A1; + + BOOST_CHECK(spatial_inertia_join1.isApprox(I11_ref)); + + const auto A2 = cm.getA2(cd, WorldFrameTag()); + const Inertia::Matrix6 I22_ref = A2.transpose() * diagonal_inertia.asDiagonal() * A2; + + const Inertia::Matrix6 I12_ref = A1.transpose() * diagonal_inertia.asDiagonal() * A2; + + Inertia::Matrix6 I11 = -Inertia::Matrix6::Ones(), I12 = -Inertia::Matrix6::Ones(), + I22 = -Inertia::Matrix6::Ones(); + + cm.computeConstraintInertias(cd, diagonal_inertia, I11, I12, I22, WorldFrameTag()); + BOOST_CHECK(I11.isApprox(I11_ref)); + BOOST_CHECK(I12.isApprox(I12_ref)); + BOOST_CHECK(I22.isApprox(I22_ref)); + + // Check against scalar signature + const double constant_inertia_value = 10; + const Eigen::Vector3d diagonal_inertia_scalar = + Eigen::Vector3d::Constant(constant_inertia_value); + Inertia::Matrix6 I11_scalar = -Inertia::Matrix6::Ones(), I12_scalar = -Inertia::Matrix6::Ones(), + I22_scalar = -Inertia::Matrix6::Ones(); + + cm.computeConstraintInertias(cd, diagonal_inertia_scalar, I11, I12, I22, WorldFrameTag()); + cm.computeConstraintInertias( + cd, constant_inertia_value, I11_scalar, I12_scalar, I22_scalar, WorldFrameTag()); + BOOST_CHECK(I11 == I11_scalar); + BOOST_CHECK(I12 == I12_scalar); + BOOST_CHECK(I22 == I22_scalar); + } + + // Check null values + { + BilateralPointConstraintModel cm1(model, model.getJointId(RF_name), SE3::Random()); + BilateralPointConstraintData cd1(cm1); + cm1.calc(model, data, cd1); + + Inertia::Matrix6 I11 = -Inertia::Matrix6::Ones(), I12 = -Inertia::Matrix6::Ones(), + I22 = -Inertia::Matrix6::Ones(); + + const double constant_inertia_value = 10; + cm1.computeConstraintInertias(cd1, constant_inertia_value, I11, I12, I22, WorldFrameTag()); + BOOST_CHECK(!I11.isZero(0)); + BOOST_CHECK(I12.isZero(0)); + BOOST_CHECK(I22.isZero(0)); + + I11.fill(-1); + I12.fill(-1); + I22.fill(-1); + cm1.computeConstraintInertias(cd1, constant_inertia_value, I11, I12, I22, LocalFrameTag()); + BOOST_CHECK(!I11.isZero(0)); + BOOST_CHECK(I12.isZero(0)); + BOOST_CHECK(I22.isZero(0)); + + BilateralPointConstraintModel cm2( + model, 0, SE3::Identity(), model.getJointId(RF_name), SE3::Random()); + BilateralPointConstraintData cd2(cm2); + cm2.calc(model, data, cd2); + + I11.fill(-1); + I12.fill(-1); + I22.fill(-1); + cm2.computeConstraintInertias(cd2, constant_inertia_value, I11, I12, I22, WorldFrameTag()); + BOOST_CHECK(I11.isZero(0)); + BOOST_CHECK(I12.isZero(0)); + BOOST_CHECK(!I22.isZero(0)); + + I11.fill(-1); + I12.fill(-1); + I22.fill(-1); + cm2.computeConstraintInertias(cd2, constant_inertia_value, I11, I12, I22, LocalFrameTag()); + BOOST_CHECK(I11.isZero(0)); + BOOST_CHECK(I12.isZero(0)); + BOOST_CHECK(!I22.isZero(0)); + } +} + +template +Eigen::MatrixXd compute_jacobian_fd( + const Model & model, + const BilateralPointConstraintModel & cmodel, + const Eigen::MatrixBase & q, + const double eps) +{ + Data data_fd(model), data(model); + BilateralPointConstraintData cdata(cmodel), cdata_fd(cmodel); + + Eigen::MatrixXd res(3, model.nv); + res.setZero(); + + forwardKinematics(model, data, q), + + cmodel.calc(model, data, cdata); + Eigen::VectorXd v_plus(model.nv); + v_plus.setZero(); + + for (int i = 0; i < model.nv; ++i) + { + v_plus[i] = eps; + const auto q_plus = integrate(model, q, v_plus); + forwardKinematics(model, data_fd, q_plus), + + cmodel.calc(model, data_fd, cdata_fd); + + res.col(i) = (cdata_fd.constraint_position_error - cdata.constraint_position_error) / eps; + + v_plus[i] = 0; + } + + return res; +} + +Vector3d computeConstraintError( + const Model & model, const Data & data, const BilateralPointConstraintModel & cm) +{ + PINOCCHIO_UNUSED_VARIABLE(model); + + const SE3 oMc1 = data.oMi[cm.joint1_id] * cm.joint1_placement; + const SE3 oMc2 = data.oMi[cm.joint2_id] * cm.joint2_placement; + + const Vector3d error_world_frame = oMc2.translation() - oMc1.translation(); + const Vector3d error_local_frame1 = oMc1.rotation().transpose() * error_world_frame; + + return error_local_frame1; +} + +BOOST_AUTO_TEST_CASE(contact_models_sparsity_and_jacobians) +{ + + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + Data data(model); + + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); + VectorXd q = randomConfiguration(model); + VectorXd v = VectorXd::Random(model.nv); + VectorXd a = VectorXd::Random(model.nv); + + forwardKinematics(model, data, q, v); + computeJointJacobians(model, data, q); + + const std::string RF = "rleg6_joint"; + const std::string LF = "lleg6_joint"; + const double eps_fd = 1e-8; + + const BilateralPointConstraintModel cm_RF(model, model.getJointId(RF), SE3::Random()); + const BilateralPointConstraintModel cm_LF(model, model.getJointId(LF), SE3::Random()); + const BilateralPointConstraintModel clm_RF_LF( + model, cm_RF.joint1_id, cm_RF.joint1_placement, cm_LF.joint1_id, cm_LF.joint1_placement); + + // Check errors values + { + Data data(model); + + BilateralPointConstraintData cd_RF(cm_RF); + BilateralPointConstraintData cd_LF(cm_LF); + BilateralPointConstraintData cld_RF_LF(clm_RF_LF); + + forwardKinematics(model, data, q); + + cm_RF.calc(model, data, cd_RF); + const Vector3d position_error_RF_ref = computeConstraintError(model, data, cm_RF); + BOOST_CHECK(cd_RF.constraint_position_error.isApprox(position_error_RF_ref)); + + cm_LF.calc(model, data, cd_LF); + const Vector3d position_error_LF_ref = computeConstraintError(model, data, cm_LF); + BOOST_CHECK(cd_LF.constraint_position_error.isApprox(position_error_LF_ref)); + + clm_RF_LF.calc(model, data, cld_RF_LF); + const Vector3d position_error_RF_LF_ref = computeConstraintError(model, data, clm_RF_LF); + BOOST_CHECK(cld_RF_LF.constraint_position_error.isApprox(position_error_RF_LF_ref)); + } + { + forwardKinematics(model, data, q, v, a); + + BilateralPointConstraintData cd_RF(cm_RF); + cm_RF.calc(model, data, cd_RF); + BilateralPointConstraintData cd_LF(cm_LF); + cm_LF.calc(model, data, cd_LF); + BilateralPointConstraintData cld_RF_LF(clm_RF_LF); + clm_RF_LF.calc(model, data, cld_RF_LF); + + Data::Matrix6x J6_RF_LOCAL(6, model.nv); + J6_RF_LOCAL.setZero(); + getFrameJacobian(model, data, cm_RF.joint1_id, cm_RF.joint1_placement, LOCAL, J6_RF_LOCAL); + Data::Matrix3x J_RF_LOCAL(3, model.nv); + J_RF_LOCAL = -J6_RF_LOCAL.middleRows<3>(SE3::LINEAR); + J_RF_LOCAL += cross(cd_RF.constraint_position_error, J6_RF_LOCAL.middleRows<3>(SE3::ANGULAR)); + + Data::Matrix6x J6_LF_LOCAL(6, model.nv); + J6_LF_LOCAL.setZero(); + getFrameJacobian(model, data, cm_LF.joint1_id, cm_LF.joint1_placement, LOCAL, J6_LF_LOCAL); + Data::Matrix3x J_LF_LOCAL(3, model.nv); + J_LF_LOCAL = -J6_LF_LOCAL.middleRows<3>(SE3::LINEAR); + J_LF_LOCAL += cross(cd_LF.constraint_position_error, J6_LF_LOCAL.middleRows<3>(SE3::ANGULAR)); + + for (DenseIndex k = 0; k < model.nv; ++k) + { + BOOST_CHECK( + J_RF_LOCAL.middleRows<3>(SE3::LINEAR).col(k).isZero() != cm_RF.colwise_joint1_sparsity[k]); + BOOST_CHECK( + J_LF_LOCAL.middleRows<3>(SE3::LINEAR).col(k).isZero() != cm_LF.colwise_joint1_sparsity[k]); + } + BOOST_CHECK(cm_RF.colwise_joint2_sparsity.isZero()); + BOOST_CHECK(cm_LF.colwise_joint2_sparsity.isZero()); + + const SE3 oMc1 = data.oMi[clm_RF_LF.joint1_id] * clm_RF_LF.joint1_placement; + const SE3 oMc2 = data.oMi[clm_RF_LF.joint2_id] * clm_RF_LF.joint2_placement; + const SE3 c1Mc2 = oMc1.actInv(oMc2); + Data::Matrix3x J_clm_LOCAL = c1Mc2.rotation() * J6_LF_LOCAL.middleRows<3>(SE3::LINEAR) + - J6_RF_LOCAL.middleRows<3>(SE3::LINEAR); + J_clm_LOCAL += + cross(cld_RF_LF.constraint_position_error, J6_RF_LOCAL.middleRows<3>(SE3::ANGULAR)); + + for (DenseIndex k = 0; k < model.nv; ++k) + { + BOOST_CHECK(J_clm_LOCAL.col(k).isZero(0) != within(k, clm_RF_LF.colwise_span_indexes)); + } + + // Check Jacobian vs sparse Jacobian computation + Data::MatrixXs J_RF_sparse(3, model.nv); + J_RF_sparse.setZero(); // TODO: change input type when all the API would be refactorized + // with CRTP on contact constraints + getConstraintJacobian(model, data, cm_RF, cd_RF, J_RF_sparse); + BOOST_CHECK(J_RF_LOCAL.isApprox(J_RF_sparse)); + + const auto J_RF_fd = compute_jacobian_fd(model, cm_RF, q, eps_fd); + BOOST_CHECK(J_RF_sparse.isApprox(J_RF_fd, sqrt(eps_fd))); + + Data::MatrixXs J_LF_sparse(3, model.nv); + J_LF_sparse.setZero(); // TODO: change input type when all the API would be refactorized + // with CRTP on contact constraints + getConstraintJacobian(model, data, cm_LF, cd_LF, J_LF_sparse); + BOOST_CHECK(J_LF_LOCAL.middleRows<3>(SE3::LINEAR).isApprox(J_LF_sparse)); + + const auto J_LF_fd = compute_jacobian_fd(model, cm_LF, q, eps_fd); + BOOST_CHECK(J_LF_sparse.isApprox(J_LF_fd, sqrt(eps_fd))); + + Data::MatrixXs J_clm_sparse(3, model.nv); + J_clm_sparse.setZero(); // TODO: change input type when all the API would be refactorized + // with CRTP on contact constraints + getConstraintJacobian(model, data, clm_RF_LF, cld_RF_LF, J_clm_sparse); + BOOST_CHECK(J_clm_LOCAL.isApprox(J_clm_sparse)); + + const auto J_clm_fd = compute_jacobian_fd(model, clm_RF_LF, q, eps_fd); + BOOST_CHECK(J_clm_sparse.isApprox(J_clm_fd, sqrt(eps_fd))); + + // Check velocity and acceleration + { + const double dt = eps_fd; + BilateralPointConstraintData cd_RF(cm_RF), cd_RF_plus(cm_RF); + cm_RF.calc(model, data, cd_RF); + + Data data_plus(model); + const VectorXd v_plus = v + a * dt; + const VectorXd q_plus = integrate(model, q, v_plus * dt); + forwardKinematics(model, data_plus, q_plus, v_plus); + + { + BilateralPointConstraintData cd_RF(cm_RF), cd_RF_plus(cm_RF); + cm_RF.calc(model, data, cd_RF); + BOOST_CHECK(cd_RF.constraint_velocity_error.isApprox(J_RF_sparse * v)); + + cm_RF.calc(model, data_plus, cd_RF_plus); + const Vector3d constraint_velocity_error_fd = + (cd_RF_plus.constraint_position_error - cd_RF.constraint_position_error) / dt; + BOOST_CHECK( + cd_RF.constraint_velocity_error.isApprox(constraint_velocity_error_fd, sqrt(dt))); + + const Vector3d constraint_acceleration_error_fd = + (cd_RF_plus.constraint_velocity_error - cd_RF.constraint_velocity_error) / dt; + BOOST_CHECK( + cd_RF.constraint_acceleration_error.isApprox(constraint_acceleration_error_fd, sqrt(dt))); + } + + { + BilateralPointConstraintData cd_LF(cm_LF), cd_LF_plus(cm_LF); + cm_LF.calc(model, data, cd_LF); + BOOST_CHECK(cd_LF.constraint_velocity_error.isApprox(J_LF_sparse * v)); + + cm_LF.calc(model, data_plus, cd_LF_plus); + const Vector3d constraint_velocity_error_fd = + (cd_LF_plus.constraint_position_error - cd_LF.constraint_position_error) / dt; + BOOST_CHECK( + cd_LF.constraint_velocity_error.isApprox(constraint_velocity_error_fd, sqrt(dt))); + + const Vector3d constraint_acceleration_error_fd = + (cd_LF_plus.constraint_velocity_error - cd_LF.constraint_velocity_error) / dt; + BOOST_CHECK( + cd_LF.constraint_acceleration_error.isApprox(constraint_acceleration_error_fd, sqrt(dt))); + } + + { + BilateralPointConstraintData cld_RF_LF(clm_RF_LF), cld_RF_LF_plus(clm_RF_LF); + clm_RF_LF.calc(model, data, cld_RF_LF); + BOOST_CHECK(cld_RF_LF.constraint_velocity_error.isApprox(J_clm_sparse * v)); + + clm_RF_LF.calc(model, data_plus, cld_RF_LF_plus); + const Vector3d constraint_velocity_error_fd = + (cld_RF_LF_plus.constraint_position_error - cld_RF_LF.constraint_position_error) / dt; + BOOST_CHECK( + cld_RF_LF.constraint_velocity_error.isApprox(constraint_velocity_error_fd, sqrt(dt))); + + const Vector3d constraint_acceleration_error_fd = + (cld_RF_LF_plus.constraint_velocity_error - cld_RF_LF.constraint_velocity_error) / dt; + BOOST_CHECK(cld_RF_LF.constraint_acceleration_error.isApprox( + constraint_acceleration_error_fd, sqrt(dt))); + } + } + + check_A1_and_A2(model, data, cm_RF, cd_RF); + check_jacobians_operations(model, data, cm_RF, cd_RF); + + check_A1_and_A2(model, data, cm_LF, cd_LF); + check_jacobians_operations(model, data, cm_LF, cd_LF); + + check_A1_and_A2(model, data, clm_RF_LF, cld_RF_LF); + check_jacobians_operations(model, data, clm_RF_LF, cld_RF_LF); + + // Check acceleration contributions + { + Data data(model), data_zero_acc(model); + forwardKinematics(model, data, q, v, a); + computeJointJacobians(model, data, q); + forwardKinematics(model, data_zero_acc, q, v, VectorXd::Zero(model.nv)); + + // RF + BilateralPointConstraintData cd_RF(cm_RF), cd_RF_zero_acc(cm_RF); + cm_RF.calc(model, data, cd_RF); + cm_RF.calc(model, data_zero_acc, cd_RF_zero_acc); + + Data::MatrixXs J_RF_sparse(3, model.nv); + J_RF_sparse.setZero(); + cm_RF.jacobian(model, data, cd_RF, J_RF_sparse); + + BOOST_CHECK((J_RF_sparse * a + cd_RF_zero_acc.constraint_acceleration_error) + .isApprox(cd_RF.constraint_acceleration_error)); + + // LF + BilateralPointConstraintData cd_LF(cm_LF), cd_LF_zero_acc(cm_LF); + cm_LF.calc(model, data, cd_LF); + cm_LF.calc(model, data_zero_acc, cd_LF_zero_acc); + + Data::MatrixXs J_LF_sparse(3, model.nv); + J_LF_sparse.setZero(); + cm_LF.jacobian(model, data, cd_LF, J_LF_sparse); + + BOOST_CHECK((J_LF_sparse * a + cd_LF_zero_acc.constraint_acceleration_error) + .isApprox(cd_LF.constraint_acceleration_error)); + + // Close loop + BilateralPointConstraintData cld_RF_LF(clm_RF_LF), cld_RF_LF_zero_acc(clm_RF_LF); + clm_RF_LF.calc(model, data, cld_RF_LF); + clm_RF_LF.calc(model, data_zero_acc, cld_RF_LF_zero_acc); + + Data::MatrixXs J_clm_sparse(3, model.nv); + J_clm_sparse.setZero(); + clm_RF_LF.jacobian(model, data, cld_RF_LF, J_clm_sparse); + + BOOST_CHECK((J_clm_sparse * a + cld_RF_LF_zero_acc.constraint_acceleration_error) + .isApprox(cld_RF_LF.constraint_acceleration_error)); + } + } +} + +BOOST_AUTO_TEST_CASE(cast) +{ + + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + + const std::string RF = "rleg6_joint"; + + const BilateralPointConstraintModel cm_RF(model, model.getJointId(RF), SE3::Random()); + const auto cm_RF_cast_double = cm_RF.cast(); + BOOST_CHECK(cm_RF_cast_double == cm_RF); + + const auto cm_RF_cast_long_double = cm_RF.cast(); + BOOST_CHECK(cm_RF_cast_long_double.cast() == cm_RF); +} + +BOOST_AUTO_TEST_CASE(cholesky) +{ + + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + Data data(model), data_ref(model); + + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); + VectorXd q = randomConfiguration(model); + VectorXd v = VectorXd::Random(model.nv); + VectorXd a = VectorXd::Random(model.nv); + + crba(model, data, q, Convention::WORLD); + + const std::string RF = "rleg6_joint"; + const std::string LF = "lleg6_joint"; + + const BilateralPointConstraintModel cm_RF(model, model.getJointId(RF), SE3::Random()); + const BilateralPointConstraintModel cm_LF(model, model.getJointId(LF), SE3::Random()); + const BilateralPointConstraintModel clm_RF_LF( + model, cm_RF.joint1_id, cm_RF.joint1_placement, cm_LF.joint1_id, cm_LF.joint1_placement); + + std::vector constraint_models; + constraint_models.push_back(cm_RF); + constraint_models.push_back(cm_LF); + constraint_models.push_back(clm_RF_LF); + + std::vector constraint_datas, constraint_datas_ref; + for (const auto & cm : constraint_models) + { + constraint_datas.push_back(cm.createData()); + constraint_datas_ref.push_back(cm.createData()); + } + + const double mu = 1e-10; + ContactCholeskyDecomposition cholesky(model, constraint_models); + cholesky.compute(model, data, constraint_models, constraint_datas, mu); + + crba(model, data_ref, q, Convention::WORLD); + make_symmetric(data_ref.M); + const auto total_size = getTotalConstraintSize(constraint_models); + Eigen::MatrixXd J_constraints(total_size, model.nv); + J_constraints.setZero(); + getConstraintsJacobian(model, data_ref, constraint_models, constraint_datas, J_constraints); + + Eigen::MatrixXd H_ref = Eigen::MatrixXd::Zero(total_size + model.nv, total_size + model.nv); + H_ref.topLeftCorner(total_size, total_size).diagonal().fill(-mu); + H_ref.bottomRightCorner(model.nv, model.nv) = data_ref.M; + H_ref.topRightCorner(total_size, model.nv) = J_constraints; + H_ref.bottomLeftCorner(model.nv, total_size) = J_constraints.transpose(); + + BOOST_CHECK(cholesky.matrix().isApprox(H_ref)); +} + +void check_maps_impl( + const Model & model, + Data & data, + const BilateralPointConstraintModel & cm, + BilateralPointConstraintData & cd) +{ + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + crba(model, data, q, Convention::WORLD); + forwardKinematics(model, data, q, v); + + cm.calc(model, data, cd); + const auto constraint_jacobian = cm.jacobian(model, data, cd); + + // Test mapConstraintForceToJointForces : WorldFrameTag + { + std::vector joint_forces(size_t(model.njoints), Force::Zero()); + const Eigen::Vector3d constraint_force = Eigen::Vector3d::Ones(); + const auto joint_torque_ref = constraint_jacobian.transpose() * constraint_force; + + cm.mapConstraintForceToJointForces( + model, data, cd, constraint_force, joint_forces, WorldFrameTag()); + + for (JointIndex joint_id = 1; joint_id < JointIndex(model.njoints); ++joint_id) + { + if (joint_id == cm.joint1_id || joint_id == cm.joint2_id) + { + BOOST_CHECK(!joint_forces[joint_id].isZero(0)); + } + else + { + BOOST_CHECK(joint_forces[joint_id].isZero(0)); + } + } + + // Backward pass over the joint forces + Eigen::VectorXd joint_torque = Eigen::VectorXd::Zero(model.nv); + for (JointIndex joint_id = JointIndex(model.njoints) - 1; joint_id > 0; --joint_id) + { + const JointModel & jmodel = model.joints[joint_id]; + const auto joint_nv = jmodel.nv(); + const auto joint_idx_v = jmodel.idx_v(); + + joint_torque.segment(joint_idx_v, joint_nv) = + data.J.middleCols(joint_idx_v, joint_nv).transpose() * joint_forces[joint_id].toVector(); + + const JointIndex parent_id = model.parents[joint_id]; + joint_forces[parent_id] += joint_forces[joint_id]; + } + + BOOST_CHECK(joint_torque.isApprox(joint_torque_ref)); + } + + // Test mapConstraintForceToJointForces : LocalFrameTag + { + std::vector joint_forces(size_t(model.njoints), Force::Zero()); + const Eigen::Vector3d constraint_force = Eigen::Vector3d::Ones(); + const auto joint_torque_ref = constraint_jacobian.transpose() * constraint_force; + + cm.mapConstraintForceToJointForces( + model, data, cd, constraint_force, joint_forces, LocalFrameTag()); + + for (JointIndex joint_id = 1; joint_id < JointIndex(model.njoints); ++joint_id) + { + if (joint_id == cm.joint1_id || joint_id == cm.joint2_id) + { + BOOST_CHECK(!joint_forces[joint_id].isZero(0)); + } + else + { + BOOST_CHECK(joint_forces[joint_id].isZero(0)); + } + } + + // Backward pass over the joint forces + Eigen::VectorXd joint_torque = Eigen::VectorXd::Zero(model.nv); + for (JointIndex joint_id = JointIndex(model.njoints) - 1; joint_id > 0; --joint_id) + { + const JointModel & jmodel = model.joints[joint_id]; + const JointData & jdata = data.joints[joint_id]; + const auto joint_nv = jmodel.nv(); + const auto joint_idx_v = jmodel.idx_v(); + + joint_torque.segment(joint_idx_v, joint_nv) = + jdata.S().matrix().transpose() * joint_forces[joint_id].toVector(); + + const JointIndex parent_id = model.parents[joint_id]; + joint_forces[parent_id] += data.liMi[joint_id].act(joint_forces[joint_id]); + } + + BOOST_CHECK(joint_torque.isApprox(joint_torque_ref)); + } + + // Test mapJointMotionsToConstraintMotion : WorldFrameTag + { + const auto constraint_motion_ref = constraint_jacobian * v; + for (JointIndex joint_id = 1; joint_id < JointIndex(model.njoints); ++joint_id) + { + data.ov[joint_id] = data.oMi[joint_id].act(data.v[joint_id]); + } + + const auto & joint_accelerations = data.ov; + Eigen::Vector3d constraint_motion = Eigen::Vector3d::Zero(); + cm.mapJointMotionsToConstraintMotion( + model, data, cd, joint_accelerations, constraint_motion, WorldFrameTag()); + + BOOST_CHECK(constraint_motion.isApprox(constraint_motion_ref)); + } + + // Test mapJointMotionsToConstraintMotion : LocalFrameTag + { + const auto constraint_motion_ref = constraint_jacobian * v; + + const auto & joint_motions = data.v; + Eigen::Vector3d constraint_motion = Eigen::Vector3d::Zero(); + cm.mapJointMotionsToConstraintMotion( + model, data, cd, joint_motions, constraint_motion, LocalFrameTag()); + + BOOST_CHECK(constraint_motion.isApprox(constraint_motion_ref)); + } +} + +BOOST_AUTO_TEST_CASE(check_maps) +{ + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + Data data(model), data_ref(model); + + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); + + const std::string RF = "rleg6_joint"; + const std::string LF = "lleg6_joint"; + + const BilateralPointConstraintModel cm_RF(model, model.getJointId(RF), SE3::Random()); + auto cd_RF = cm_RF.createData(); + + const BilateralPointConstraintModel cm_LF(model, model.getJointId(LF), SE3::Random()); + auto cd_LF = cm_LF.createData(); + const BilateralPointConstraintModel clm_RF_LF( + model, cm_RF.joint1_id, cm_RF.joint1_placement, cm_LF.joint1_id, cm_LF.joint1_placement); + auto cld_RF_LF = clm_RF_LF.createData(); + + check_maps_impl(model, data, cm_RF, cd_RF); + check_maps_impl(model, data, cm_LF, cd_LF); + check_maps_impl(model, data, clm_RF_LF, cld_RF_LF); +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/preconditioner.cpp b/unittest/preconditioner.cpp new file mode 100644 index 0000000000..0088b6c109 --- /dev/null +++ b/unittest/preconditioner.cpp @@ -0,0 +1,41 @@ +// +// Copyright (c) 2025 INRIA +// + +#include "pinocchio/algorithm/diagonal-preconditioner.hpp" + +#include + +using namespace pinocchio; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(diagonal_preconditioner) +{ + Eigen::Index n = 10; + Eigen::VectorXd precond_vec = Eigen::VectorXd::Random(n); + precond_vec = precond_vec.array().abs() + 1e-6; + DiagonalPreconditionerTpl precond(precond_vec); + + Eigen::VectorXd x = Eigen::VectorXd::Random(n); + Eigen::VectorXd x_scaled; + + precond.scale(x, x_scaled); + Eigen::VectorXd x_scaled_true = x.array() / precond_vec.array(); + BOOST_CHECK(x_scaled.isApprox(x_scaled_true)); + + precond.scaleSquare(x, x_scaled); + x_scaled_true.array() = x.array() / (precond_vec.array() * precond_vec.array()); + BOOST_CHECK(x_scaled.isApprox(x_scaled_true)); + + Eigen::VectorXd x_unscaled; + precond.unscale(x, x_unscaled); + Eigen::VectorXd x_unscaled_true = x.array() * precond_vec.array(); + BOOST_CHECK(x_unscaled.isApprox(x_unscaled_true)); + + precond.unscaleSquare(x, x_unscaled); + x_unscaled_true = x.array() * (precond_vec.array() * precond_vec.array()); + BOOST_CHECK(x_unscaled.isApprox(x_unscaled_true)); +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/python/CMakeLists.txt b/unittest/python/CMakeLists.txt index 2121b7b26f..661837a1f1 100644 --- a/unittest/python/CMakeLists.txt +++ b/unittest/python/CMakeLists.txt @@ -1,5 +1,5 @@ # -# Copyright (c) 2015-2023 CNRS INRIA, 2024-2025 INRIA +# Copyright (c) 2015-2025 CNRS INRIA # include(${JRL_CMAKE_MODULES}/python-helpers.cmake) @@ -30,6 +30,9 @@ set(${PROJECT_NAME}_PYTHON_TESTS bindings_rnea bindings_aba bindings_joint_algorithms + bindings_constraints + # Solvers + bindings_admm # Algo derivatives bindings_kinematics_derivatives bindings_frame_derivatives @@ -39,6 +42,7 @@ set(${PROJECT_NAME}_PYTHON_TESTS bindings_com_velocity_derivatives # Parsers bindings_sample_models + bindings_mjcf # Others robot_wrapper utils diff --git a/unittest/python/bindings_admm.py b/unittest/python/bindings_admm.py new file mode 100644 index 0000000000..a8c6024932 --- /dev/null +++ b/unittest/python/bindings_admm.py @@ -0,0 +1,133 @@ +import unittest +from pathlib import Path + +import numpy as np +import pinocchio as pin +from test_case import ContactSolverTestCase as TestCase + +import importlib.util + +coal_spec = importlib.util.find_spec("coal") +coal_found = coal_spec is not None + +matplotlib_spec = importlib.util.find_spec("matplotlib") +matplotlib_found = matplotlib_spec is not None + +meshcat_spec = importlib.util.find_spec("meshcat") +meshcat_found = meshcat_spec is not None + + +class TestADMM(TestCase): + def test_box(self): + model, constraint_models = self.buildStackOfCubesModel([1e-3]) + q0 = pin.neutral(model) + v0 = np.zeros(model.nv) + tau0 = np.zeros(model.nv) + fext = [pin.Force.Zero() for i in range(model.njoints)] + dt = 1e-3 + delassus_matrix, g = self.setupTest( + model, constraint_models, q0, v0, tau0, fext, dt + ) + delassus = pin.DelassusOperatorDense(delassus_matrix) + dim_pb = g.shape[0] + solver = pin.ADMMContactSolver(dim_pb) + solver.setAbsolutePrecision(1e-13) + solver.setRelativePrecision(1e-14) + solver.setLanczosSize(g.size) + solver.solve(delassus, g, constraint_models, dt) + + @unittest.skipUnless(coal_found, "Needs Coal.") + def test_cassie(self, display=False, stat_record=True): + current_dir = Path(__file__).parent + model_dir = current_dir / "../models/" + model_path = model_dir / "closed_chain.xml" + constraint_models = pin.StdVec_ConstraintModel() + + # Parsing model, constraint models and geometry model from xml description + model, constraint_models_dict, geom_model, visual_model = ( + pin.buildModelsFromMJCF(model_path) + ) + + # Adding all constraintds would be + for typed_constraint_models in constraint_models_dict.values(): + for cm in typed_constraint_models: + constraint_models.append(pin.ConstraintModel(cm)) + # Adding only bilateral constraints to the list of constraints + # for bpcm in constraint_models_dict['bilateral_point_constraint_models']: + # constraint_models.append(pin.ConstraintModel(bpcm)) + + # adding joint limit constraints + active_joints_limits = [i for i in range(1, model.njoints)] + jlcm = pin.JointLimitConstraintModel(model, active_joints_limits) + constraint_models.append(pin.ConstraintModel(jlcm)) + + # adding friction on joints + active_joints_friction = [i for i in range(1, model.njoints)] + fjcm = pin.FrictionalJointConstraintModel(model, active_joints_friction) + fjcm.set = pin.BoxSet(model.lowerDryFrictionLimit, model.upperDryFrictionLimit) + constraint_models.append(pin.ConstraintModel(fjcm)) + + q0 = model.referenceConfigurations["home"] + v0 = np.zeros(model.nv) + tau0 = np.zeros(model.nv) + fext = [pin.Force.Zero() for i in range(model.njoints)] + dt = 1e-3 + self.addFloor(geom_model, visual_model) + self.addSystemCollisionPairs(model, geom_model, q0) + + # Adding constraints from frictional contacts + contact_constraints = self.computeContactConstraints(model, geom_model, q0) + for fpcm in contact_constraints: + constraint_models.append(pin.ConstraintModel(fpcm)) + + delassus_matrix, g = self.setupTest( + model, constraint_models, q0, v0, tau0, fext, dt + ) + delassus = pin.DelassusOperatorDense(delassus_matrix) + + self.assertTrue( + delassus.matrix().shape[0] + == (3 * len(constraint_models_dict["bilateral_point_constraint_models"])) + + (6 * len(constraint_models_dict["weld_constraint_models"])) + + (3 * len(contact_constraints)) + + (model.upperPositionLimit != np.inf).sum() + - 4 * 3 + + (model.lowerPositionLimit != -np.inf).sum() + - 4 * 3 + + model.nv, + "constraint problem is of wrong size.", + ) + + dim_pb = g.shape[0] + solver = pin.ADMMContactSolver(dim_pb) + solver.setAbsolutePrecision(1e-13) + solver.setRelativePrecision(1e-14) + solver.setLanczosSize(g.size) + + has_converged = solver.solve( + delassus, + g, + constraint_models, + dt, + None, + None, + None, + True, + pin.ADMMUpdateRule.SPECTRAL, + stat_record, + ) + self.assertTrue(has_converged, "Solver did not converge.") + print(solver.getIterationCount()) + print(solver.getAbsoluteConvergenceResidual()) + print(solver.getRelativeConvergenceResidual()) + + if stat_record and matplotlib_found: + self.plotContactSolver(solver) + + if display and meshcat_found: + vizer, viewer = self.createVisualizer(model, geom_model, geom_model) + vizer.display(q0) + + +if __name__ == "__main__": + unittest.main() diff --git a/unittest/python/bindings_bilateral_constraint.py b/unittest/python/bindings_bilateral_constraint.py new file mode 100644 index 0000000000..acc0b484d3 --- /dev/null +++ b/unittest/python/bindings_bilateral_constraint.py @@ -0,0 +1,17 @@ +import unittest +import pinocchio as pin +from test_case import PinocchioTestCase as TestCase + + +class TestBilateralBindings(TestCase): + def test_vector(self): + m = pin.Model() + placement1 = pin.SE3.Identity() + list_bpcm = pin.StdVec_BilateralPointConstraintModel() + bpcm = pin.BilateralPointConstraintModel(m, 0, placement1) + list_bpcm.append(bpcm) + assert list_bpcm[-1].joint1_id == 0 + + +if __name__ == "__main__": + unittest.main() diff --git a/unittest/python/bindings_constraints.py b/unittest/python/bindings_constraints.py new file mode 100644 index 0000000000..8e0d0e9f8f --- /dev/null +++ b/unittest/python/bindings_constraints.py @@ -0,0 +1,483 @@ +import itertools +import unittest + +import coal as coal +import numpy as np +import pinocchio as pin +from test_case import PinocchioTestCase as TestCase + + +class TestJointsAlgo(TestCase): + def setUp(self): + self.construct_model() + self.construct_constraints() + + def construct_model(self): + model = pin.Model() + geom_model = pin.GeometryModel() + + world_joint_id = 0 + + # Add a plane in world model + plane_geom_name = "geom_plane" + plane_geom_shape = coal.Halfspace(0.0, 0.0, 1.0, 0.0) + plane_geom_placement = pin.SE3.Identity() + plane_geom_obj = pin.GeometryObject( + plane_geom_name, world_joint_id, plane_geom_placement, plane_geom_shape + ) + plane_geom_id = geom_model.addGeometryObject(plane_geom_obj) + + # Add a freeflyer with a ball attach to it + ball_joint_name = "joint_ball_ff" + ball_joint_obj = pin.JointModelFreeFlyer() + ball_joint_placement = pin.SE3.Identity() + ball_joint_id = model.addJoint( + world_joint_id, ball_joint_obj, ball_joint_placement, ball_joint_name + ) + ball_geom_radius = 1.0 + ball_geom_name = "geom_ball_ff" + ball_geom_shape = coal.Sphere(ball_geom_radius) + ball_geom_placement = pin.SE3.Identity() + ball_geom_obj = pin.GeometryObject( + ball_geom_name, ball_joint_id, ball_geom_placement, ball_geom_shape + ) + ball_geom_id = geom_model.addGeometryObject(ball_geom_obj) + ball_body_mass = 1.0 + ball_body_placement = pin.SE3.Identity() + ball_body_inertia = pin.Inertia.FromSphere(ball_body_mass, ball_geom_radius) + model.appendBodyToJoint( + ball_joint_id, ball_body_inertia, ball_body_placement + ) # Add inertia of the ball to the model + geom_model.addCollisionPair( + pin.CollisionPair(plane_geom_id, ball_geom_id) + ) # Add collision pair with the floor to the floor + + # Add a prismatic with a cylinder attach to it + cyl_joint_name = "joint_cyl_PZ" + cyl_joint_obj = pin.JointModelPZ() + cyl_joint_placement = pin.SE3.Identity() + cyl_joint_id = model.addJoint( + world_joint_id, cyl_joint_obj, cyl_joint_placement, cyl_joint_name + ) + cyl_geom_radius = 1.0 + cyl_geom_length = 1.0 + cyl_geom_name = "geom_cyl_PZ" + cyl_geom_shape = coal.Cylinder(cyl_geom_radius, cyl_geom_length) + cyl_geom_placement = pin.SE3.Identity() + cyl_geom_obj = pin.GeometryObject( + cyl_geom_name, cyl_joint_id, cyl_geom_placement, cyl_geom_shape + ) + cyl_geom_id = geom_model.addGeometryObject(cyl_geom_obj) + cyl_body_mass = 1.0 + cyl_body_placement = pin.SE3.Identity() + cyl_body_inertia = pin.Inertia.FromCylinder( + cyl_body_mass, cyl_geom_radius, cyl_geom_length + ) + model.appendBodyToJoint( + cyl_joint_id, cyl_body_inertia, cyl_body_placement + ) # Add inertia of the ball to the model + geom_model.addCollisionPair( + pin.CollisionPair(plane_geom_id, cyl_geom_id) + ) # Add collision pair with the floor to the floor + + # Add a revolute joint with a capsule attach to it + caps_joint_name = "joint_caps_RX" + caps_joint_obj = pin.JointModelRX() + caps_joint_placement = pin.SE3.Identity() + caps_joint_id = model.addJoint( + world_joint_id, caps_joint_obj, caps_joint_placement, caps_joint_name + ) + caps_geom_radius = 1.0 + caps_geom_halflength = 1.0 + caps_geom_name = "geom_caps_RX" + caps_geom_shape = coal.Capsule(caps_geom_radius, caps_geom_halflength) + caps_geom_placement = pin.SE3.Identity() + caps_geom_obj = pin.GeometryObject( + caps_geom_name, caps_joint_id, caps_geom_placement, caps_geom_shape + ) + caps_geom_id = geom_model.addGeometryObject(caps_geom_obj) + caps_body_mass = 1.0 + caps_body_placement = pin.SE3.Identity() + caps_body_inertia = pin.Inertia.FromCylinder( + caps_body_mass, caps_geom_radius, caps_geom_halflength * 2 + ) + model.appendBodyToJoint( + caps_joint_id, caps_body_inertia, caps_body_placement + ) # Add inertia of the ball to the model + geom_model.addCollisionPair(pin.CollisionPair(plane_geom_id, caps_geom_id)) + geom_model.addCollisionPair(pin.CollisionPair(ball_geom_id, caps_geom_id)) + + # Set up limits + model.positionLimitMargin = np.array([1.0] * model.nq) + model.upperPositionLimit = np.array([0.5] * model.nq) + model.upperPositionLimit[-1] = 2.0 + model.lowerPositionLimit = np.array([-0.5] * model.nq) + model.lowerDryFrictionLimit = -np.ones(model.nv) + model.upperDryFrictionLimit = np.ones(model.nv) + + # Store some values + self.model = model + self.geom_model = geom_model + self.world_joint_id = world_joint_id + self.caps_joint_id = caps_joint_id + self.cyl_joint_id = cyl_joint_id + + def construct_constraints(self): + model = self.model + geom_model = self.geom_model + world_joint_id = self.world_joint_id + caps_joint_id = self.caps_joint_id + cyl_joint_id = self.cyl_joint_id + + # Add all constraints + constraints_std_vec = pin.StdVec_ConstraintModel() + constraints_list = [] + + # Bilateral constraints + bilat_joint1_anchor_placement = pin.SE3.Identity() + bilat1 = pin.BilateralPointConstraintModel(model, caps_joint_id) + bilat2 = pin.BilateralPointConstraintModel( + model, caps_joint_id, bilat_joint1_anchor_placement + ) + bilat3 = pin.BilateralPointConstraintModel(model, caps_joint_id, world_joint_id) + bilat4 = pin.BilateralPointConstraintModel( + model, + caps_joint_id, + bilat_joint1_anchor_placement, + world_joint_id, + pin.SE3.Identity(), + ) + bilats_list = [bilat1, bilat2, bilat3, bilat4] + for b in bilats_list: + gb = pin.ConstraintModel(b) + constraints_std_vec.append(gb) + constraints_list.append(b) + + # weld constraints + weld_joint1_anchor_placement = pin.SE3.Identity() + weld1 = pin.WeldConstraintModel(model, cyl_joint_id) + weld2 = pin.WeldConstraintModel( + model, cyl_joint_id, weld_joint1_anchor_placement + ) + weld3 = pin.WeldConstraintModel(model, cyl_joint_id, world_joint_id) + weld4 = pin.WeldConstraintModel( + model, + cyl_joint_id, + weld_joint1_anchor_placement, + world_joint_id, + pin.SE3.Identity(), + ) + welds_list = [weld1, weld2, weld3, weld4] + for w in welds_list: + gw = pin.ConstraintModel(w) + constraints_std_vec.append(gw) + constraints_list.append(w) + + # Joint friction + jfc = pin.FrictionalJointConstraintModel(model, [1, 3]) + jfc.set = pin.BoxSet( + np.array([model.lowerDryFrictionLimit[i] for i in jfc.getActiveDofs()]), + np.array([model.upperDryFrictionLimit[i] for i in jfc.getActiveDofs()]), + ) + constraints_std_vec.append(pin.ConstraintModel(jfc)) + constraints_list.append(jfc) + + # Limit joint + model.positionLimitMargin = np.array([1.0] * model.nq) + model.upperPositionLimit = np.array([0.5] * model.nq) + model.upperPositionLimit[-1] = 2.0 + model.lowerPositionLimit = np.array([-0.5] * model.nq) + jlc_raw = pin.JointLimitConstraintModel(model, [1, 2, 3]) + constraints_std_vec.append(pin.ConstraintModel(jlc_raw)) + constraints_list.append(jlc_raw) + + # Create some contacts and active limits + data = model.createData() + geom_data = geom_model.createData() + q = np.array( + [ + -0.49999217, + -0.36846221, + 0.25560532, + -0.72022615, + 0.66439729, + 0.13124927, + -0.1504133, + -0.45295538, + 1.19716179, + ] + ) + pin.forwardKinematics(model, data, q) + pin.updateGeometryPlacements(model, data, geom_model, geom_data) + pin.computeCollisions(model, data, geom_model, geom_data, q, False) + pin.computeContactPatches(geom_model, geom_data) + + jlc = pin.ConstraintModel(jlc_raw).extract() + jlc.resize(model, data, jlc.createData()) + + frictional_points_list = [] + for col_pair, col_res, patch_res in zip( + geom_model.collisionPairs, + geom_data.collisionResults, + geom_data.contactPatchResults, + ): + if col_res.isCollision() and patch_res.numContactPatches() > 0: + geom_id1 = col_pair.first + geom_id2 = col_pair.second + geom1 = geom_model.geometryObjects[geom_id1] + geom2 = geom_model.geometryObjects[geom_id2] + joint_id1 = geom1.parentJoint + joint_id2 = geom2.parentJoint + oMi1 = data.oMi[joint_id1] + oMi2 = data.oMi[joint_id2] + patch = patch_res.getContactPatch(0) + contact_normal = patch.getNormal() + oMc = pin.SE3.Identity() + contact_normal = contact_normal / np.linalg.norm(contact_normal) + e_ref = ( + np.array([0, 1, 0]) + if np.isclose(contact_normal[0], 1.0) + else np.array([1, 0, 0]) + ) + comp = np.cross(e_ref, contact_normal) + comp = comp / np.linalg.norm(comp) + oMc.rotation[:, 2] = contact_normal + oMc.rotation[:, 0] = comp + oMc.rotation[:, 1] = np.cross(contact_normal, comp) + for i in range(patch.size()): + oMc.translation = patch.getPointShape1(i) + i1Mc = oMi1.actInv(oMc) + oMc.translation = patch.getPointShape2(i) + i2Mc = oMi2.actInv(oMc) + fp = pin.FrictionalPointConstraintModel( + model, joint_id1, i1Mc, joint_id2, i2Mc + ) + gfp = pin.ConstraintModel(fp) + constraints_std_vec.append(gfp) + constraints_list.append(fp) + frictional_points_list.append(fp) + + # Sotre some values + self.data = data + self.geom_data = geom_data + self.constraints_std_vec = constraints_std_vec + self.constraints_list = constraints_list + self.bilats_list = bilats_list + self.bilat = bilat1 + self.welds_list = welds_list + self.weld = weld1 + self.frictional_points_list = frictional_points_list + self.fp = frictional_points_list[0] + self.jlc_raw = jlc_raw + self.jlc = jlc + self.jfc = jfc + self.one_of_each = [self.bilat, self.weld, self.fp, self.jlc, self.jfc] + + def test_bilateral(self): + # Coherence between all inits + for b_1, b_2 in itertools.product(self.bilats_list, self.bilats_list): + self.assertTrue(b_1 == b_2) + + # Check size + for b in self.bilats_list: + self.assertTrue(b.size() == b.activeSize() == 3) + + def test_weld(self): + # Coherence between all inits + for w_1, w_2 in itertools.product(self.welds_list, self.welds_list): + self.assertTrue(w_1 == w_2) + + # Check size + for w in self.welds_list: + self.assertTrue(w.size() == w.activeSize() == 6) + + def test_frictional_point(self): + for fp in self.frictional_points_list: + self.assertTrue(fp.size() == fp.activeSize() == 3) + + def test_joint_frictional(self): + self.assertTrue(self.jfc.activeSize() == self.jfc.size() <= self.model.nv) + + def test_joint_limit(self): + self.assertTrue( + self.jlc_raw.activeSize() <= self.jlc_raw.size() <= 2 * self.model.nq + ) + self.assertTrue(self.jlc_raw.activeSize() == 0) + self.assertTrue(self.jlc.activeSize() == (self.jlc.size() - 1)) + self.assertTrue(self.jlc.activeSize() <= self.jlc.size() <= 2 * self.model.nq) + + def test_generic_methods(self): + ref_set = set(range(self.model.nv)) + + for gcm, ccm in zip(self.constraints_std_vec, self.constraints_list): + # Test hierarchy + self.assertTrue(gcm.extract() == ccm) + self.assertTrue(gcm.shortname() == ccm.classname() == ccm.shortname()) + for i in range(gcm.activeSize()): + self.assertTrue( + np.all( + np.where(gcm.getRowActiveSparsityPattern(i))[0] + == np.array(gcm.getRowActiveIndexes(i)) + ) + ) + self.assertTrue( + np.all( + np.where(gcm.getRowActivableSparsityPattern(i))[0] + == np.array(gcm.getRowActivableIndexes(i)) + ) + ) + self.assertTrue( + set(gcm.getRowActiveIndexes(i)) + <= set(gcm.getRowActivableIndexes(i)) + <= ref_set + ) + self.assertTrue(gcm.activeSize() <= gcm.size()) + dummy_compliance = 0.1 * np.ones(gcm.size()) + gcm.compliance = dummy_compliance + self.assertTrue(np.all(dummy_compliance == gcm.compliance)) + self.assertTrue(len(ccm.getActiveCompliance()) == ccm.activeSize()) + self.assertTrue(ccm.activeSize() == ccm.set.size() == ccm.set.dim()) + if not hasattr(ccm, "baumgarte_corrector_parameters"): + self.assertTrue(isinstance(ccm, pin.FrictionalJointConstraintModel)) + do_except = False + self.assertTrue("baumgarte_corrector_parameters" in dir(gcm)) + try: + gcm.baumgarte_corrector_parameters + except Exception as _: + do_except = True + self.assertTrue(do_except) + else: + ccm.baumgarte_corrector_parameters.Kp = 1.0 + ccm.baumgarte_corrector_parameters.Kd = 1.0 + + def test_jacobians_methods(self): + model = self.model + data = self.data + + v = np.stack([np.ones(model.nv), 2 * np.ones(model.nv)], axis=1) + for cmodel in self.one_of_each: + gcmodel = pin.ConstraintModel(cmodel) + cdata = cmodel.createData() + gcdata = gcmodel.createData() + g2cdata = pin.ConstraintData(cdata) + + self.assertTrue(g2cdata == gcdata) + self.assertTrue(gcdata.extract() == cdata) + self.assertTrue(g2cdata.extract() == cdata) + + self.assertTrue( + gcdata.shortname() == cdata.classname() == cdata.shortname() + ) + + lamb = np.stack( + [np.ones(cmodel.activeSize()), 2 * np.ones(cmodel.activeSize())], axis=1 + ) + + if isinstance(cmodel, pin.JointLimitConstraintModel): + cmodel.resize(model, data, cdata) + cmodel.calc(model, data, cdata) + jac = cmodel.jacobian(model, data, cdata) + sig = cmodel.jacobianMatrixProduct(model, data, cdata, v) + tau = cmodel.jacobianTransposeMatrixProduct(model, data, cdata, lamb) + + self.assertTrue(np.all(jac @ v == sig)) + self.assertTrue(np.all(jac.T @ lamb == tau)) + + if not isinstance(cmodel, pin.JointLimitConstraintModel): + gcmodel.calc(model, data, gcdata) + gjac = gcmodel.jacobian(model, data, gcdata) + gsig = gcmodel.jacobianMatrixProduct(model, data, gcdata, v) + gtau = gcmodel.jacobianTransposeMatrixProduct(model, data, gcdata, lamb) + + self.assertTrue(np.all(jac == gjac)) + self.assertTrue(np.all(sig == gsig)) + self.assertTrue(np.all(tau == gtau)) + + def test_sets_of_constraints(self): + # Test projection + # bilat + force = np.array([1] * 3) + p_force = self.bilat.set.project(force) + self.assertTrue(self.bilat.set.isInside(force)) + self.assertTrue(np.all(p_force == force)) + + # weld + force = np.array([1] * 6) + p_force = self.weld.set.project(force) + self.assertTrue(self.weld.set.isInside(force)) + self.assertTrue(np.all(p_force == force)) + + # jlc + force_out = np.array([1] * self.jlc.activeSize()) + p_force_out = self.jlc.set.project(force_out) + self.assertTrue(not self.jlc.set.isInside(force_out)) + p2_force_out = self.jlc.set.project(p_force_out) + self.assertTrue(self.jlc.set.isInside(p_force_out)) + self.assertTrue(np.all(p_force_out == p2_force_out)) + force_in = np.array([0] * self.jlc.activeSize()) + p_force_in = self.jlc.set.project(force_in) + self.assertTrue(self.jlc.set.isInside(p_force_in)) + self.assertTrue(np.all(p_force_in == force_in)) + + # jfc + force_out = np.array([2] * self.jfc.activeSize()) + p_force_out = self.jfc.set.project(force_out) + self.assertTrue(not self.jfc.set.isInside(force_out)) + p2_force_out = self.jfc.set.project(p_force_out) + self.assertTrue(self.jfc.set.isInside(p_force_out)) + self.assertTrue(np.all(p2_force_out == p_force_out)) + force_in = np.array([0] * self.jfc.activeSize()) + p_force_in = self.jfc.set.project(force_in) + self.assertTrue(self.jfc.set.isInside(p_force_in)) + self.assertTrue(np.all(p_force_in == force_in)) + + # fp + self.fp.set.mu = 2.0 + force_out = np.array([0.0, 3.0, 1.0]) + p_force_out = self.fp.set.project(force_out) + self.assertTrue(not self.fp.set.isInside(force_out)) + p2_force_out = self.fp.set.project(p_force_out) + self.assertTrue(self.fp.set.isInside(p_force_out)) + self.assertTrue(np.all(p2_force_out == p_force_out)) + + force_in = np.array([0.0, 1.0, 1.0]) + p_force_in = self.fp.set.project(force_in) + self.assertTrue(self.fp.set.isInside(force_in)) + self.assertTrue(np.all(p_force_in == force_in)) + + def test_constraints_data(self): + for cmodel in self.one_of_each: + cdata = cmodel.createData() + model_name = cmodel.shortname() + data_name = cdata.shortname() + + if isinstance(cmodel, pin.JointLimitConstraintModel): + cmodel.resize(self.model, self.data, cdata) + cmodel.calc(self.model, self.data, cdata) + + self.assertTrue(model_name[:-5] == data_name[:-4]) + self.assertTrue(model_name[-5:] == "Model") + self.assertTrue(data_name[-4:] == "Data") + + for cmodel in [self.bilat, self.weld]: + cdata = cmodel.createData() + cmodel.calc(self.model, self.data, cdata) + self.assertTrue(hasattr(cdata, "constraint_force")) + self.assertTrue(hasattr(cdata, "oMc1")) + self.assertTrue(hasattr(cdata, "oMc2")) + self.assertTrue(hasattr(cdata, "c1Mc2")) + self.assertTrue(hasattr(cdata, "constraint_position_error")) + self.assertTrue(hasattr(cdata, "constraint_velocity_error")) + self.assertTrue(hasattr(cdata, "constraint_acceleration_error")) + self.assertTrue(hasattr(cdata, "constraint_acceleration_biais_term")) + self.assertTrue(cdata.oMc1.inverse() * cdata.oMc2 == cdata.c1Mc2) + + cmodel = self.jlc + cdata = cmodel.createData() + cmodel.resize(self.model, self.data, cdata) + cmodel.calc(self.model, self.data, cdata) + self.assertTrue(hasattr(cdata, "constraint_residual")) + + +if __name__ == "__main__": + unittest.main() diff --git a/unittest/python/bindings_contact_inverse_dynamics.py b/unittest/python/bindings_contact_inverse_dynamics.py index 7886ed5a88..a223b67397 100644 --- a/unittest/python/bindings_contact_inverse_dynamics.py +++ b/unittest/python/bindings_contact_inverse_dynamics.py @@ -48,7 +48,7 @@ def test_call_to_contact_inverse_dynamics(self): contact_model = pin.RigidConstraintModel( pin.ContactType.CONTACT_3D, model, frame.parentJoint, frame.placement ) - + contact_model.compliance = 0 contact_models_list.append(contact_model) contact_datas_list.append(contact_model.createData()) cones_list.append(pin.CoulombFrictionCone(0.4)) @@ -62,7 +62,6 @@ def test_call_to_contact_inverse_dynamics(self): constraint_dim += m.size() dt = 1e-3 - R = np.zeros(constraint_dim) constraint_correction = np.zeros(constraint_dim) lambda_guess = np.zeros(constraint_dim) prox_settings = pin.ProximalSettings(1e-12, 1e-6, 1) @@ -79,7 +78,6 @@ def test_call_to_contact_inverse_dynamics(self): contact_models_vec, contact_datas_vec, cones_vec, - R, constraint_correction, prox_settings, lambda_guess, @@ -96,7 +94,6 @@ def test_call_to_contact_inverse_dynamics(self): contact_models_list, contact_datas_vec, cones_list, - R, constraint_correction, prox_settings, lambda_guess, @@ -113,7 +110,6 @@ def test_call_to_contact_inverse_dynamics(self): contact_models_list, contact_datas_list, cones_list, - R, constraint_correction, prox_settings, lambda_guess, diff --git a/unittest/python/bindings_joints.py b/unittest/python/bindings_joints.py index f82778be9c..27e425d241 100644 --- a/unittest/python/bindings_joints.py +++ b/unittest/python/bindings_joints.py @@ -55,6 +55,18 @@ def test_basic(self): self.assertFalse(pin.isSameConfiguration(model, q_rand1, q_rand2, 1e-8)) + lgo1 = pin.lieGroup(model) + self.assertTrue(model.nq == lgo1.nq) + self.assertTrue(model.nv == lgo1.nv) + + lgo2 = pin.LieGroup() + for j in model.joints[1:]: + lgo2 *= j.lieGroup() + + self.assertTrue(lgo1.name == lgo2.name) + self.assertTrue(lgo1 == lgo2) + self.assertApprox(lgo1.neutral, pin.neutral(model)) + def test_derivatives(self): model = self.model @@ -77,6 +89,23 @@ def test_derivatives(self): self.assertApprox(J0, res_0) self.assertApprox(J1, res_1) + TM = pin.tangentMap(model, q) + + TMv1 = TM.reshape(model.nq, model.nv) @ v.reshape(model.nv, 1) + TMv2 = pin.tangentMapProduct(model, q, v.reshape(model.nv, 1)) + self.assertApprox(TMv1, TMv2) + + TMq1 = TM.reshape(model.nq, model.nv).T @ q.reshape(model.nq, 1) + TMq2 = pin.tangentMapTransposeProduct(model, q, q.reshape(model.nq, 1)) + self.assertApprox(TMq1, TMq2) + + nvs, idx_vs = pin.indexvInfo(model) + TMc = pin.compactTangentMap(model, q) + TM_recons = np.zeros((model.nq, model.nv)) + for i in range(model.nq): + TM_recons[i, idx_vs[i] : (idx_vs[i] + nvs[i])] = TMc[i, : nvs[i]] + self.assertApprox(TM, TM_recons) + if __name__ == "__main__": unittest.main() diff --git a/unittest/python/bindings_liegroups.py b/unittest/python/bindings_liegroups.py index 28e7983438..5288cd4bb7 100644 --- a/unittest/python/bindings_liegroups.py +++ b/unittest/python/bindings_liegroups.py @@ -104,6 +104,28 @@ def test_dIntegrateTransport(self): Jout1_ref = Jint.dot(J0) self.assertApprox(Jout1, Jout1_ref) + def test_tangentMap_methods(self): + for lg in [ + pin.liegroups.R3(), + pin.liegroups.SO3(), + pin.liegroups.SO2(), + pin.liegroups.SE3(), + pin.liegroups.SE2(), + pin.liegroups.R3() * pin.liegroups.SO3(), + ]: + q = lg.random() + vs = np.random.rand(lg.nv, 100) + dqs = np.random.rand(lg.nq, 100) + + TM = lg.tangentMap(q).reshape(lg.nq, lg.nv) + TMvs_1 = TM @ vs + TMvs_2 = lg.tangentMapProduct(q, vs) + self.assertApprox(TMvs_1, TMvs_2) + + TMTdqs_1 = TM.T @ dqs + TMTdqs_2 = lg.tangentMapTransposeProduct(q, dqs) + self.assertApprox(TMTdqs_1, TMTdqs_2) + def test_dIntegrateTransport_inverse(self): for lg in [ pin.liegroups.R3(), diff --git a/unittest/python/bindings_mjcf.py b/unittest/python/bindings_mjcf.py new file mode 100644 index 0000000000..7ca8b738a0 --- /dev/null +++ b/unittest/python/bindings_mjcf.py @@ -0,0 +1,62 @@ +import unittest +from pathlib import Path + +import pinocchio as pin + +import importlib.util + +mujoco_spec = importlib.util.find_spec("mujoco") +mujoco_found = mujoco_spec is not None + + +class TestMJCFBindings(unittest.TestCase): + def test_load(self): + model = pin.Model() + current_dir = Path(__file__).parent + model_dir = current_dir / "../models/" + model_path = model_dir / "closed_chain.xml" + model = pin.buildModelFromMJCF(model_path, model) + bilateral_constraint_models = pin.buildBilateralConstraintModelsFromMJCF( + model, model_path + ) + self.assertEqual(len(bilateral_constraint_models), 4) + + +@unittest.skipUnless(mujoco_found, "Needs MuJoCo.") +class TestMJCFBindingsWithMujoco(unittest.TestCase): + def test_cassie(self): + import mujoco + import numpy as np + + model_pin = pin.Model() + current_dir = Path(__file__).parent + model_dir = current_dir / "../models/" + model_path = model_dir / "closed_chain.xml" + model_pin = pin.buildModelFromMJCF(model_path, model_pin) + bilateral_constraint_models_pin = pin.buildBilateralConstraintModelsFromMJCF( + model_pin, model_path + ) + weld_constraint_models_pin = pin.buildWeldConstraintModelsFromMJCF( + model_pin, model_path + ) + print(bilateral_constraint_models_pin, weld_constraint_models_pin) + data_pin = model_pin.createData() + q0_pin = model_pin.referenceConfigurations["home"] + pin.forwardKinematics(model_pin, data_pin, q0_pin) + model_mj = mujoco.MjModel.from_xml_path(str(model_path)) + data_mj = mujoco.MjData(model_mj) + q0_mujoco = model_mj.key_qpos[0].copy() + data_mj.qpos = q0_mujoco + mujoco.mj_fwdPosition(model_mj, data_mj) + for joint_id in range(model_mj.njnt): # Total number of joints + assert ( + np.linalg.norm( + data_mj.xanchor[joint_id] - data_pin.oMi[joint_id + 1].translation + ) + < 1e-6 + ) + return + + +if __name__ == "__main__": + unittest.main() diff --git a/unittest/python/bindings_model.py b/unittest/python/bindings_model.py index e6b9474d7e..dfd77196b1 100644 --- a/unittest/python/bindings_model.py +++ b/unittest/python/bindings_model.py @@ -49,8 +49,8 @@ def test_add_joint(self): self.assertEqual(model.nq, 2) self.assertEqual(model.nv, 2) - self.assertEqual(float(model.effortLimit[1]), MAX_EFF) - self.assertEqual(float(model.velocityLimit[1]), MAX_VEL) + self.assertEqual(float(model.upperEffortLimit[1]), MAX_EFF) + self.assertEqual(float(model.upperVelocityLimit[1]), MAX_VEL) self.assertEqual(float(model.lowerPositionLimit[1]), MIN_POS) self.assertEqual(float(model.upperPositionLimit[1]), MAX_POS) diff --git a/unittest/python/bindings_pgs.py b/unittest/python/bindings_pgs.py new file mode 100644 index 0000000000..1b63a447d3 --- /dev/null +++ b/unittest/python/bindings_pgs.py @@ -0,0 +1,114 @@ +import unittest +from pathlib import Path + +import numpy as np +import pinocchio as pin +from test_case import ContactSolverTestCase as TestCase + +import importlib.util + +coal_spec = importlib.util.find_spec("coal") +coal_found = coal_spec is not None + +matplotlib_spec = importlib.util.find_spec("matplotlib") +matplotlib_found = matplotlib_spec is not None + +meshcat_spec = importlib.util.find_spec("meshcat") +meshcat_found = meshcat_spec is not None + + +class TestPGS(TestCase): + def test_box(self): + model, constraint_models = self.buildStackOfCubesModel([1e-3]) + q0 = pin.neutral(model) + v0 = np.zeros(model.nv) + tau0 = np.zeros(model.nv) + fext = [pin.Force.Zero() for i in range(model.njoints)] + dt = 1e-3 + delassus, g = self.setupTest(model, constraint_models, q0, v0, tau0, fext, dt) + dim_pb = g.shape[0] + solver = pin.PGSContactSolver(dim_pb) + solver.setAbsolutePrecision(1e-13) + solver.setRelativePrecision(1e-14) + solver.solve(delassus, g, constraint_models, dt) + + @unittest.skipUnless(coal_found, "Needs Coal.") + def test_cassie(self, display=False, stat_record=True): + current_dir = Path(__file__).parent + model_dir = current_dir / "../models/" + model_path = model_dir / "closed_chain.xml" + constraint_models = pin.StdVec_ConstraintModel() + + # Parsing model, constraint models and geometry model from xml description + model, constraint_models_dict, geom_model, visual_model = ( + pin.buildModelsFromMJCF(model_path) + ) + + # Adding all constraintds would be + for typed_constraint_models in constraint_models_dict.values(): + for cm in typed_constraint_models: + constraint_models.append(pin.ConstraintModel(cm)) + # Adding only bilateral constraints to the list of constraints + # for bpcm in constraint_models_dict['bilateral_point_constraint_models']: + # constraint_models.append(pin.ConstraintModel(bpcm)) + + # adding joint limit constraints + active_joints_limits = [i for i in range(1, model.njoints)] + jlcm = pin.JointLimitConstraintModel(model, active_joints_limits) + constraint_models.append(pin.ConstraintModel(jlcm)) + + # adding friction on joints + active_joints_friction = [i for i in range(1, model.njoints)] + fjcm = pin.FrictionalJointConstraintModel(model, active_joints_friction) + fjcm.set = pin.BoxSet(model.lowerDryFrictionLimit, model.upperDryFrictionLimit) + constraint_models.append(pin.ConstraintModel(fjcm)) + + q0 = model.referenceConfigurations["home"] + v0 = np.zeros(model.nv) + tau0 = np.zeros(model.nv) + fext = [pin.Force.Zero() for i in range(model.njoints)] + dt = 1e-3 + self.addFloor(geom_model, visual_model) + self.addSystemCollisionPairs(model, geom_model, q0) + + # Adding constraints from frictional contacts + contact_constraints = self.computeContactConstraints(model, geom_model, q0) + for fpcm in contact_constraints: + constraint_models.append(pin.ConstraintModel(fpcm)) + + delassus, g = self.setupTest(model, constraint_models, q0, v0, tau0, fext, dt) + + self.assertTrue( + delassus.shape[0] + == (3 * len(constraint_models_dict["bilateral_point_constraint_models"])) + + (6 * len(constraint_models_dict["weld_constraint_models"])) + + (3 * len(contact_constraints)) + + (model.upperPositionLimit != np.inf).sum() + - 4 * 3 + + (model.lowerPositionLimit != -np.inf).sum() + - 4 * 3 + + model.nv, + "constraint problem is of wrong size.", + ) + + dim_pb = g.shape[0] + solver = pin.PGSContactSolver(dim_pb) + solver.setAbsolutePrecision(1e-13) + solver.setRelativePrecision(1e-14) + + has_converged = solver.solve(delassus, g, constraint_models, dt) + self.assertTrue(has_converged, "Solver did not converge.") + print(solver.getIterationCount()) + print(solver.getAbsoluteConvergenceResidual()) + print(solver.getRelativeConvergenceResidual()) + + if stat_record and matplotlib_found: + self.plotContactSolver(solver) + + if display and meshcat_found: + vizer, viewer = self.createVisualizer(model, geom_model, geom_model) + vizer.display(q0) + + +if __name__ == "__main__": + unittest.main() diff --git a/unittest/python/test_case.py b/unittest/python/test_case.py index c4545c84f4..de83e634c5 100644 --- a/unittest/python/test_case.py +++ b/unittest/python/test_case.py @@ -2,6 +2,27 @@ from pinocchio.utils import isapprox +import pinocchio as pin +import numpy as np + +import importlib.util + +coal_spec = importlib.util.find_spec("coal") +coal_found = coal_spec is not None +if coal_found: + import coal + +matplotlib_spec = importlib.util.find_spec("matplotlib") +matplotlib_found = matplotlib_spec is not None +if matplotlib_found: + import matplotlib.pyplot as plt + +meshcat_spec = importlib.util.find_spec("meshcat") +meshcat_found = meshcat_spec is not None +if meshcat_found: + import meshcat + from pinocchio.visualize import MeshcatVisualizer + def tracefunc(frame, event, arg): print(f"{event}, {frame.f_code.co_filename}: {frame.f_lineno}") @@ -14,3 +35,228 @@ def assertApprox(self, a, b, eps=1e-6): isapprox(a, b, eps), f"\n{a}\nis not approximately equal to\n{b}\nwith precision {eps:f}", ) + + +class ContactSolverTestCase(PinocchioTestCase): + def buildStackOfCubesModel(self, masses): + model = pin.Model() + n_cubes = len(masses) + box_dims = np.ones((3, 1)) + for i in range(n_cubes): + box_mass = masses[i] + box_inertia = pin.Inertia.FromBox( + box_mass, box_dims[0, 0], box_dims[1, 0], box_dims[2, 0] + ) + joint_id = model.addJoint( + 0, pin.JointModelFreeFlyer(), pin.SE3.Identity(), "free_flyer_" + str(i) + ) + model.appendBodyToJoint(joint_id, box_inertia, pin.SE3.Identity()) + + friction_coeff = 0.4 + list_cm = [] + for i in range(n_cubes): + local_trans_box_1 = 0.5 * box_dims + local_trans_box_2 = 0.5 * box_dims + local_trans_box_2[2] *= -1 + rot = np.identity(3) + theta = np.pi / 2 + c, s = np.cos(theta), np.sin(theta) + R = np.array([[c, -s, 0], [s, c, 0], [0, 0, 1]]) + for j in range(4): + local_placement_1 = pin.SE3(np.identity(3), (rot @ local_trans_box_1)) + local_placement_2 = pin.SE3(np.identity(3), (rot @ local_trans_box_2)) + fpcm = pin.FrictionalPointConstraintModel( + model, i, local_placement_1, i + 1, local_placement_2 + ) + fpcm.set = pin.CoulombFrictionCone(friction_coeff) + list_cm.append(pin.ConstraintModel(fpcm)) + rot = R @ rot + + return model, list_cm + + def setupTest(self, model, constraint_models, q0, v0, tau0, fext, dt): + data = model.createData() + data.q_in = q0 + constraint_datas = [] + for cm in constraint_models: + constraint_datas.append(cm.createData()) + pin.crba(model, data, q0, pin.Convention.WORLD) + chol = pin.ContactCholeskyDecomposition(model, constraint_models) + chol.compute(model, data, constraint_models, constraint_datas, 1e-10) + delassus_matrix = chol.getDelassusCholeskyExpression().matrix() + vfree = v0 + dt * pin.aba(model, data, q0, v0, tau0, fext) + Jc = pin.getConstraintsJacobian( + model, data, constraint_models, constraint_datas + ) + g = Jc @ vfree + idx_cm = 0 + for i, cm in enumerate(constraint_models): + cd = constraint_datas[i] + cm_size = cm.size() + cm.calc(model, data, cd) + if cm.shortname() == "FrictionalPointConstraintModel": + continue + elif cm.shortname() == "FrictionalJointConstraintModel": + continue + elif cm.shortname() == "JointLimitConstraintModel": + g[idx_cm : idx_cm + cm_size] *= dt + g[idx_cm : idx_cm + cm_size] += cd.extract().constraint_residual + elif cm.shortname() == "BilateralPointConstraintModel": + continue + g[idx_cm : idx_cm + cm_size] *= dt + g[idx_cm : idx_cm + cm_size] += cd.constraint_residual + idx_cm += cm_size + return delassus_matrix, g + + @unittest.skipUnless(coal_found, "Needs Coal.") + def addFloor(self, geom_model: pin.GeometryModel, visual_model: pin.GeometryModel): + floor_collision_shape = coal.Halfspace(0, 0, 1, 0) + M = pin.SE3.Identity() + floor_collision_object = pin.GeometryObject( + "floor", 0, 0, M, floor_collision_shape + ) + floor_collision_object.meshColor = np.array([0.5, 0.5, 0.5, 0.5]) + geom_model.addGeometryObject(floor_collision_object) + + h = 0.01 + floor_visual_shape = coal.Box(20, 20, h) + Mvis = pin.SE3.Identity() + Mvis.translation = np.array([0.0, 0.0, -h / 2]) + floor_visual_object = pin.GeometryObject( + "floor", 0, 0, Mvis, floor_visual_shape + ) + floor_visual_object.meshColor = np.array([0.5, 0.5, 0.5, 0.4]) + visual_model.addGeometryObject(floor_visual_object) + + @unittest.skipUnless(coal_found, "Needs Coal.") + def addSystemCollisionPairs(self, model, geom_model, qref): + """ + Add the right collision pairs of a model, given qref. + qref is here as a `T-pose`. The function uses this pose to determine which objects are in collision + in this ref pose. If objects are in collision, they are not added as collision pairs, as they are considered + to always be in collision. + """ + data = model.createData() + geom_data = geom_model.createData() + pin.updateGeometryPlacements(model, data, geom_model, geom_data, qref) + geom_model.removeAllCollisionPairs() + num_col_pairs = 0 + for i in range(len(geom_model.geometryObjects)): + for j in range(i + 1, len(geom_model.geometryObjects)): + # Don't add collision pair if same object + if i != j: + gobj_i: pin.GeometryObject = geom_model.geometryObjects[i] + gobj_j: pin.GeometryObject = geom_model.geometryObjects[j] + if gobj_i.name == "floor" or gobj_j.name == "floor": + num_col_pairs += 1 + col_pair = pin.CollisionPair(i, j) + geom_model.addCollisionPair(col_pair) + else: + if gobj_i.parentJoint != gobj_j.parentJoint: + # Compute collision between the geometries. Only add the collision pair if there is no collision. + M1 = geom_data.oMg[i] + M2 = geom_data.oMg[j] + colreq = coal.CollisionRequest() + colreq.security_margin = 1e-2 # 1cm of clearance + colres = coal.CollisionResult() + coal.collide( + gobj_i.geometry, M1, gobj_j.geometry, M2, colreq, colres + ) + if not colres.isCollision(): + num_col_pairs += 1 + col_pair = pin.CollisionPair(i, j) + geom_model.addCollisionPair(col_pair) + + def complete_orthonormal_basis(self, ez, joint_placement): + ex = joint_placement.rotation[:, 0] + ey = np.cross(ez, ex) + if np.linalg.norm(ey) < 1e-6: + ex = joint_placement.rotation[:, 1] + ey = np.cross(ez, ex) + ey /= np.linalg.norm(ey) + ex = np.cross(ey, ez) + return ex, ey + + @unittest.skipUnless(coal_found, "Needs Coal.") + def computeContactConstraints(self, model, geom_model, q): + data = model.createData() + geom_data = geom_model.createData() + pin.updateGeometryPlacements(model, data, geom_model, geom_data, q) + pin.computeCollisions(geom_model, geom_data, False) + pin.computeContactPatches(geom_model, geom_data) + contact_constraints = pin.StdVec_ConstraintModel() + friction_coeff = 0.4 + for i, res in enumerate(geom_data.collisionResults): + patch_res = geom_data.contactPatchResults[i] + if res.isCollision() and patch_res.numContactPatches(): + geom_id1, geom_id2 = ( + geom_model.collisionPairs[i].first, + geom_model.collisionPairs[i].second, + ) + joint_id1 = geom_model.geometryObjects[geom_id1].parentJoint + joint_id2 = geom_model.geometryObjects[geom_id2].parentJoint + joint_placement_1 = data.oMi[joint_id1] + joint_placement_2 = data.oMi[joint_id2] + patch = patch_res.getContactPatch(0) + contact_normal = patch.getNormal() + num_contacts_colpair = min(patch.size(), 4) + for contact_id in range(num_contacts_colpair): + contact_position = patch.getPoint(contact_id) + ex_i, ey_i = self.complete_orthonormal_basis( + contact_normal, joint_placement_1 + ) + ex_i = np.expand_dims(ex_i, axis=1) + ey_i = np.expand_dims(ey_i, axis=1) + normal_i = np.expand_dims(contact_position, axis=1) + R_i = np.concatenate((ex_i, ey_i, normal_i), axis=1) + R_i1 = np.dot(joint_placement_1.rotation.T, R_i) + R_i2 = np.dot(joint_placement_2.rotation.T, R_i) + pos_i1 = joint_placement_1.rotation.T @ ( + contact_position - joint_placement_1.translation + ) + pos_i2 = joint_placement_2.rotation.T @ ( + contact_position - joint_placement_2.translation + ) + placement_i1 = pin.SE3(R_i1, pos_i1) + placement_i2 = pin.SE3(R_i2, pos_i2) + contact_model_i = pin.FrictionalPointConstraintModel( + model, joint_id2, placement_i2, joint_id1, placement_i1 + ) + contact_model_i.set = pin.CoulombFrictionCone(friction_coeff) + contact_constraints.append(contact_model_i) + return contact_constraints + + @unittest.skipUnless(meshcat_found, "Needs meshcat.") + def createVisualizer( + self, + model: pin.GeometryModel, + geom_model: pin.GeometryModel, + visual_model: pin.GeometryModel, + ): + viewer = meshcat.Visualizer(zmq_url="tcp://127.0.0.1:6000") + viewer.delete() + for obj in visual_model.geometryObjects: + color = np.random.rand(4) + color[3] = 1.0 + obj.meshColor = color + vizer: MeshcatVisualizer = MeshcatVisualizer(model, geom_model, visual_model) + vizer.initViewer(viewer=viewer, open=False, loadModel=True) + return vizer, viewer + + @unittest.skipUnless(matplotlib_found, "Needs Matplotlib.") + def plotContactSolver(self, solver): + stats: pin.SolverStats = solver.getStats() + if stats.size() > 0: + plt.figure() + it = solver.getIterationCount() + abs_res = solver.getAbsoluteConvergenceResidual() + rel_res = solver.getRelativeConvergenceResidual() + plt.cla() + plt.title(f"it = {it}, abs res = {abs_res:.2e}, rel res = {rel_res:.2e}") + plt.plot(stats.complementarity, label="complementarity") + plt.plot(stats.primal_feasibility, label="primal feas") + plt.plot(stats.dual_feasibility, label="dual feas") + plt.yscale("log") + plt.legend() + plt.ion() + plt.show() diff --git a/unittest/reference.cpp b/unittest/reference.cpp new file mode 100644 index 0000000000..660cab6ec3 --- /dev/null +++ b/unittest/reference.cpp @@ -0,0 +1,69 @@ +// +// Copyright (c) 2025 INRIA +// + +#include "pinocchio/utils/reference.hpp" + +#include +#include +#include + +using namespace pinocchio; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(test_get_ref) +{ + using namespace ::pinocchio::helper; + + { + double v = 10; + BOOST_CHECK(&v == &get_ref(v)); + + std::reference_wrapper v_ref = v; + BOOST_CHECK(&v == &get_ref(v_ref)); + + std::shared_ptr v_ptr = std::make_shared(v); + BOOST_CHECK(v_ptr.get() != &get_ref(v_ref)); + BOOST_CHECK(v_ptr.get() == &get_ref(v_ptr)); + + const std::shared_ptr v_const_ptr = std::make_shared(v); + BOOST_CHECK(v_const_ptr.get() != &get_ref(v_ref)); + BOOST_CHECK(v_const_ptr.get() == &get_ref(v_const_ptr)); + + std::unique_ptr v_uptr = std::make_unique(v); + BOOST_CHECK(v_uptr.get() != &get_ref(v_ref)); + BOOST_CHECK(v_uptr.get() == &get_ref(v_uptr)); + + const std::unique_ptr v_const_uptr = std::make_unique(v); + BOOST_CHECK(v_const_uptr.get() != &get_ref(v_ref)); + BOOST_CHECK(v_const_uptr.get() == &get_ref(v_const_uptr)); + } + + { + const double const_v = 10; + BOOST_CHECK(&const_v == &get_ref(const_v)); + + std::reference_wrapper const_v_ref = const_v; + BOOST_CHECK(&const_v == &get_ref(const_v_ref)); + + std::shared_ptr const_v_ptr = std::make_shared(const_v); + BOOST_CHECK(const_v_ptr.get() != &get_ref(const_v_ref)); + BOOST_CHECK(const_v_ptr.get() == &get_ref(const_v_ptr)); + + const std::shared_ptr const_v_const_ptr = std::make_shared(const_v); + BOOST_CHECK(const_v_const_ptr.get() != &get_ref(const_v_ref)); + BOOST_CHECK(const_v_const_ptr.get() == &get_ref(const_v_const_ptr)); + + std::unique_ptr const_v_uptr = std::make_unique(const_v); + BOOST_CHECK(const_v_uptr.get() != &get_ref(const_v_ref)); + BOOST_CHECK(const_v_uptr.get() == &get_ref(const_v_uptr)); + + const std::unique_ptr const_v_const_uptr = + std::make_unique(const_v); + BOOST_CHECK(const_v_const_uptr.get() != &get_ref(const_v_ref)); + BOOST_CHECK(const_v_const_uptr.get() == &get_ref(const_v_const_uptr)); + } +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/rotation.cpp b/unittest/rotation.cpp index 3860ba4ea8..acb6ea2cf7 100644 --- a/unittest/rotation.cpp +++ b/unittest/rotation.cpp @@ -6,7 +6,6 @@ #include #include -#include #include // to avoid C99 warnings diff --git a/unittest/sdf.cpp b/unittest/sdf.cpp index 9eafcc5949..586a11f61f 100644 --- a/unittest/sdf.cpp +++ b/unittest/sdf.cpp @@ -11,6 +11,9 @@ #include +using BilateralPointConstraintModelVector = + PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::BilateralPointConstraintModel); + BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) BOOST_AUTO_TEST_CASE(build_model) @@ -22,8 +25,8 @@ BOOST_AUTO_TEST_CASE(build_model) pinocchio::Model model; const std::string rootLinkName = "pelvis"; - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintModel) contact_models; - pinocchio::sdf::buildModel(filename, model, contact_models, rootLinkName); + BilateralPointConstraintModelVector constraint_models; + pinocchio::sdf::buildModel(filename, model, constraint_models, rootLinkName); pinocchio::GeometryModel geomModel; pinocchio::sdf::buildGeom(model, filename, pinocchio::COLLISION, geomModel, rootLinkName, dir); @@ -39,9 +42,9 @@ BOOST_AUTO_TEST_CASE(build_model_with_joint) const std::string dir = PINOCCHIO_MODEL_DIR; const std::string rootLinkName = "pelvis"; pinocchio::Model model; - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintModel) contact_models; + BilateralPointConstraintModelVector constraint_models; pinocchio::sdf::buildModel( - filename, pinocchio::JointModelFreeFlyer(), model, contact_models, rootLinkName); + filename, pinocchio::JointModelFreeFlyer(), model, constraint_models, rootLinkName); pinocchio::GeometryModel geomModel; pinocchio::sdf::buildGeom(model, filename, pinocchio::COLLISION, geomModel, rootLinkName, dir); @@ -57,9 +60,9 @@ BOOST_AUTO_TEST_CASE(build_model_without_rootLink) const std::string dir = PINOCCHIO_MODEL_DIR; const std::string rootLinkName = ""; pinocchio::Model model; - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintModel) contact_models; + BilateralPointConstraintModelVector constraint_models; pinocchio::sdf::buildModel( - filename, pinocchio::JointModelFreeFlyer(), model, contact_models, rootLinkName); + filename, pinocchio::JointModelFreeFlyer(), model, constraint_models, rootLinkName); pinocchio::GeometryModel geomModel; pinocchio::sdf::buildGeom(model, filename, pinocchio::COLLISION, geomModel, rootLinkName, dir); @@ -71,17 +74,17 @@ BOOST_AUTO_TEST_CASE(build_model_with_root_joint_name) const std::string filename = PINOCCHIO_MODEL_DIR + std::string("/simple_humanoid.sdf"); const std::string dir = PINOCCHIO_MODEL_DIR; const std::string rootLinkName = "WAIST_LINK0"; - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintModel) contact_models; + BilateralPointConstraintModelVector constraint_models; pinocchio::Model model; pinocchio::sdf::buildModel( - filename, pinocchio::JointModelFreeFlyer(), model, contact_models, rootLinkName); + filename, pinocchio::JointModelFreeFlyer(), model, constraint_models, rootLinkName); BOOST_CHECK(model.names[1] == "root_joint"); pinocchio::Model model_name; const std::string name_ = "freeFlyer_joint"; - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintModel) contact_models_name; + BilateralPointConstraintModelVector constraint_models_name; pinocchio::sdf::buildModel( - filename, pinocchio::JointModelFreeFlyer(), name_, model_name, contact_models_name, + filename, pinocchio::JointModelFreeFlyer(), name_, model_name, constraint_models_name, rootLinkName); BOOST_CHECK(model_name.names[1] == name_); } @@ -93,9 +96,9 @@ BOOST_AUTO_TEST_CASE(compare_model_with_urdf) pinocchio::Model model_sdf; const std::string rootLinkName = "WAIST_LINK0"; - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintModel) contact_models; + BilateralPointConstraintModelVector constraint_models; pinocchio::sdf::buildModel( - filename, pinocchio::JointModelFreeFlyer(), model_sdf, contact_models, rootLinkName); + filename, pinocchio::JointModelFreeFlyer(), model_sdf, constraint_models, rootLinkName); pinocchio::GeometryModel geomModel; pinocchio::sdf::buildGeom( model_sdf, filename, pinocchio::COLLISION, geomModel, rootLinkName, dir); @@ -140,8 +143,8 @@ BOOST_AUTO_TEST_CASE(compare_model_with_urdf) BOOST_CHECK(model_urdf.armature.size() == model_sdf.armature.size()); BOOST_CHECK(model_urdf.armature == model_sdf.armature); - BOOST_CHECK(model_urdf.friction.size() == model_sdf.friction.size()); - BOOST_CHECK(model_urdf.friction == model_sdf.friction); + BOOST_CHECK(model_urdf.upperDryFrictionLimit.size() == model_sdf.upperDryFrictionLimit.size()); + BOOST_CHECK(model_urdf.upperDryFrictionLimit == model_sdf.upperDryFrictionLimit); BOOST_CHECK(model_urdf.damping.size() == model_sdf.damping.size()); @@ -155,12 +158,12 @@ BOOST_AUTO_TEST_CASE(compare_model_with_urdf) BOOST_CHECK(model_urdf.rotorGearRatio == model_sdf.rotorGearRatio); - BOOST_CHECK(model_urdf.effortLimit.size() == model_sdf.effortLimit.size()); - BOOST_CHECK(model_urdf.effortLimit == model_sdf.effortLimit); + BOOST_CHECK(model_urdf.upperEffortLimit.size() == model_sdf.upperEffortLimit.size()); + BOOST_CHECK(model_urdf.upperEffortLimit == model_sdf.upperEffortLimit); - BOOST_CHECK(model_urdf.velocityLimit.size() == model_sdf.velocityLimit.size()); + BOOST_CHECK(model_urdf.upperVelocityLimit.size() == model_sdf.upperVelocityLimit.size()); - BOOST_CHECK(model_urdf.velocityLimit == model_sdf.velocityLimit); + BOOST_CHECK(model_urdf.upperVelocityLimit == model_sdf.upperVelocityLimit); BOOST_CHECK(model_urdf.lowerPositionLimit.size() == model_sdf.lowerPositionLimit.size()); BOOST_CHECK(model_urdf.lowerPositionLimit == model_sdf.lowerPositionLimit); @@ -381,8 +384,8 @@ BOOST_AUTO_TEST_CASE(compare_model_in_version_1_6) model.appendBodyToJoint(joint4_id, inertia_link_A_2, placement_center_link_A_minus); pinocchio::Model model_sdf; - PINOCCHIO_STD_VECTOR_WITH_EIGEN_ALLOCATOR(pinocchio::RigidConstraintModel) contact_models; - pinocchio::sdf::buildModelFromXML(filestr, model_sdf, contact_models); + BilateralPointConstraintModelVector constraint_models; + pinocchio::sdf::buildModelFromXML(filestr, model_sdf, constraint_models); BOOST_CHECK(model.nq == model_sdf.nq); BOOST_CHECK(model.nv == model_sdf.nv); @@ -411,13 +414,11 @@ BOOST_AUTO_TEST_CASE(compare_model_in_version_1_6) BOOST_CHECK(model.inertias[k].isApprox(model_sdf.inertias[k])); } - BOOST_CHECK(contact_models.size() == 1); - BOOST_CHECK(contact_models[0].joint1_id == 4); - BOOST_CHECK(contact_models[0].joint1_placement == placement_center_link_A_minus); - BOOST_CHECK(contact_models[0].joint2_id == 2); - BOOST_CHECK(contact_models[0].joint2_placement == placement_center_link_A); - BOOST_CHECK(contact_models[0].type == pinocchio::CONTACT_6D); - BOOST_CHECK(contact_models[0].reference_frame == pinocchio::LOCAL); + BOOST_CHECK(constraint_models.size() == 1); + BOOST_CHECK(constraint_models[0].joint1_id == 4); + BOOST_CHECK(constraint_models[0].joint1_placement == placement_center_link_A_minus); + BOOST_CHECK(constraint_models[0].joint2_id == 2); + BOOST_CHECK(constraint_models[0].joint2_placement == placement_center_link_A); } BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/serialization.cpp b/unittest/serialization.cpp index fc810abb67..19da9fd027 100644 --- a/unittest/serialization.cpp +++ b/unittest/serialization.cpp @@ -1,11 +1,12 @@ // -// Copyright (c) 2019-2023 INRIA +// Copyright (c) 2019-2025 INRIA // #include "pinocchio/multibody/data.hpp" #include "pinocchio/algorithm/joint-configuration.hpp" #include "pinocchio/algorithm/kinematics.hpp" #include "pinocchio/algorithm/geometry.hpp" +#include "pinocchio/algorithm/crba.hpp" #include "pinocchio/serialization/fwd.hpp" #include "pinocchio/serialization/archive.hpp" @@ -20,6 +21,14 @@ #include "pinocchio/serialization/geometry.hpp" +#include "pinocchio/serialization/delassus.hpp" + +#include "pinocchio/serialization/constraints-model.hpp" +#include "pinocchio/serialization/constraints-data.hpp" + +#include "pinocchio/serialization/eigen-storage.hpp" +#include "pinocchio/serialization/double-entry-container.hpp" + #include "pinocchio/multibody/sample-models.hpp" #include @@ -61,6 +70,17 @@ struct call_equality_op +struct call_equality_op> +{ + typedef Eigen::Array T; + + static bool run(const T & a1, const T & a2) + { + return a1.matrix() == a2.matrix(); + } +}; + template struct empty_contructor_algo { @@ -79,6 +99,15 @@ struct empty_contructor_algo } }; +template<> +struct empty_contructor_algo +{ + static pinocchio::DelassusOperatorDense * run() + { + return new pinocchio::DelassusOperatorDense(Eigen::MatrixXd(2, 2)); + } +}; + template T * empty_contructor() { @@ -222,6 +251,9 @@ BOOST_AUTO_TEST_CASE(test_eigen_serialization) Eigen::array array = {1, 2, 3}; generic_test(array, TEST_SERIALIZATION_FOLDER "/eigen_array", "array"); + Eigen::ArrayXXd Array = Eigen::ArrayXXd::Random(num_rows, num_cols); + generic_test(Array, TEST_SERIALIZATION_FOLDER "/eigen_array", "array"); + const Eigen::DenseIndex tensor_size = 3; const Eigen::DenseIndex x_dim = 10, y_dim = 20, z_dim = 30; @@ -587,6 +619,7 @@ struct TestJointData model.addJoint(0, jmodel_build, pinocchio::SE3::Random(), "model"); model.lowerPositionLimit.fill(-1.); model.upperPositionLimit.fill(1.); + model.positionLimitMargin.fill(1.5); JointModel & jmodel = boost::get(model.joints[1]); Eigen::VectorXd q_random = pinocchio::randomConfiguration(model); @@ -689,6 +722,68 @@ BOOST_AUTO_TEST_CASE(test_data_serialization) generic_test(data, TEST_SERIALIZATION_FOLDER "/Data", "Data"); } +BOOST_AUTO_TEST_CASE(test_delassus_operator_dense_serialization) +{ + using namespace pinocchio; + + // create model + Model model; + buildModels::manipulator(model); + model.lowerPositionLimit.setConstant(-1.0); + model.upperPositionLimit.setConstant(1.0); + model.positionLimitMargin.setConstant(1.5); + model.lowerDryFrictionLimit.setConstant(-1.0); + model.upperDryFrictionLimit.setConstant(1.0); + Data data(model); + + // setup data + Eigen::VectorXd q0 = ::pinocchio::neutral(model); + Eigen::VectorXd v0 = Eigen::VectorXd::Zero(model.nv); + Eigen::VectorXd tau = Eigen::VectorXd::Zero(model.nv); + data.q_in = q0; + aba(model, data, q0, v0, tau, Convention::WORLD); + crba(model, data, q0, Convention::WORLD); + + // create constraints + std::vector constraint_models; + std::vector constraint_datas; + + FrictionalJointConstraintModel::JointIndexVector active_friction_idxs; + FrictionalJointConstraintModel::JointIndexVector active_limit_idxs; + for (size_t i = 1; i < model.joints.size(); ++i) + { + const Model::JointModel & joint = model.joints[i]; + active_friction_idxs.push_back(joint.id()); + active_limit_idxs.push_back(joint.id()); + } + FrictionalJointConstraintModel joints_friction(model, active_friction_idxs); + constraint_models.push_back(joints_friction); + constraint_datas.push_back(joints_friction.createData()); + // + JointLimitConstraintModel joints_limit(model, active_limit_idxs); + constraint_models.push_back(joints_limit); + constraint_datas.push_back(joints_limit.createData()); + + for (size_t i = 0; i < constraint_models.size(); ++i) + { + ConstraintModel & cmodel = constraint_models[i]; + ConstraintData & cdata = constraint_datas[i]; + cmodel.resize(model, data, cdata); + cmodel.calc(model, data, cdata); + } + + // compute delassus + ContactCholeskyDecomposition chol(model, constraint_models); + chol.compute(model, data, constraint_models, constraint_datas, 1e-10); + + // check dense method + DelassusOperatorDense delassus_operator_dense = chol.getDelassusCholeskyExpression().dense(); + + generic_test( + delassus_operator_dense, TEST_SERIALIZATION_FOLDER "/DelassusOperatorDense", + "DelassusOperatorDense"); +} + BOOST_AUTO_TEST_CASE(test_collision_pair) { using namespace pinocchio; @@ -791,4 +886,334 @@ BOOST_AUTO_TEST_CASE(test_geometry_model_and_data_serialization) #endif // PINOCCHIO_WITH_HPP_FCL } +template +struct JointLimitAndFrictionConstraintModelInitializer +{ + typedef pinocchio::Model Model; + typedef pinocchio::JointIndex JointIndex; + + static DerivedConstraintModel run(const Model & model) + { + const std::string ee_name = "wrist2_joint"; + const JointIndex ee_id = model.getJointId(ee_name); + + // get joint path to end-effector + const Model::IndexVector & ee_support = model.supports[ee_id]; + // get joint ids to put in the joint limit constraint (omit first joint as it is always the + // universe) + const Model::IndexVector active_joint_ids(ee_support.begin() + 1, ee_support.end()); + + DerivedConstraintModel cmodel(model, active_joint_ids); + cmodel.name = cmodel.classname(); + cmodel.compliance().setRandom(); + + return cmodel; + } +}; + +template +struct PointAndFrameConstraintModelInitializer +{ + typedef pinocchio::Model Model; + typedef pinocchio::JointIndex JointIndex; + typedef pinocchio::SE3 SE3; + + static DerivedConstraintModel run(const Model & model) + { + const std::string joint1_name = "elbow_joint"; + const JointIndex joint1_id = model.getJointId(joint1_name); + + const std::string joint2_name = "wrist2_joint"; + const JointIndex joint2_id = model.getJointId(joint2_name); + + DerivedConstraintModel cmodel(model, joint1_id, SE3::Random(), joint2_id, SE3::Random()); + cmodel.name = cmodel.classname(); + cmodel.compliance().setRandom(); + // CHOICE: right now we use the scalar Baumgarte + // cmodel.baumgarte_corrector_vector_parameters().Kd.setRandom(); + // cmodel.baumgarte_corrector_vector_parameters().Kp.setRandom(); + cmodel.baumgarte_corrector_parameters().Kd = 1.0; + cmodel.baumgarte_corrector_parameters().Kp = 3.14; + + return cmodel; + } +}; + +template +struct initConstraint; + +template<> +struct initConstraint +{ + typedef pinocchio::Model Model; + typedef pinocchio::JointLimitConstraintModel ConstraintModel; + + static ConstraintModel run(const Model & model) + { + // Note: JointLimitConstraintModel's constraint set is automatically constructed + // uppon construction of the constraint model. + ConstraintModel cmodel = + JointLimitAndFrictionConstraintModelInitializer::run(model); + cmodel.baumgarte_corrector_parameters().Kd = 1.0; + cmodel.baumgarte_corrector_parameters().Kp = 3.14; + return cmodel; + } +}; + +template<> +struct initConstraint +{ + typedef pinocchio::Model Model; + typedef pinocchio::FrictionalJointConstraintModel ConstraintModel; + + static ConstraintModel run(const Model & model) + { + // Note: The upper/lower bounds of FrictionalJointConstraintModel's constraint set + // need to be set after constructing the constraint model. + ConstraintModel cmodel = + JointLimitAndFrictionConstraintModelInitializer::run(model); + Eigen::VectorXd lb = -Eigen::VectorXd::Random(cmodel.size()).array().abs(); + Eigen::VectorXd ub = Eigen::VectorXd::Random(cmodel.size()).array().abs(); + cmodel.set() = pinocchio::BoxSet(lb, ub); + return cmodel; + } +}; + +template<> +struct initConstraint +{ + typedef pinocchio::Model Model; + typedef pinocchio::BilateralPointConstraintModel ConstraintModel; + + static ConstraintModel run(const Model & model) + { + // Note: For bilateral constraints, no need to manually set the constraint set. + ConstraintModel cmodel = PointAndFrameConstraintModelInitializer::run(model); + return cmodel; + } +}; + +template<> +struct initConstraint +{ + typedef pinocchio::Model Model; + typedef pinocchio::FrictionalPointConstraintModel ConstraintModel; + + static ConstraintModel run(const Model & model) + { + // Note: For frictional point constraints, the friction coeff of the coulomb cone needs to be + // set. + ConstraintModel cmodel = PointAndFrameConstraintModelInitializer::run(model); + cmodel.set() = pinocchio::CoulombFrictionCone(0.1234); + return cmodel; + } +}; + +template<> +struct initConstraint +{ + typedef pinocchio::Model Model; + typedef pinocchio::WeldConstraintModel ConstraintModel; + + static ConstraintModel run(const Model & model) + { + // Note: For weld constraints, no need to manually set the constraint set. + ConstraintModel cmodel = PointAndFrameConstraintModelInitializer::run(model); + return cmodel; + } +}; + +struct TestConstraintModel +{ + typedef pinocchio::Model Model; + + void operator()(boost::blank) const + { + // do nothing + } + + template + void operator()(const pinocchio::ConstraintModelBase &) const + { + Model model; + pinocchio::buildModels::manipulator(model); + ConstraintModel cmodel = initConstraint::run(model); + test(cmodel); + } + + template + static void test(ConstraintModel & cmodel) + { + generic_test(cmodel, TEST_SERIALIZATION_FOLDER "/Constraint", "cmodel"); + } +}; + +BOOST_AUTO_TEST_CASE(test_constraints_model_serialization) +{ + using namespace pinocchio; + boost::mpl::for_each(TestConstraintModel()); +} + +struct TestConstraintData +{ + typedef pinocchio::Model Model; + typedef pinocchio::Data Data; + + void operator()(boost::blank) const + { + // do nothing + } + + template + void operator()(const pinocchio::ConstraintDataBase &) const + { + Model model; + pinocchio::buildModels::manipulator(model); + Data data(model); + + // run aba to populate data + Eigen::VectorXd q = pinocchio::randomConfiguration(model); + Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv); + Eigen::VectorXd tau = Eigen::VectorXd::Random(model.nv); + pinocchio::aba(model, data, q, v, tau, pinocchio::Convention::WORLD); + + typedef typename ConstraintData::ConstraintModel ConstraintModel; + ConstraintModel cmodel = initConstraint::run(model); + ConstraintData cdata(cmodel); + cmodel.resize(model, data, cdata); + cmodel.calc(model, data, cdata); + test(cdata); + } + + template + static void test(ConstraintData & cdata) + { + generic_test(cdata, TEST_SERIALIZATION_FOLDER "/Constraint", "cdata"); + } +}; + +BOOST_AUTO_TEST_CASE(test_constraints_data_serialization) +{ + using namespace pinocchio; + boost::mpl::for_each(TestConstraintData()); +} + +BOOST_AUTO_TEST_CASE(test_constraint_model_variant) +{ + using namespace pinocchio; + + Model model; + pinocchio::buildModels::manipulator(model); + Data data(model); + + // run aba to populate data + Eigen::VectorXd q = pinocchio::randomConfiguration(model); + Eigen::VectorXd v = Eigen::VectorXd::Random(model.nv); + Eigen::VectorXd tau = Eigen::VectorXd::Random(model.nv); + aba(model, data, q, v, tau, pinocchio::Convention::WORLD); + + std::vector cmodels; + std::vector cdatas; + { + JointLimitConstraintModel cmodel_ = initConstraint::run(model); + ConstraintModel cmodel(cmodel_); + ConstraintData cdata(cmodel.createData()); + cmodel.resize(model, data, cdata); + cmodel.calc(model, data, cdata); + + cmodels.push_back(cmodel); + cdatas.push_back(cdata); + + generic_test(cmodel, TEST_SERIALIZATION_FOLDER "/Constraint", "cmodel_variant"); + // generic_test(cdata, TEST_SERIALIZATION_FOLDER "/Constraint", "cdata_variant"); + } + { + FrictionalJointConstraintModel cmodel_ = + initConstraint::run(model); + ConstraintModel cmodel(cmodel_); + ConstraintData cdata(cmodel.createData()); + cmodel.resize(model, data, cdata); + cmodel.calc(model, data, cdata); + + cmodels.push_back(cmodel); + cdatas.push_back(cdata); + + generic_test(cmodel, TEST_SERIALIZATION_FOLDER "/Constraint", "cmodel_variant"); + generic_test(cdata, TEST_SERIALIZATION_FOLDER "/Constraint", "cdata_variant"); + } + { + FrictionalPointConstraintModel cmodel_ = + initConstraint::run(model); + ConstraintModel cmodel(cmodel_); + ConstraintData cdata(cmodel.createData()); + cmodel.resize(model, data, cdata); + cmodel.calc(model, data, cdata); + + cmodels.push_back(cmodel); + cdatas.push_back(cdata); + + generic_test(cmodel, TEST_SERIALIZATION_FOLDER "/Constraint", "cmodel_variant"); + generic_test(cdata, TEST_SERIALIZATION_FOLDER "/Constraint", "cdata_variant"); + } + { + BilateralPointConstraintModel cmodel_ = + initConstraint::run(model); + ConstraintModel cmodel(cmodel_); + ConstraintData cdata(cmodel.createData()); + cmodel.resize(model, data, cdata); + cmodel.calc(model, data, cdata); + + cmodels.push_back(cmodel); + cdatas.push_back(cdata); + + generic_test(cmodel, TEST_SERIALIZATION_FOLDER "/Constraint", "cmodel_variant"); + generic_test(cdata, TEST_SERIALIZATION_FOLDER "/Constraint", "cdata_variant"); + } + { + WeldConstraintModel cmodel_ = initConstraint::run(model); + ConstraintModel cmodel(cmodel_); + ConstraintData cdata(cmodel.createData()); + cmodel.resize(model, data, cdata); + cmodel.calc(model, data, cdata); + + cmodels.push_back(cmodel); + cdatas.push_back(cdata); + + generic_test(cmodel, TEST_SERIALIZATION_FOLDER "/Constraint", "cmodel_variant"); + generic_test(cdata, TEST_SERIALIZATION_FOLDER "/Constraint", "cdata_variant"); + } + + // test vector of constraints + for (ConstraintModel & cmodel : cmodels) + { + cmodel.compliance().setRandom(); + } + generic_test(cmodels, TEST_SERIALIZATION_FOLDER "/Constraint", "cmodel_vector"); +} + +BOOST_AUTO_TEST_CASE(eigen_storage) +{ + typedef pinocchio::EigenStorageTpl EigenStorage; + + EigenStorage storage(15, 8, 15, 8); + storage.map().setRandom(); + storage.resize(10, 5); + + generic_test(storage, TEST_SERIALIZATION_FOLDER "/Container", "eigen_storage"); +} + +BOOST_AUTO_TEST_CASE(double_entry_container) +{ + typedef pinocchio::Inertia::Matrix6 Matrix6; + typedef pinocchio::container::DoubleEntryContainer DoubleEntryContainer; + + DoubleEntryContainer container(10, 20); + for (Eigen::DenseIndex k = 0; k < 10; ++k) + { + container[{k, k}] = Matrix6::Random(); + } + + generic_test(container, TEST_SERIALIZATION_FOLDER "/Container", "double_entry_container"); +} + BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/spatial.cpp b/unittest/spatial.cpp index 65cb9b9279..2f68f81938 100644 --- a/unittest/spatial.cpp +++ b/unittest/spatial.cpp @@ -17,6 +17,8 @@ #include #include +#include + BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) BOOST_AUTO_TEST_CASE(test_SE3) diff --git a/unittest/storage.cpp b/unittest/storage.cpp new file mode 100644 index 0000000000..ff646a5d46 --- /dev/null +++ b/unittest/storage.cpp @@ -0,0 +1,152 @@ +// +// Copyright (c) 2024 INRIA +// + +#include "pinocchio/container/storage.hpp" + +#include +#include +#include + +using namespace pinocchio; +typedef EigenStorageTpl EigenStorageMatrix; +typedef EigenStorageTpl + EigenStorageRowMatrix; +typedef EigenStorageTpl EigenStorageVector; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(eigen_storage_default) +{ + EigenStorageMatrix storage_matrix; + BOOST_CHECK(!storage_matrix.isValid()); + EigenStorageVector storage_vector; + BOOST_CHECK(!storage_vector.isValid()); +} + +BOOST_AUTO_TEST_CASE(eigen_storage_matrix) +{ + const Eigen::DenseIndex rows = 10, cols = 20; + + const Eigen::DenseIndex initial_capacity = rows * cols; + EigenStorageMatrix storage(rows, cols); + BOOST_CHECK(storage.isValid()); + + BOOST_CHECK(storage.capacity() == initial_capacity); + BOOST_CHECK(storage.rows() == rows); + BOOST_CHECK(storage.cols() == cols); + + EigenStorageMatrix::RefMapType matrix_map = storage.map(); + BOOST_CHECK(matrix_map.data() == storage.data()); + + matrix_map.setIdentity(); + BOOST_CHECK(storage.map().isIdentity(0.)); + BOOST_CHECK(static_cast(storage).map().isIdentity(0.)); + matrix_map.setOnes(); + BOOST_CHECK(storage.map().isOnes(0.)); + BOOST_CHECK(static_cast(storage).map().isOnes(0.)); + + // Check copy + EigenStorageMatrix storage_copy(storage); + BOOST_CHECK(storage_copy.data() != storage.data()); + BOOST_CHECK(storage_copy.map() == storage.map()); + BOOST_CHECK(storage_copy.capacity() == storage.capacity()); + BOOST_CHECK(storage_copy.storage() == storage.storage()); + + // Check resize + const Eigen::DenseIndex new_rows = 2 * rows, new_cols = cols; + storage.conservativeResize(new_rows, new_cols); + BOOST_CHECK(matrix_map.data() == storage.data()); + BOOST_CHECK(storage.map().topLeftCorner(rows, cols).isOnes(0.)); +} + +BOOST_AUTO_TEST_CASE(cast) +{ + const Eigen::DenseIndex rows = 10, cols = 20; + + EigenStorageMatrix storage(rows, cols); + storage.map().setConstant(1.895); + + const auto storage_cast_double = storage.cast(); + BOOST_CHECK(storage_cast_double.map() == storage.map()); + + const auto storage_cast_long_double = storage.cast(); + BOOST_CHECK(storage_cast_long_double.cast().map() == storage.map()); +} + +BOOST_AUTO_TEST_CASE(eigen_storage_row_matrix) +{ + const Eigen::DenseIndex rows = 10, cols = 20; + + const Eigen::DenseIndex initial_capacity = rows * cols; + EigenStorageRowMatrix storage(rows, cols); + BOOST_CHECK(storage.isValid()); + + BOOST_CHECK(storage.capacity() == initial_capacity); + BOOST_CHECK(storage.rows() == rows); + BOOST_CHECK(storage.cols() == cols); + + EigenStorageRowMatrix::RefMapType matrix_map = storage.map(); + BOOST_CHECK(matrix_map.data() == storage.data()); + + matrix_map.setIdentity(); + BOOST_CHECK(storage.map().isIdentity(0.)); + BOOST_CHECK(static_cast(storage).map().isIdentity(0.)); + matrix_map.setOnes(); + BOOST_CHECK(storage.map().isOnes(0.)); + BOOST_CHECK(static_cast(storage).map().isOnes(0.)); + + // Check copy + EigenStorageRowMatrix storage_copy(storage); + BOOST_CHECK(storage_copy.data() != storage.data()); + BOOST_CHECK(storage_copy.map() == storage.map()); + BOOST_CHECK(storage_copy.capacity() == storage.capacity()); + BOOST_CHECK(storage_copy.storage() == storage.storage()); + + // Check resize + const Eigen::DenseIndex new_rows = 2 * rows, new_cols = cols; + storage.conservativeResize(new_rows, new_cols); + BOOST_CHECK(matrix_map.data() == storage.data()); + BOOST_CHECK(storage.map().topLeftCorner(rows, cols).isOnes(0.)); +} + +BOOST_AUTO_TEST_CASE(eigen_storage_vector) +{ + const Eigen::DenseIndex size = 100; + + const Eigen::DenseIndex initial_capacity = size; + EigenStorageVector storage(size); + BOOST_CHECK(storage.isValid()); + + BOOST_CHECK(storage.capacity() == initial_capacity); + BOOST_CHECK(storage.rows() == size); + BOOST_CHECK(storage.cols() == 1); + + EigenStorageVector::RefMapType vector_map = storage.map(); + BOOST_CHECK(vector_map.data() == storage.data()); + + vector_map.setOnes(); + BOOST_CHECK(storage.map().isOnes(0.)); + BOOST_CHECK(static_cast(storage).map().isOnes(0.)); + + // Check copy + EigenStorageVector storage_copy(storage); + BOOST_CHECK(storage_copy.data() != storage.data()); + BOOST_CHECK(storage_copy.map() == storage.map()); + BOOST_CHECK(storage_copy.capacity() == storage.capacity()); + BOOST_CHECK(storage_copy.storage() == storage.storage()); + + // Check resize + const Eigen::DenseIndex new_size = 2 * size; + storage.conservativeResize(new_size); + BOOST_CHECK(vector_map.data() == storage.data()); + BOOST_CHECK(storage.map().head(size).isOnes(0.)); + + storage.conservativeResize(new_size, 1); + BOOST_CHECK(vector_map.data() == storage.data()); + BOOST_CHECK(storage.map().head(size).isOnes(0.)); + + // storage.conservativeResize(1,new_size); // will not pass +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/symmetric.cpp b/unittest/symmetric.cpp index 2ac957a64b..8b263e3a48 100644 --- a/unittest/symmetric.cpp +++ b/unittest/symmetric.cpp @@ -22,7 +22,6 @@ #include "pinocchio/utils/timer.hpp" #include -#include #include "pinocchio/spatial/symmetric3.hpp" diff --git a/unittest/tridiagonal-matrix.cpp b/unittest/tridiagonal-matrix.cpp index 6fdb109e73..5c9c2dae36 100644 --- a/unittest/tridiagonal-matrix.cpp +++ b/unittest/tridiagonal-matrix.cpp @@ -5,7 +5,9 @@ #include #include +#include +#include #include // to avoid C99 warnings #include @@ -48,7 +50,7 @@ BOOST_AUTO_TEST_CASE(test_identity) // Fill matrix { PlainMatrixType mat(mat_size, mat_size); - mat = tridiagonal_matrix; + mat = tridiagonal_matrix.eigen(); BOOST_CHECK(mat.isIdentity(0)); } @@ -59,7 +61,7 @@ BOOST_AUTO_TEST_CASE(test_identity) PlainMatrixType mat = PlainMatrixType::Random(mat_size, mat_size); PlainMatrixType plain(mat_size, mat_size); - plain = tridiagonal_matrix; + plain = tridiagonal_matrix.eigen(); PlainMatrixType res_apply_on_the_right = tridiagonal_matrix * mat; PlainMatrixType res_apply_on_the_right_ref = plain * mat; @@ -87,7 +89,7 @@ BOOST_AUTO_TEST_CASE(test_random) // Fill matrix { PlainMatrixType mat(mat_size, mat_size); - mat = tridiagonal_matrix; + mat = tridiagonal_matrix.eigen(); BOOST_CHECK(mat.diagonal() == tridiagonal_matrix.diagonal()); BOOST_CHECK(mat.diagonal<-1>() == tridiagonal_matrix.subDiagonal()); @@ -100,7 +102,7 @@ BOOST_AUTO_TEST_CASE(test_random) PlainMatrixType rhs_mat = PlainMatrixType::Random(mat_size, mat_size); PlainMatrixType plain(mat_size, mat_size); - plain = tridiagonal_matrix; + plain = tridiagonal_matrix.eigen(); PlainMatrixType res = tridiagonal_matrix * rhs_mat; @@ -121,7 +123,7 @@ BOOST_AUTO_TEST_CASE(test_inverse) tridiagonal_matrix.setRandom(); PlainMatrixType plain_mat(mat_size, mat_size); - plain_mat = tridiagonal_matrix; + plain_mat = tridiagonal_matrix.eigen(); const PlainMatrixType plain_mat_inverse = plain_mat.inverse(); const TridiagonalSymmetricMatrixInverse & @@ -172,4 +174,55 @@ BOOST_AUTO_TEST_CASE(test_inverse) } } +BOOST_AUTO_TEST_CASE(test_eigenvalues) +{ + const Eigen::DenseIndex mat_size = 20; + TridiagonalSymmetricMatrixTpl tridiagonal_matrix(mat_size); + + const double eps = 1e-8; + + // Case: Identity matrix + { + tridiagonal_matrix.setIdentity(); + const auto spectrum = computeSpectrum(tridiagonal_matrix, eps); + + BOOST_CHECK(spectrum.isOnes(eps)); + } + + // Case: Zero matrix + { + tridiagonal_matrix.setZero(); + const auto spectrum = computeSpectrum(tridiagonal_matrix, eps); + + BOOST_CHECK(spectrum.isZero(eps)); + } + + // Case: Random matrix +#ifndef NDEBUG + for (int k = 0; k < 100; ++k) +#else + for (int k = 0; k < 10000; ++k) +#endif + { + tridiagonal_matrix.setRandom(); + const auto spectrum = computeSpectrum(tridiagonal_matrix, eps); + + const Eigen::MatrixXd dense_matrix = tridiagonal_matrix.matrix(); + + const Eigen::SelfAdjointEigenSolver eigen_solver( + dense_matrix, Eigen::EigenvaluesOnly); + const auto spectrum_ref = eigen_solver.eigenvalues(); + BOOST_CHECK(spectrum.isApprox(spectrum_ref, eps)); + + // Compute largest and lowest eigenvalues + const Eigen::DenseIndex last_index = tridiagonal_matrix.rows() - 1; + const Eigen::DenseIndex first_index = 0; + const double largest_eigenvalue = computeEigenvalue(tridiagonal_matrix, last_index, eps); + BOOST_CHECK(math::fabs(largest_eigenvalue - spectrum_ref[last_index]) <= eps); + + const double lowest_eigenvalue = computeEigenvalue(tridiagonal_matrix, first_index, eps); + BOOST_CHECK(math::fabs(lowest_eigenvalue - spectrum_ref[first_index]) <= eps); + } +} + BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/unbounded-set.cpp b/unittest/unbounded-set.cpp new file mode 100644 index 0000000000..c46fc208aa --- /dev/null +++ b/unittest/unbounded-set.cpp @@ -0,0 +1,43 @@ +// +// Copyright (c) 2024 INRIA +// + +#include "pinocchio/algorithm/constraints/unbounded-set.hpp" + +#include +#include + +using namespace pinocchio; + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(test_proj) +{ + const int num_tests = int(1e6); + const int dim = 10; + + const UnboundedSet set(dim); + + BOOST_CHECK(set.dim() == dim); + + BOOST_CHECK(set.isInside(UnboundedSet::Vector::Zero(dim))); + BOOST_CHECK(set.project(UnboundedSet::Vector::Zero(dim)) == UnboundedSet::Vector::Zero(dim)); + + for (int k = 0; k < num_tests; ++k) + { + const UnboundedSet::Vector x = UnboundedSet::Vector::Random(dim); + + const auto proj_x = set.project(x); + const auto proj_proj_x = set.project(proj_x); + + BOOST_CHECK(set.isInside(proj_x, 1e-12)); + BOOST_CHECK(set.isInside(proj_proj_x, 1e-12)); + BOOST_CHECK(proj_x == proj_proj_x); + if (set.isInside(x)) + BOOST_CHECK(x == proj_x); + + BOOST_CHECK(fabs((x - proj_x).dot(proj_x)) <= 1e-12); // orthogonal projection + } +} + +BOOST_AUTO_TEST_SUITE_END() diff --git a/unittest/weld-constraint.cpp b/unittest/weld-constraint.cpp new file mode 100644 index 0000000000..e6330412d1 --- /dev/null +++ b/unittest/weld-constraint.cpp @@ -0,0 +1,760 @@ +// +// Copyright (c) 2024 INRIA +// + +#include "pinocchio/algorithm/aba.hpp" +#include "pinocchio/algorithm/rnea.hpp" +#include "pinocchio/algorithm/jacobian.hpp" +#include "pinocchio/algorithm/kinematics.hpp" +#include "pinocchio/algorithm/crba.hpp" +#include "pinocchio/algorithm/frames.hpp" +#include "pinocchio/algorithm/contact-info.hpp" +#include "pinocchio/algorithm/contact-cholesky.hpp" +#include "pinocchio/algorithm/contact-jacobian.hpp" +#include "pinocchio/algorithm/joint-configuration.hpp" +#include "pinocchio/multibody/sample-models.hpp" +#include "pinocchio/utils/timer.hpp" +#include "pinocchio/spatial/classic-acceleration.hpp" +#include "pinocchio/algorithm/constraints/weld-constraint.hpp" + +// Helpers +#include "constraints/jacobians-checker.hpp" + +#include + +#include +#include + +using namespace pinocchio; +using namespace Eigen; + +template +bool within(const T & elt, const std::vector & vec) +{ + typename std::vector::const_iterator it; + + it = std::find(vec.begin(), vec.end(), elt); + if (it != vec.end()) + return true; + else + return false; +} + +template +bool within(const typename Matrix::Scalar & elt, const Eigen::MatrixBase & mat) +{ + for (DenseIndex i = 0; i < mat.rows(); ++i) + for (DenseIndex j = 0; j < mat.rows(); ++j) + { + if (elt == mat(i, j)) + return true; + } + + return false; +} + +BOOST_AUTO_TEST_SUITE(BOOST_TEST_MODULE) + +BOOST_AUTO_TEST_CASE(basic_constructor) +{ + Model model; + buildModels::humanoidRandom(model, true); + + // Check complete constructor + const SE3 M(SE3::Random()); + WeldConstraintModel cmodel2(model, 0, M); + BOOST_CHECK(cmodel2.joint1_id == 0); + BOOST_CHECK(cmodel2.joint1_placement == M); + BOOST_CHECK(cmodel2.size() == 6); + + // Check contructor with two arguments + WeldConstraintModel cmodel2prime(model, 0); + BOOST_CHECK(cmodel2prime.joint1_id == 0); + BOOST_CHECK(cmodel2prime.joint1_placement.isIdentity(0.)); + BOOST_CHECK(cmodel2prime.size() == 6); + + // Check default copy constructor + WeldConstraintModel cmodel3(cmodel2); + BOOST_CHECK(cmodel3 == cmodel2); +} + +void check_A1_and_A2( + const Model & model, + const Data & data, + const WeldConstraintModel & cmodel, + WeldConstraintData & cdata) +{ + const WeldConstraintModel::Matrix6 A1_world = cmodel.getA1(cdata, WorldFrameTag()); + WeldConstraintModel::Matrix6 A1_world_ref = -cdata.oMc1.toActionMatrixInverse(); + + BOOST_CHECK(A1_world.isApprox(A1_world_ref)); + + const WeldConstraintModel::Matrix6 A2_world = cmodel.getA2(cdata, WorldFrameTag()); + const WeldConstraintModel::Matrix6 A2_world_ref = -A1_world_ref; + + BOOST_CHECK(A2_world.isApprox(A2_world_ref)); + + const WeldConstraintModel::Matrix6 A1_local = cmodel.getA1(cdata, LocalFrameTag()); + WeldConstraintModel::Matrix6 A1_local_ref = -cmodel.joint1_placement.toActionMatrixInverse(); + + BOOST_CHECK(A1_local.isApprox(A1_local_ref)); + + const WeldConstraintModel::Matrix6 A2_local = cmodel.getA2(cdata, LocalFrameTag()); + const WeldConstraintModel::Matrix6 A2_local_ref = + (cdata.c1Mc2 * cmodel.joint2_placement.inverse()).toActionMatrix(); + + BOOST_CHECK(A2_local.isApprox(A2_local_ref)); + + // Check Jacobians + Data::MatrixXs J_ref(6, model.nv); + J_ref.setZero(); + getConstraintJacobian(model, data, cmodel, cdata, J_ref); + + // World + const Data::Matrix6x J1_world = getJointJacobian(model, data, cmodel.joint1_id, WORLD); + const Data::Matrix6x J2_world = getJointJacobian(model, data, cmodel.joint2_id, WORLD); + const Data::Matrix6x J_world = A1_world * J1_world + A2_world * J2_world; + + BOOST_CHECK(J_world.isApprox(J_ref)); + + // Local + const Data::Matrix6x J1_local = getJointJacobian(model, data, cmodel.joint1_id, LOCAL); + const Data::Matrix6x J2_local = getJointJacobian(model, data, cmodel.joint2_id, LOCAL); + const Data::Matrix6x J_local = A1_local * J1_local + A2_local * J2_local; + + BOOST_CHECK(J_local.isApprox(J_ref)); +} + +BOOST_AUTO_TEST_CASE(basic_operations) +{ + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + Data data(model), data_ref(model); + + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); + const VectorXd q = randomConfiguration(model); + + crba(model, data, q, Convention::WORLD); + + const std::string RF_name = "rleg6_joint"; + const std::string LF_name = "lleg6_joint"; + + WeldConstraintModel cm( + model, model.getJointId(RF_name), SE3::Random(), model.getJointId(LF_name), SE3::Random()); + WeldConstraintData cd(cm); + cm.calc(model, data, cd); + + // Vector LOCAL + { + const Inertia::Vector6 diagonal_inertia(1, 2, 3, 4, 5, 6); + + const auto A1 = cm.getA1(cd, LocalFrameTag()); + const Inertia::Matrix6 I11_ref = A1.transpose() * diagonal_inertia.asDiagonal() * A1; + + const auto A2 = cm.getA2(cd, LocalFrameTag()); + const Inertia::Matrix6 I22_ref = A2.transpose() * diagonal_inertia.asDiagonal() * A2; + + const Inertia::Matrix6 I12_ref = A1.transpose() * diagonal_inertia.asDiagonal() * A2; + + Inertia::Matrix6 I11 = -Inertia::Matrix6::Ones(), I12 = -Inertia::Matrix6::Ones(), + I22 = -Inertia::Matrix6::Ones(); + + cm.computeConstraintInertias(cd, diagonal_inertia, I11, I12, I22, LocalFrameTag()); + BOOST_CHECK(I11.isApprox(I11_ref)); + BOOST_CHECK(I12.isApprox(I12_ref)); + BOOST_CHECK(I22.isApprox(I22_ref)); + + // Check against scalar signature + const double constant_inertia_value = 10; + const Inertia::Vector6 diagonal_inertia_scalar = + Inertia::Vector6::Constant(constant_inertia_value); + Inertia::Matrix6 I11_scalar = -Inertia::Matrix6::Ones(), I12_scalar = -Inertia::Matrix6::Ones(), + I22_scalar = -Inertia::Matrix6::Ones(); + + cm.computeConstraintInertias(cd, diagonal_inertia_scalar, I11, I12, I22, LocalFrameTag()); + cm.computeConstraintInertias( + cd, constant_inertia_value, I11_scalar, I12_scalar, I22_scalar, LocalFrameTag()); + BOOST_CHECK(I11 == I11_scalar); + BOOST_CHECK(I12 == I12_scalar); + BOOST_CHECK(I22 == I22_scalar); + } + + // Vector WORLD + { + const Inertia::Vector6 diagonal_inertia(1, 2, 3, 4, 5, 6); + + const auto A1 = cm.getA1(cd, WorldFrameTag()); + const Inertia::Matrix6 I11_ref = A1.transpose() * diagonal_inertia.asDiagonal() * A1; + + const auto A2 = cm.getA2(cd, WorldFrameTag()); + const Inertia::Matrix6 I22_ref = A2.transpose() * diagonal_inertia.asDiagonal() * A2; + + const Inertia::Matrix6 I12_ref = A1.transpose() * diagonal_inertia.asDiagonal() * A2; + + Inertia::Matrix6 I11 = -Inertia::Matrix6::Ones(), I12 = -Inertia::Matrix6::Ones(), + I22 = -Inertia::Matrix6::Ones(); + + cm.computeConstraintInertias(cd, diagonal_inertia, I11, I12, I22, WorldFrameTag()); + BOOST_CHECK(I11.isApprox(I11_ref)); + BOOST_CHECK(I12.isApprox(I12_ref)); + BOOST_CHECK(I22.isApprox(I22_ref)); + + // Check against scalar signature + const double constant_inertia_value = 10; + const Inertia::Vector6 diagonal_inertia_scalar = + Inertia::Vector6::Constant(constant_inertia_value); + Inertia::Matrix6 I11_scalar = -Inertia::Matrix6::Ones(), I12_scalar = -Inertia::Matrix6::Ones(), + I22_scalar = -Inertia::Matrix6::Ones(); + + cm.computeConstraintInertias(cd, diagonal_inertia_scalar, I11, I12, I22, WorldFrameTag()); + cm.computeConstraintInertias( + cd, constant_inertia_value, I11_scalar, I12_scalar, I22_scalar, WorldFrameTag()); + BOOST_CHECK(I11 == I11_scalar); + BOOST_CHECK(I12 == I12_scalar); + BOOST_CHECK(I22 == I22_scalar); + } + + // Check null values + { + WeldConstraintModel cm1(model, model.getJointId(RF_name), SE3::Random()); + WeldConstraintData cd1(cm1); + cm1.calc(model, data, cd1); + + Inertia::Matrix6 I11 = -Inertia::Matrix6::Ones(), I12 = -Inertia::Matrix6::Ones(), + I22 = -Inertia::Matrix6::Ones(); + + const double constant_inertia_value = 10; + cm1.computeConstraintInertias(cd1, constant_inertia_value, I11, I12, I22, WorldFrameTag()); + BOOST_CHECK(!I11.isZero(0)); + BOOST_CHECK(I12.isZero(0)); + BOOST_CHECK(I22.isZero(0)); + + I11.fill(-1); + I12.fill(-1); + I22.fill(-1); + cm1.computeConstraintInertias(cd1, constant_inertia_value, I11, I12, I22, LocalFrameTag()); + BOOST_CHECK(!I11.isZero(0)); + BOOST_CHECK(I12.isZero(0)); + BOOST_CHECK(I22.isZero(0)); + + WeldConstraintModel cm2(model, 0, SE3::Identity(), model.getJointId(RF_name), SE3::Random()); + WeldConstraintData cd2(cm2); + cm2.calc(model, data, cd2); + + I11.fill(-1); + I12.fill(-1); + I22.fill(-1); + cm2.computeConstraintInertias(cd2, constant_inertia_value, I11, I12, I22, WorldFrameTag()); + BOOST_CHECK(I11.isZero(0)); + BOOST_CHECK(I12.isZero(0)); + BOOST_CHECK(!I22.isZero(0)); + + I11.fill(-1); + I12.fill(-1); + I22.fill(-1); + cm2.computeConstraintInertias(cd2, constant_inertia_value, I11, I12, I22, LocalFrameTag()); + BOOST_CHECK(I11.isZero(0)); + BOOST_CHECK(I12.isZero(0)); + BOOST_CHECK(!I22.isZero(0)); + } +} + +template +Eigen::MatrixXd compute_jacobian_fd( + const Model & model, + const WeldConstraintModel & cmodel, + const Eigen::MatrixBase & q, + const double eps) +{ + Data data_fd(model), data(model); + WeldConstraintData cdata(cmodel), cdata_fd(cmodel); + + Eigen::MatrixXd res(cmodel.size(), model.nv); + res.setZero(); + + forwardKinematics(model, data, q), + + cmodel.calc(model, data, cdata); + Eigen::VectorXd v_plus(model.nv); + v_plus.setZero(); + + for (int i = 0; i < model.nv; ++i) + { + v_plus[i] = eps; + const auto q_plus = integrate(model, q, v_plus); + forwardKinematics(model, data_fd, q_plus), + + cmodel.calc(model, data_fd, cdata_fd); + + res.col(i) = log6(cdata_fd.c1Mc2.act(cdata.c1Mc2.inverse())).toVector() / eps; + + v_plus[i] = 0; + } + + return res; +} + +SE3 computeConstraintError(const Model & model, const Data & data, const WeldConstraintModel & cm) +{ + PINOCCHIO_UNUSED_VARIABLE(model); + + const SE3 oMc1 = data.oMi[cm.joint1_id] * cm.joint1_placement; + const SE3 oMc2 = data.oMi[cm.joint2_id] * cm.joint2_placement; + + const SE3 c1Mc2 = oMc1.actInv(oMc2); + + return c1Mc2; +} + +BOOST_AUTO_TEST_CASE(contact_models_sparsity_and_jacobians) +{ + + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + Data data(model); + + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); + VectorXd q = randomConfiguration(model); + VectorXd v = VectorXd::Random(model.nv); + VectorXd a = VectorXd::Random(model.nv); + + forwardKinematics(model, data, q, v); + computeJointJacobians(model, data, q); + + const std::string RF = "rleg6_joint"; + const std::string LF = "lleg6_joint"; + const double eps_fd = 1e-8; + + const WeldConstraintModel cm_RF(model, model.getJointId(RF), SE3::Random()); + const WeldConstraintModel cm_LF(model, model.getJointId(LF), SE3::Random()); + const WeldConstraintModel clm_RF_LF( + model, cm_RF.joint1_id, cm_RF.joint1_placement, cm_LF.joint1_id, cm_LF.joint1_placement); + + // Check errors values + { + Data data(model); + + WeldConstraintData cd_RF(cm_RF); + WeldConstraintData cd_LF(cm_LF); + WeldConstraintData cld_RF_LF(clm_RF_LF); + + forwardKinematics(model, data, q); + + cm_RF.calc(model, data, cd_RF); + const auto error_RF_ref = computeConstraintError(model, data, cm_RF); + BOOST_CHECK(cd_RF.c1Mc2.isApprox(error_RF_ref)); + BOOST_CHECK(cd_RF.constraint_position_error.isApprox(log6(error_RF_ref).toVector())); + + cm_LF.calc(model, data, cd_LF); + const auto error_LF_ref = computeConstraintError(model, data, cm_LF); + BOOST_CHECK(cd_LF.c1Mc2.isApprox(error_LF_ref)); + + clm_RF_LF.calc(model, data, cld_RF_LF); + const auto error_RF_LF_ref = computeConstraintError(model, data, clm_RF_LF); + BOOST_CHECK(cld_RF_LF.c1Mc2.isApprox(error_RF_LF_ref)); + } + + { + forwardKinematics(model, data, q, v, a); + + WeldConstraintData cd_RF(cm_RF); + cm_RF.calc(model, data, cd_RF); + WeldConstraintData cd_LF(cm_LF); + cm_LF.calc(model, data, cd_LF); + WeldConstraintData cld_RF_LF(clm_RF_LF); + clm_RF_LF.calc(model, data, cld_RF_LF); + + Data::Matrix6x J_RF_LOCAL(6, model.nv); + J_RF_LOCAL.setZero(); + getFrameJacobian(model, data, cm_RF.joint1_id, cm_RF.joint1_placement, LOCAL, J_RF_LOCAL); + + const Data::Matrix6x J_RF_LOCAL_constraint = -J_RF_LOCAL; + + Data::Matrix6x J_LF_LOCAL(6, model.nv); + J_LF_LOCAL.setZero(); + getFrameJacobian(model, data, cm_LF.joint1_id, cm_LF.joint1_placement, LOCAL, J_LF_LOCAL); + + const Data::Matrix6x J_LF_LOCAL_constraint = -J_LF_LOCAL; + + for (DenseIndex k = 0; k < model.nv; ++k) + { + BOOST_CHECK( + J_RF_LOCAL.middleRows<3>(SE3::LINEAR).col(k).isZero() != cm_RF.colwise_joint1_sparsity[k]); + BOOST_CHECK( + J_LF_LOCAL.middleRows<3>(SE3::LINEAR).col(k).isZero() != cm_LF.colwise_joint1_sparsity[k]); + } + BOOST_CHECK(cm_RF.colwise_joint2_sparsity.isZero()); + BOOST_CHECK(cm_LF.colwise_joint2_sparsity.isZero()); + + const SE3 oMc1 = data.oMi[clm_RF_LF.joint1_id] * clm_RF_LF.joint1_placement; + const SE3 oMc2 = data.oMi[clm_RF_LF.joint2_id] * clm_RF_LF.joint2_placement; + const SE3 c1Mc2 = oMc1.actInv(oMc2); + const Data::Matrix6x J_clm_LOCAL = c1Mc2.toActionMatrix() * J_LF_LOCAL - J_RF_LOCAL; + + for (DenseIndex k = 0; k < model.nv; ++k) + { + BOOST_CHECK(J_clm_LOCAL.col(k).isZero(0) != within(k, clm_RF_LF.colwise_span_indexes)); + } + + // Check Jacobian vs sparse Jacobian computation + Data::MatrixXs J_RF_constraint_sparse(6, model.nv); + J_RF_constraint_sparse.setZero(); + getConstraintJacobian(model, data, cm_RF, cd_RF, J_RF_constraint_sparse); + BOOST_CHECK(J_RF_LOCAL_constraint.isApprox(J_RF_constraint_sparse)); + + const auto J_RF_constraint_fd = compute_jacobian_fd(model, cm_RF, q, eps_fd); + BOOST_CHECK(J_RF_constraint_sparse.isApprox(J_RF_constraint_fd, sqrt(eps_fd))); + + Data::MatrixXs J_LF_constraint_sparse(6, model.nv); + J_LF_constraint_sparse.setZero(); + getConstraintJacobian(model, data, cm_LF, cd_LF, J_LF_constraint_sparse); + BOOST_CHECK(J_LF_LOCAL_constraint.isApprox(J_LF_constraint_sparse)); + + const auto J_LF_constraint_fd = compute_jacobian_fd(model, cm_LF, q, eps_fd); + BOOST_CHECK(J_LF_constraint_sparse.isApprox(J_LF_constraint_fd, sqrt(eps_fd))); + + Data::MatrixXs J_clm_constraint_sparse(6, model.nv); + J_clm_constraint_sparse.setZero(); + getConstraintJacobian(model, data, clm_RF_LF, cld_RF_LF, J_clm_constraint_sparse); + BOOST_CHECK(J_clm_LOCAL.isApprox(J_clm_constraint_sparse)); + + const auto J_clm_fd = compute_jacobian_fd(model, clm_RF_LF, q, eps_fd); + BOOST_CHECK(J_clm_constraint_sparse.isApprox(J_clm_fd, sqrt(eps_fd))); + + // Check velocity and acceleration + { + const double dt = eps_fd; + WeldConstraintData cd_RF(cm_RF), cd_RF_plus(cm_RF); + cm_RF.calc(model, data, cd_RF); + + Data data_plus(model); + const VectorXd v_plus = v + a * dt; + const VectorXd q_plus = integrate(model, q, v_plus * dt); + forwardKinematics(model, data_plus, q_plus, v_plus); + + { + WeldConstraintData cd_RF(cm_RF), cd_RF_plus(cm_RF); + cm_RF.calc(model, data, cd_RF); + BOOST_CHECK(cd_RF.constraint_velocity_error.isApprox(J_RF_constraint_sparse * v)); + + cm_RF.calc(model, data_plus, cd_RF_plus); + const Motion::Vector6 constraint_velocity_error_fd = + log6(cd_RF_plus.c1Mc2.act(cd_RF.c1Mc2.inverse())).toVector() / dt; + BOOST_CHECK( + cd_RF.constraint_velocity_error.isApprox(constraint_velocity_error_fd, sqrt(dt))); + + const Motion::Vector6 constraint_acceleration_error_fd = + (cd_RF_plus.constraint_velocity_error - cd_RF.constraint_velocity_error) / dt; + BOOST_CHECK( + cd_RF.constraint_acceleration_error.isApprox(constraint_acceleration_error_fd, sqrt(dt))); + } + + { + WeldConstraintData cd_LF(cm_LF), cd_LF_plus(cm_LF); + cm_LF.calc(model, data, cd_LF); + BOOST_CHECK(cd_LF.constraint_velocity_error.isApprox(J_LF_constraint_sparse * v)); + + cm_LF.calc(model, data_plus, cd_LF_plus); + const Motion::Vector6 constraint_velocity_error_fd = + log6(cd_LF_plus.c1Mc2.act(cd_LF.c1Mc2.inverse())).toVector() / dt; + BOOST_CHECK( + cd_LF.constraint_velocity_error.isApprox(constraint_velocity_error_fd, sqrt(dt))); + + const Motion::Vector6 constraint_acceleration_error_fd = + (cd_LF_plus.constraint_velocity_error - cd_LF.constraint_velocity_error) / dt; + BOOST_CHECK( + cd_LF.constraint_acceleration_error.isApprox(constraint_acceleration_error_fd, sqrt(dt))); + } + + { + WeldConstraintData cld_RF_LF(clm_RF_LF), cld_RF_LF_plus(clm_RF_LF); + clm_RF_LF.calc(model, data, cld_RF_LF); + BOOST_CHECK(cld_RF_LF.constraint_velocity_error.isApprox(J_clm_constraint_sparse * v)); + + clm_RF_LF.calc(model, data_plus, cld_RF_LF_plus); + const Motion::Vector6 constraint_velocity_error_fd = + log6(cld_RF_LF_plus.c1Mc2.act(cld_RF_LF.c1Mc2.inverse())).toVector() / dt; + BOOST_CHECK( + cld_RF_LF.constraint_velocity_error.isApprox(constraint_velocity_error_fd, sqrt(dt))); + + const Motion::Vector6 constraint_acceleration_error_fd = + (cld_RF_LF_plus.constraint_velocity_error - cld_RF_LF.constraint_velocity_error) / dt; + BOOST_CHECK(cld_RF_LF.constraint_acceleration_error.isApprox( + constraint_acceleration_error_fd, sqrt(dt))); + } + } + + check_A1_and_A2(model, data, cm_RF, cd_RF); + check_jacobians_operations(model, data, cm_RF, cd_RF); + + check_A1_and_A2(model, data, cm_LF, cd_LF); + check_jacobians_operations(model, data, cm_LF, cd_LF); + + check_A1_and_A2(model, data, clm_RF_LF, cld_RF_LF); + check_jacobians_operations(model, data, clm_RF_LF, cld_RF_LF); + + // Check acceleration contributions + { + Data data(model), data_zero_acc(model); + forwardKinematics(model, data, q, v, a); + computeJointJacobians(model, data, q); + forwardKinematics(model, data_zero_acc, q, v, VectorXd::Zero(model.nv)); + + // RF + WeldConstraintData cd_RF(cm_RF), cd_RF_zero_acc(cm_RF); + cm_RF.calc(model, data, cd_RF); + cm_RF.calc(model, data_zero_acc, cd_RF_zero_acc); + + Data::MatrixXs J_RF_sparse(6, model.nv); + J_RF_sparse.setZero(); + cm_RF.jacobian(model, data, cd_RF, J_RF_sparse); + + BOOST_CHECK((J_RF_sparse * a + cd_RF_zero_acc.constraint_acceleration_error) + .isApprox(cd_RF.constraint_acceleration_error)); + + // LF + WeldConstraintData cd_LF(cm_LF), cd_LF_zero_acc(cm_LF); + cm_LF.calc(model, data, cd_LF); + cm_LF.calc(model, data_zero_acc, cd_LF_zero_acc); + + Data::MatrixXs J_LF_sparse(6, model.nv); + J_LF_sparse.setZero(); + cm_LF.jacobian(model, data, cd_LF, J_LF_sparse); + + BOOST_CHECK((J_LF_sparse * a + cd_LF_zero_acc.constraint_acceleration_error) + .isApprox(cd_LF.constraint_acceleration_error)); + + // Close loop + WeldConstraintData cld_RF_LF(clm_RF_LF), cld_RF_LF_zero_acc(clm_RF_LF); + clm_RF_LF.calc(model, data, cld_RF_LF); + clm_RF_LF.calc(model, data_zero_acc, cld_RF_LF_zero_acc); + + Data::MatrixXs J_clm_sparse(6, model.nv); + J_clm_sparse.setZero(); + clm_RF_LF.jacobian(model, data, cld_RF_LF, J_clm_sparse); + + BOOST_CHECK((J_clm_sparse * a + cld_RF_LF_zero_acc.constraint_acceleration_error) + .isApprox(cld_RF_LF.constraint_acceleration_error)); + } + } +} + +BOOST_AUTO_TEST_CASE(cast) +{ + + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + + const std::string RF = "rleg6_joint"; + + const WeldConstraintModel cm_RF(model, model.getJointId(RF), SE3::Random()); + const auto cm_RF_cast_double = cm_RF.cast(); + BOOST_CHECK(cm_RF_cast_double == cm_RF); + + const auto cm_RF_cast_long_double = cm_RF.cast(); + BOOST_CHECK(cm_RF_cast_long_double.cast() == cm_RF); +} + +BOOST_AUTO_TEST_CASE(cholesky) +{ + + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + Data data(model), data_ref(model); + + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); + VectorXd q = randomConfiguration(model); + VectorXd v = VectorXd::Random(model.nv); + VectorXd a = VectorXd::Random(model.nv); + + crba(model, data, q, Convention::WORLD); + + const std::string RF = "rleg6_joint"; + const std::string LF = "lleg6_joint"; + + const WeldConstraintModel cm_RF(model, model.getJointId(RF), SE3::Random()); + const WeldConstraintModel cm_LF(model, model.getJointId(LF), SE3::Random()); + const WeldConstraintModel clm_RF_LF( + model, cm_RF.joint1_id, cm_RF.joint1_placement, cm_LF.joint1_id, cm_LF.joint1_placement); + + std::vector constraint_models; + constraint_models.push_back(cm_RF); + constraint_models.push_back(cm_LF); + constraint_models.push_back(clm_RF_LF); + + std::vector constraint_datas, constraint_datas_ref; + for (const auto & cm : constraint_models) + { + constraint_datas.push_back(cm.createData()); + constraint_datas_ref.push_back(cm.createData()); + } + + const double mu = 1e-10; + ContactCholeskyDecomposition cholesky(model, constraint_models); + cholesky.compute(model, data, constraint_models, constraint_datas, mu); + + crba(model, data_ref, q, Convention::WORLD); + make_symmetric(data_ref.M); + const auto total_size = getTotalConstraintSize(constraint_models); + Eigen::MatrixXd J_constraints(total_size, model.nv); + J_constraints.setZero(); + getConstraintsJacobian(model, data_ref, constraint_models, constraint_datas, J_constraints); + + Eigen::MatrixXd H_ref = Eigen::MatrixXd::Zero(total_size + model.nv, total_size + model.nv); + H_ref.topLeftCorner(total_size, total_size).diagonal().fill(-mu); + H_ref.bottomRightCorner(model.nv, model.nv) = data_ref.M; + H_ref.topRightCorner(total_size, model.nv) = J_constraints; + H_ref.bottomLeftCorner(model.nv, total_size) = J_constraints.transpose(); + + BOOST_CHECK(cholesky.matrix().isApprox(H_ref)); +} + +void check_maps_impl( + const Model & model, Data & data, const WeldConstraintModel & cm, WeldConstraintData & cd) +{ + const VectorXd q = randomConfiguration(model); + const VectorXd v = VectorXd::Random(model.nv); + crba(model, data, q, Convention::WORLD); + forwardKinematics(model, data, q, v); + + cm.calc(model, data, cd); + const auto constraint_jacobian = cm.jacobian(model, data, cd); + + // Test mapConstraintForceToJointForces : WorldFrameTag + { + std::vector joint_forces(size_t(model.njoints), Force::Zero()); + const Motion::Vector6 constraint_force = Motion::Vector6::Ones(); + const auto joint_torque_ref = constraint_jacobian.transpose() * constraint_force; + + cm.mapConstraintForceToJointForces( + model, data, cd, constraint_force, joint_forces, WorldFrameTag()); + + for (JointIndex joint_id = 1; joint_id < JointIndex(model.njoints); ++joint_id) + { + if (joint_id == cm.joint1_id || joint_id == cm.joint2_id) + { + BOOST_CHECK(!joint_forces[joint_id].isZero(0)); + } + else + { + BOOST_CHECK(joint_forces[joint_id].isZero(0)); + } + } + + // Backward pass over the joint forces + Eigen::VectorXd joint_torque = Eigen::VectorXd::Zero(model.nv); + for (JointIndex joint_id = JointIndex(model.njoints) - 1; joint_id > 0; --joint_id) + { + const JointModel & jmodel = model.joints[joint_id]; + const auto joint_nv = jmodel.nv(); + const auto joint_idx_v = jmodel.idx_v(); + + joint_torque.segment(joint_idx_v, joint_nv) = + data.J.middleCols(joint_idx_v, joint_nv).transpose() * joint_forces[joint_id].toVector(); + + const JointIndex parent_id = model.parents[joint_id]; + joint_forces[parent_id] += joint_forces[joint_id]; + } + + BOOST_CHECK(joint_torque.isApprox(joint_torque_ref)); + } + + // Test mapConstraintForceToJointForces : LocalFrameTag + { + std::vector joint_forces(size_t(model.njoints), Force::Zero()); + const Motion::Vector6 constraint_force = Motion::Vector6::Ones(); + const auto joint_torque_ref = constraint_jacobian.transpose() * constraint_force; + + cm.mapConstraintForceToJointForces( + model, data, cd, constraint_force, joint_forces, LocalFrameTag()); + + for (JointIndex joint_id = 1; joint_id < JointIndex(model.njoints); ++joint_id) + { + if (joint_id == cm.joint1_id || joint_id == cm.joint2_id) + { + BOOST_CHECK(!joint_forces[joint_id].isZero(0)); + } + else + { + BOOST_CHECK(joint_forces[joint_id].isZero(0)); + } + } + + // Backward pass over the joint forces + Eigen::VectorXd joint_torque = Eigen::VectorXd::Zero(model.nv); + for (JointIndex joint_id = JointIndex(model.njoints) - 1; joint_id > 0; --joint_id) + { + const JointModel & jmodel = model.joints[joint_id]; + const JointData & jdata = data.joints[joint_id]; + const auto joint_nv = jmodel.nv(); + const auto joint_idx_v = jmodel.idx_v(); + + joint_torque.segment(joint_idx_v, joint_nv) = + jdata.S().matrix().transpose() * joint_forces[joint_id].toVector(); + + const JointIndex parent_id = model.parents[joint_id]; + joint_forces[parent_id] += data.liMi[joint_id].act(joint_forces[joint_id]); + } + + BOOST_CHECK(joint_torque.isApprox(joint_torque_ref)); + } + + // Test mapJointMotionsToConstraintMotion : WorldFrameTag + { + const auto constraint_motion_ref = constraint_jacobian * v; + for (JointIndex joint_id = 1; joint_id < JointIndex(model.njoints); ++joint_id) + { + data.ov[joint_id] = data.oMi[joint_id].act(data.v[joint_id]); + } + + const auto & joint_accelerations = data.ov; + Motion::Vector6 constraint_motion = Motion::Vector6::Zero(); + cm.mapJointMotionsToConstraintMotion( + model, data, cd, joint_accelerations, constraint_motion, WorldFrameTag()); + + BOOST_CHECK(constraint_motion.isApprox(constraint_motion_ref)); + } + + // Test mapJointMotionsToConstraintMotion : LocalFrameTag + { + const auto constraint_motion_ref = constraint_jacobian * v; + + const auto & joint_motions = data.v; + Motion::Vector6 constraint_motion = Motion::Vector6::Zero(); + cm.mapJointMotionsToConstraintMotion( + model, data, cd, joint_motions, constraint_motion, LocalFrameTag()); + + BOOST_CHECK(constraint_motion.isApprox(constraint_motion_ref)); + } +} + +BOOST_AUTO_TEST_CASE(check_maps) +{ + pinocchio::Model model; + pinocchio::buildModels::humanoidRandom(model, true); + Data data(model), data_ref(model); + + model.lowerPositionLimit.head<3>().fill(-1.); + model.upperPositionLimit.head<3>().fill(1.); + + const std::string RF = "rleg6_joint"; + const std::string LF = "lleg6_joint"; + + const WeldConstraintModel cm_RF(model, model.getJointId(RF), SE3::Random()); + auto cd_RF = cm_RF.createData(); + + const WeldConstraintModel cm_LF(model, model.getJointId(LF), SE3::Random()); + auto cd_LF = cm_LF.createData(); + const WeldConstraintModel clm_RF_LF( + model, cm_RF.joint1_id, cm_RF.joint1_placement, cm_LF.joint1_id, cm_LF.joint1_placement); + auto cld_RF_LF = clm_RF_LF.createData(); + + check_maps_impl(model, data, cm_RF, cd_RF); + check_maps_impl(model, data, cm_LF, cd_LF); + check_maps_impl(model, data, clm_RF_LF, cld_RF_LF); +} + +BOOST_AUTO_TEST_SUITE_END()