New versions of mujoco no longer allow global coordinates. We therefore convert them to local ones. The original files are kept as reference.
		
			
				
	
	
		
			55 lines
		
	
	
		
			3.4 KiB
		
	
	
	
		
			XML
		
	
	
	
	
	
			
		
		
	
	
			55 lines
		
	
	
		
			3.4 KiB
		
	
	
	
		
			XML
		
	
	
	
	
	
| <mujoco model="hopper">
 | |
|   <compiler angle="radian" autolimits="true"/>
 | |
|   <option integrator="RK4"/>
 | |
|   <visual>
 | |
|     <map znear="0.02"/>
 | |
|   </visual>
 | |
|   <default class="main">
 | |
|     <joint limited="true" armature="1" damping="1"/>
 | |
|     <geom condim="1" solimp="0.8 0.8 0.01 0.5 2" margin="0.001" material="geom" rgba="0.8 0.6 0.4 1"/>
 | |
|     <general ctrllimited="true" ctrlrange="-0.4 0.4"/>
 | |
|   </default>
 | |
|   <asset>
 | |
|     <texture type="skybox" builtin="gradient" rgb1="0.4 0.5 0.6" rgb2="0 0 0" width="100" height="600"/>
 | |
|     <texture type="cube" name="texgeom" builtin="flat" mark="cross" rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" markrgb="1 1 1" width="127" height="762"/>
 | |
|     <texture type="2d" name="texplane" builtin="checker" rgb1="0 0 0" rgb2="0.8 0.8 0.8" width="100" height="100"/>
 | |
|     <material name="MatPlane" texture="texplane" texrepeat="60 60" specular="1" shininess="1" reflectance="0.5"/>
 | |
|     <material name="geom" texture="texgeom" texuniform="true"/>
 | |
|   </asset>
 | |
|   <worldbody>
 | |
|     <geom name="floor" size="20 20 0.125" type="plane" condim="3" material="MatPlane" rgba="0.8 0.9 0.8 1"/>
 | |
|     <light pos="0 0 1.3" dir="0 0 -1" directional="true" cutoff="100" exponent="1" diffuse="1 1 1" specular="0.1 0.1 0.1"/>
 | |
|     <body name="torso" pos="0 0 1.25" gravcomp="0">
 | |
|       <joint name="rootx" pos="0 0 -1.25" axis="1 0 0" limited="false" type="slide" armature="0" damping="0"/>
 | |
|       <joint name="rootz" pos="0 0 -1.25" axis="0 0 1" limited="false" type="slide" ref="1.25" armature="0" damping="0"/>
 | |
|       <joint name="rooty" pos="0 0 0" axis="0 1 0" limited="false" armature="0" damping="0"/>
 | |
|       <geom name="torso_geom" size="0.05 0.2" type="capsule" friction="0.9 0.005 0.0001"/>
 | |
|       <camera name="track" pos="0 -3 -0.25" quat="0.707107 0.707107 0 0" mode="trackcom"/>
 | |
|       <body name="thigh" pos="0 0 -0.2" gravcomp="0">
 | |
|         <joint name="thigh_joint" pos="0 0 0" axis="0 -1 0" range="-2.61799 0"/>
 | |
|         <geom name="thigh_geom" size="0.05 0.225" pos="0 0 -0.225" type="capsule" friction="0.9 0.005 0.0001"/>
 | |
|         <body name="leg" pos="0 0 -0.7" gravcomp="0">
 | |
|           <joint name="leg_joint" pos="0 0 0.25" axis="0 -1 0" range="-2.61799 0"/>
 | |
|           <geom name="leg_geom" size="0.04 0.25" type="capsule" friction="0.9 0.005 0.0001"/>
 | |
|           <body name="foot" pos="0.065 0 -0.25" gravcomp="0">
 | |
|             <joint name="foot_joint" pos="-0.065 0 0" axis="0 -1 0" range="-0.785398 0.785398"/>
 | |
|             <geom name="foot_geom" size="0.06 0.195" quat="0.707107 0 -0.707107 0" type="capsule" friction="2 0.005 0.0001"/>
 | |
|           </body>
 | |
|         </body>
 | |
|       </body>
 | |
|     </body>
 | |
|     <body name="ball" pos="0 0 1.53" gravcomp="0">
 | |
|       <joint name="tar:x" pos="0 0 0" axis="1 0 0" limited="false" type="slide" armature="0" damping="0"/>
 | |
|       <joint name="tar:y" pos="0 0 0" axis="0 1 0" limited="false" type="slide" armature="0" damping="0"/>
 | |
|       <joint name="tar:z" pos="0 0 0" axis="0 0 1" limited="false" type="slide" armature="0" damping="0"/>
 | |
|       <geom name="ball_geom" size="0.025" condim="4" priority="1" friction="0.1 0.1 0.1" solref="-10000 -10" solimp="0.9 0.95 0.001 0.5 2" mass="0.1" rgba="0.8 0.2 0.1 1"/>
 | |
|       <site name="target_ball" pos="0 0 0" size="0.04" rgba="1 0 0 1"/>
 | |
|     </body>
 | |
|   </worldbody>
 | |
|   <actuator>
 | |
|     <general joint="thigh_joint" ctrlrange="-1 1" gear="200 0 0 0 0 0" actdim="0"/>
 | |
|     <general joint="leg_joint" ctrlrange="-1 1" gear="200 0 0 0 0 0" actdim="0"/>
 | |
|     <general joint="foot_joint" ctrlrange="-1 1" gear="200 0 0 0 0 0" actdim="0"/>
 | |
|   </actuator>
 | |
| </mujoco>
 |