Using mj_applyFT

Discussion in 'Simulation' started by Michael J Mathew, Sep 25, 2016.

  1. Hi,

    I have an object lying on a table. I would like to apply random forces at certain known locations on the object so as to move it. This is what I tried:

    void mj_applyFT(const mjModel* m, mjData* d,
    const mjtNum* force, const mjtNum* torque,
    const mjtNum* point, int body, mjtNum* qfrc_target);
    where force is a 3x1 vector, torque is another 3x1 vector, point is a point on the box, body is the index of box, qfrc_target is a buffer of 6x1.

    After calling the function, I call the mj_step() function.

    But the box doesn't move. I don't know why. I increased the force to arbitrarily high values still no change. Could you please suggest something on how to do it? (I saw a few works from your lab applying forces on simulations to exhibit robustness).

    Best,

    Mike
     
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    You should pass d->qfrc_applied as the last argument. "qfrc_target" means the joint force vector which is the target (i.e. the output) of the computation. Or you could use your own buffer, add different forces into it, and the copy it into d->qfrc_applied. Note that the size of this buffer should be m->nv, not 6.

    Also, MuJoCo will not change the values of d->qfrc_applied. So if you call mj_applyFT once and keep calling mj_step afterwards, the forces will be applied forever. You need to clear d->qfrc_applied in order to remove them.
     
  3. If I am copying the values directly to q_frc applied, that would mean, I will have to compute the torque and force felt by the object at its center of mass and copy it to d->qfrc_applied.
    Hence I thought of going via mj_applyFT.

    But I tried both ways, but still the qfrc_applied remains zero before and after copying. I tried called mj_forward() after the copy, still, nothing happened. But no errors are thrown up.
     
  4. I solved the issue. :)
    I copied what was computed by mj_applyFT to qfrc_applied.
    But it would have been nice if mj_applyFT directly copied to the indexes corresponding to the object in qfrc_applied.
     
  5. Emo Todorov

    Emo Todorov Administrator Staff Member

    That would be more convenient when it does what you want, but one could use this function in more flexible ways, to transform forces from Cartesian to joint space without applying them to the simulation.
     
  6. Yeah,.. you are right... I didn't think about that. :)