Configuration Reference
Complete parameter reference for the sonar 3D mapping system.
Location: scripts/config.py
Overview
Parameters are organized into dataclasses and loaded from ROS2 parameters at node startup. Some parameters can be changed at runtime (dynamic), while others require node restart (read-only).
Key Components:
ParameterDef- Parameter definition with metadata (name, default, description, handler)ParameterManager- Utility for parameter declaration and callbacksSonarMapperConfig- Complete configuration dataclassParameter lists:
MAPPER_PARAMS,VISUALIZER_PARAMS,WORLD_INIT_PARAMS
SonarMapperConfig
├── Sonar Hardware
├── Filtering
├── Mounting
├── Voxel Map
├── IWLO Algorithm
├── Adaptive Scaling
├── Out-of-Core Storage
├── Crosstalk Filter (optional)
└── Robot Detection (optional)
Parameter Categories
Sonar Hardware
Hardware specifications for Oculus multibeam sonar.
Parameter |
ROS2 Name |
Default |
Type |
Description |
|---|---|---|---|---|
|
|
130.0 |
float |
Horizontal field of view in degrees. Oculus M750d supports 130° wide mode. |
|
|
20.0 |
float |
Vertical beam aperture in degrees. Affects vertical spread of each ray. |
Read-only: These values are fixed based on sonar hardware.
Filtering
Controls which sonar returns are processed.
Parameter |
ROS2 Name |
Default |
Dynamic |
Description |
|---|---|---|---|---|
|
|
0.5 |
Yes |
Minimum valid range in meters. Ignores returns closer than this. |
|
|
35 |
Yes |
Intensity threshold (0-255). Returns above this are considered occupied. |
Tuning Guide:
intensity_threshold: Lower values detect weaker returns (more points, more noise). Higher values require stronger reflections (fewer points, less noise). Start with 35-50 for typical underwater environments.
Mounting
Sonar mounting position and orientation relative to base_link.
Parameter |
ROS2 Name |
Default |
Dynamic |
Description |
|---|---|---|---|---|
|
|
0.0 |
No |
X offset in meters (forward) |
|
|
0.0 |
No |
Y offset in meters (left) |
|
|
-0.5 |
No |
Z offset in meters (down) |
|
|
0.0 |
Yes |
Roll angle in degrees |
|
|
90.0 |
Yes |
Pitch angle in degrees |
|
|
0.0 |
Yes |
Yaw angle in degrees |
Note: Position is read-only (requires restart). Orientation is dynamic and updates TF when changed.
Common Configurations:
Downward-looking:
pitch=90°(default)Forward-looking:
pitch=0°45° down:
pitch=45°
Voxel Map
Controls the 3D occupancy grid structure.
Parameter |
ROS2 Name |
Default |
Dynamic |
Description |
|---|---|---|---|---|
|
|
0.05 |
No |
Voxel size in meters. Smaller = higher detail, more memory. |
|
|
0.7 |
Yes |
Probability threshold for occupied classification. |
|
|
0.5 |
Yes |
Vertical cone width in degrees for shadow protection. |
|
|
True |
Yes |
Allow map boundary expansion. |
|
|
True |
No |
Use C++ backend for ~10x speedup. |
Tuning Guide:
voxel_resolution: 0.05m is good for detailed mapping. Use 0.1m for larger areas.occupied_threshold: Higher values (0.8-0.9) require more confident observations.
IWLO Algorithm
Intensity-Weighted Log-Odds Bayesian probability update parameters.
Parameter |
ROS2 Name |
Default |
Description |
|---|---|---|---|
|
|
3.5 |
Log-odds increment for occupied observations. Higher = faster convergence to occupied. |
|
|
-3.0 |
Log-odds decrement for free observations. Lower (more negative) = faster convergence to free. |
|
|
-10.0 |
Minimum log-odds (saturation floor). Prevents probability from reaching exactly 0. |
|
|
10.0 |
Maximum log-odds (saturation ceiling). Prevents probability from reaching exactly 1. |
|
|
3.0 |
Sigmoid slope for intensity-to-weight conversion. Higher = more binary response. |
|
|
0.1 |
Learning rate decay factor. Higher = faster stabilization. |
|
|
0.1 |
Minimum learning rate. Maintains ability to detect changes. |
|
- |
255 |
Maximum intensity value for normalization. |
Read-only: All IWLO parameters require node restart.
How IWLO Works:
Occupied: ΔL = L_occ × w(I) × α(n)
Free: ΔL = L_free × α(n)
w(I) = sigmoid(sharpness × (normalized_intensity - 0.5))
α(n) = max(min_alpha, 1 / (1 + decay_rate × n))
Tuning Guide:
sharpness: Low (0.1-1) for smooth intensity response, High (3-5) for binary-like responsedecay_rate: Low (0.05) for slow convergence, High (0.3-0.5) for fast convergence
See IWLO Design for detailed algorithm explanation.
Adaptive Scaling
Suppresses noisy occupied updates in regions already classified as free.
Parameter |
ROS2 Name |
Default |
Description |
|---|---|---|---|
|
|
True |
Enable adaptive scaling. |
|
|
0.5 |
Probability threshold below which scaling applies. |
|
|
0.3 |
Maximum scale factor for suppressed updates. |
Read-only: Requires node restart.
How It Works:
if current_prob < adaptive_threshold:
scale = (current_prob / adaptive_threshold) × adaptive_max_ratio
else:
scale = 1.0
This prevents random noise from flipping free voxels back to occupied.
Out-of-Core Storage
Disk-based tile storage for large-scale mapping.
Parameter |
ROS2 Name |
Default |
Description |
|---|---|---|---|
|
|
False |
Enable disk-based storage. |
|
|
“/workspace/data/map_tiles” |
Directory for tile storage. |
|
|
10.0 |
Tile size in meters. |
|
|
16 |
Number of tiles to keep in memory. |
Read-only: Requires node restart.
When to Use:
Large-scale mapping (>100m×100m)
Limited RAM environments
Long-duration missions
Trade-offs:
Slower than in-memory mode
Requires
map_visualizer_nodefor visualizationEnables incremental map updates
Crosstalk Filter
Removes cross-talk noise (horizontal stripes) from multibeam sonar images.
Enable: Set crosstalk.enabled=True at launch.
Parameter |
ROS2 Name |
Default |
Dynamic |
Description |
|---|---|---|---|---|
|
|
True |
Yes |
Enable morphological filtering. |
|
|
5 |
Yes |
Kernel size for opening operation. |
|
|
“rect” |
Yes |
Kernel shape: “rect”, “ellipse”, “cross”. |
|
|
True |
Yes |
Enable azimuth consistency check. |
|
|
0.5 |
Yes |
Consistency threshold (0-1). |
How It Works:
Morphological opening removes small horizontal artifacts
Azimuth consistency check removes isolated noise across beams
Robot Detection
Separates terrain returns from other underwater robot returns based on intensity.
Enable: Set robot_detection.enabled=True at launch.
Parameter |
ROS2 Name |
Default |
Dynamic |
Description |
|---|---|---|---|---|
|
|
80 |
Yes |
Minimum intensity for terrain. |
|
|
180 |
Yes |
Maximum intensity for terrain. |
|
|
180 |
Yes |
Minimum intensity for robot detection. |
|
|
“/sonar_robot_detections” |
No |
Output topic for robot detections. |
Intensity Classification:
[0, 80) → Ignored (too weak)
[80, 180) → Terrain
[180, 255] → Robot (high reflectivity)
Processing
General processing parameters.
Parameter |
ROS2 Name |
Default |
Dynamic |
Description |
|---|---|---|---|---|
|
|
1 |
Yes |
Process every Nth frame. Use 2+ for high-rate sonars. |
Node-Only Parameters
These parameters are only used by 3d_mapper_node.py, not stored in config dataclass.
Parameter |
ROS2 Name |
Default |
Description |
|---|---|---|---|
Frame IDs |
|
“sonar_link” |
Sonar TF frame |
|
“base_link” |
Base TF frame |
|
|
“map” |
Map TF frame |
|
|
True |
Publish static TF |
|
Topics |
|
“/sensor/sonar/oculus/m750d/image” |
Sonar image topic |
|
“/fast_lio/odometry” |
Odometry topic |
|
|
“/sonar_3d_map” |
Output pointcloud |
|
|
“/sonar_3d_map_markers” |
Marker array |
|
Visualization |
|
False |
Show debug windows |
|
10.0 |
Hz (in-memory) |
|
|
5.0 |
Seconds (out-of-core) |
Configuration Flow
Launch File / CLI Args
↓
ROS2 Parameter Server
↓
ParameterManager.declare_all(node, MAPPER_PARAMS)
↓
SonarMapperConfig.from_ros_params(node)
↓
config.to_mapper_dict()
↓
SonarTo3DMapper(config_dict)
Parameter Management System
ParameterDef
Dataclass for defining ROS2 parameters with metadata.
@dataclass
class ParameterDef:
name: str # Parameter name (e.g., "iwlo.sharpness")
default: Any # Default value
description: str # ROS2 ParameterDescriptor description
read_only: bool # Cannot change at runtime
handler: str # Dynamic update handler method name
ParameterManager
Utility class for parameter management.
# Declare all parameters in node
ParameterManager.declare_all(node, MAPPER_PARAMS)
# Get all parameter values
params_dict = ParameterManager.get_all(node, MAPPER_PARAMS)
# Create dynamic update callback
callback = ParameterManager.create_callback(node, MAPPER_PARAMS, mapper)
node.add_on_set_parameters_callback(callback)
Parameter Lists
List |
Node |
Description |
|---|---|---|
|
|
Main mapper parameters |
|
|
Conditional robot detection |
|
|
Conditional crosstalk filter |
|
|
Visualization parameters |
|
|
World frame initialization |
Dynamic Parameter Updates
Parameters with handler specified support runtime updates via ros2 param set:
# Change intensity threshold at runtime
ros2 param set /sonar_3d_mapper filtering.intensity_threshold 50
# Change visualization
ros2 param set /sonar_3d_mapper visualization.show_opencv_visualization true
The handler method is called automatically when the parameter changes.
YAML Configuration Example
# config/mapper_params.yaml
sonar_3d_mapper:
ros__parameters:
# Sonar
sonar:
horizontal_fov: 130.0
vertical_aperture: 20.0
# Filtering
filtering:
min_range: 0.5
intensity_threshold: 50
# Mounting
mounting:
position:
x: 0.0
y: 0.0
z: -0.5
orientation:
roll: 0.0
pitch: 90.0
yaw: 0.0
# Octree
octree:
voxel_resolution: 0.1
use_cpp_backend: true
# IWLO
iwlo:
sharpness: 3.0
L_occ: 3.5
L_free: -3.0
# Out-of-Core (disabled)
outofcore:
use: false