6-axis force-torque sensor

Discussion in 'Priority support' started by Isaac, Jul 23, 2019.

  1. Hi,
    I put one force and one torque sensor in the wrist of my robot and when I read the data and multiply it by transformation matrix to transform it into world frame, I get following signal values. I have a bias of about 12 in z-direction: (the change in signal is because of touching the desk) I want to do force control.

    [​IMG]


    The data before multiplying transformation matrix is almost similar too. Is it ok or it has to be zero?
    Thre code in XML is as follows:

    in body tag:
    site name="lumi_torque7" pos="0 0 0.107" quat="0.92388 0 0 -0.382683"

    in sensor tag:
    torque name="lumi_joint7_torque" site="lumi_torque7"
    force name="lumi_joint7_force" site="lumi_torque7"

    and I read data using sensordata:

    int torque_sensor_id = 7;
    int adr = m->sensor_adr[torque_sensor_id];
    int dim = m->sensor_dim[torque_sensor_id];
    mjtNum torque_data_temp[dim];
    mju_copy(torque_data_temp, &d->sensordata[adr], dim);

    and same for force data.

    And I have another question. How can I read force-torque values without sensor and from mujoco calculations? Is it possible?
     
    Last edited: Jul 23, 2019
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    If you have a force sensor mounted between a fixed body and a moving body, the sensor will measure the weight of the moving body (the hand of your robot in this case). During free motion it essentially acts as a scale. A real force sensor will do the same. You could subtract that value if you want and effectively zero the sensor, but keep in mind that if the arm rotates before contact, the direction of gravity will change relative to the sensor frame and the output will no longer be zero.

    You cannot just read force-torque values because this requires additional calculations, and these calculations are executed internally only if force-torque sensors are defined in the model.

    Maybe you want to know what the sensor output would be without the contact force? You can do this by disabling contacts and running mj_forward in the same state. Then you can enable contacts again and run the "official" mj_forward or mj_step. This should be done in each time step.
     
  3. Thank you for your quick response.

    My sensor is between two arm links in a joint before the end effector. You mean it measures the weight of the links after it?
    When I rotate the arm, all signal values change:

    upload_2019-7-23_16-58-48.png

    I don't know how to do it in mujoco? Do I need to use the inertia matrix? I want to measure force/torque data and compare it with a referenced value and then use a PI controller to keep a constant force value when the end effector is in contact with the object and then slide on the object or push it or ...

    I didn't get your final question. what do you mean by disabling contact and official mj_forward?
     
  4. The franka panda robot has 7 torque sensors in its 7 joints and their output is 7 scalar values (not 3 values). The force control code that they released uses these values and multiplies them with J to get force/torque of end effector in cartesian space. Is it possible to simulate these sensors in mujoco?
    I can also use my current force-torque measured values and J to calculate it and then use their approach. Their code is here: ( the force_control_callback function)

    https://frankaemika.github.io/libfranka/force_control_8cpp-example.html

    But they use gravity in their approach and I don't know how to get it in mujoco. I think qfrc_bias is gravity+coriolis+centrifugial together.
    Do you have any idea?
     
  5. Emo Todorov

    Emo Todorov Administrator Staff Member

    the scalar value is just one component of the 3D torque vector, corresponding to the axis of joint rotation. you can extract that value from sensordata.

    the output of a force/torque sensor depends not only on gravity and mass, but also on velocity (due to coriolis and centripetal forces) and on acceleration/applied force. there is no simple way for you to compute the output of such a sensor; you have to do all the computations that mujoco is doing. which is why you have mujoco :)

    as for endeffector - to - joint mappings, keep in mind that the Jacobian maps joint velocities to endeffector velocities, while the Jacobian transposed maps endeffector forces to joint forces. the mapping from joint to endeffector forces (and from endeffector to joint velocities) is not well defined and you need some pseudo-inverse of the Jacobian.

    my recommendation is this: forget about the code from Franka for now, figure out the underlying physics and math, make sure your mujoco model corresponds to the physical robot (and in particular the torque sensors are defined in the right place) and then it will make sense.

    again, if you want to measure the contribution of contact forces to the torque readings (and remove everything else), you can call mj_forward twice in the same state, with and without contacts, and subtract the sensor data. forces are additive, so this works despite all the complexities in the simulation.
     
    Isaac likes this.
  6. Thank you for your response.
     
  7. I put a lot of time on this and have a problem yet. Based on what you said, I cannot subtract a constant value from force/torque readings. I convert values to the global frame and there are some changes in them when I move the robot arm or rotate it. I don't understand why the force changes when the arm moves and rotates. The mass is constant. Am I wrong?
    I couldn't find a proper textbook or reference to do it on my own. Can you please introduce a book that contains these calculations or equations?
     
  8. Emo Todorov

    Emo Todorov Administrator Staff Member

    A force sensor measures the interaction force between two bodies. This is not the same thing as measuring mass. The interaction force also reflects acceleration. Consider a simple example: two bodies on a horizontal linear slide, with a force sensor between them attached rigidly. No contacts anywhere, constant masses. Now you push on one body. Since the two bodies are rigidly attached, they will both accelerate. But you only pushed on one body. So why is the other body accelerating? Because the force was transmitted from one body to the other via the force sensor. So in this case the force sensor will act like an accelerometer.
     
    Isaac likes this.