Intro
Hi!
I am a undergrad student at Cambridge using MuJoCo for deformable material and hybrid robotics simulation.
My setup
MuJoCo version: 3.3.4
API: Python
Architecture: x86-64
OS: Windows 11
What's happening? What did you expect?
I created a 3D tetrahedral mesh and pinned several vertices, but the deformation disappeared after the vertices were pinned.
In a minimal example, I generated a cap-shaped tetrahedral mesh. Before pinning any vertices, the deformation behaved as expected. I examined the vertex positions in data.flexvert_xpos to identify those lying on the flat surface of the mesh and extracted their indices to use as the pin IDs.
However, after pinning all the vertices on the flat side of the cap-shaped mesh, the deformation no longer occurred.
Below is a compressed video showing the deformation before and after pinning the vertices.
No Visible Deformation after Pinning vertices.zip
Steps for reproduction
- Download the msh and scene file
- Load the xml model below
- Run the code below
- Control the actuator and see the deformation
MSH File and the Scene XML file
Mesh_and_Scene.zip
Minimal model for reproduction
<mujoco model="Press">
<include file="scene_rigid.xml"/>
<compiler meshdir="./"/>
<compiler autolimits="true"/>
<option solver="Newton" tolerance="1e-6" timestep=".001" integrator="implicitfast"/>
<visual>
<map stiffness="100"/>
</visual>
<worldbody>
<flexcomp type="gmsh" file="RoundTip" pos="0 0 -0.01" dim="3" euler="0 -90 0"
radius=".001" rgba="0 .7 .7 1" mass=".5" name="left"
dof="trilinear" scale=".001 .001 .001">
<contact condim="3" solref="0.01 1" solimp=".95 .99 .0001" selfcollide="none"/>
<edge equality="true" damping=".01"/>
<elasticity young="1e5" poisson="0.4" damping="0.01"/>
<pin id="0 1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121"/>
</flexcomp>
<body name="ball_up">
<joint name="ball_up" type="slide" axis="0 0 1"/>-->
<geom type="sphere" size=".01" pos="0.0 0 .1" rgba=".5 .5 0 1" density="1e5"/>
</body>
</worldbody>
<actuator>
<position name="sliding" joint="ball_up" kp="60" dampratio="1" ctrlrange="-0.2 0.2"/>
</actuator>
</mujoco>
Code required for reproduction
import mujoco
import numpy as np
import mujoco.viewer as viewer
model = mujoco.MjModel.from_xml_path('Round_Tip.xml')
data = mujoco.MjData(model)
viewer.launch(model, data)
Confirmations
Intro
Hi!
I am a undergrad student at Cambridge using MuJoCo for deformable material and hybrid robotics simulation.
My setup
MuJoCo version: 3.3.4
API: Python
Architecture: x86-64
OS: Windows 11
What's happening? What did you expect?
I created a 3D tetrahedral mesh and pinned several vertices, but the deformation disappeared after the vertices were pinned.
In a minimal example, I generated a cap-shaped tetrahedral mesh. Before pinning any vertices, the deformation behaved as expected. I examined the vertex positions in data.flexvert_xpos to identify those lying on the flat surface of the mesh and extracted their indices to use as the pin IDs.
However, after pinning all the vertices on the flat side of the cap-shaped mesh, the deformation no longer occurred.
Below is a compressed video showing the deformation before and after pinning the vertices.
No Visible Deformation after Pinning vertices.zip
Steps for reproduction
MSH File and the Scene XML file
Mesh_and_Scene.zip
Minimal model for reproduction
Code required for reproduction
Confirmations