Goran Lazarevski 669cf5383b Lucky World source code
2025-03-18 19:25:25 +01:00

72 lines
2.8 KiB
XML

<mujoco model="Skydio X2">
<compiler autolimits="true" assetdir="assets"/>
<option timestep="0.01" density="1.225" viscosity="1.8e-5"/>
<default>
<default class="x2">
<geom mass="0"/>
<motor ctrlrange="0 13"/>
<mesh scale="0.01 0.01 0.01"/>
<default class="visual">
<geom group="2" type="mesh" contype="0" conaffinity="0"/>
</default>
<default class="collision">
<geom group="3" type="box"/>
<default class="rotor">
<geom type="ellipsoid" size=".13 .13 .01"/>
</default>
</default>
<site group="5"/>
</default>
</default>
<asset>
<texture type="2d" file="X2_lowpoly_texture_SpinningProps_1024.png"/>
<material name="phong3SG" texture="X2_lowpoly_texture_SpinningProps_1024"/>
<material name="invisible" rgba="0 0 0 0"/>
<mesh class="x2" file="X2_lowpoly.obj"/>
</asset>
<worldbody>
<light name="spotlight" mode="targetbodycom" target="x2" pos="0 -1 2"/>
<body name="x2" pos="0 0 0.1" childclass="x2">
<freejoint/>
<camera name="track" pos="-1 0 .5" xyaxes="0 -1 0 1 0 2" mode="trackcom"/>
<site name="imu" pos="0 0 .02"/>
<geom material="phong3SG" mesh="X2_lowpoly" class="visual" quat="0 0 1 1"/>
<geom class="collision" size=".06 .027 .02" pos=".04 0 .02"/>
<geom class="collision" size=".06 .027 .02" pos=".04 0 .06"/>
<geom class="collision" size=".05 .027 .02" pos="-.07 0 .065"/>
<geom class="collision" size=".023 .017 .01" pos="-.137 .008 .065" quat="1 0 0 1"/>
<geom name="rotor1" class="rotor" pos="-.14 -.18 .05" mass=".25"/>
<geom name="rotor2" class="rotor" pos="-.14 .18 .05" mass=".25"/>
<geom name="rotor3" class="rotor" pos=".14 .18 .08" mass=".25"/>
<geom name="rotor4" class="rotor" pos=".14 -.18 .08" mass=".25"/>
<geom size=".16 .04 .02" pos="0 0 0.02" type="ellipsoid" mass=".325" class="visual" material="invisible"/>
<site name="thrust1" pos="-.14 -.18 .05"/>
<site name="thrust2" pos="-.14 .18 .05"/>
<site name="thrust3" pos=".14 .18 .08"/>
<site name="thrust4" pos=".14 -.18 .08"/>
</body>
</worldbody>
<actuator>
<motor class="x2" name="thrust1" site="thrust1" gear="0 0 1 0 0 -.0201"/>
<motor class="x2" name="thrust2" site="thrust2" gear="0 0 1 0 0 .0201"/>
<motor class="x2" name="thrust3" site="thrust3" gear="0 0 1 0 0 .0201"/>
<motor class="x2" name="thrust4" site="thrust4" gear="0 0 1 0 0 -.0201"/>
</actuator>
<sensor>
<gyro name="body_gyro" site="imu"/>
<accelerometer name="body_linacc" site="imu"/>
<framequat name="body_quat" objtype="site" objname="imu"/>
</sensor>
<keyframe>
<key name="hover" qpos="0 0 .3 1 0 0 0" ctrl="3.2495625 3.2495625 3.2495625 3.2495625"/>
</keyframe>
</mujoco>