Skip to content
Merged
Show file tree
Hide file tree
Changes from all 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
26 changes: 14 additions & 12 deletions vrx_urdf/wamv_gazebo/urdf/components/wamv_pinger.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -21,35 +21,37 @@
<child link="${namespace}/${name}"/>
</joint>

<!--
<gazebo>
<plugin name="pinger_plugin" filename="libusv_gazebo_acoustic_pinger_plugin.so">
<frameId>${frameId}</frameId>
<topicName>${namespace}/${sensor_namespace}${pinger_namespace}${name}/range_bearing</topicName>
<setPositionTopicName>${namespace}/${sensor_namespace}${pinger_namespace}${name}/set_pinger_position</setPositionTopicName>
<rangeNoise>
<plugin
filename="libAcousticPingerPlugin.so"
name="vrx::AcousticPingerPlugin">
<position>${position}</position>
<topic>${namespace}/${pinger_namespace}${name}/range_bearing</topic>
<set_position_topic>${namespace}/${pinger_namespace}${name}/set_pinger_position
</set_position_topic>
<frame_id>${namespace}/${name}</frame_id>
<range_noise>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>3.0</stddev>
</noise>
</rangeNoise>
<bearingNoise>
</range_noise>
<bearing_noise>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</bearingNoise>
<elevationNoise>
</bearing_noise>
<elevation_noise>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.01</stddev>
</noise>
</elevationNoise>
</elevation_noise>
</plugin>
</gazebo>
-->
</xacro:macro>
</robot>
4 changes: 2 additions & 2 deletions vrx_urdf/wamv_gazebo/urdf/wamv_gazebo.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@

<!-- Add pinger -->
<xacro:if value="$(arg pinger_enabled)">
<xacro:wamv_pinger name="pinger" position="1.0 0 -1.0" />
<xacro:wamv_pinger name="pinger" position="-528 191 -2.0" />
</xacro:if>

<!-- Add ball shooter (default pitch angle: ~-60 deg) -->
Expand Down Expand Up @@ -194,7 +194,7 @@
<xacro:lidar name="lidar_wamv" type="16_beam"/>

<!-- Add pinger -->
<xacro:wamv_pinger name="pinger" position="1.0 0 -1.0" />
<xacro:wamv_pinger name="pinger" position="-528 191 -2.0" />

<!-- Add ball shooter (default pitch angle: ~-60 deg) -->
<xacro:wamv_ball_shooter name="ball_shooter" x="0.54" y="0.30" z="1.296" pitch="-1.04"/>
Expand Down