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 @@
-
+
-
-
+
+
-
+
-
+
@@ -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 |
 |
| CI on Linux via Robotpkg |
-  |
+  |
@@ -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.
-
+
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