A Gazebo Ray vs Gazebo Sonar comparison - Field-Robotics-Lab/dave GitHub Wiki
This page compares Gazebo ray sensor against the Gazebo Sonar sensor and presents a prototype and example of the Gazebo Sonar sensor. We concluded that the ray sensor could be used to calculate beam intensity while the Sonar sensor, which detects mesh collision, could not.
Gazebo provides more sensors than ROS has Gazebo plugins for. Here is a list of Gazebo sensors taken from Gazebo's sensors
source code directory:
AltimeterSensor ImuSensor SensorManager
AltimeterSensor_TEST ImuSensor_TEST SensorManager_TEST
CameraSensor LogicalCameraSensor SensorsIface
CameraSensor_TEST MagnetometerSensor Sensor_TEST
ContactSensor MagnetometerSensor_TEST SensorTypes
DepthCameraSensor MultiCameraSensor SonarSensor
DepthCameraSensor_TEST Noise SonarSensor_TEST
ForceTorqueSensor Noise_TEST WideAngleCameraSensor
ForceTorqueSensor_TEST RaySensor WirelessReceiver
GaussianNoiseModel RaySensor_TEST WirelessReceiver_TEST
GpsSensor RFIDSensor WirelessTransceiver
GpsSensor_TEST RFIDTag WirelessTransmitter
GpuRaySensor Sensor WirelessTransmitter_TEST
GpuRaySensor_TEST SensorFactory
For ROS sensors, see https://github.com/ros-simulation/gazebo_ros_pkgs/tree/kinetic-devel/gazebo_plugins/include/gazebo_plugins.
Notes:
- The Gazebo 9 API is available here: http://gazebosim.org/api.html.
- Gazebo source code is available here: http://gazebosim.org/download. Sensors are under
gazebo/sensors
. - Gazebo includes
SonarSensor
. Side note: Gazebo also includesMagnetometerSensor
.
The Gazebo Sonar sensor, sensors/SonarSensor.cc
, uses configuration parameters that define the shape of the Sonar cone, see <sonar>
under http://sdformat.org/spec?ver=1.7&elem=sensor. Specifically:
-
min
: The minimum range of the Sonar cone. -
max
: The maximum range of the Sonar cone. -
radius
: The radius of the cone at maximum range. -
geometry
: The Sonar collision shape, currently:cone
orsphere
. Shape is aphysics::MeshShape
. This shape is used to generate the Sonar contact information.
The Gazebo SonarSensor works by defining a mesh collision object (cone) to collide against. Range is determined by looping through points of contact with this cone and returning the shortest length as range
. The Gazebo SonarSensor additionally tracks the location of the contact relative to sensor origin as Vector3d contact
, which could assist in calculating beam intensity, but this value is not available at the sensor's interface.
Here are strengths of Gazebo Sonar vs. Gazebo Ray:
- The Sonar model excels because it identifies reflections based on actual mesh shapes rather than projecting out a set of rays and finding the range of the closest ray.
- Unless modified, the Sonar model does not offer a power value. The Ray model returns power based on the target object's laser_retro value.
Here are some possibilities for working with the Gazebo Sonar model:
- Create a
nps_gazebo_ros_sonar
ROS plugin so we can examine existing performance of the Gazebo Sonar model (done). Note that this provides range but not intensity. - Change the shape of the cone to model an actual 3 dB loss boundary. This shape can include lobes.
- Add an Intensity measure. Intensity can be a vector of values bucketed by distance and weighted. For example a Sonar response might consist of an array of 100 intensity values for 100 buckets from min range to max range, where intensity is weighted on the number of collision points and the angle of incidence of the collisions.
- Add "sweep" capability for measuring range across an angular sweep. Currently, only a point is returned, not a horizontal trace or a horizontal/vertical point cloud.
Step (1) requires a new Gazebo ROS plugin (now available). It uses the existing sensor_msgs/Range
topic for measuring the distance. Current limitation: The Range topic does not include a retro field.
Step (2) involves changing the shape of the mesh object in the Gazebo sensor to match Sonar radiation characteristics.
Step (3) involves changing the iteration loop in UpdateImpl
in the Gazebo sensor to additionally calculate intensity values.
Step (4) requires installing angular sweep capability into the Gazebo sensor. The implementation might require a new message type or it might overload sensor_msgs/LaserScan
. The implementation might be computationally expensive if calculating range for one point is expensive.
A Gazebo ROS Sonar plugin is available at https://github.com/Field-Robotics-Lab/nps_sonar. It is currently built as described in Step (1) above, which provides range but not intensity. It may be run by installing it with other plugins in the Project DAVE workspace as described at https://github.com/Field-Robotics-Lab/dave/wiki/Install-Directly-on-Host. Its demo is run by typing the following:
roslaunch nps_sonar blueview_basement_cylinder.launch
Here is the view, showing the Sonar cone in blue and the reflection vector in red:
Here is an example range setting from the sensor_msgs/Range
message, indicating that the cylinder target is about 1.8 meters away:
header:
seq: 506
stamp:
secs: 41
nsecs: 109000000
frame_id: "standalone_nps_sonar_robot/nps_sonar1_link"
radiation_type: 0
field_of_view: 0.0
min_range: 0.10000000149
max_range: 7.0
range: 1.80746734142
---
Here is the SDF Sonar specification used in this demo, defining a cone mesh detection region with a 0.5 meter radius at its maximum distance of 7 meters away:
<sonar>
<geometry>cone</geometry>
<min>0.1</min>
<max>7</max>
<radius>0.5</radius>
</sonar>
Here is example sensor_msgs/Range
output indicating that the cylinder is 1.8 meters away:
header:
seq: 506
stamp:
secs: 41
nsecs: 109000000
frame_id: "standalone_nps_sonar_robot/nps_sonar1_link"
radiation_type: 0
field_of_view: 0.0
min_range: 0.10000000149
max_range: 7.0
range: 1.80746734142
---
An alternative approach considered it to esitmate Sonar from lidar rays using the gazebo_ros_block_laser plugin where the ray sensor takes horizontal and vertical scan bounds, range bounds, and parameters for applying signal noise. Note: this Sonar from Ray approach may not be chosen depending on evaluation of the native Gazebo Sonar sensor.
The Gazebo Ray sensor sensors/RaySensor.cc
takes horizontal and vertical scan bounds, range bounds, and parameters for applying signal noise, see <ray>
.
The NPS Sonar plugin, nps_gazebo_ros_sonar
, returns a list of Sonar (range, intensity) tuples. Internally, this works by calculating lidar points across a horizontal and vertical span covering the Sonar region and applying math on that to present a sweep of Sonar data, specifically, a list of Sonar tuples.
In the first draft:
- The Sonar output is of type
sensor_msgs/LaserScan
and has exactly one element in it. We use this message type because it already exists and it is closest to what we need. A new type such as "SonarPoint" may be more concise. We cannot use typesensor_msgs/Range
because although it has range, it lacks the intensity field. - The Sonar output is calculated from an array of horizontal and vertical lidar range and retro values. The code for accessing this array is based on how
gazebo_ros_block_laser
accesses LaserShape when it generates its point cloud. - The Sonar distance property is the average of the distances.
- The Sonar intensity property is from factors including:
- Beam pattern (based on axially symmetric function of angle away from Sonar center).
- The incident angle on the target.
- The retro reflectivity of the target.
- The Sonar intensity value is calculated from the intensities of the lidar rays, collectively. The lidar rays used might be the set of rays within the beam pattern where the power loss is no more than 3 dB.