Skip to content

Commit

Permalink
Add bumper sensor separately
Browse files Browse the repository at this point in the history
  • Loading branch information
Nico van Duijn authored and TSC21 committed Mar 27, 2019
1 parent da97fe5 commit 2f0070e
Show file tree
Hide file tree
Showing 3 changed files with 61 additions and 35 deletions.
41 changes: 41 additions & 0 deletions models/bumper_sensor/bumper_sensor.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,41 @@
<?xml version="1.0" ?>
<sdf version="1.4">
<model name="bumper_sensor">
<!-- Only difference to regular iris is this sensor and a MAVLink stream -->
<link name="bumper_link">
<inertial>
<pose>0.01 0.025 0.025 0 0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>4.15e-6</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>2.407e-6</iyy>
<iyz>0</iyz>
<izz>2.407e-6</izz>
</inertia>
</inertial>

<collision name='bumper_collision'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<box>
<size>0.47 0.47 0.11</size>
</box>
</geometry>
</collision>

<sensor name="bumper_sensor" type="contact">
<always_on>true</always_on>
<update_rate>30.0</update_rate>
<contact>
<collision>bumper_collision</collision>
</contact>
<plugin name="benchmarking_bumper" filename="libgazebo_ros_bumper.so">
<bumperTopicName>benchmarker/collision</bumperTopicName>
</plugin>
</sensor>

</link>
</model>
</sdf>
16 changes: 16 additions & 0 deletions models/bumper_sensor/model.config
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
<?xml version="1.0"?>
<model>
<name>Bumper Sensor</name>
<version>1.0</version>
<sdf version='1.4'>bumper_sensor.sdf</sdf>

<author>
<name>Nico van Duijn</name>
<email>nico@auterion.com</email>
</author>

<description>
This is a model of a simple bumper sensor.
It uses the gazebo-ros plugin to publish collisions on a ROS topic
</description>
</model>
39 changes: 4 additions & 35 deletions models/iris_obs_avoid/iris_obs_avoid.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -5,43 +5,12 @@
</include>

<!-- Only difference to regular iris is this sensor and a MAVLink stream -->
<link name="bumper_link">
<inertial>
<pose>0.01 0.025 0.025 0 0 0</pose>
<mass>0.01</mass>
<inertia>
<ixx>4.15e-6</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>2.407e-6</iyy>
<iyz>0</iyz>
<izz>2.407e-6</izz>
</inertia>
</inertial>

<collision name='bumper_collision'>
<pose>0 0 0 0 -0 0</pose>
<geometry>
<box>
<size>0.47 0.47 0.11</size>
</box>
</geometry>
</collision>

<sensor name="bumper_sensor" type="contact">
<always_on>true</always_on>
<update_rate>30.0</update_rate>
<contact>
<collision>bumper_collision</collision>
</contact>
<plugin name="benchmarking_bumper" filename="libgazebo_ros_bumper.so">
<bumperTopicName>benchmarker/collision</bumperTopicName>
</plugin>
</sensor>
</link>
<include>
<uri>model://bumper_sensor</uri>
</include>

<joint name="bumper_joint" type="revolute">
<child>bumper_link</child>
<child>bumper_sensor::bumper_link</child>
<parent>iris::base_link</parent>
<axis>
<xyz>0 0 1</xyz>
Expand Down

0 comments on commit 2f0070e

Please sign in to comment.