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.84k stars 386 forks source link

Using external force applied not at joint location for rnea inverse dynamics #1544

Closed manumerous closed 2 years ago

manumerous commented 2 years ago

I am trying to use pinocchios rnea to compute the needed feed forward torques for a bipedal robot.

If I understood the documentation correctly the fext should be the custom aligned_vector type with an entry for each joint, where the entry is a 3D vector expressing the external force in the joint frame.

However, I would like to apply the contact forces of my bipedal robot at the point of contact. In my urdf my feet are described as a fixed joint between the shin body and a small sphere. But if I check model_.njoints I have only 5 joints, which I assume to correspond to base + 4 joints.

How would I best compute the inverse dynamics for that problem? Any tips would be much appreciated! Best, Manuel

amber_frames

jcarpent commented 2 years ago

You just need to account for the transform between the contact point and the center of the joint supporting the body in contact. f_local = iMc.act(f_contact)

manumerous commented 2 years ago

Thanks for your response. I will give that a try.

manumerous commented 2 years ago

After implementing the wrenches of the impact forces on the knee joints I observed that the algorithm produced torques for the unactuated base coordinates (x, z and theta in the case of the planar 5-link) which is not physical. This reminded me that the rnea algorithm is only defined for fully actuated systems, which i guess i should have known in hindsight.

I could solve this now by using the following formula: image

If I am correct there is no function implemented in pinocchio yet for a general inverse dynamics computation right?

To prevent others from running into the same mistake it could be helpful to add such a function something along the lines of:

inverseDynamics(model, data, q, v, a ,fext, std::vector<bool> actuated = {True, ...True })

In that case the user could specify if any joints are not actuated (Which is the default state of the base coordinated for legged robotics) and the function could have the following logic:

If you think this proposal would be a meaningful addition to the pinocchio framework I would be motivated to contribute and make a PR on the devel branch.

jcarpent commented 2 years ago

Your first comment was not clear enough to understand your setup. This is not directly available in Pinocchio but rather in TSID which is rooted on Pinocchio. We will add this feature to Pinocchio next year.