ami-iit / jaxsim

A differentiable physics engine and multibody dynamics library for control and robot learning.
https://jaxsim.readthedocs.io/
BSD 3-Clause "New" or "Revised" License
69 stars 10 forks source link

Add algorithm to compute the free-floating Coriolis matrix #172

Closed diegoferigo closed 3 months ago

diegoferigo commented 3 months ago

This PR introduces a new function to compute the free-floating Coriolis matrix $C(\mathbf{q}, \boldsymbol{\nu}) \in \mathbb{R}^{(6+n)\times(6+n)}$:

image

image

Note that this PR does not compute $C$ using iterative algorithms, therefore its computation can be pretty slow, especially for models with many degrees of freedom. In particular, converting the body-fixed Coriolis matrix to either inertial-fixed or mixed requires the computation of the mass matrix $M$, that means also a call of CRBA.

Nonetheless, it can be useful having at least one implementation, even if not fast. It can be useful to prototype controllers that need the standalone $C$ and, if anyone in the future is willing to propose an iterative algorithm, it can be used as ground thruth.

cc @ami-iit/vertical_control-oriented-learning

[^1]: Silvio Traversaro, Eq. (3.58b) pag. 54, Modelling, Estimation, and Identification of Humanoid Robots Dynamics, Ph.D. thesis, URL. [^2]: Silvio Traversaro, Eq. (3.60b) pag. 56, Modelling, Estimation, and Identification of Humanoid Robots Dynamics, Ph.D. thesis, URL.


📚 Documentation preview 📚: https://jaxsim--172.org.readthedocs.build//172/

diegoferigo commented 3 months ago

Here below a quick benchmark performed in body-fixed on my laptop with JAX running on CPU:

DoFs JIT compilation Runtime
5 3.45 s 111 µs ± 9.68 µs
10 3.65 s 419 µs ± 130 µs
20 3.71 s 577 µs ± 280 µs
40 4.20 s 1.35 ms ± 225 µs

Note that in other velocity representations, there's the extra overhead of computing $M$.