google-deepmind / dm_robotics

Libraries, tools and tasks created and used at DeepMind Robotics.
Apache License 2.0
332 stars 32 forks source link

Joint F/T Sensor Readings Advice #10

Closed kevinzakka closed 1 year ago

kevinzakka commented 2 years ago

Hi!

I've been playing around with F/T sensors in MuJoCo over the last few days and was wondering if I could get some advice / explanations for some things I am observing.

  1. Is the recommendation to place F/T sensor sites right after the joint definition in the XML tree? I see that the sawyer arm does this dynamically via PyMJCF by adding a site to the parent element of the joint. However, according to the MuJoCo documentation here, it recommends "creating a dummy body welded to its parent".
  2. How come your torque readings only read every 3rd value? Wouldn't you want to project onto the joint's axis? I guess this is overly specific to the Sawyer where all the joints have a Z-axis rotation (0 0 1)?
  3. I wrote a few unit tests where I apply a force or a torque at the parent body and then check to make sure the sensor reading matches the applies force. I did this by mimicking this unit test here in dm_control for the kinova arm. Unfortunately, I don't get matching values for desired / observed forces -- the only way that happens is if I step the physics until qvel is below a threshold and then read from the sensor. Would love an explanation as to what is different in the Kinova arm that applying a torque instantly displays the reading but this won't happen for other models I've messed with.
  4. Lastly, I noticed that things like frictionloss, damping and armature affect these sensory readings. Was curious if I could get some intuition about that as well!

Just to make things easy, I made a very simple 2-link arm and wrote a minimal example to unit test force and torque if that helps clarify my questions! You can find them here: https://gist.github.com/kevinzakka/701a1b9dea30bc675a4cf40b2af01659

@shacklestone @alaurens Would really appreciate your help!!

yuvaltassa commented 2 years ago

Hi Kevin!

  1. This is about interpretability. The F/T sensors between welded bodies are easier to understand, since there is no relative motion. The F/T reading in the joint space does read the effective F/T in that subspace, but it cannot read the forces that create acceleration. See example below.

  2. No idea, maybe @alaurens knows?

  3. Can you write a minimal test that shows unexpected behaviour? Ideally building on the model below.

  4. This is related to what I explained above. Some of the torque is causing acceleration and some isn't. The sensor can only report forces that do not contribute to acceleration.

Here is my minimal model. Note that as the pendulum swing freely under gravity the torque sensor is measuring nothing, since %100 of the torque goes to creating acceleration in the joint space. The force sensor is always measuring the full force since there are no linear motion DoFs.

<mujoco>
  <option gravity="0 0 -10"/>
  <worldbody>
    <geom type="plane" size="1.5 1.5 .01"/>
    <light pos="0 0 2.5"/>
    <body pos="0 0 1.2">
      <site name="sensor1"/>
      <joint name="hinge" axis="0 1 0" limited="true" range="-180 180"/>
      <geom type="capsule" size=".03" fromto="0 0 0 1 0 0" mass="0"/>
      <geom size=".1" pos="1 0 0" mass="1"/>
    </body>
  </worldbody>

  <sensor>
    <force site="sensor1"/>
    <torque site="sensor1"/>
  </sensor>
</mujoco>

Note that I made gravity and all the lengths and masses nice round numbers so that it will be very obvious what the expected measurements should be.