pxmlw6n2f/Gazebo_Distributed_TCP/worlds/pressure_sensor.world

161 lines
4.1 KiB
XML

<?xml version="1.0" ?>
<sdf version="1.5">
<world name="default">
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<model name="pressure_sensor_test">
<link name="base">
<pose>0 0 0.012 0 0 0</pose>
<collision name="base_collision">
<geometry>
<box>
<size>1 1 0.2</size>
</box>
</geometry>
</collision>
<visual name="base_visual">
<geometry>
<box>
<size>1 1 0.2</size>
</box>
</geometry>
<transparency>0.5</transparency>
</visual>
<collision name="pressure_pad_1">
<pose>0.45 0.45 -0.1 0 0 0</pose>
<geometry>
<box>
<size>0.1 0.1 0.02</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<kp>100000</kp>
<kd>1</kd>
</ode>
</contact>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
</ode>
</friction>
</surface>
</collision>
<collision name="pressure_pad_2">
<pose>0.45 -0.45 -0.1 0 0 0</pose>
<geometry>
<box>
<size>0.1 0.1 0.02</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<kp>100000</kp>
<kd>1</kd>
</ode>
</contact>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
</ode>
</friction>
</surface>
</collision>
<collision name="pressure_pad_3">
<pose>-0.45 0.45 -0.1 0 0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.02</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<kp>100000</kp>
<kd>1</kd>
</ode>
</contact>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
</ode>
</friction>
</surface>
</collision>
<collision name="pressure_pad_4">
<pose>-0.45 -0.45 -0.1 0 0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.02</size>
</box>
</geometry>
<surface>
<contact>
<ode>
<kp>100000</kp>
<kd>1</kd>
</ode>
</contact>
<friction>
<ode>
<mu>1</mu>
<mu2>1</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="pressure_pad_1">
<pose>0.45 0.45 -0.1 0 0 0</pose>
<geometry>
<box>
<size>0.1 0.1 0.02</size>
</box>
</geometry>
</visual>
<visual name="pressure_pad_2">
<pose>0.45 -0.45 -0.1 0 0 0</pose>
<geometry>
<box>
<size>0.1 0.1 0.02</size>
</box>
</geometry>
</visual>
<visual name="pressure_pad_3">
<pose>-0.45 0.45 -0.1 0 0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.02</size>
</box>
</geometry>
</visual>
<visual name="pressure_pad_4">
<pose>-0.45 -0.45 -0.1 0 0 0</pose>
<geometry>
<box>
<size>0.05 0.05 0.02</size>
</box>
</geometry>
</visual>
<sensor name="my_contact" type="contact">
<contact>
<collision>pressure_pad_1</collision>
<collision>pressure_pad_2</collision>
<collision>pressure_pad_3</collision>
<collision>pressure_pad_4</collision>
</contact>
<plugin name="my_plugin" filename="libPressurePlugin.so" />
</sensor>
</link>
</model>
</world>
</sdf>