modeling and simulation of a tactile sensor array.

Discussion in 'Simulation' started by Yi Zheng, Apr 29, 2020.

  1. Hello,
    I am using Mujoco-py but I think for my problem this might be a better place to post.
    I am trying to use the Touch Sensor in Mujoco 2.0 to model and simulation a pressure based tactile sensor array, this is what my partial model file looks like:
    In my robot.xml
    Code:
    .......
    <body name="panda_leftfinger" pos="0 0 0.1654" quat="0.92388 0 0 -0.382683" childclass='panda_finger'>
                                            <inertial pos="-1.57863e-05 0.0118731 0.0434103" quat="0.705868 0.0310348 -0.0314925 0.706962" mass="0.0927059" diaginertia="6.57134e-05 6.09611e-05 1.09932e-05" />
                                         
                                            <joint name="panda_finger_joint1"  axis="0 1 0" type="slide" range="0 0.04" class="panda_finger"/>
                                            <geom class="panda_viz" mesh="finger_viz"/>
                                            <geom pos="0 -0.0015 0.0446 " type="box" size="0.01 0.002 0.01" rgba=".5 .6 .7 1" mass="0.00001"/>
                                            <geom pos="0 -0.0015 0.0446 " type="box" size="0.01 0.002 0.01" rgba="1 0 0 1" group="0"/>
                                            <site name="touch_l0" type="box" pos="0.001 -0.0035 0.0536" size="0.001 0.001 0.001" rgba="0 0.5 0.5 0.33"/>
                                            <site name="touch_l1" type="box" pos="0.003 -0.0035 0.0536" size="0.001 0.001 0.001" rgba="0 0.5 0.5 0.33"/>
                                            <site name="touch_l2" type="box" pos="0.005 -0.0035 0.0536" size="0.001 0.001 0.001" rgba="0 0.5 0.5 0.33"/>
                                            <site name="touch_l3" type="box" pos="0.007 -0.0035 0.0536" size="0.001 0.001 0.001" rgba="0 0.5 0.5 0.33"/>
                                            <site name="touch_l4" type="box" pos="0.009 -0.0035 0.0536" size="0.001 0.001 0.001" rgba="0 0.5 0.5 0.33"/>
                                            <site name="touch_l5" type="box" pos="-0.001 -0.0035 0.0536" size="0.001 0.001 0.001" rgba="0 0.5 0.5 0.33"/>
                                             <site name="touch_l6" type="box" pos="-0.003 -0.0035 0.0536" size="0.001 0.001 0.001" rgba="0 0.5 0.5 0.33"/>
                                            <site name="touch_l7" type="box" pos="-0.005 -0.0035 0.0536" size="0.001 0.001 0.001" rgba="0 0.5 0.5 0.33"/>
                                            <site name="touch_l8" type="box" pos="-0.007 -0.0035 0.0536" size="0.001 0.001 0.001" rgba="0 0.5 0.5 0.33"/>
                                            <site name="touch_l9" type="box" pos="-0.009 -0.0035 0.0536" size="0.001 0.001 0.001" rgba="0 0.5 0.5 0.33"/>
    ......
    in my touch_sensor.xml
    Code:
    <mujoco>
        <sensor>
            <touch name="touch_l0" site="touch_l0"></touch>
            <touch name="touch_l1" site="touch_l1"></touch>
            <touch name="touch_l2" site="touch_l2"></touch>
            <touch name="touch_l3" site="touch_l3"></touch>
            <touch name="touch_l4" site="touch_l4"></touch>
            <touch name="touch_l5" site="touch_l5"></touch>
            <touch name="touch_l6" site="touch_l6"></touch>
            <touch name="touch_l7" site="touch_l7"></touch>
            <touch name="touch_l8" site="touch_l8"></touch>
            <touch name="touch_l9" site="touch_l9"></touch>
            .......
        <sensor>
    <mujoco>
    Over all I have two gripper pad, and on each pad I create a 10 x 10 touch sensor array, each sensor is represented by a "box" with the size parameter [0.001, 0.001, 0.001], the visualizations can be seen in the following:
    1.png
    [​IMG]
    [​IMG]
    2.png
    Then I use the gripper to grad a block, as shown in the following:
    3.png
    [​IMG]

    However, when I print out the sensor values, majority of them are zero:
    [​IMG]
    4.png

    May I ask what is the possible reason for this ? I expect majority of the sensors should have non-zero values since they are in contact with the object.

    Thanks very much for your time and patience.
     
  2. I'm pretty certain that any individual contact is calculated with up to only 4 points.
    Imagine the interaction with a cube on the ground. Handling the only the 4 corner points is sufficient to calculate the dynamics. Or if you imagine an arbitrary shape falling down, it will only have either 1, 2, 3 or 4 contact points, never an actual surface. Something like contact pressure doesn't really exist for physics simulators in general.
    (Pretty sure about this, but not certain,)

    What are you trying to accomplish, that you need so many sensors?
     
  3. Thanks for the reply !

    However according to the principle you mentioned, I still expect more sensors to have non-zero values than what is shown in the 4th screenshot. Because wouldn't the principle you mentioned apply to each individual site representing the touch sensor, and Mujoco will compute a contact force for each individual touch sensor represented by the site ? And based on the 3rd screenshot, many of the sensors are in contact with the object.

    At a high level, my goal is to obtain a finer contact force distribution from the "sensor pad", which can reflect different status of the object-environment interaction, and this reflection might be used to design some manipulation algorithms. Conceptually it is similar to what this paper is doing: https://arxiv.org/pdf/1903.04128.pdf

    Thanks
     
  4. I don't know how the touch sensors really work. I'm guessing they reflect the actual contacts which are inside their volume, i.e. they wouldn't 'produce' additional contact points.

    So I don't think you can accomplish what you're looking for in MuJoCo.
     
  5. Thanks for your reply !

    Do you mean that since the contact of a geom object is computed up to only 4 points, therefore even I create this many sensors and just by looking at the image all sensors seem to be in contact with the object, but the 4 points used to compute contacts only fall inside the volume of very few of them, and that's the why the majority of the outputs is 0 ?
     
  6. I think I sort of see what you mean, I will see if I can get things to work by adding a small geom on each site.
    Thanks
     
  7. To give an update, I added one geom on each site of the touch sensor, and the image for the left gripper looks like the following:
    1.png
    The blue-greenish box represent the touch sensor site, and the red ellipsoid is the geom, I didn't assign a geom for every touch sensor site, because I find doing that will significantly reduce the simulation speed.

    WHhen the gripper grips the object, I still get 0 values for the most touch sensors on the left gripper pad, at several instants when the gripper starts to make contact with the object, the right touch sensor values are non-zero, as shown be the following:
    3.png

    However after this several instants, the values for the right touch sensor also become 0

    Also when I check the simulation after the object is being gripped and lifted off, there seems to be a space between the gripper and the object:
    4.png
    Not sure if this is just a rendering issue, or it actually causes problem to the contact computation ?

    Last but not least, when I print out the number of contacts by checking mj_Data.contacts, it says at the moment where the above image is shown, there are 62 contants, so some of the touch sensors should be still in contact with the object ? However the sensor values output are all 0.


    Any thoughts or ideas about the possible issues ? Thanks
     
  8. Yup, that's exactly what I suspect.

    Good idea, but I doubt it makes much difference (which you also seen in your results), since multiple geoms still make up a single object and a single object needs only the few contact points.

    Maybe the best way to get around is by creating separate bodies. You could create little spring dampers based on a single spherical geom each. This way you still get a single contact point per body, but a lot more for the whole plate. Note that would need overdamped and pretty stiff springs.
    Maybe you should try this with a smaller setting first? You could create this array, place it horizontally and let a cube fall on top. Just do 3x3 touch-spheres with sensors and see what kind of results you get.

    I don't know. I could be that it's just a little much for the simulation.

    That is a little strange. There are not other contacts in the model?
    You could enable the mjVIS_CONTACTPOINT to investigate this.

    Good luck!
     
  9. Not really, before I use the gripper to grip the object, there are only 4 contacts when I print out mj_Data.contacts.ncon, which are between the object and the table:
    5.png
    There is also one geom on each joint of the robot, but since is no self collision, no contacts are produced from those geoms.

    Great suggestion ! I will give it a try, thanks for the help !