Files
RL-Sim-Framework/assets/motor/motor.xml
2026-06-10 21:15:34 +02:00

41 lines
1.4 KiB
XML

<?xml version="1.0" encoding="utf-8"?>
<mujoco model="motor_sysid">
<compiler angle="radian" autolimits="true"/>
<option timestep="0.002" integrator="Euler"/>
<worldbody>
<light pos="0 0 1" dir="0 0 -1"/>
<!-- Fixed base (gearbox housing) -->
<body name="base" pos="0 0 0.15">
<geom type="cylinder" size="0.04 0.06" mass="0.921"
rgba="0.3 0.3 0.3 1" contype="0" conaffinity="0"/>
<!-- Arm: rotates around motor_joint (z-axis) -->
<body name="arm" pos="0 0 0">
<joint name="motor_joint" type="hinge" axis="0 0 1"
range="-1.5708 1.5708"
damping="0.001" armature="0.0001" frictionloss="0.03"/>
<!-- Rotor disk: mass is tunable by the optimizer -->
<geom name="rotor_disk" type="cylinder" size="0.008 0.004"
mass="0.012" pos="0 0 0" rgba="0.6 0.6 0.6 1"
contype="0" conaffinity="0"/>
<!-- Arm load: lightweight arm attached to motor shaft -->
<geom name="arm_load" type="capsule" size="0.004"
fromto="0 0 0 -0.014 0.002 0.016"
mass="0.021" rgba="0.8 0.3 0.1 1"
contype="0" conaffinity="0"/>
</body>
</body>
</worldbody>
<actuator>
<general name="motor" joint="motor_joint"
gear="0.064"
ctrllimited="true" ctrlrange="-1 1"
dyntype="filter" dynprm="0.03"/>
</actuator>
</mujoco>