qfrc_inverse

Discussion in 'Simulation' started by Junhyeok, Jul 9, 2017.

  1. Hi all,
    I have a question on qfrc_inverse term!
    I read the documentation about it saying, qfrc_inverse = qfrc_applied + J'*xfrc_applied + qfrc_actuator.
    According to Multi body dynamics, which is
    M*qddot + b + g + J'*Fr = B*u ( M : inertia matrix, b, g : coriolis and gravity, J' : jacobian at contact, Fr : reaction force, B : selection matrix ),
    I assume qfrc_applied + qfrc_actuator corresponds to B*u, and J'*xfrc_applied corrensponds to J'*Fr.
    Is that correct?
    If so, qfrc_inverse is equivalent to M*qddot + b + g ?
    I am not so sure about qfrc_actuator term.

    I would appreciate if anyone give me some help!
    :)
     
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    The equation of motion in your notation is

    M*qddot + b + g = qfrc_inverse + J'*Fr,

    where

    qfrc_inverse = qfrc_applied + J'*xfrc_applied + qfrc_actuator

    is the sum of all applied forces -- namely forces applied directly on the joints (qfrc_applied), or on the bodies (xfrc_applied), or via the actuators (qfrc_actuator). The term Jx'*xfrc_applied is the joint force resulting from Cartesian force xfrc_applied applied to the bodies; Jx is the end-effector / body Jacobian, not the constraint Jacobian (the latter is J).

    As for actuation, we have

    qfrc_actuator = B*u

    in simple cases, but MuJoCo can also model more elaborate actuators.

    See the Computation chapter in the documentation for details.
     
  3. Hi Emo,
    I guess there is a typo in your equation.

    J'*xfrc_applied should be Jx'*xfrc_applied, I assume.
    Other than that, this post really helped a lot.

    Just to be on the safe side concerning my understanding of the above qfrc_inverse.
    qfrc_applied and J'*xfrc_applied are user defined external forces or forces from spring damper mechanisms.

    Assuming i wanted to do inverse dynamics control, where qfrc_applied = 0_vec and J'*xfrc_applied = 0_vec, I would use the result of mj_inverse and set the resulting torques as actuator input in the control callback? Calling mj_inverse won't already alter my system state in any way?

    Kind regards,

    Florian
     
  4. Emo Todorov

    Emo Todorov Administrator Staff Member

    Yes, qfrc_applied and Jx'*xfrc_applied are user-defined external forces. Users can compute them however they wish, including user-side spring-damper mechanisms. However for spring-dampers defined in the model, the corresponding forces are automatically computed in qfrc_passive.

    mj_inverse does not alter the system state. Its input is (qpos, qvel, act, qacc) and the output is qfrc_inverse. If you set qfrc_applied = qfrc_inverse and run mj_forward, the resulting acceleration will be the same qacc as provided to mj_inverse.

    Note however that qfrc_applied/inverse is not the same as actuator controls. In particular, the inverse dynamics can generate forces at un-actuated joints. So in the case of under-actuated systems, computing feasible controls that approximate the desired acceleration is up to you. Incidentally, I developed an optimization method called Goal Directed Dynamics that does that (see my UW website). It will be included in a new product called Optico which I am currently developing.