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

Rnea inverse dynamics solution display error (did not match C++ signature:) #1573

Closed tianbaoloin closed 2 years ago

tianbaoloin commented 2 years ago

I write an example of solving inverse kinematics by Python, The command can be executed when there is no external force. However, when there is an external force, the command prompts an error. Some codes are as follows: pos_inf = tuple(All_joint_pos_inf[:3]) + tuple(All_joint_pos_inf2[3:]) vel_inf = tuple(All_joint_vel[:3]) + tuple(All_joint_vel2[3:]) acc_inf = tuple(All_joint_acc[:3]) + tuple(All_joint_acc2[3:]) foot_force = Virtual_spring_k * pos_robot_change external_forces = np.array([0, 0, foot_force[2], 0, 0, foot_force[2]]) tau = pin.rnea(model1, data1, np.array(pos_inf), np.array(vel_inf), np.array(acc_inf), external_forces)

The error message is as follows: Traceback (most recent call last): File "G:/controlenv/control/test000.py", line 218, in tau = pin.rnea(model1, data1, np.array(pos_inf), np.array(vel_inf), np.array(acc_inf), external_forces) Boost.Python.ArgumentError: Python argument types in pinocchio.pinocchio_pywrap.rnea(Model, Data, numpy.ndarray, numpy.ndarray, numpy.ndarray, numpy.ndarray) did not match C++ signature: rnea(struct pinocchio::ModelTpl<double,0,struct pinocchio::JointCollectionDefaultTpl> model, struct pinocchio::DataTpl<double,0,struct pinocchio::JointCollectionDefaultTpl> {lvalue} data, class Eigen::MatrixBase<class Eigen::Matrix<double,-1,1,0,-1,1> > q, class Eigen::MatrixBase<class Eigen::Matrix<double,-1,1,0,-1,1> > v, class Eigen::MatrixBase<class Eigen::Matrix<double,-1,1,0,-1,1> > a, struct pinocchio::container::aligned_vector<class pinocchio::ForceTpl<double,0> > fext) rnea(struct pinocchio::ModelTpl<double,0,struct pinocchio::JointCollectionDefaultTpl> model, struct pinocchio::DataTpl<double,0,struct pinocchio::JointCollectionDefaultTpl> {lvalue} data, class Eigen::MatrixBase<class Eigen::Matrix<double,-1,1,0,-1,1> > q, class Eigen::MatrixBase<class Eigen::Matrix<double,-1,1,0,-1,1> > v, class Eigen::MatrixBase<class Eigen::Matrix<double,-1,1,0,-1,1> > a) What type of data should I set in python program to execute this code?

jcarpent commented 2 years ago

external_forces Should be a list of Force elements expressed in the local frame of each joint. The list size should be equal to the total number of joints contained in the Model

tianbaoloin commented 2 years ago

external_forces Should be a list of Force elements expressed in the local frame of each joint. The list size should be equal to the total number of joints contained in the Model The model has six joints and a floating base. Should the external_forces applied be [forcex, forcey, forcez] multiplied by 6 ?

jcarpent commented 2 years ago

Spatial forces. pin.Force() and the number of joints is given by model.njoints.

tianbaoloin commented 2 years ago

There are too few application examples about RNEA(add external force). Can you give me a simple example? For example, a two-degree-of-freedom floating robotic arm. For a floating robotic arm with two freedoms, model.njoints should be 4. How should the external force applied in the Rnea function be written ? I tried several times just now, the above error continues to appear.

jcarpent commented 2 years ago

This test file should help you: https://github.com/stack-of-tasks/pinocchio/blob/593d4d43fded997bb9aa2421f4e55294dbd233c4/unittest/python/bindings_inverse_dynamics_derivatives.py

tianbaoloin commented 2 years ago

This test file should help you: https://github.com/stack-of-tasks/pinocchio/blob/593d4d43fded997bb9aa2421f4e55294dbd233c4/unittest/python/bindings_inverse_dynamics_derivatives.py The problem has been solved, thank you very much