Best way to represent robots torque sensors

Discussion in 'Priority support' started by Alireza Ranjbar, May 25, 2020.

  1. What is the best way in mujoco to obtain joint torque readings similar to what we obtain from a real robot's sensor.

    It seemed to me that the mjData.qfrc_applied can be one source to read such sensor readings, but its values for me has been always zero and seemed more like a placeholder for giving input torques to the simulator rather than getting output.

    Another way which seemed to me based on the documentation of Mujoco was reading mjData.qfrc_actuator, where if we have used motors would be equal to mjData.ctrl.

    One more way also seemed defining a torque sensor for each joint and calculating the torque magnitude obtained from each, but this seemed a bit messy.

    In addition, mjData.qfrc_inverse also seemed another alternative but was not sure if in case of collision or contact it may be a good choice.

    So I was wondering given the torque sensors that are usually available in robot arms, what might be the best way to represent their outputs in Mujoco, e.g., a robot arm such as Franka Emika which possibly has strain gauges or current measurements for its torque sensors.
     
    Last edited: May 25, 2020
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    The best way to do it is to look at mjData. All the forces acting on the joints are there. In particular, mjData.qfrc_unc is the sum of all forces outside constraints (passive, actuation, gravity, applied etc), while mjData.qfrc_constraint is the sum of all constraint forces. If you add up these two quantities you get the total force acting on each joint -- which is what a torque sensor should measure.

    qfrc_inverse is used in inverse dynamics.
     
    Alireza Ranjbar likes this.