Gemini Sonar Driver  1.0.0
A ROS2 Package for the Tritech Gemini 1200ikd sonar
Loading...
Searching...
No Matches
Gemini Sonar Driver

ROS2 driver for the Tritech Gemini 1200ikd multibeam imaging sonar.

Features

  • Configure sonar parameters via ROS2 parameters
  • Start/stop sonar operation via ROS2 services
  • Publish multibeam data using marine_acoustic_msgs RawSonarImage msg
  • Log data in native Gemini .glf format
  • Publish raw Gemini SDK packets for debugging

Dependencies

  • ROS2 Humble or Jazzy
  • marine_acoustic_msgs package
  • Gemini SDK v2.0.41.0 (v2.0.39.0 should also work)

Installation

Put gemini sdk in gemini_sonar_driver top level directory. Make sure to run InstallSDK.sh to install the libs system wide.

cd ~/your/ros/worskspace
rosdep install --from-paths src -y --ignore-src
colcon build --packages-select gemini_sonar_driver_interfaces gemini_sonar_driver
source install/setup.bash

[NOTE!] For some reason on 24.04 and Jazzy the node can fail to find the gemini SDK libs at runtime. If this happpens you can manually source these in the terminal prior to running the node it termporaily fixes the problem. You could also add to .bashrc so it persists.

export GEMINI_BIN="/path/to/ros_workspace/src/gemini_sonar_driver/GeminiSDK_v2.0.39.0_Ubuntu_24.04_x86_64/bin"
export LD_LIBRARY_PATH="$GEMINI_BIN:$LD_LIBRARY_PATH"

Configuration

Edit config/gemini_sonar.yaml to configure sonar parameters:

sonar_id: 0 # Sonar ID on network (0 WORKS FOR ALL SONARS IF ID IS NOT KNOWN)
software_mode: "Evo" # SDK mode (Evo/EvoC/SeaNet/SeaNetC)
range_m: 5.0 # Max range in meters
gain_percent: 100.0 # Receiver gain 0-100%
sound_speed_ms: 1500 # Sound speed in m/s

Usage

Launch the Driver

ros2 launch gemini_sonar_driver gemini_sonar.launch.py

Start the Sonar

# Start with native logging enabled
ros2 service call /gemini/start_sonar gemini_sonar_driver_interfaces/srv/StartSonar "{enable_logging: true, log_directory: '~/gemini_logs'}"
# Start without native logging
ros2 service call /gemini/start_sonar gemini_sonar_driver_interfaces/srv/StartSonar "{enable_logging: false, log_directory: ''}"

Stop the Sonar

ros2 service call /gemini/stop_sonar gemini_sonar_driver_interfaces/srv/StopSonar

Monitor Topics

You can use acoustic_image_view from the acoustic_msgs_tools package to visualize raw_sonar_image messages.

ros2 run acoustic_msgs_tools acoustic_image_view

You can also echo the raw topics.

# View sonar images
ros2 topic echo /gemini/raw_sonar_image --once
# View gemini status msgs
ros2 topic echo /gemini/status
# View raw packets
ros2 topic echo /gemini/raw

Record ROS2 Bags

ros2 bag record -a # Record all topics
# or specifically:
ros2 bag record /gemini/raw_sonar_image

Published Topics

Topic Message Type Description
/gemini/raw_sonar_image marine_acoustic_msgs/RawSonarImage Raw sonar data with beam angles and samples
/gemini/raw gemini_sonar_driver_interfaces/RawPacket Raw Gemini SDK packets for debugging
/gemini/status gemini_sonar_driver_interfaces/GeminiStatus Sonar status information
/gemini/logger_status gemini_sonar_driver_interfaces/LoggerStatus Native GLF logger status

Services

Service Type Description
/gemini/start_sonar StartSonar Start sonar pinging
/gemini/stop_sonar StopSonar Stop sonar pinging

Parameters

Parameter Type Default Description
sonar_id int 0 Sonar ID on network
software_mode string "Evo" SDK mode (Evo/EvoC/SeaNet/SeaNetC)
frame_id string "gemini_fls" TF frame ID for sonar data
log_directory string "/data/gemini" Directory to save GLF log files
range_m double 5.0 Maximum range in meters
gain_percent double 100.0 Receiver gain 0-100%
aperture double 120.0 Sonar aperture in degrees (120 or 65)
sound_speed_ms int 1500 Sound speed in m/s
sound_speed_manual bool true Sound speed mode (true=manual, false=auto)
high_resolution bool true High resolution mode (1200ik only)
frequency_mode int 0 Frequency selection (0=auto, 1=low, 2=high, 3=combined)
frequency_auto_threshold_m double 40.0 Threshold for auto mode LF/HF switching
chirp_mode int 2 Chirp mode (0=disabled, 1=enabled, 2=auto)
ping_free_run bool false Continuous pinging (true) vs interval-based (false)
ping_interval_ms int 100 Ping interval in ms when ping_free_run=false
ping_ext_trigger bool false External TTL hardware trigger (true) vs software (false)

Troubleshooting

To run with verbosity output set to DEBUG use

run gemini_sonar_driver gemini_sonar_node --ros-args --log-level gemini_sonar_driver:=debug

"Failed to initialize Gemini network"

  • Check that no other program is using the Gemini SDK
  • Verify sonar is powered and connected to network and the subnet (i.e 192.168.2.x)
  • Check sonar_id matches your hardware or use id=0 if unknown

Docs

For full docs go to gemini_sonar_driver.

TODO / Future Features

  • make raw_msg type publisher optional
  • Create glf-to-ROS2 conversions to play back log files
  • Implement range/gain adjustment on the fly
  • Log ping metadata in custom interfaace msg
  • add marine_acoustic_msgs detections and/or projection msg
  • Add parameter validation and bounds checking
  • Add diagnostic publishing for sonar health
  • Utilize compression/decompression from SDK

License

Apache 2.0

Maintainer

Jake Bonney (jake@.nosp@m.bonr.nosp@m.ov.co.nosp@m.m)