Skip to content

Commit 5e6af47

Browse files
DeepMindcopybara-github
authored andcommitted
Add mjx_2f85.xml model to robotiq_2f85_v4.
PiperOrigin-RevId: 716182252 Change-Id: Ife6cbe68da43b410309b486011de1a475075fd15
1 parent 680740f commit 5e6af47

File tree

1 file changed

+153
-0
lines changed

1 file changed

+153
-0
lines changed

robotiq_2f85_v4/mjx_2f85.xml

Lines changed: 153 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,153 @@
1+
<mujoco model="robotiq_2f85">
2+
<compiler angle="radian" meshdir="assets" autolimits="true"/>
3+
4+
<asset>
5+
6+
<material name="metal" rgba="0.58 0.58 0.58 1"/>
7+
<material name="silicone" rgba="0.1882 0.1882 0.1882 1"/>
8+
<material name="black" rgba="0.149 0.149 0.149 1"/>
9+
10+
<mesh file="base.stl"/>
11+
<mesh file="base_coupling.stl"/>
12+
<mesh file="c-a01-85-open.stl"/>
13+
<mesh file="driver.stl"/>
14+
<mesh file="coupler.stl"/>
15+
<mesh file="spring_link.stl"/>
16+
<mesh file="follower.stl"/>
17+
<mesh file="tongue.stl"/>
18+
</asset>
19+
20+
21+
<default>
22+
<default class="2f85">
23+
<mesh scale="0.001 0.001 0.001"/>
24+
<general biastype="affine"/>
25+
26+
<joint axis="0 0 1"/>
27+
<default class="driver">
28+
<joint range="0 0.9" armature="0.005" damping="0.1" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
29+
</default>
30+
<default class="follower">
31+
<joint range="-0.872664 0.9" armature="0.001" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
32+
</default>
33+
<default class="spring_link">
34+
<joint range="-0.29670597283 0.9" armature="0.001" stiffness="0.05" springref="2.62" damping="0.00125"/>
35+
</default>
36+
<default class="coupler">
37+
<joint range="-1.57 0" armature="0.001" solimplimit="0.95 0.99 0.001" solreflimit="0.005 1"/>
38+
</default>
39+
40+
<default class="visual">
41+
<geom type="mesh" contype="0" conaffinity="0" group="2" material="black"/>
42+
</default>
43+
<default class="collision">
44+
<geom group="3" type="mesh" contype="0" conaffinity="0"/>
45+
<default class="pad_box1">
46+
<geom group="3" mass="1e-6" type="box" pos="0.043258 0 0.12" size="0.002 0.011 0.009375"
47+
solimp="0.99 0.995 0.01" solref="0.01 1" friction="1 0.005 0.0001" rgba="1.0 0.55 0.55 1" conaffinity="3"/>
48+
</default>
49+
<default class="pad_box2">
50+
<geom group="3" mass="1e-6" type="box" pos="0.041258 0 0.12875" size="0.004 0.011 0.01875"
51+
solimp="0.99 0.995 0.01" solref="0.01 1" friction="1 0.005 0.0001" rgba="0.0 0.45 0.45 1" conaffinity="3"/>
52+
</default>
53+
</default>
54+
</default>
55+
</default>
56+
57+
58+
<worldbody>
59+
<body name="base" childclass="2f85" quat="1 0 0 -1">
60+
<inertial mass="0.777441" pos="0 -2.70394e-05 0.0354675" quat="1 0 0 0"
61+
diaginertia="0.000260285 0.000225381 0.000152708"/>
62+
<geom class="visual" pos="0 0 0.0108" quat="0 0 0 1" mesh="base"/>
63+
<geom class="visual" pos="0 0 0.004" quat="1 -1 0 0" mesh="base_coupling"/>
64+
<geom class="visual" pos="0 0 0.0108" quat="1 0 0 0" material="metal" mesh="c-a01-85-open"/>
65+
<geom name="hand_capsule" class="collision" type="capsule" conaffinity="1" size="0.04 0.06" rgba="1 1 1 0.3" pos="0 0 0.01"/>
66+
67+
<!-- Left-hand side 4-bar linkage -->
68+
<body name="left_driver" pos="-0.0306011 0.00475 0.0657045" quat="1 -1 0 0">
69+
<inertial mass="0.00899563" pos="0 0.0177547 0.00107314" quat="0.681301 0.732003 0 0"
70+
diaginertia="1.72352e-06 1.60906e-06 3.22006e-07"/>
71+
<joint name="left_driver_joint" class="driver"/>
72+
<geom class="visual" pos="0.0306011 0.0549045 -0.0047" quat="1 1 0 0" material="metal" mesh="driver"/>
73+
<body name="left_coupler" pos="-0.0314249 0.00453223 -0.0102" quat="0 0 0 1">
74+
<inertial mass="0.0140974" pos="0 0.00301209 0.0232175" quat="0.705636 -0.0455904 0.0455904 0.705636"
75+
diaginertia="4.16206e-06 3.52216e-06 8.88131e-07"/>
76+
<geom class="visual" pos="-0.062026 -0.0503723 0.0055" quat="1 -1 0 0" mesh="coupler"/>
77+
<geom name="left_coupler_col_1" class="pad_box2" pos="0.005 0.025 0.01" quat="1 1 -0.1 0" type="capsule" size="0.009 0.02"/>
78+
<geom name="left_coupler_col_2" class="pad_box2" pos="0.005 0.025 0.001" quat="1 1 -0.1 0" type="capsule" size="0.009 0.02"/>
79+
</body>
80+
</body>
81+
<body name="left_spring_link" pos="-0.0127 -0.012 0.07222" quat="1 -1 0 0">
82+
<inertial mass="0.0221642" pos="-8.65005e-09 0.0181624 0.0212658" quat="0.663403 -0.244737 0.244737 0.663403"
83+
diaginertia="8.96853e-06 6.71733e-06 2.63931e-06"/>
84+
<joint name="left_spring_link_joint" class="spring_link"/>
85+
<geom class="visual" pos="0.0127 0.06142 0.01205" quat="1 1 0 0" type="mesh" mesh="spring_link"/>
86+
<body name="left_follower" pos="-0.0382079 -0.0425003 0.00295" quat="0 -1 0 0">
87+
<inertial mass="0.0125222" pos="0 -0.011046 0.0124786" quat="1 0.1664 0 0"
88+
diaginertia="2.67415e-06 2.4559e-06 6.02031e-07"/>
89+
<joint name="left_follower" class="follower"/>
90+
<geom class="visual" pos="0.0509079 -0.10392 -0.0091" quat="1 -1 0 0" type="mesh" mesh="follower"/>
91+
<geom class="visual" pos="0.0509079 -0.10392 -0.0091" quat="1 -1 0 0" type="mesh" material="metal" mesh="tongue"/>
92+
<geom name="left_follower_pad2" class="pad_box2" type="capsule" size="0.009 0.012 0.008" pos="-0.0035 -0.002 -0.009" quat="1 1 0 0"/>
93+
<body name="left_pad" pos="-0.0377897 -0.103916 -0.0091" quat="1 -1 0 0">
94+
<geom class="pad_box2" name="left_finger_pad"/>
95+
</body>
96+
</body>
97+
</body>
98+
<!-- Right-hand side 4-bar linkage -->
99+
<body name="right_driver" pos="0.0306011 -0.00475 0.0657045" quat="0 0 -1 1">
100+
<inertial mass="0.00899563" pos="2.96931e-12 0.0177547 0.00107314" quat="0.681301 0.732003 0 0"
101+
diaginertia="1.72352e-06 1.60906e-06 3.22006e-07"/>
102+
<joint name="right_driver_joint" class="driver"/>
103+
<geom class="visual" pos="0.0306011 0.0549045 -0.0047" quat="1 1 0 0" material="metal" mesh="driver"/>
104+
<body name="right_coupler" pos="-0.0314249 0.00453223 -0.0102" quat="0 0 0 1">
105+
<inertial mass="0.0140974" pos="0 0.00301209 0.0232175" quat="0.705636 -0.0455904 0.0455904 0.705636"
106+
diaginertia="4.16206e-06 3.52216e-06 8.88131e-07"/>
107+
<geom class="visual" pos="-0.062026 -0.0503723 0.0055" quat="1 -1 0 0" mesh="coupler"/>
108+
<geom name="right_coupler_col_1" class="pad_box2" pos="0.005 0.025 0.01" quat="1 1 -0.1 0" type="capsule" size="0.009 0.02"/>
109+
<geom name="right_coupler_col_2" class="pad_box2" pos="0.005 0.025 0.001" quat="1 1 -0.1 0" type="capsule" size="0.009 0.02"/>
110+
</body>
111+
</body>
112+
<body name="right_spring_link" pos="0.0127 0.012 0.07222" quat="0 0 -1 1">
113+
<inertial mass="0.0221642" pos="-8.65005e-09 0.0181624 0.0212658" quat="0.663403 -0.244737 0.244737 0.663403"
114+
diaginertia="8.96853e-06 6.71733e-06 2.63931e-06"/>
115+
<joint name="right_spring_link_joint" class="spring_link"/>
116+
<geom class="visual" pos="0.0127 0.06142 0.01205" quat="1 1 0 0" mesh="spring_link"/>
117+
<body name="right_follower" pos="-0.0382079 -0.0425003 0.00295" quat="0 -1 0 0">
118+
<inertial mass="0.0125222" pos="0 -0.011046 0.0124786" quat="1 0.1664 0 0"
119+
diaginertia="2.67415e-06 2.4559e-06 6.02031e-07"/>
120+
<joint name="right_follower_joint" class="follower"/>
121+
<geom class="visual" pos="0.0509079 -0.10392 -0.0091" quat="1 -1 0 0" material="metal" mesh="tongue"/>
122+
<geom class="visual" pos="0.0509079 -0.10392 -0.0091" quat="1 -1 0 0" mesh="follower"/>
123+
<geom name="right_follower_pad2" class="pad_box2" type="capsule" size="0.009 0.012 0.008" pos="-0.0035 -0.002 -0.009" quat="1 1 0 0"/>
124+
<body name="right_pad" pos="-0.0377897 -0.103916 -0.0091" quat="1 -1 0 0">
125+
<geom class="pad_box2" name="right_finger_pad"/>
126+
</body>
127+
</body>
128+
</body>
129+
</body>
130+
</worldbody>
131+
132+
<contact>
133+
<exclude body1="base" body2="left_driver"/>
134+
<exclude body1="base" body2="right_driver"/>
135+
<exclude body1="base" body2="left_spring_link"/>
136+
<exclude body1="base" body2="right_spring_link"/>
137+
<exclude body1="right_coupler" body2="right_follower"/>
138+
<exclude body1="left_coupler" body2="left_follower"/>
139+
</contact>
140+
141+
<equality>
142+
<connect anchor="-0.0179014 -0.00651468 0.0044" body1="right_follower" body2="right_coupler" solimp="0.95 0.99 0.001" solref="0.005 1"/>
143+
<connect anchor="-0.0179014 -0.00651468 0.0044" body1="left_follower" body2="left_coupler" solimp="0.95 0.99 0.001" solref="0.005 1"/>
144+
<joint joint1="right_driver_joint" joint2="left_driver_joint" polycoef="0 1 0 0 0" solimp="0.95 0.99 0.001"
145+
solref="0.005 1"/>
146+
</equality>
147+
148+
<actuator>
149+
<general class="2f85" name="fingers_actuator" joint="left_driver_joint" forcerange="-5 5" ctrlrange="0 0.82"
150+
gainprm="100 0 0" biasprm="0 -100 -10"/>
151+
</actuator>
152+
153+
</mujoco>

0 commit comments

Comments
 (0)