File size: 7,337 Bytes
4523cad
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
 
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
<mujoco model="model">
  <compiler angle="radian"/>
  <asset>
    <texture file="visuals/material_0.png" name="tex-model" type="2d"/>
    <texture type="2d" name="image0" file="visuals/image0.png"/>
    <material name="model" reflectance="0.5" texrepeat="1 1" texture="tex-model" texuniform="false"/>
    <material name="MI_electric_range_01" texture="image0" specular="0.5" shininess="0.25"/>
    <material name="MI_electric_range_glass" specular="0.5" shininess="1.0" rgba="0.103704 0.103704 0.103704 0.250000"/>
    <mesh file="visuals/model_0.obj" name="model_0_vis" scale="1 1 1"/>
    <mesh file="visuals/model_1.obj" name="model_1_vis" scale="1 1 1"/>
    <mesh file="visuals/knob_rear_center_0.obj" name="knob_rear_center_0_vis" scale="1 1 1"/>
    <mesh file="visuals/knob_rear_right_0.obj" name="knob_rear_right_0_vis" scale="1 1 1"/>
    <mesh file="visuals/knob_front_left_0.obj" name="knob_front_left_0_vis" scale="1 1 1"/>
    <mesh file="visuals/knob_front_right_0.obj" name="knob_front_right_0_vis" scale="1 1 1"/>
    <mesh file="visuals/knob_rear_left_0.obj" name="knob_rear_left_0_vis" scale="1 1 1"/>
  </asset>
  <default>
    <default class="visual">
      <geom conaffinity="0" contype="0" group="1" type="mesh"/>
    </default>
    <default class="collision">
      <geom group="0" rgba="0.5 0 0 0.5"/>
    </default>
  </default>
  <worldbody>
    <body>
      <body name="object">
        <geom solimp="0.998 0.998 0.001" solref="0.001 1" density="100" friction="0.95 0.3 0.1" type="mesh" mesh="model_0_vis" material="MI_electric_range_glass" class="visual"/>
        <geom solimp="0.998 0.998 0.001" solref="0.001 1" density="100" friction="0.95 0.3 0.1" type="mesh" mesh="model_1_vis" material="MI_electric_range_01" class="visual"/>
        <!--Add Collision Geom(s) for model here - i.e. <geom class="collision" type="" pos="" size=""/>-->
        <geom class="collision" pos="0 0.02 -0.13" size="0.32 0.275 0.36" type="box"/>
        <geom class="collision" pos="0 0.27 0.35" size="0.32 0.03 0.15" type="box"/>
        <geom class="collision" pos="0 0.23 0.37" size="0.32 0.01 0.025" type="box"/>
        <geom class="collision" pos="-0.025 0.24 0.43" size="0.13 0.01 0.03" type="box"/>
        <site name="burner_on_front_left" pos="-0.152 -0.10 0.223" size="0.10 0.0001" rgba="0.5 0 0 1" type="cylinder"/>
        <site name="burner_on_front_right" pos="0.152 -0.10 0.223" size="0.10 0.0001" rgba="0.5 0 0 1" type="cylinder"/>
        <site name="burner_on_rear_left" pos="-0.192 0.115 0.223" size="0.07 0.0001" rgba="0.5 0 0 1" type="cylinder"/>
        <site name="burner_on_rear_right" pos="0.19 0.115 0.223" size="0.07 0.0001" rgba="0.5 0 0 1" type="cylinder"/>
        <site name="burner_on_rear_center" pos="0.0 0.107 0.223" size="0.065 0.0001" rgba="0.5 0 0 1" type="cylinder"/>
        <site name="burner_front_left_place_site" pos="-0.152 -0.10 0.223" size="0.10 0.0001" rgba="0.5 0 0 0" type="cylinder"/>
        <site name="burner_front_right_place_site" pos="0.152 -0.10 0.223" size="0.10 0.0001" rgba="0.5 0 0 0" type="cylinder"/>
        <site name="burner_rear_left_place_site" pos="-0.192 0.115 0.223" size="0.07 0.0001" rgba="0.5 0 0 0" type="cylinder"/>
        <site name="burner_rear_right_place_site" pos="0.19 0.115 0.223" size="0.07 0.0001" rgba="0.5 0 0 0" type="cylinder"/>
        <site name="burner_rear_center_place_site" pos="0.0 0.107 0.223" size="0.065 0.0001" rgba="0.5 0 0 0" type="cylinder"/>
        <body name="knob_rear_center">
          <!--Add Joint Here-->
          <geom solimp="0.998 0.998 0.001" solref="0.001 1" density="100" friction="0.95 0.3 0.1" type="mesh" mesh="knob_rear_center_0_vis" material="MI_electric_range_01" class="visual"/>
          <!--Add Collision Geom(s) for knob_rear_center here - i.e. <geom class="collision" type="" pos="" size=""/>-->
          <joint pos="0.14 0.22 0.427" axis="0 1 0" type="hinge" damping="1" name="knob_rear_center_joint"/>
          <geom class="collision" pos="0.14 0.22 0.427" size="0.01 0.015 0.022" type="box" name="knob_rear_center_main"/>
        </body>
        <body name="knob_rear_right">
          <!--Add Joint Here-->
          <geom solimp="0.998 0.998 0.001" solref="0.001 1" density="100" friction="0.95 0.3 0.1" type="mesh" mesh="knob_rear_right_0_vis" material="MI_electric_range_01" class="visual"/>
          <!--Add Collision Geom(s) for knob_rear_right here - i.e. <geom class="collision" type="" pos="" size=""/>-->
          <joint pos="0.20 0.22 0.427" axis="0 1 0" type="hinge" damping="1" name="knob_rear_right_joint"/>
          <geom class="collision" pos="0.20 0.22 0.427" size="0.01 0.015 0.022" type="box" name="knob_rear_right_main"/>
        </body>
        <body name="knob_front_left">
          <!--Add Joint Here-->
          <geom solimp="0.998 0.998 0.001" solref="0.001 1" density="100" friction="0.95 0.3 0.1" type="mesh" mesh="knob_front_left_0_vis" material="MI_electric_range_01" class="visual"/>
          <!--Add Collision Geom(s) for knob_front_left here - i.e. <geom class="collision" type="" pos="" size=""/>-->
          <joint pos="-0.26 0.22 0.427" axis="0 1 0" type="hinge" damping="1" name="knob_front_left_joint"/>
          <geom class="collision" pos="-0.26 0.22 0.427" size="0.01 0.015 0.022" type="box" name="knob_front_left_main"/>
        </body>
        <body name="knob_front_right">
          <!--Add Joint Here-->
          <geom solimp="0.998 0.998 0.001" solref="0.001 1" density="100" friction="0.95 0.3 0.1" type="mesh" mesh="knob_front_right_0_vis" material="MI_electric_range_01" class="visual"/>
          <!--Add Collision Geom(s) for knob_front_right here - i.e. <geom class="collision" type="" pos="" size=""/>-->
          <joint pos="0.265 0.22 0.427" axis="0 1 0" type="hinge" damping="1" name="knob_front_right_joint"/>
          <geom class="collision" pos="0.265 0.22 0.427" size="0.01 0.015 0.022" type="box" name="knob_front_right_main"/>
        </body>
        <body name="knob_rear_left">
          <!--Add Joint Here-->
          <geom solimp="0.998 0.998 0.001" solref="0.001 1" density="100" friction="0.95 0.3 0.1" type="mesh" mesh="knob_rear_left_0_vis" material="MI_electric_range_01" class="visual"/>
          <!--Add Collision Geom(s) for knob_rear_left here - i.e. <geom class="collision" type="" pos="" size=""/>-->
          <joint pos="-0.20 0.22 0.427" axis="0 1 0" type="hinge" damping="1" name="knob_rear_left_joint"/>
          <geom class="collision" pos="-0.20 0.22 0.427" size="0.01 0.015 0.022" type="box" name="knob_rear_left_main"/>
        </body>
        <!-- exterior bounding box points -->
        <site rgba="1 1 1 1" size="0.01" pos="-0.32 -0.255 -0.50" name="ext_p0"/>
        <site rgba="1 0 0 1" size="0.01" pos="0.32 -0.255 -0.50" name="ext_px"/>
        <site rgba="0 1 0 1" size="0.01" pos="-0.32 0.295 -0.50" name="ext_py"/>
        <site rgba="0 0 1 1" size="0.01" pos="-0.32 -0.255 0.233" name="ext_pz"/>
        <!-- interior bounding box points -->
        <site rgba="0.5 0.5 0.5 1" size="0.01" pos="0 0 0" name="int_p0"/>
        <site rgba="1 1 0 1" size="0.01" pos="0 0 0" name="int_px"/>
        <site rgba="0 1 1 1" size="0.01" pos="0 0 0" name="int_py"/>
        <site rgba="1 0 1 1" size="0.01" pos="0 0 0" name="int_pz"/>
      </body>
    </body>
  </worldbody>
</mujoco>