NPS Ray based Sonar - Field-Robotics-Lab/dave GitHub Wiki
Here we examine simulating Sonar using the Gazebo GpuRaySensor sensor. We start with a single-beam plugin prototype with the expectation of expanding to offer a ray trace plugin.
-
Gazebo 9 API: http://osrf-distributions.s3.amazonaws.com/gazebo/api/9.0.0/index.html
-
Gazebo 9 source code: Download Version 9.0 from http://gazebosim.org/download and unzip. Some files of interest include:
gazebo/sensors/GpuRaySensor.cc gazebo/sensors/GpuRaySensor.hh gazebo/sensors/GpuRaySensorPrivate.hh plugins/GpuRayPlugin.cc plugins/GpuRayPlugin.hh
-
Ros Melodic source online: https://github.com/ros-simulation/gazebo_ros_pkgs/tree/melodic-devel/gazebo_plugins.
-
ROS Melodic source download: Clone
gazebo_ros_pkgs
and checkout branch melodic-devel:git clone https://github.com/ros-simulation/gazebo_ros_pkgs.git git checkout melodic-devel
Some files of interest:
gazebo_plugins/src/gazebo_ros_laser.cpp gazebo_plugins/src/gazebo_ros_gpu_laser.cpp gazebo_plugins/src/gazebo_ros_block_laser.cpp gazebo_plugins/src/gazebo_ros_range.cpp gazebo_plugins/include/gazebo_plugins/gazebo_ros_gpu_laser.h gazebo_plugins/include/gazebo_plugins/gazebo_ros_block_laser.h gazebo_plugins/include/gazebo_plugins/gazebo_ros_laser.h gazebo_plugins/include/gazebo_plugins/gazebo_ros_range.h
The SDF tag for the <ray>
sensor is at http://sdformat.org/spec?ver=1.7&elem=sensor. Tag <ray>
will be replaced by <lidar>
. Their contents are the same:
- scan
- horizontal
- samples
- resolution
- min_angle
- max_angle
- vertical
- samples
- resolution
- min_angle
- max_angle
- range
- min
- max
- resolution
- noise
- type
- mean
- stddev
- horizontal
Horizontal and vertical scan settings are defined. For one ray trace, set vertical samples to 1. For resolution equal to sample resolution, use 1. Set min_angle, max_angle, and samples for three horizontal samples at -0.1°, 0.0°, and 0.1°.
Gazebo message is C++ type ConstLaserScanStampedPtr
, type gazebo.msgs.LaserScanStamped
, see gazebo/msgs/laserscan_stamped.proto
.
ROS message is C++ type sensor_msgs::LaserScan
, see http://docs.ros.org/melodic/api/sensor_msgs/html/msg/LaserScan.html.
We created a single-beam Sonar based on the Gazebo ROS gazebo_ros_gpu_laser
plugin. Rather than returning an array of rays, the single-beam Sonar calculates one range and intensity value based on range and intensity values in the underlying ray scan. This calculation happens in the OnScan
function, see file https://github.com/Field-Robotics-Lab/nps_uw_sensors_gazebo/blob/master/src/nps_gazebo_ros_gpu_sonar_single_beam.cpp.
To build: Clone this repository under ~/uuv_ws/src
(see https://github.com/Field-Robotics-Lab/dave/wiki/Install-Directly-on-Host), checkout the sonar_eqns
branch, then at ~/uuv_ws
type catkin_make
:
cd ~/uuv_ws/src
git clone https://github.com/uuvsimulator/nps_uw_sensors_gazebo.git
cd nps_uw_sensors_gazebo
git checkout sonar_eqns
cd ~/uuv_ws
catkin_make
An alternative to cloning with https is to use the git protocol: git clone [email protected]:Field-Robotics-Lab/nps_uw_sensors_gazebo.git
.
To run:
roslaunch nps_uw_sensors_gazebo sonar_single_beam_basic.launch
Here is an example view:
To see the beam message, use rostopic echo
:
rostopic echo sonar_single_beam_robot/sonar_single_beam1_sonar_range
Here is example output:
header:
seq: 0
stamp:
secs: 42
nsecs: 813000000
frame_id: "sonar_single_beam_robot/sonar_single_beam_robot/sonar_single_beam1_link"
angle_min: -0.10000000149
angle_max: 0.10000000149
angle_increment: 0.10000000149
time_increment: 0.0
scan_time: 0.0
range_min: 0.10000000149
range_max: 10.0
ranges: [1.75006902217865]
intensities: [3.530477523803711]
---