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!