Doubt regarding derivative.cpp

Discussion in 'Simulation' started by Michael J Mathew, May 31, 2016.

  1. The first Jacobian from derivative.cpp for a 2 link pendulum with just one motor at the second joint is given by
    17.35727428 4.33931857 4.33931857 4.33931857 , (I believe this is w.r.t to data->qfrc_applied) this is when the pendulum is hanging down. I get the same result when the pendulum is swung up. My doubts are the following.
    From the documentation; data->qfrc_applied is: "directly applied forces and torques specified in joint space"

    1) Does this mean that this Jacobian involves values of all forces that are experienced by the pendulum other than joint torques (like gravity and all)? Because according to my xml file, there should be only one column in the Jacobian, right? Even the second column, [ 4.33931857 4.33931857 ]' should be different right? My both links are unequal and hence at least values as well as sign should be different.

    Am I interpreting it in a wrong way?
     
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    The Jacobians are computed with respect to torques, not controls. So you will get the same (square) matrices regardless of the actuators defined in the model. To compute derivatives with respect to actuators, you should modify the code to finite-difference in control space instead of joint torque space.

    For a coupled system like this, applying a torque to one joint causes acceleration at both joints.

    Can you tell me which Jacobian exactly are we talking about? There are 6 of them, represented in the following order in mjtNum* deriv:

    dinv/dpos (inverse dynamics derivative: d qfrc_inverse / d qpos)
    dinv/dvel
    dinv/dacc
    dacc/dpos (forward dynamics derivative: d qacc / d qpos)
    dacc/dvel
    dacc/dfrc
     
  3. Thanks for the reply. According to this write up, the order of the mjtNum* derv seems different. First forward dynamics and next inverse dynamics is mentioned.
    forward dynamics: qacc(qfrc_applied, qvel, qpos)
    inverse dynamics: qfrc_inverse(qacc, qvel, qpos)
    The complete Jacobian is:

    [17.35727414 4.33932003 4.33931843 4.33932205
    0.00000089 0.00000041 0.00000047 0.00000000
    0.95780540 0.30196820 0.30196820 0.12503371
    -30.09495448 26.87052331 37.97696496 -99.60006411
    0.00000113 -0.00000181 -0.00000652 0.00000438
    4.37591334 -10.56824329 -10.56824329 33.52114698 ]

    So I thought the six Jacobians are in that order. If so, the above jacobian mentioned is the first 4 elements of the mjtNum*derv which I suppose is dacc/dfrc.
    Which is the right order of Jacobian?
    Yes applying torque on one joint indeed put acceleration in both joints, since there is only one actuator at joint 2, a positive torque on that would result in a negative torque at the base joint right? Which means one value should be of negative sign and the magnitude of those elements should be also different. Could you please tell me the right order of matrices?
     
  4. Emo Todorov

    Emo Todorov Administrator Staff Member

    The order is the one listed in the message above. The documentation you are referring to explains the concept of forward and inverse dynamics derivatives in general. If you look at the function checkderiv(), it defines pointers to the 6 matrices as:

    // get pointers to derivative matrices
    mjtNum* G0 = deriv; // dinv/dpos
    mjtNum* G1 = deriv + nv*nv; // dinv/dvel
    mjtNum* G2 = deriv + 2*nv*nv; // dinv/dacc
    mjtNum* F0 = deriv + 3*nv*nv; // dacc/dpos
    mjtNum* F1 = deriv + 4*nv*nv; // dacc/dvel
    mjtNum* F2 = deriv + 5*nv*nv; // dacc/dfrc

    G stands for inverse dynamics, F for forward dynamics. 0 is derivative w.r.t position, 1 - velocity, 2 - force or acceleration.