forked from google-deepmind/mujoco_menagerie
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathfr3.xml
160 lines (152 loc) · 8.31 KB
/
fr3.xml
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
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
<mujoco model="fr3">
<compiler angle="radian" meshdir="assets"/>
<option integrator="implicitfast"/>
<default>
<default class="fr3">
<joint armature="0.1" damping="1"/>
<position inheritrange="1"/>
<default class="visual">
<geom type="mesh" group="2" contype="0" conaffinity="0"/>
</default>
<default class="collision">
<geom type="mesh" group="3" mass="0" density="0"/>
</default>
<site size="0.001" rgba="0.5 0.5 0.5 0.3" group="4"/>
</default>
</default>
<asset>
<material name="black" rgba=".2 .2 .2 1"/>
<material name="white" rgba="1 1 1 1"/>
<material name="red" rgba="1 0.072272 0.039546 1"/>
<material name="gray" rgba="0.863156 0.863156 0.863157 1"/>
<material name="button_green" rgba="0.102241 0.571125 0.102242 1"/>
<material name="button_red" rgba="0.520996 0.008023 0.013702 1"/>
<material name="button_blue" rgba="0.024157 0.445201 0.737911 1"/>
<mesh file="link0_0.obj"/>
<mesh file="link0_1.obj"/>
<mesh file="link0_2.obj"/>
<mesh file="link0_3.obj"/>
<mesh file="link0_4.obj"/>
<mesh file="link0_5.obj"/>
<mesh file="link0_6.obj"/>
<mesh file="link1.obj"/>
<mesh file="link2.obj"/>
<mesh file="link3_0.obj"/>
<mesh file="link3_1.obj"/>
<mesh file="link4_0.obj"/>
<mesh file="link4_1.obj"/>
<mesh file="link5_0.obj"/>
<mesh file="link5_1.obj"/>
<mesh file="link5_2.obj"/>
<mesh file="link6_0.obj"/>
<mesh file="link6_1.obj"/>
<mesh file="link6_2.obj"/>
<mesh file="link6_3.obj"/>
<mesh file="link6_4.obj"/>
<mesh file="link6_5.obj"/>
<mesh file="link6_6.obj"/>
<mesh file="link6_7.obj"/>
<mesh file="link7_0.obj"/>
<mesh file="link7_1.obj"/>
<mesh file="link7_2.obj"/>
<mesh file="link7_3.obj"/>
<mesh name="link0_coll" file="link0.stl"/>
<mesh name="link1_coll" file="link1.stl"/>
<mesh name="link2_coll" file="link2.stl"/>
<mesh name="link3_coll" file="link3.stl"/>
<mesh name="link4_coll" file="link4.stl"/>
<mesh name="link5_coll" file="link5.stl"/>
<mesh name="link6_coll" file="link6.stl"/>
<mesh name="link7_coll" file="link7.stl"/>
</asset>
<worldbody>
<body name="base" childclass="fr3">
<body name="fr3_link0">
<geom mesh="link0_0" material="black" class="visual"/>
<geom mesh="link0_1" material="white" class="visual"/>
<geom mesh="link0_2" material="white" class="visual"/>
<geom mesh="link0_3" material="white" class="visual"/>
<geom mesh="link0_4" material="white" class="visual"/>
<geom mesh="link0_5" material="red" class="visual"/>
<geom mesh="link0_6" material="black" class="visual"/>
<geom name="fr3_link0_collision" mesh="link0_coll" class="collision"/>
<body name="fr3_link1" pos="0 0 0.333">
<inertial pos="4.128e-07 -0.0181251 -0.0386036" quat="0.999901 0.0021545 0.00429041 0.0132325" mass="2.92747"
diaginertia="0.0186043 0.0181194 0.00538716"/>
<joint name="fr3_joint1" axis="0 0 1" range="-2.7437 2.7437" actuatorfrcrange="-87 87"/>
<geom name="fr3_link1_collision" class="collision" mesh="link1_coll"/>
<geom material="white" mesh="link1" class="visual"/>
<body name="fr3_link2" quat="1 -1 0 0">
<inertial pos="0.00318289 -0.0743222 0.00881461" quat="0.356855 0.680818 -0.434812 0.469126" mass="2.93554"
diaginertia="0.0299291 0.0299291 0.0299291"/>
<joint name="fr3_joint2" axis="0 0 1" range="-1.7837 1.7837" actuatorfrcrange="-87 87"/>
<geom material="white" mesh="link2" class="visual"/>
<geom name="fr3_link2_collision" class="collision" mesh="link2_coll"/>
<body name="fr3_link3" pos="0 -0.316 0" quat="1 1 0 0">
<inertial pos="0.0407016 -0.00482006 -0.0289731" quat="0.950032 -0.148357 0.229935 0.150201" mass="2.2449"
diaginertia="0.0140109 0.0140109 0.0140109"/>
<joint name="fr3_joint3" axis="0 0 1" range="-2.9007 2.9007" actuatorfrcrange="-87 87"/>
<geom mesh="link3_0" material="white" class="visual"/>
<geom mesh="link3_1" material="black" class="visual"/>
<geom name="fr3_link3_collision" class="collision" mesh="link3_coll"/>
<body name="fr3_link4" pos="0.0825 0 0" quat="1 1 0 0">
<inertial pos="-0.0459101 0.0630493 -0.00851879" quat="0.23761 0.892458 -0.00078702 0.383484"
mass="2.6156" diaginertia="0.0206104 0.0206104 0.0206104"/>
<joint name="fr3_joint4" axis="0 0 1" range="-3.0421 -0.1518" actuatorfrcrange="-87 87"/>
<geom mesh="link4_0" material="white" class="visual"/>
<geom mesh="link4_1" material="black" class="visual"/>
<geom name="fr3_link4_collision" class="collision" mesh="link4_coll"/>
<body name="fr3_link5" pos="-0.0825 0.384 0" quat="1 -1 0 0">
<inertial pos="-0.00160396 0.0292536 -0.0972966" quat="0.922285 0.098826 0.0982562 -0.360514"
mass="2.32712" diaginertia="0.0182879 0.0182879 0.0182879"/>
<joint name="fr3_joint5" axis="0 0 1" range="-2.8065 2.8065" actuatorfrcrange="-12 12"/>
<geom mesh="link5_0" material="white" class="visual"/>
<geom mesh="link5_1" material="white" class="visual"/>
<geom mesh="link5_2" material="black" class="visual"/>
<geom name="fr3_link5_collision" class="collision" mesh="link5_coll"/>
<body name="fr3_link6" quat="1 1 0 0">
<inertial pos="0.0597131 -0.0410295 -0.0101693" quat="0.593933 0.525442 0.520644 0.316361"
mass="1.81704" diaginertia="0.00483538 0.00483538 0.00483538"/>
<joint name="fr3_joint6" axis="0 0 1" range="0.5445 4.5169" actuatorfrcrange="-12 12"/>
<geom mesh="link6_0" material="button_green" class="visual"/>
<geom mesh="link6_1" material="white" class="visual"/>
<geom mesh="link6_2" material="white" class="visual"/>
<geom mesh="link6_3" material="gray" class="visual"/>
<geom mesh="link6_4" material="button_red" class="visual"/>
<geom mesh="link6_5" material="white" class="visual"/>
<geom mesh="link6_6" material="black" class="visual"/>
<geom mesh="link6_7" material="button_blue" class="visual"/>
<geom name="fr3_link6_collision" class="collision" mesh="link6_coll"/>
<body name="fr3_link7" pos="0.088 0 0" quat="1 1 0 0">
<inertial pos="0.00452258 0.00862619 -0.0161633" quat="0.120255 0.394761 -0.799132 0.437139"
mass="0.627143" diaginertia="3.076e-07 3.076e-07 3.076e-07"/>
<joint name="fr3_joint7" axis="0 0 1" range="-3.0159 3.0159" actuatorfrcrange="-12 12"/>
<geom mesh="link7_0" material="black" class="visual"/>
<geom mesh="link7_1" material="white" class="visual"/>
<geom mesh="link7_2" material="white" class="visual"/>
<geom mesh="link7_3" material="black" class="visual"/>
<geom name="fr3_link7_collision" class="collision" mesh="link7_coll"/>
<site name="attachment_site" pos="0 0 0.107"/>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</body>
</worldbody>
<actuator>
<position class="fr3" name="fr3_joint1" joint="fr3_joint1" kp="4500" kv="450"/>
<position class="fr3" name="fr3_joint2" joint="fr3_joint2" kp="4500" kv="450"/>
<position class="fr3" name="fr3_joint3" joint="fr3_joint3" kp="3500" kv="350"/>
<position class="fr3" name="fr3_joint4" joint="fr3_joint4" kp="3500" kv="350"/>
<position class="fr3" name="fr3_joint5" joint="fr3_joint5" kp="2000" kv="200"/>
<position class="fr3" name="fr3_joint6" joint="fr3_joint6" kp="2000" kv="200"/>
<position class="fr3" name="fr3_joint7" joint="fr3_joint7" kp="2000" kv="200"/>
</actuator>
<keyframe>
<key name="home" qpos="0 0 0 -1.57079 0 1.57079 -0.7853" ctrl="0 0 0 -1.57079 0 1.57079 -0.7853"/>
</keyframe>
</mujoco>