stack-of-tasks / pinocchio

A fast and flexible implementation of Rigid Body Dynamics algorithms and their analytical derivatives
http://stack-of-tasks.github.io/pinocchio/
BSD 2-Clause "Simplified" License
1.83k stars 383 forks source link

Derivatives of mass matrix times acceleration w.r.t. the configuration #1403

Closed avoelz closed 3 years ago

avoelz commented 3 years ago

Dear pinocchio developers,

first of all, thanks a lot for developing this library and providing it as open source to the robotics community. Both the performance and the ease of use are really impressive. For my application I need to compute the partial derivatives of M(q)a with respect to the configuration q. I could not find an algorithm in pinocchio that directly computes this expression. One option would be to call the derivatives of RNEA two times, i.e. d M(q)a / dq = d RNEA(q, v, a) / dq - d RNEA(q, v, 0) / dq.

However, I thought there might be a more efficient solution, e.g. using the analytical derivatives of CRBA. I already implemented a new version of CodeGenCRBA that computes the desired quantity using evalJacobian. It seems to be 10 to 20 percent faster than one call to CodeGenRNEADerivatives for a 7-dof KUKA arm. Maybe you could give me some hint on which is the preferred approach to compute d M(q)*a / dq with pinocchio (in C++, not Python)?

jcarpent commented 3 years ago

Thanks for your comments and clear explanations.

One way to retrieve your quantity would be to:

  1. set the gravity to zero to eliminate the gravity term in the Lagrangian dynamics (model.gravity.setZero())
  2. set the joint velocity vector to zero
  3. code generate the rnea derivatives by only extracting the dtau/dq quantity.

Normally, the code generation should drop out the unnecessary computations related to dtau/dv and dtau/da. Your current computations are much higher because you are extracting more quantities than needed.

For some small mechanical systems, evalJacobian can be very fast. But for more complex robots like quadrupeds or humanoids, this is no more the case.

avoelz commented 3 years ago

Dear Justin,

thanks for the fast reply. Less than 15 minutes after posting this question I realized I had a thinking error and computing the RNEA derivatives is exactly what I need for my application. Nonetheless, I like your solution with gravity zero, velocity zero and then performing code generation. From a user point of view, this is definitely simpler than modifying the code of computeRNEADerivatives by hand.

Concerning evalJacobian, my benchmark for the KUKA arm showed that CodeGenABADerivatives and CodeGenRNEADerivatives are both faster than calling evalJacobian for CodeGenABA and CodeGenRNEA, so the analytical derivatives are more performant than the automatic differentiation approach. However, CodeGenRNEA with evalJacobian was faster than computeRNEADerivatives without code generation. Therefore, if minimal computation times are required, using code generation seems to me to be the best approach.

jcarpent commented 3 years ago

Thanks for your nice user feedback.

However, CodeGenRNEA with evalJacobian was faster than computeRNEADerivatives without code generation.

Indeed, for small robots, this seems to be the case. I observed the same behaviour a while ago. Unfortunately, this does not scale for larger robots. One fundamental aspect is that I've tried to best exploit vectorization inside computeRNEADerivatives, that code generation does not support yet.

Best, Justin