mj_inverse

Discussion in 'Simulation' started by jernejc, Mar 25, 2018.

  1. Hi,

    I want to use the mj_inverse to calculate the joint torques based on the experimental kinematics data I have. As I understand I need to set qpos, qvel and qacc and then run mj_inverse. I also have ground reaction forces and one other external force. Should I load these forces to d->xfrc_applied? And what is the correct procedure?
    These are my steps:
    for (int j = 0; j < kinSize; j++)
    {
    1. fill in the qpos, qvel and qacc
    2. fill in the xfrc_applied
    3. run the my_inverse
    4. save the result
    }​
    The way I do it now is as shown in the steps above. I load the kinematics data and then in a loop for each time step fill in the qpos, qvel, qacc and xfrc_applied and then run the mj_inverse. Based on the visualisation during the my_inverse, everything looks good - the model executes the motion correctly.
    I save the result and then use it as an input for qfrc_applied, to check whether the model performs the same kinematics (I do this step in Matlab and Haptix). However, the joint trajectories that come from this simulation do not match the one I used as input for inverse dynamics. What am I doing wrong?
    Thanks!

    Jernej
     
  2. Can anyone help me with this, please?

    Thank you!
    Jernej
     
  3. Anyone has an answer to this?
     
  4. Emo Todorov

    Emo Todorov Administrator Staff Member

    mj_inverse takes (qpos, qvel, qacc) as inputs and produces qfrc_inverse as output. At this point the animation looks right simply because you are replaying your own data.

    Now, if you switch to forward dynamics and set qfrc_applied = qfrc_inverse (as computed by inverse dynamics) AND also set xfrc_applied = ctrl = 0, the forward should match the inverse. In other words, qfrc_inverse is the net applied force acting on the system, i.e. the of qfrc_applied, control forces, and J'*xfrc_applied. There is no way for the inverse solver to guess the values of the individual terms, it can only compute their sum.

    Note that contact forces are taken into account in mj_inverse, and are not present in qfrc_inverse. If you want to treat the measured contact forces as being external forces (i.e. you want them to be included in qfrc_inverse), you should disable contacts in the model before running mj_inverse.

    Coming from a biomechanics background you may find this confusing. MuJoCo performs a much more powerful computation than what you are used to: it computes both the contact forces and the applied forces given the kinematics. The applied forces are written in qfrc_applied, while the (inferred) contact forces are written in efc_force (check the documentation on how to decode that data). So you can actually compare your ground reaction force measurements to the force output of mj_inverse; if there is a mismatch, it means that either the model is wrong or the kinematic data are not perfect.
     
  5. Thank you a lot! This explains most of the issuses I have.
    One more question though. I now disabled the contact forces in the model before running the mj_inverse. Now, how do I set the xfrc_applied with my measured data from force plates? The way I do it now is I that in each step of the simulation I set the ground reaction forces to the models feet, run the mj_forward, then set the qpos, qvel and qacc and then run mj_inverse. If I don't run the mj_forward after seting the xfrc_applied it appears as they were not included in the inverse dynamics calculation - resulting in a much too low calculated forces.
    Thank you for your answer!