-
Notifications
You must be signed in to change notification settings - Fork 4
Expand file tree
/
Copy pathteleOp_objects.xml
More file actions
104 lines (84 loc) · 5.19 KB
/
teleOp_objects.xml
File metadata and controls
104 lines (84 loc) · 5.19 KB
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
95
96
97
98
99
100
101
102
103
104
<mujoco model="fetch_objects(v2.0)">
<!-- =================================================
Copyright 2016 Vikash Kumar
Model :: Fetch (MuJoCoV2.0)
Author :: Vikash Kumar (vikashplus@gmail.com)
Details :: https://github.com/vikashplus/fetch_sim
License :: Under Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
====================================================== -©vk©-->
<visual>
<quality shadowsize="2048"/>
<map fogstart="6" fogend="10"/>
<headlight diffuse=".6 .6 .6" specular="0 0 0"/>
</visual>
<size nconmax="500" njmax="1000"/>
<include file="../fetch_sim/assets/asset.xml"/>
<include file="door/asset.xml"/>
<include file="table/asset.xml"/>
<include file="box/asset.xml"/>
<asset>
<texture name="texplane" type="2d" builtin="checker" rgb1=".2 .3 .4" rgb2=".1 0.15 0.2" width="100" height="100"/>
<material name='MatPlane' reflectance='0.5' texture="texplane" texrepeat="1 1" texuniform="true"/>
</asset>
<!-- Bind mocap -©vk©-->
<equality>
<weld body1="mocap0" body2="gripper_link" solref="0.01 1" solimp=".02 .1 0.050"/>
</equality>
<default>
<default class="obj">
<geom solref="0.008 1" solimp="0.93 0.97 0.001" margin="0.001" user="0" type="mesh" rgba="1 1 1 1" material="geomMat" condim="4"/>
</default>
</default>
<worldbody>
<geom name='floor' pos='0 0 0' size='10 10 0.125' type='plane' material="MatPlane" condim='3'/>
<light directional="false" cutoff="35" exponent="10" diffuse=".7 .7 .7" pos="1 -0.2 2.5" dir="-0.4 1 -1.5" specular=".3 .3 .3"/>
<!--Mocap body for tele-op-©vk©-->
<body name="mocap0" mocap="true" pos="0.300 1.234 0.786" euler="1.57 0 0">
<geom type="mesh" mesh="gripper_link" group="2" euler="1.57 0 -1.57" contype="0" conaffinity="0" rgba=".5 .5 .5 0.15" pos="0 0 -0.16645"/>
<geom type="mesh" mesh="wrist_roll_link" group="2" euler="0 1.57 0" contype="0" conaffinity="0" rgba=".5 .5 .5 0.15"/>
</body>
<include file="../fetch_sim/assets/body.xml"/>
<body name="Table" pos="0.3 1 0.5">
<include file="table/chain.xml"/>
</body>
<body name="DoorLR" pos="-.225 0.45 0.57" euler="0 0 1.57">
<include file="door/chain0.xml"/>
</body>
<body name="DoorUR" pos="-.225 0.45 1.175" euler="0 0 1.57">
<include file="door/chain1.xml"/>
</body>
<body name="Shelf" pos="-1 -.2 0.5">
<include file="shelf/chain.xml"/>
</body>
<body childclass="obj" name="book" pos=".8 1.2 .8" euler="0 0 1.2">
<inertial pos="0 0 0" mass=".01" diaginertia="0.00005 0.00008 0.00004"/>
<geom name="C_book" type="box" group="3" size="0.1 0.030 .2" rgba="0.1 0.5 0.6 1" contype="0" conaffinity="1"/>
<geom group="1" name="V_book" type="box" size="0.1 0.030 .2" rgba="0.3 0.2 0.5 1"/>
<joint name="Jrect" type="free" limited="false"/>
<!--<site name="book_handle" pos="-.07 0 0" group="2" euler="0 0 -1.57"/>-©vk©-->
</body>
<body childclass="obj" name="bottle" pos="-.1 1.0 .5" >
<inertial pos="0 0 0.13" mass=".01" diaginertia="0.00003 0.00003 0.000005"/>
<geom group="1" type="capsule" size="0.0351 .095" rgba="0.8 0.6 0.8 1" pos="0 0 .125"/>
<geom group="1" type="cylinder" size="0.0351 .02" rgba="0.8 0.6 0.8 1" pos="0 0 .015"/>
<geom group="1" type="cylinder" size="0.015 .007" rgba="0.8 0.7 0.8 1" pos="0 0 .260"/>
<geom type="capsule" group="3" size="0.035 0.09" rgba="0.1 0.5 0.6 1" contype="0" conaffinity="1" pos="0 0 .13"/>
<geom type="capsule" group="3" size="0.005 0.04" rgba="0.1 0.5 0.6 1" contype="0" conaffinity="1" euler="1.57 0 0"/>
<geom type="capsule" group="3" size="0.005 0.04" rgba="0.1 0.5 0.6 1" contype="0" conaffinity="1" euler="0 1.57 0"/>
<joint name="Jbottle" type="free" limited="false" damping="0.0001" armature="0"/>
<!--<site name="bottle_handle" pos="0 0 .13" group="2" euler="0 0 0"/>-©vk©-->
</body>
<body childclass="obj" name="glass" pos="-.15 1.2 .5">
<inertial pos="0 0 0.13" mass=".05" diaginertia="0.00003 0.00003 0.000005"/>
<geom group="1" type="capsule" size="0.0351 .07" rgba="0.7 0.9 0.8 1" pos="0 0 .15"/>
<geom group="1" type="cylinder" size="0.0351 .002" rgba="0.7 0.9 0.8 1" pos="0 0 -.003"/>
<geom group="1" type="cylinder" size="0.0351 .020" rgba="0.7 0.9 0.8 1" pos="0 0 .237"/>
<geom group="1" type="cylinder" size="0.0050 .025" rgba="0.7 0.9 0.8 1" pos="0 0 .025"/>
<geom type="capsule" group="3" size="0.035 0.07" rgba="0.1 0.5 0.6 1" contype="0" conaffinity="1" pos="0 0 .15"/>
<geom type="capsule" group="3" size="0.005 0.04" rgba="0.1 0.5 0.6 1" contype="0" conaffinity="1" euler="1.57 0 0"/>
<geom type="capsule" group="3" size="0.005 0.04" rgba="0.1 0.5 0.6 1" contype="0" conaffinity="1" euler="0 1.57 0"/>
<joint name="Jglass" type="free" limited="false" damping="0.0001" armature="0"/>
<!--<site name="glass_handle" pos="0 0 .15" group="2"/>-©vk©-->
</body>
</worldbody>
</mujoco>