Add the initial (untested) gazebo plugin configuration.
This commit is contained in:
@@ -34,24 +34,47 @@
|
||||
<!-- ─────────────────────────────────────────────────────────────────────
|
||||
Gazebo sonar sensor (Gazebo Harmonic / gz-sim)
|
||||
|
||||
Simulated as a narrow-cone ray sensor. Data is published on gz topic
|
||||
/ultrasonic/range and bridged to ROS 2 via ros_gz_bridge:
|
||||
/ultrasonic/range (gz) → /ultrasonic/range (ROS 2, sensor_msgs/Range)
|
||||
gz-sim has no native sonar sensor type. The HC-SR04 is approximated
|
||||
as a narrow-cone gpu_lidar — a 5×5 ray grid spanning ±7.5° (≈15° FOV)
|
||||
in both axes, which matches the HC-SR04's beam pattern.
|
||||
|
||||
The sensor publishes a gz LaserScan on /ultrasonic/scan. Bridge this
|
||||
to ROS 2 via ros_gz_bridge, then convert to sensor_msgs/Range with a
|
||||
small relay node (or just consume the LaserScan directly):
|
||||
/ultrasonic/scan (gz LaserScan) → /ultrasonic/scan (ROS 2)
|
||||
───────────────────────────────────────────────────────────────────── -->
|
||||
<gazebo reference="ultrasonic">
|
||||
<sensor name="sonar" type="sonar">
|
||||
<sensor name="sonar" type="gpu_lidar">
|
||||
<always_on>1</always_on>
|
||||
<update_rate>10</update_rate>
|
||||
<visualize>true</visualize>
|
||||
<topic>/ultrasonic/range</topic>
|
||||
<topic>/ultrasonic/scan</topic>
|
||||
<gz_frame_id>ultrasonic</gz_frame_id>
|
||||
<sonar>
|
||||
<!-- HC-SR04 datasheet values -->
|
||||
<min>${sonar_min_range}</min>
|
||||
<max>${sonar_max_range}</max>
|
||||
<!-- Half-angle of the cone in radians (~15° full FOV → 0.13 rad half-angle) -->
|
||||
<radius>0.13</radius>
|
||||
</sonar>
|
||||
<lidar>
|
||||
<scan>
|
||||
<horizontal>
|
||||
<samples>5</samples>
|
||||
<resolution>1</resolution>
|
||||
<min_angle>-0.1309</min_angle> <!-- −7.5° -->
|
||||
<max_angle> 0.1309</max_angle> <!-- +7.5° -->
|
||||
</horizontal>
|
||||
<vertical>
|
||||
<samples>5</samples>
|
||||
<min_angle>-0.1309</min_angle>
|
||||
<max_angle> 0.1309</max_angle>
|
||||
</vertical>
|
||||
</scan>
|
||||
<range>
|
||||
<min>${sonar_min_range}</min>
|
||||
<max>${sonar_max_range}</max>
|
||||
<resolution>0.01</resolution>
|
||||
</range>
|
||||
<noise>
|
||||
<type>gaussian</type>
|
||||
<mean>0.0</mean>
|
||||
<stddev>0.005</stddev>
|
||||
</noise>
|
||||
</lidar>
|
||||
</sensor>
|
||||
</gazebo>
|
||||
|
||||
|
||||
Reference in New Issue
Block a user