1
1
<mujoco model =" hopper" >
2
- <compiler angle =" degree" inertiafromgeom =" true" />
3
- <default >
4
- <joint armature =" 1" damping =" 1" limited =" true" />
5
- <geom conaffinity =" 1" condim =" 1" contype =" 1" margin =" 0.001" friction =" 0.8 .1 .1" rgba =" 0.8 0.6 .4 1" solimp =" .8 .8 .01" solref =" .02 1" />
6
- <motor ctrllimited =" true" ctrlrange =" -.4 .4" />
7
- </default >
8
- <option integrator =" RK4" timestep =" 0.002" />
9
- <worldbody >
10
- <body name =" torso" >
11
- <joint armature =" 0" axis =" 1 0 0" damping =" 0" limited =" false" name =" ignore1" pos =" 0 0 0" stiffness =" 0" type =" slide" />
12
- <joint armature =" 0" axis =" 0 0 1" damping =" 0" limited =" false" name =" ignore2" pos =" 0 0 0" ref =" 1.25" stiffness =" 0" type =" slide" />
13
- <joint armature =" 0" axis =" 0 1 0" damping =" 0" limited =" false" name =" ignore3" pos =" 0 0 0" stiffness =" 0" type =" hinge" />
14
- <geom fromto =" 0 0 1.45 0 0 1.05" name =" torso_geom" size =" 0.05" type =" capsule" />
15
- <body name =" thigh" >
16
- <joint axis =" 0 -1 0" name =" thigh_joint" pos =" 0 0 1.05" range =" -150 0" type =" hinge" />
17
- <geom fromto =" 0 0 1.05 0 0 0.6" name =" thigh_geom" size =" 0.05" type =" capsule" />
18
- <body name =" leg" >
19
- <joint axis =" 0 -1 0" name =" leg_joint" pos =" 0 0 0.6" range =" -150 0" type =" hinge" />
20
- <geom fromto =" 0 0 0.6 0 0 0.1" name =" leg_geom" size =" 0.04" type =" capsule" />
21
- <body name =" foot" >
22
- <joint axis =" 0 -1 0" name =" foot_joint" pos =" 0 0 0.1" range =" -45 45" type =" hinge" />
23
- <geom fromto =" -0.13 0 0.1 0.26 0 0.1" name =" foot_geom" size =" 0.06" type =" capsule" />
24
- </body >
2
+ <compiler angle =" degree" />
3
+ <default >
4
+ <joint armature =" 1" damping =" 1" limited =" true" />
5
+ <geom conaffinity =" 1" condim =" 1" contype =" 1" margin =" 0.001" friction =" 0.8 .1 .1" rgba =" 0.8 0.6 .4 1"
6
+ solimp =" .8 .8 .01" solref =" .02 1" />
7
+ <motor ctrllimited =" true" ctrlrange =" -.4 .4" />
8
+ </default >
9
+ <option integrator =" RK4" timestep =" 0.002" />
10
+ <worldbody >
11
+ <body name =" torso" >
12
+ <inertial mass =" 10" pos =" 0 0 0" diaginertia =" 0.1 0.1 0.1" />
13
+ <joint armature =" 0" axis =" 1 0 0" damping =" 0" limited =" false" name =" ignore1" stiffness =" 0" type =" slide" />
14
+ <body >
15
+ <inertial mass =" 1" pos =" 0 0 0" diaginertia =" 0.01 0.01 0.01" />
16
+ <joint armature =" 0" axis =" 0 0 1" damping =" 0" limited =" false" name =" ignore2" ref =" 1.25" stiffness =" 0" type =" slide" />
17
+ <body >
18
+ <joint armature =" 0" axis =" 0 1 0" damping =" 0" limited =" false" name =" ignore3" stiffness =" 0" type =" hinge" />
19
+ <geom fromto =" 0 0 1.45 0 0 1.05" name =" torso_geom" size =" 0.05" type =" capsule" />
20
+ <body name =" thigh" >
21
+ <joint axis =" 0 -1 0" name =" thigh_joint" pos =" 0 0 1.05" range =" -150 0" type =" hinge" />
22
+ <geom fromto =" 0 0 1.05 0 0 0.6" name =" thigh_geom" size =" 0.05" type =" capsule" />
23
+ <body name =" leg" >
24
+ <joint axis =" 0 -1 0" name =" leg_joint" pos =" 0 0 0.6" range =" -150 0" type =" hinge" />
25
+ <geom fromto =" 0 0 0.6 0 0 0.1" name =" leg_geom" size =" 0.04" type =" capsule" />
26
+ <body name =" foot" >
27
+ <joint axis =" 0 -1 0" name =" foot_joint" pos =" 0 0 0.1" range =" -45 45" type =" hinge" />
28
+ <geom fromto =" -0.13 0 0.1 0.26 0 0.1" name =" foot_geom" size =" 0.06" type =" capsule" />
29
+ </body >
30
+ </body >
31
+ </body >
32
+ </body >
33
+ </body >
25
34
</body >
26
- </body >
27
- </body >
28
- </worldbody >
29
- <actuator >
30
- <motor ctrllimited =" true" ctrlrange =" -1.0 1.0" gear =" 200.0" joint =" thigh_joint" />
31
- <motor ctrllimited =" true" ctrlrange =" -1.0 1.0" gear =" 200.0" joint =" leg_joint" />
32
- <motor ctrllimited =" true" ctrlrange =" -1.0 1.0" gear =" 200.0" joint =" foot_joint" />
33
- </actuator >
35
+ </worldbody >
36
+ <actuator >
37
+ <motor ctrllimited =" true" ctrlrange =" -1.0 1.0" gear =" 200.0" joint =" thigh_joint" />
38
+ <motor ctrllimited =" true" ctrlrange =" -1.0 1.0" gear =" 200.0" joint =" leg_joint" />
39
+ <motor ctrllimited =" true" ctrlrange =" -1.0 1.0" gear =" 200.0" joint =" foot_joint" />
40
+ </actuator >
34
41
</mujoco >
0 commit comments