How to get Coriolis and Centrifugal forces matrix from KDL
Hello everyone, this may seem a trivial question but I really don't know how to solve it. Is there any way to get the complete Coriolis and Centrifugal forces matrix C(q, q_dot)
by using the KDL library? Checking for the library documentation i found this function KDL::ChainDynParam::JntToCoriolis (const JntArray &q, const JntArray &q_dot, JntArray &coriolis)
. For what I understood it is just able to compute the third term coriolis
that, being a JntArray
, I think it should be something like C(q, q_dot)*q_dot
. Is there any way to get the full C(q, q_dot)
matrix, instead, as it happens withKDL::ChainDynParam::JntToMass
for the inertia matrix?
Asked by iopoi97 on 2023-04-19 08:08:22 UTC
Answers
Getting a C(q, q_dot) matrix numerically is possible but I guess it's not actually unique.
This paper talks about one method to get a Coriolis/Centrifugal matrix that is suitable for both the arm dynamics and satisfying the extra skew-symmetry of Mdot-2C that I think the typical symbolic algorithms in textbooks give you:
https://arxiv.org/abs/2010.01033 https://asmedigitalcollection.asme.org/computationalnonlinear/article/16/9/091004/1109302/Numerical-Methods-to-Compute-the-Coriolis-Matrix
If you look at the footnotes 1 and 2 in the ArXiV version it seems like the Pinocchio rigid body dynamics library actually implements this paper now. That might be an option instead of KDL or you could see if it's helpful for the C++ implementation in terms of other KDL calculations.
https://github.com/stack-of-tasks/pinocchio
It looks like it's released for Galactic.
Asked by danzimmerman on 2023-04-23 12:09:01 UTC
Comments