mujoco
mujoco copied to clipboard
I would like to get some ideas on how to measure the force and torque between body and body.
Hi, I'm a student and I'm trying to use MuJoCo for estimation of the state of holding an object/
I'm looking for some help with how you can measure sensor values
Here is a model which explains my question:
Fingers with the following sensors were modeled.
Currently, the orange part is the force/torque sensor. I would like to use mujoco simulator to measure Force and torque in simulator like real environment.
Is there a way to implement this using mujoco simulator? I would really appreciate it if you could tell me how.
Here is a screenshot / video, illustrating my question:
Hello,
If I understand correctly, you want to measure the force/torque between the parent and child bodies (the two "phalanges" in this case)? There are sensors to do exactly that! https://mujoco.readthedocs.io/en/stable/XMLreference.html#sensor-force
If you add them to the MJCF model of your hand, their readings will be available to you each simulation step.
Hello,
Thank you for letting me know the good features.
As you said, I simplified the model and experimented with it, can you tell me why the force and torque are taken abnormally?
I will show you my model and mujoco simulator sensor data.
XML:
<body name="Test_body_1" pos="0.1 0.1 0.1">
<geom name="Test_body_1" size="0.05 0.05 0.05" type="box" rgba="1 0 0 0.5"/>
<site name="ft_sensor" type="box" pos="0 0 0.05" />
<body name="Test_body_2" pos="0.0 0.0 0.1">
<geom name="Test_body_2" type="box" size="0.05 0.05 0.05" rgba="0 0 1 0.5"/>
</body>
</body>
</worldbody>
<sensor>
<force name="force_sensor" site="ft_sensor"/>
<torque name="torque_sensor" site="ft_sensor"/>
</sensor>
Hello, the site should be on the child body, check out the "site" part of the force sensor documentation for details
From: rororofo2 @.> Sent: Thursday, April 18, 2024 9:22:27 AM To: google-deepmind/mujoco @.> Cc: Hodossy, Bálint K @.>; Comment @.> Subject: Re: [google-deepmind/mujoco] I would like to get some ideas on how to measure the force and torque between body and body. (Issue #1597)
This email from @.*** originates from outside Imperial. Do not click on links and attachments unless you recognise the sender. If you trust the sender, add them to your safe senders listhttps://spam.ic.ac.uk/SpamConsole/Senders.aspx to disable email stamping for this address.
Hello,
Thank you for letting me know the good features.
As you said, I simplified the model and experimented with it, can you tell me why the force and torque are taken abnormally?
I will show you my model and mujoco simulator sensor data.
XML:
<body name="Test_body_1" pos="0.1 0.1 0.1">
<geom name="Test_body_1" size="0.05 0.05 0.05" type="box" rgba="1 0 0 0.5"/>
<site name="ft_sensor" type="box" pos="0 0 0.05" />
<body name="Test_body_2" pos="0.0 0.0 0.1">
<geom name="Test_body_2" type="box" size="0.05 0.05 0.05" rgba="0 0 1 0.5"/>
</body>
</body>
image.png (view on web)https://github.com/google-deepmind/mujoco/assets/109202740/69880ea6-2a48-4053-a906-b3a34ee339c1
— Reply to this email directly, view it on GitHubhttps://github.com/google-deepmind/mujoco/issues/1597#issuecomment-2063305106, or unsubscribehttps://github.com/notifications/unsubscribe-auth/AJZVOK3YODXH7GZEE37ZJ2LY557EHAVCNFSM6AAAAABGIZTVXCVHI2DSMVQWIX3LMV43OSLTON2WKQ3PNVWWK3TUHMZDANRTGMYDKMJQGY. You are receiving this because you commented.Message ID: @.***>
**Hello, Is this what you said correct?
<body name="Base" pos="0.1 0.1 0.1">
<geom name="Base" mass="1" size="0.05 0.05 0.05" type="box" rgba="1 0 0 0.5"/>
<body name="Parent_Body" pos="0.0 0.0 0.055">
<geom name="Parent_Body" mass="10e-6" size="0.05 0.05 0.005" type="box" rgba="0 1 0 0.5"/>
<site name="ft_sensor" type="box" pos="0 0 0.0" />
<body name="Child_Body" pos="0.0 0.0 0.055">
<!-- <site name="ft_sensor" type="box" pos="0 0 0.0" /> -->
<geom name="Child_Body" type="box" mass="1" size="0.05 0.05 0.05" rgba="0 0 1 0.5"/>
</body>
</body>
</body>**
Yeah, except remove the site from the parent body and uncomment it in the child body? Or does that give you an error?
Yeah, The sensor value is still strange
Can't I use the mocap to apply external force to the geom?
<body name="Base" pos="0.1 0.1 0.1">
<geom name="Base" mass="1" size="0.05 0.05 0.05" type="box" rgba="1 0 0 0.5"/>
<body name="Parent_Body" pos="0.0 0.0 0.055">
<geom name="Parent_Body" mass="10e-6" size="0.05 0.05 0.005" type="box" rgba="0 1 0 0.5"/>
<body name="Child_Body" pos="0.0 0.0 0.055">
<site name="ft_sensor" type="box" pos="0 0 0.0" />
<geom name="Child_Body" type="box" mass="1" size="0.05 0.05 0.05" rgba="0 0 1 0.5"/>
</body>
</body>
</body>
Trying your MWE gives correct results as expected. The huge values show on your figure makes me think there's some collision issue. Maybe a plane oriented the wrong way? You can visualize contact points in Simulate, or try disabling collisions in the Physics options.
Hello, I'm sorry for the late thank you for your response.
It helped me a lot through sincere answers.
I have an additional question, so I'd like to ask you, is it possible?
- I added the ft sensor, and even if the weight of the object changes while the gripper is closed, the data measured in the ft sensor appears the same. For example, if a 1kg object holds and lifts an object when the joint is free, and if there is no joint and the object does not move, it will slip. I want to know why the data appear the same.
Glad you are making progress. Could you please rephrase your point 1? I had trouble understanding it.
Could you please share the xml, or describe the hierarchy and where the sensor is?
Currently, a force/Torque sensor has been attached to that part.
The experiment I want to proceed with is that when I hold the object with the gripper and the gripper moves up and down, I want to compare the ft sensor data.
Case 1 :
<body pos="0.13 0 0.08">
<joint type="free"/>
<geom name="object" type="box" mass="5" size="0.015 0.015 0.08" rgba="0.1 0 0.5 0.1"/>
</body>
The object was declared as follows, and the data were obtained when the gripper held the object stably and moved upward.
Case 2 :
<body pos="0.13 0 0.08">
<geom name="object" type="box" mass="5" size="0.015 0.015 0.08" rgba="0.1 0 0.5 0.1"/>
</body>
This time, the object is fixed, and I got the data that appears when the gripper holds and moves the object. (In this case, the object does not move and only the gripper moves -> Slip)
In this case, the data appears the same, and I wonder if it is measured correctly..
Additionally, is it correct that the data appear similar even if the experiment is conducted in the same way by changing the mass of the object? For example, when there are 1kg and 5kg objects, holding the gripper with the same grasping force and moving the gripper upward, the data on the f/t sensor is the same.
Well, if the object is fixed, you expect the same data measured with any mass (as the slip conditions would stay the same). Do you still see the same measurements when the object is free as well and lifted?
Yes. In the case of a free object, it also shows the same measurement values.