Inverse dynamics through mujoco-py

Discussion in 'Simulation' started by austinspwang, Nov 7, 2017.

  1. Hello,

    I'm trying to code up a low-level force/position controller for the Sawyer using mujoco-py.
    However, though I have access to mjData.qacc, mjData.qvel, and mjData.qpos, I cannot find a way to call mj_inverse through the API and mjData.qfrc_inverse always returns a zero vector.

    Is there a way to access inverse dynamics through mujoco-py, or perhaps there is an easier way to get that information from mujoco directly?

    Also, the values in qfrc_actuator does not match, what might be a possible reason for that?

    Thanks!
     
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    If you use the native C API you can call mj_inverse, and it will populate the vector mjData.qfrc_inverse. Note that these are joint torques. The actuation model is not inverted, i.e. mj_inverse does not compute mjData.qfrc_actuator.

    As for mujoco-py, I am not sure if it exposes the inverse dynamics function, but it is open-source so you should be able to add that call yourself.
     
  3. Thank you very much for the quick response!

    Just to make sure, qfrc_inverse is the net force(including external forces, inertia forces, and actuation forces) required to excite the designated qacc, qvel, and qpos, expressed in the joint coordinates, right?
    If that's the case, how can I obtain the correct values of qfrc_actuator?
     
  4. Emo Todorov

    Emo Todorov Administrator Staff Member

    qfrc_inverse is the sum of applied and actuation forces needed to explain the specified acceleration (it does not include the inertial forces). How to get qfrc_actuator depends on the set of actuators you have. This is an open-ended problem, which is why MuJoCo does not attempt to handle it automatically. If all DOFs are actuated, then the two are equal. But if you have under-actuation, then it may not be possible to find valid actuation forces that account for qfrc_inverse. In that case you want to compute some projection, usually by solving an optimization problem.
     
  5. Thank you very much for your help so far, the information was very helpful!

    Also good news, I found a way to access MuJoCo internal functions through mujoco-py.
    There is a submodule called 'functions' inside the mujoco-py API.

    However, I have a fully actuated system, but I am achieving very different results when I directly set qfrc_applied = qfrc_inverse compared to setting ctrl = qfrc_inverse
    Also, qfrc_passive is a zero vector even though I have damping on my joints.
    What might be causing these inconsistencies?

    Thanks again!
     
  6. Emo Todorov

    Emo Todorov Administrator Staff Member

    ctrl is a vector of control signals that are sent to the actuators. Do you have actuators in your model, and if so, are they motor that generate torques? If so, you can set ctrl=0 and qfrc_applied=X, or ctrl=X and qfrc_applied=0, and the result should be the same for all X (including qfrc_inverse). If actuators are not defined or are not simple motors, then there is no reason to expect the results to be different.

    Not sure why you are seeing qfrc_passive=0, it is definitely being computed in inverse dynamics... maybe address the above issue first, and then take another look?
     
  7. I tried both setting ctrl=0 and qfrc_applied=X, and ctrl=X and qfrc_applied=0. The results not similar at all, even though all my actuators are defined as motors on rotational joints.
    My model isn't exactly fully-actuated because I have free manipulable objects, but I have a fully-actuated arm and the inverse dynamics are acquired by syncing simulation states with an identical mujoco model with only the arm in parallel.

    However, directly setting qfrc_applied=X solves my control problem, and also I'm not sure starting from when, but the I'm getting reasonable values in qfrc_passive now.
    So I think I will leave this issue as it is for now.

    Thanks for all the help!
     
  8. Emo Todorov

    Emo Todorov Administrator Staff Member

    If you have gear ratios different from 1, or control/force limits on your actuators, the results will be different. They will also be different if you have under-actuation. Anyway, good to hear you have a working solution.