Yochish commited on
Commit
59da178
·
verified ·
1 Parent(s): 2753a7d

Upload g1_23dof_lock_wrist_fitmotionONLY.xml

Browse files
TextOpRobotMDAR/description/robots/g1/g1_23dof_lock_wrist_fitmotionONLY.xml ADDED
@@ -0,0 +1,244 @@
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
1
+ <mujoco model="g1_29dof_rev_1_0">
2
+ <compiler angle="radian" meshdir="meshes"/>
3
+
4
+ <asset>
5
+ <mesh name="pelvis" file="pelvis.STL"/>
6
+ <mesh name="pelvis_contour_link" file="pelvis_contour_link.STL"/>
7
+ <mesh name="left_hip_pitch_link" file="left_hip_pitch_link.STL"/>
8
+ <mesh name="left_hip_roll_link" file="left_hip_roll_link.STL"/>
9
+ <mesh name="left_hip_yaw_link" file="left_hip_yaw_link.STL"/>
10
+ <mesh name="left_knee_link" file="left_knee_link.STL"/>
11
+ <mesh name="left_ankle_pitch_link" file="left_ankle_pitch_link.STL"/>
12
+ <mesh name="left_ankle_roll_link" file="left_ankle_roll_link.STL"/>
13
+ <mesh name="right_hip_pitch_link" file="right_hip_pitch_link.STL"/>
14
+ <mesh name="right_hip_roll_link" file="right_hip_roll_link.STL"/>
15
+ <mesh name="right_hip_yaw_link" file="right_hip_yaw_link.STL"/>
16
+ <mesh name="right_knee_link" file="right_knee_link.STL"/>
17
+ <mesh name="right_ankle_pitch_link" file="right_ankle_pitch_link.STL"/>
18
+ <mesh name="right_ankle_roll_link" file="right_ankle_roll_link.STL"/>
19
+ <mesh name="waist_yaw_link" file="waist_yaw_link_rev_1_0.STL"/>
20
+ <mesh name="waist_roll_link" file="waist_roll_link_rev_1_0.STL"/>
21
+ <mesh name="torso_link" file="torso_link_rev_1_0.STL"/>
22
+ <mesh name="logo_link" file="logo_link.STL"/>
23
+ <mesh name="head_link" file="head_link.STL"/>
24
+ <mesh name="left_shoulder_pitch_link" file="left_shoulder_pitch_link.STL"/>
25
+ <mesh name="left_shoulder_roll_link" file="left_shoulder_roll_link.STL"/>
26
+ <mesh name="left_shoulder_yaw_link" file="left_shoulder_yaw_link.STL"/>
27
+ <mesh name="left_elbow_link" file="left_elbow_link.STL"/>
28
+
29
+ <mesh name="right_shoulder_pitch_link" file="right_shoulder_pitch_link.STL"/>
30
+ <mesh name="right_shoulder_roll_link" file="right_shoulder_roll_link.STL"/>
31
+ <mesh name="right_shoulder_yaw_link" file="right_shoulder_yaw_link.STL"/>
32
+ <mesh name="right_elbow_link" file="right_elbow_link.STL"/>
33
+
34
+ </asset>
35
+
36
+ <worldbody>
37
+ <body name="pelvis" pos="0 0 0.793">
38
+ <inertial pos="0 0 -0.07605" quat="1 0 -0.000399148 0" mass="3.813" diaginertia="0.010549 0.0093089 0.0079184"/>
39
+ <joint name="floating_base_joint" type="free" limited="false" actuatorfrclimited="false"/>
40
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="pelvis"/>
41
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
42
+ <geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="pelvis_contour_link"/>
43
+ <site name="imu_in_pelvis" size="0.01" pos="0.04525 0 -0.08339"/>
44
+ <body name="left_hip_pitch_link" pos="0 0.064452 -0.1027">
45
+ <inertial pos="0.002741 0.047791 -0.02606" quat="0.954862 0.293964 0.0302556 0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
46
+ <joint name="left_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
47
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
48
+ <geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="left_hip_pitch_link"/>
49
+ <body name="left_hip_roll_link" pos="0 0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
50
+ <inertial pos="0.029812 -0.001045 -0.087934" quat="0.977808 -1.97119e-05 0.205576 -0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
51
+ <joint name="left_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.5236 2.9671" actuatorfrcrange="-139 139"/>
52
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
53
+ <geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_roll_link"/>
54
+ <body name="left_hip_yaw_link" pos="0.025001 0 -0.12412">
55
+ <inertial pos="-0.057709 -0.010981 -0.15078" quat="0.600598 0.15832 0.223482 0.751181" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
56
+ <joint name="left_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
57
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
58
+ <geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_hip_yaw_link"/>
59
+ <body name="left_knee_link" pos="-0.078273 0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
60
+ <inertial pos="0.005457 0.003964 -0.12074" quat="0.923418 -0.0327699 0.0158246 0.382067" mass="1.932" diaginertia="0.0113804 0.0112778 0.00146458"/>
61
+ <joint name="left_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
62
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
63
+ <geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_knee_link"/>
64
+ <body name="left_ankle_pitch_link" pos="0 -9.4445e-05 -0.30001">
65
+ <inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
66
+ <joint name="left_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
67
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
68
+ <geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_ankle_pitch_link"/>
69
+ <body name="left_ankle_roll_link" pos="0 0 -0.017558">
70
+ <inertial pos="0.026505 0 -0.016425" quat="-0.000481092 0.728482 -0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
71
+ <joint name="left_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
72
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="left_ankle_roll_link"/>
73
+ <geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
74
+ <geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
75
+ <geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
76
+ <geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
77
+ </body>
78
+ </body>
79
+ </body>
80
+ </body>
81
+ </body>
82
+ </body>
83
+ <body name="right_hip_pitch_link" pos="0 -0.064452 -0.1027">
84
+ <inertial pos="0.002741 -0.047791 -0.02606" quat="0.954862 -0.293964 0.0302556 -0.030122" mass="1.35" diaginertia="0.00181517 0.00153422 0.00116212"/>
85
+ <joint name="right_hip_pitch_joint" pos="0 0 0" axis="0 1 0" range="-2.5307 2.8798" actuatorfrcrange="-88 88"/>
86
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
87
+ <geom type="mesh" rgba="0.2 0.2 0.2 1" mesh="right_hip_pitch_link"/>
88
+ <body name="right_hip_roll_link" pos="0 -0.052 -0.030465" quat="0.996179 0 -0.0873386 0">
89
+ <inertial pos="0.029812 0.001045 -0.087934" quat="0.977808 1.97119e-05 0.205576 0.0403793" mass="1.52" diaginertia="0.00254986 0.00241169 0.00148755"/>
90
+ <joint name="right_hip_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.9671 0.5236" actuatorfrcrange="-139 139"/>
91
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
92
+ <geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_roll_link"/>
93
+ <body name="right_hip_yaw_link" pos="0.025001 0 -0.12412">
94
+ <inertial pos="-0.057709 0.010981 -0.15078" quat="0.751181 0.223482 0.15832 0.600598" mass="1.702" diaginertia="0.00776166 0.00717575 0.00160139"/>
95
+ <joint name="right_hip_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.7576 2.7576" actuatorfrcrange="-88 88"/>
96
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
97
+ <geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_hip_yaw_link"/>
98
+ <body name="right_knee_link" pos="-0.078273 -0.0021489 -0.17734" quat="0.996179 0 0.0873386 0">
99
+ <inertial pos="0.005457 -0.003964 -0.12074" quat="0.923439 0.0345276 0.0116333 -0.382012" mass="1.932" diaginertia="0.011374 0.0112843 0.00146452"/>
100
+ <joint name="right_knee_joint" pos="0 0 0" axis="0 1 0" range="-0.087267 2.8798" actuatorfrcrange="-139 139"/>
101
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
102
+ <geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_knee_link"/>
103
+ <body name="right_ankle_pitch_link" pos="0 9.4445e-05 -0.30001">
104
+ <inertial pos="-0.007269 0 0.011137" quat="0.603053 0.369225 0.369225 0.603053" mass="0.074" diaginertia="1.89e-05 1.40805e-05 6.9195e-06"/>
105
+ <joint name="right_ankle_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.87267 0.5236" actuatorfrcrange="-50 50"/>
106
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
107
+ <geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_ankle_pitch_link"/>
108
+ <body name="right_ankle_roll_link" pos="0 0 -0.017558">
109
+ <inertial pos="0.026505 0 -0.016425" quat="0.000481092 0.728482 0.000618967 0.685065" mass="0.608" diaginertia="0.00167218 0.0016161 0.000217621"/>
110
+ <joint name="right_ankle_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.2618 0.2618" actuatorfrcrange="-50 50"/>
111
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="right_ankle_roll_link"/>
112
+ <geom size="0.005" pos="-0.05 0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
113
+ <geom size="0.005" pos="-0.05 -0.025 -0.03" rgba="0.2 0.2 0.2 1"/>
114
+ <geom size="0.005" pos="0.12 0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
115
+ <geom size="0.005" pos="0.12 -0.03 -0.03" rgba="0.2 0.2 0.2 1"/>
116
+ </body>
117
+ </body>
118
+ </body>
119
+ </body>
120
+ </body>
121
+ </body>
122
+ <body name="waist_yaw_link">
123
+ <inertial pos="0.003494 0.000233 0.018034" quat="0.289697 0.591001 -0.337795 0.672821" mass="0.214" diaginertia="0.000163531 0.000107714 0.000102205"/>
124
+ <joint name="waist_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-88 88"/>
125
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_yaw_link"/>
126
+ <body name="waist_roll_link" pos="-0.0039635 0 0.044">
127
+ <inertial pos="0 2.3e-05 0" quat="0.5 0.5 -0.5 0.5" mass="0.086" diaginertia="8.245e-06 7.079e-06 6.339e-06"/>
128
+ <joint name="waist_roll_joint" pos="0 0 0" axis="1 0 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
129
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="waist_roll_link"/>
130
+ <body name="torso_link">
131
+ <inertial pos="0.00203158 0.000339683 0.184568" quat="0.999803 -6.03319e-05 0.0198256 0.00131986" mass="7.818" diaginertia="0.121847 0.109825 0.0273735"/>
132
+ <joint name="waist_pitch_joint" pos="0 0 0" axis="0 1 0" range="-0.52 0.52" actuatorfrcrange="-50 50"/>
133
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
134
+ <geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="torso_link"/>
135
+ <geom pos="0.0039635 0 -0.044" quat="1 0 0 0" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
136
+ <geom pos="0.0039635 0 -0.044" quat="1 0 0 0" type="mesh" rgba="0.2 0.2 0.2 1" mesh="logo_link"/>
137
+ <geom pos="0.0039635 0 -0.044" type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
138
+ <geom pos="0.0039635 0 -0.044" type="mesh" rgba="0.2 0.2 0.2 1" mesh="head_link"/>
139
+ <site name="imu_in_torso" size="0.01" pos="-0.03959 -0.00224 0.14792"/>
140
+ <body name="left_shoulder_pitch_link" pos="0.0039563 0.10022 0.24778" quat="0.990264 0.139201 1.38722e-05 -9.86868e-05">
141
+ <inertial pos="0 0.035892 -0.011628" quat="0.654152 0.0130458 -0.326267 0.68225" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
142
+ <joint name="left_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
143
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_pitch_link"/>
144
+ <geom size="0.03 0.025" pos="0 0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
145
+ <body name="left_shoulder_roll_link" pos="0 0.038 -0.013831" quat="0.990268 -0.139172 0 0">
146
+ <inertial pos="-0.000227 0.00727 -0.063243" quat="0.701256 -0.0196223 -0.00710317 0.712604" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
147
+ <joint name="left_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-1.5882 2.2515" actuatorfrcrange="-25 25"/>
148
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_roll_link"/>
149
+ <geom size="0.03 0.015" pos="-0.004 0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
150
+ <body name="left_shoulder_yaw_link" pos="0 0.00624 -0.1032">
151
+ <inertial pos="0.010773 -0.002949 -0.072009" quat="0.716879 -0.0964829 -0.0679942 0.687134" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
152
+ <joint name="left_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
153
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
154
+ <geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_shoulder_yaw_link"/>
155
+ <body name="left_elbow_link" pos="0.015783 0 -0.080518">
156
+ <inertial pos="0.064956 0.004454 -0.010062" quat="0.541765 0.636132 0.388821 0.388129" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
157
+ <joint name="left_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
158
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
159
+ <geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="left_elbow_link"/>
160
+ </body>
161
+ </body>
162
+ </body>
163
+ </body>
164
+ <body name="right_shoulder_pitch_link" pos="0.0039563 -0.10021 0.24778" quat="0.990264 -0.139201 1.38722e-05 9.86868e-05">
165
+ <inertial pos="0 -0.035892 -0.011628" quat="0.68225 -0.326267 0.0130458 0.654152" mass="0.718" diaginertia="0.000465864 0.000432842 0.000406394"/>
166
+ <joint name="right_shoulder_pitch_joint" pos="0 0 0" axis="0 1 0" range="-3.0892 2.6704" actuatorfrcrange="-25 25"/>
167
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_pitch_link"/>
168
+ <geom size="0.03 0.025" pos="0 -0.04 -0.01" quat="0.707107 0 0.707107 0" type="cylinder" rgba="0.7 0.7 0.7 1"/>
169
+ <body name="right_shoulder_roll_link" pos="0 -0.038 -0.013831" quat="0.990268 0.139172 0 0">
170
+ <inertial pos="-0.000227 -0.00727 -0.063243" quat="0.712604 -0.00710317 -0.0196223 0.701256" mass="0.643" diaginertia="0.000691311 0.000618011 0.000388977"/>
171
+ <joint name="right_shoulder_roll_joint" pos="0 0 0" axis="1 0 0" range="-2.2515 1.5882" actuatorfrcrange="-25 25"/>
172
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_roll_link"/>
173
+ <geom size="0.03 0.015" pos="-0.004 -0.006 -0.053" type="cylinder" rgba="0.7 0.7 0.7 1"/>
174
+ <body name="right_shoulder_yaw_link" pos="0 -0.00624 -0.1032">
175
+ <inertial pos="0.010773 0.002949 -0.072009" quat="0.687134 -0.0679942 -0.0964829 0.716879" mass="0.734" diaginertia="0.00106187 0.00103217 0.000400661"/>
176
+ <joint name="right_shoulder_yaw_joint" pos="0 0 0" axis="0 0 1" range="-2.618 2.618" actuatorfrcrange="-25 25"/>
177
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
178
+ <geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_shoulder_yaw_link"/>
179
+ <body name="right_elbow_link" pos="0.015783 0 -0.080518">
180
+ <inertial pos="0.064956 -0.004454 -0.010062" quat="0.388129 0.388821 0.636132 0.541765" mass="0.6" diaginertia="0.000443035 0.000421612 0.000259353"/>
181
+ <joint name="right_elbow_joint" pos="0 0 0" axis="0 1 0" range="-1.0472 2.0944" actuatorfrcrange="-25 25"/>
182
+ <geom type="mesh" contype="0" conaffinity="0" group="1" density="0" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
183
+ <geom type="mesh" rgba="0.7 0.7 0.7 1" mesh="right_elbow_link"/>
184
+ </body>
185
+ </body>
186
+ </body>
187
+ </body>
188
+ </body>
189
+ </body>
190
+ </body>
191
+ </body>
192
+ </worldbody>
193
+
194
+ <actuator>
195
+ <motor name="left_hip_pitch_joint" joint="left_hip_pitch_joint"/>
196
+ <motor name="left_hip_roll_joint" joint="left_hip_roll_joint"/>
197
+ <motor name="left_hip_yaw_joint" joint="left_hip_yaw_joint"/>
198
+ <motor name="left_knee_joint" joint="left_knee_joint"/>
199
+ <motor name="left_ankle_pitch_joint" joint="left_ankle_pitch_joint"/>
200
+ <motor name="left_ankle_roll_joint" joint="left_ankle_roll_joint"/>
201
+ <motor name="right_hip_pitch_joint" joint="right_hip_pitch_joint"/>
202
+ <motor name="right_hip_roll_joint" joint="right_hip_roll_joint"/>
203
+ <motor name="right_hip_yaw_joint" joint="right_hip_yaw_joint"/>
204
+ <motor name="right_knee_joint" joint="right_knee_joint"/>
205
+ <motor name="right_ankle_pitch_joint" joint="right_ankle_pitch_joint"/>
206
+ <motor name="right_ankle_roll_joint" joint="right_ankle_roll_joint"/>
207
+ <motor name="waist_yaw_joint" joint="waist_yaw_joint"/>
208
+ <motor name="waist_roll_joint" joint="waist_roll_joint"/>
209
+ <motor name="waist_pitch_joint" joint="waist_pitch_joint"/>
210
+ <motor name="left_shoulder_pitch_joint" joint="left_shoulder_pitch_joint"/>
211
+ <motor name="left_shoulder_roll_joint" joint="left_shoulder_roll_joint"/>
212
+ <motor name="left_shoulder_yaw_joint" joint="left_shoulder_yaw_joint"/>
213
+ <motor name="left_elbow_joint" joint="left_elbow_joint"/>
214
+ <motor name="right_shoulder_pitch_joint" joint="right_shoulder_pitch_joint"/>
215
+ <motor name="right_shoulder_roll_joint" joint="right_shoulder_roll_joint"/>
216
+ <motor name="right_shoulder_yaw_joint" joint="right_shoulder_yaw_joint"/>
217
+ <motor name="right_elbow_joint" joint="right_elbow_joint"/>
218
+ </actuator>
219
+
220
+ <sensor>
221
+ <gyro name="imu-torso-angular-velocity" site="imu_in_torso" noise="5e-4" cutoff="34.9"/>
222
+ <accelerometer name="imu-torso-linear-acceleration" site="imu_in_torso" noise="1e-2" cutoff="157"/>
223
+ <gyro name="imu-pelvis-angular-velocity" site="imu_in_pelvis" noise="5e-4" cutoff="34.9"/>
224
+ <accelerometer name="imu-pelvis-linear-acceleration" site="imu_in_pelvis" noise="1e-2" cutoff="157"/>
225
+ </sensor>
226
+
227
+
228
+ <!-- setup scene -->
229
+ <statistic center="1.0 0.7 1.0" extent="0.8"/>
230
+ <visual>
231
+ <headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
232
+ <rgba haze="0.15 0.25 0.35 1"/>
233
+ <global azimuth="-140" elevation="-20"/>
234
+ </visual>
235
+ <asset>
236
+ <texture type="skybox" builtin="flat" rgb1="0 0 0" rgb2="0 0 0" width="512" height="3072"/>
237
+ <texture type="2d" name="groundplane" builtin="checker" mark="edge" rgb1="0.2 0.3 0.4" rgb2="0.1 0.2 0.3" markrgb="0.8 0.8 0.8" width="300" height="300"/>
238
+ <material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
239
+ </asset>
240
+ <worldbody>
241
+ <light pos="1 0 3.5" dir="0 0 -1" directional="true"/>
242
+ <geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
243
+ </worldbody>
244
+ </mujoco>