Gemini Sonar Driver  1.0.0
A ROS2 Package for the Tritech Gemini 1200ikd sonar
Loading...
Searching...
No Matches
gemini_sonar_driver::GeminiSonarNode::Parameters Struct Reference

Sonar configuration parameters. More...

#include <gemini_sonar_node.hpp>

Collaboration diagram for gemini_sonar_driver::GeminiSonarNode::Parameters:

Classes

struct  Topics
 

Public Member Functions

 Parameters ()
 
void declare (GeminiSonarNode *node)
 
void update (GeminiSonarNode *node)
 

Public Attributes

std::string frame_id = "gemini_fls"
 TF frame ID for sonar data.
 
std::string log_directory = "/data/gemini"
 Directory to save GLF log files.
 
uint16_t sonar_id = 0
 Sonar ID (default 1, 0 will reach all sonars on network)
 
std::string software_mode = "Evo"
 SDK mode: Evo, EvoC, SeaNet, SeaNetC.
 
double range_m = 10.0
 Range in meters (1-120m for 720kHz, 1-50m for 1200kHz)
 
double gain_percent = 50.0
 Receiver gain (0-100%)
 
double aperture = 120.0
 Sonar aperture in degrees (Switch between: 120 or 65)
 
int sound_speed_ms = 1500
 Sound speed in m/s.
 
bool sound_speed_manual = false
 Sound speed mode: true=manual, false=auto (uses sonar SOS sensor)
 
int chirp_mode = 2
 Chirp mode: 0=disabled, 1=enabled, 2=auto.
 
bool high_resolution = true
 High resolution mode (1200ik only)
 
int frequency_mode = 0
 Frequency selection: 0=auto, 1=low(720kHz), 2=high(1200kHz), 3=combined.
 
double frequency_auto_threshold_m = 40.0
 Threshold (m) for auto mode to switch LF/HF (1-50m valid)
 
bool ping_free_run = false
 Ping mode: true=continuous, false=interval-based.
 
int ping_interval_ms = 100
 Ping interval in ms (0-999) when free_run=false.
 
bool ping_ext_trigger = false
 External TTL trigger: true=hardware trigger, false=software.
 
struct gemini_sonar_driver::GeminiSonarNode::Parameters::Topics topics
 

Detailed Description

Sonar configuration parameters.

Constructor & Destructor Documentation

◆ Parameters()

GeminiSonarNode::Parameters::Parameters ( )

Member Function Documentation

◆ declare()

void GeminiSonarNode::Parameters::declare ( GeminiSonarNode * node)

◆ update()

void GeminiSonarNode::Parameters::update ( GeminiSonarNode * node)

Member Data Documentation

◆ aperture

double gemini_sonar_driver::GeminiSonarNode::Parameters::aperture = 120.0

Sonar aperture in degrees (Switch between: 120 or 65)

◆ chirp_mode

int gemini_sonar_driver::GeminiSonarNode::Parameters::chirp_mode = 2

Chirp mode: 0=disabled, 1=enabled, 2=auto.

◆ frame_id

std::string gemini_sonar_driver::GeminiSonarNode::Parameters::frame_id = "gemini_fls"

TF frame ID for sonar data.

◆ frequency_auto_threshold_m

double gemini_sonar_driver::GeminiSonarNode::Parameters::frequency_auto_threshold_m = 40.0

Threshold (m) for auto mode to switch LF/HF (1-50m valid)

◆ frequency_mode

int gemini_sonar_driver::GeminiSonarNode::Parameters::frequency_mode = 0

Frequency selection: 0=auto, 1=low(720kHz), 2=high(1200kHz), 3=combined.

◆ gain_percent

double gemini_sonar_driver::GeminiSonarNode::Parameters::gain_percent = 50.0

Receiver gain (0-100%)

◆ high_resolution

bool gemini_sonar_driver::GeminiSonarNode::Parameters::high_resolution = true

High resolution mode (1200ik only)

◆ log_directory

std::string gemini_sonar_driver::GeminiSonarNode::Parameters::log_directory = "/data/gemini"

Directory to save GLF log files.

◆ ping_ext_trigger

bool gemini_sonar_driver::GeminiSonarNode::Parameters::ping_ext_trigger = false

External TTL trigger: true=hardware trigger, false=software.

◆ ping_free_run

bool gemini_sonar_driver::GeminiSonarNode::Parameters::ping_free_run = false

Ping mode: true=continuous, false=interval-based.

◆ ping_interval_ms

int gemini_sonar_driver::GeminiSonarNode::Parameters::ping_interval_ms = 100

Ping interval in ms (0-999) when free_run=false.

◆ range_m

double gemini_sonar_driver::GeminiSonarNode::Parameters::range_m = 10.0

Range in meters (1-120m for 720kHz, 1-50m for 1200kHz)

◆ software_mode

std::string gemini_sonar_driver::GeminiSonarNode::Parameters::software_mode = "Evo"

SDK mode: Evo, EvoC, SeaNet, SeaNetC.

◆ sonar_id

uint16_t gemini_sonar_driver::GeminiSonarNode::Parameters::sonar_id = 0

Sonar ID (default 1, 0 will reach all sonars on network)

◆ sound_speed_manual

bool gemini_sonar_driver::GeminiSonarNode::Parameters::sound_speed_manual = false

Sound speed mode: true=manual, false=auto (uses sonar SOS sensor)

◆ sound_speed_ms

int gemini_sonar_driver::GeminiSonarNode::Parameters::sound_speed_ms = 1500

Sound speed in m/s.

◆ topics

struct gemini_sonar_driver::GeminiSonarNode::Parameters::Topics gemini_sonar_driver::GeminiSonarNode::Parameters::topics

The documentation for this struct was generated from the following files: