Behron 60aaea751f Finished fixing merge conflicts and touched up camera settings.
More merge conflicts. Taking main changes then will integrate mine.
2025-04-10 13:20:26 -06:00

34 lines
1.5 KiB
XML

<mujoco model="apptronik_apollo scene">
<include file="apptronik_apollo.xml"/>
<option timestep="0.005" iterations="4" ls_iterations="10" integrator="implicitfast"/>
<statistic center="1 -0.8 1.1" extent=".35"/>
<visual>
<headlight diffuse="0.6 0.6 0.6" ambient="0.1 0.1 0.1" specular="0.9 0.9 0.9"/>
<rgba haze="0.15 0.25 0.35 1"/>
<global azimuth="140" elevation="-20"/>
</visual>
<asset>
<texture type="skybox" builtin="gradient" rgb1="0.3 0.5 0.7" rgb2="0 0 0" width="512" height="3072"/>
<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"/>
<material name="groundplane" texture="groundplane" texuniform="true" texrepeat="5 5" reflectance="0.2"/>
</asset>
<worldbody>
<geom name="floor" size="0 0 0.05" type="plane" material="groundplane"/>
</worldbody>
<contact>
<pair geom1="collision_l_sole" geom2="floor" condim="6" solref="0.005 1" friction="2 2 0.01 0.0001 0.0001"/>
<pair geom1="collision_r_sole" geom2="floor" condim="6" solref="0.005 1" friction="2 2 0.01 0.0001 0.0001"/>
<pair geom1="collision_cylinder_l_arm" geom2="collision_capsule_body_pelvis" condim="1"/>
<pair geom1="collision_cylinder_r_arm" geom2="collision_capsule_body_pelvis" condim="1"/>
<pair geom1="collision_capsule_body_l_thigh" geom2="collision_capsule_body_r_thigh" condim="1"/>
<pair geom1="collision_capsule_body_l_shin" geom2="collision_capsule_body_r_shin" condim="1"/>
</contact>
</mujoco>