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

Generalized velocity of the floating base #2177

Closed thuuzi closed 4 months ago

thuuzi commented 4 months ago

Hi,

After reviewing the discussion in https://github.com/stack-of-tasks/pinocchio/issues/1137, I understand that the velocity of the floating base is typically represented in the LOCAL frame. However, when I replaced a free flyer joint with a combination of JointModelTranslation() and JointModelSphericalZYX(), it appeared that the velocity is instead expressed in the WORLD frame.

To clarify my confusion, I have outputted the Jacobian Matrix in the LOCAL_WORLD_ALIGNED frame, where the section corresponding to the floating base velocity consistently turns out to be a 3x3 identity matrix.Could you please confirm it?

Thank you in advance for your clarification.

jcarpent commented 4 months ago

Could you provide a short Python example to understand what you did exactly?

thuuzi commented 4 months ago

Could you provide a short Python example to understand what you did exactly?

Yes.Here's a pseudocode snippet in C++ to illustrate the issue. First, I construct a floating base model as follows:

pinocchio::JointModelComposite rootJoint(2); rootJoint.addJoint(pinocchio::JointModelTranslation()); rootJoint.addJoint(pinocchio::JointModelSphericalZYX()); pinocchio::urdf::buildModel(my_model_urdf_path, rootJoint, my_model);

then I get the Jacobian Jac

pinocchio::getFrameJacobian(my_model, data, ee_link_number, pinocchio::LOCAL_WORLD_ALIGNED, Jac); Eigen::Matrix3d Jac_v = Jac.topLeftCorner<3, 3>();

I find Jac_v was always an identity matrix. It's corresponding to linear velocity part of the floating base. If the velocity is represented in the LOCAL frame, Jac_v should vary with the floating base pose but it' didn't. So I think the floating base velocity is instead represented in the WORLD frame.

jcarpent commented 4 months ago

Could you give us the value of the configuration vector associated with the FF?

thuuzi commented 4 months ago

Could you give us the value of the configuration vector associated with the FF?

Actually I have tried many configurations randomly, results are the same. And other parts of the jacobian are correct. I just want to know whether the generalized velocity of the floating base is represented in WORLD frame when the root joints are JointModelTranslation() and JointModelSphericalZYX(). Could you clarify this for me?

fabinsch commented 4 months ago

hi @thuuzi, after several discussions we have recently merged a python script in #2143 that could help you. You can easily extend it to have a combination of JointModelTranslation and JointModelSphericalZYX as root joint and visualize it.

thuuzi commented 4 months ago

really appreciate it

thuuzi commented 4 months ago

After test, the floating base velocity is represented in the WORLD frame with JointModelTranslationand JointModelSphericalZYX as root joint