123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172 |
- <mujoco>
- <compiler autolimits="true"/>
- <asset>
- <texture name="grid" type="2d" builtin="checker" width="512" height="512" rgb1=".1 .2 .3" rgb2=".2 .3 .4"/>
- <material name="grid" texture="grid" texrepeat="1 1" texuniform="true" reflectance=".2"/>
- <mesh name="chasis" scale=".01 .006 .0015"
- vertex=" 9 2 0
- -10 10 10
- 9 -2 0
- 10 3 -10
- 10 -3 -10
- -8 10 -10
- -10 -10 10
- -8 -10 -10
- -5 0 20"/>
- </asset>
- <default>
- <joint damping=".03" actuatorfrcrange="-0.5 0.5"/>
- <default class="wheel">
- <geom type="cylinder" size=".03 .01" rgba=".5 .5 1 1"/>
- </default>
- <default class="decor">
- <site type="box" rgba=".5 1 .5 1"/>
- </default>
- </default>
- <worldbody>
- <geom type="plane" size="3 3 .01" material="grid"/>
- <body name="car" pos="0 0 .03">
- <freejoint/>
- <light name="top light" pos="0 0 2" mode="trackcom" diffuse=".4 .4 .4"/>
- <geom name="chasis" type="mesh" mesh="chasis"/>
- <geom name="front wheel" pos=".08 0 -.015" type="sphere" size=".015" condim="1" priority="1"/>
- <light name="front light" pos=".1 0 .02" dir="2 0 -1" diffuse="1 1 1"/>
- <body name="left wheel" pos="-.07 .06 0" zaxis="0 1 0">
- <joint name="left"/>
- <geom class="wheel"/>
- <site class="decor" size=".006 .025 .012"/>
- <site class="decor" size=".025 .006 .012"/>
- </body>
- <body name="right wheel" pos="-.07 -.06 0" zaxis="0 1 0">
- <joint name="right"/>
- <geom class="wheel"/>
- <site class="decor" size=".006 .025 .012"/>
- <site class="decor" size=".025 .006 .012"/>
- </body>
- </body>
- </worldbody>
- <tendon>
- <fixed name="forward">
- <joint joint="left" coef=".5"/>
- <joint joint="right" coef=".5"/>
- </fixed>
- <fixed name="turn">
- <joint joint="left" coef="-.5"/>
- <joint joint="right" coef=".5"/>
- </fixed>
- </tendon>
- <actuator>
- <motor name="forward" tendon="forward" ctrlrange="-1 1"/>
- <motor name="turn" tendon="turn" ctrlrange="-1 1"/>
- </actuator>
- <sensor>
- <jointactuatorfrc name="right" joint="right"/>
- <jointactuatorfrc name="left" joint="left"/>
- </sensor>
- </mujoco>
|