Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Acoustic comms plugin #1608

Merged
merged 19 commits into from
Aug 24, 2022
Merged
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
254 changes: 254 additions & 0 deletions examples/worlds/acoustic_comms.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,254 @@
<?xml version="1.0" ?>
<!--
Gazebo acoustic-comms plugin demo.
-->
<sdf version="1.6">
<world name="acoustic_comms">

<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="gz-sim-physics-system"
name="gz::sim::systems::Physics">
</plugin>
<plugin
filename="gz-sim-user-commands-system"
name="gz::sim::systems::UserCommands">
</plugin>
<plugin
filename="gz-sim-scene-broadcaster-system"
name="gz::sim::systems::SceneBroadcaster">
</plugin>
<plugin
filename="gz-sim-acoustic-comms-system"
name="gz::sim::systems::AcousticComms">
<max_range>6</max_range>
<speed_of_sound>1400</speed_of_sound>
</plugin>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>1 1 1 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>

<model name="box1">
<pose>2 0 0.5 0 0 0</pose>
<link name="box_link">
<inertial>
<inertia>
<ixx>0.16666</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.16666</iyy>
<iyz>0</iyz>
<izz>0.16666</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="box_collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>

<visual name="box_visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1 0 0 1</diffuse>
<specular>1 0 0 1</specular>
</material>
</visual>
</link>

<plugin
filename="gz-sim-comms-endpoint-system"
name="gz::sim::systems::CommsEndpoint">
<address>addr1</address>
<topic>addr1/rx</topic>
</plugin>
</model>

<model name="box2">
<pose>-2 0 0.5 0 0 0</pose>
<link name="box_link">
<inertial>
<inertia>
<ixx>0.16666</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.16666</iyy>
<iyz>0</iyz>
<izz>0.16666</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="box_collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>

<visual name="box_visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<ambient>0 0 1 1</ambient>
<diffuse>0 0 1 1</diffuse>
<specular>0 0 1 1</specular>
</material>
</visual>
</link>

<plugin
filename="gz-sim-comms-endpoint-system"
name="gz::sim::systems::CommsEndpoint">
<address>addr2</address>
<topic>addr2/rx</topic>
<broker>
<bind_service>/broker/bind</bind_service>
<unbind_service>/broker/unbind</unbind_service>
</broker>
</plugin>

</model>

<model name="box3">
<pose>5 0 0.5 0 0 0</pose>
<link name="box_link">
<inertial>
<inertia>
<ixx>0.16666</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.16666</iyy>
<iyz>0</iyz>
<izz>0.16666</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="box_collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>

<visual name="box_visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1 0 0 1</diffuse>
<specular>1 0 0 1</specular>
</material>
</visual>
</link>

<plugin
filename="gz-sim-comms-endpoint-system"
name="gz::sim::systems::CommsEndpoint">
<address>addr3</address>
<topic>addr3/rx</topic>
</plugin>
</model>

<model name="box4">
<pose>-5 0 0.5 0 0 0</pose>
<link name="box_link">
<inertial>
<inertia>
<ixx>0.16666</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.16666</iyy>
<iyz>0</iyz>
<izz>0.16666</izz>
</inertia>
<mass>1.0</mass>
</inertial>
<collision name="box_collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>

<visual name="box_visual">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1 0 0 1</diffuse>
<specular>1 0 0 1</specular>
</material>
</visual>
</link>

<plugin
filename="gz-sim-comms-endpoint-system"
name="gz::sim::systems::CommsEndpoint">
<address>addr4</address>
<topic>addr4/rx</topic>
</plugin>
</model>

</world>
</sdf>
1 change: 1 addition & 0 deletions src/systems/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,7 @@ function(gz_add_system system_name)
endfunction()

add_subdirectory(ackermann_steering)
add_subdirectory(acoustic_comms)
add_subdirectory(air_pressure)
add_subdirectory(altimeter)
add_subdirectory(apply_joint_force)
Expand Down
Loading