-
Notifications
You must be signed in to change notification settings - Fork 49
/
mud_bitmask.world
59 lines (59 loc) · 1.65 KB
/
mud_bitmask.world
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
<?xml version="1.0" ?>
<sdf version="1.5">
<world name="default">
<include>
<uri>model://sun</uri>
</include>
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://pr2</uri>
<name>pr2_mud</name>
<pose>0.0 0 0 0 0 0</pose>
</include>
<model name="mud_pit">
<pose>0 0.0 0.5 0 0 0</pose>
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>5 1 1</size>
</box>
</geometry>
<surface>
<contact>
<collide_without_contact>true</collide_without_contact>
<collide_without_contact_bitmask>2</collide_without_contact_bitmask>
</contact>
</surface>
</collision>
<visual name="visual">
<geometry>
<box>
<size>5 1 1</size>
</box>
</geometry>
<material>
<ambient>0.2 0.2 0.2 1.0</ambient>
<diffuse>.421 0.225 0.0 1.0</diffuse>
</material>
</visual>
<sensor name="mud_contact" type="contact">
<always_on>true</always_on>
<update_rate>1000</update_rate>
<contact>
<collision>collision</collision>
</contact>
</sensor>
</link>
<plugin name="gazebo_mud" filename="libMudPlugin.so">
<contact_sensor_name>link/mud_contact</contact_sensor_name>
<stiffness>0.0</stiffness>
<damping>1.0</damping>
<link_name>pr2_mud::r_gripper_l_finger_link</link_name>
</plugin>
</model>
</world>
</sdf>