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

Processed ping metadata extracted from GLF::GMainImage. More...

#include <glf_processor.hpp>

Public Attributes

uint32_t ping_number = 0
 Sequential ping counter.
 
double transmit_time_seconds = 0.0
 SDK transmit timestamp (seconds)
 
uint32_t num_beams = 0
 Number of beams in this ping.
 
uint32_t samples_per_beam = 0
 Range bins per beam.
 
uint32_t start_range_bin = 0
 First valid range bin (sample0)
 
uint32_t end_range_bin = 0
 Last valid range bin.
 
uint32_t start_bearing_deg = 0
 Start bearing angle.
 
uint32_t end_bearing_deg = 0
 End bearing angle.
 
double center_frequency_khz = 0.0
 Carrier frequency (720 or 1200 kHz)
 
double modulation_frequency = 0.0
 SAMPLE RATE of processed GLF data (kHz). This encodes the relationship between range setting and num samples. For 45m range with 1356 samples: ~22.6 kHz (33mm resolution)
 
double sound_speed_ms = 0.0
 Sound speed at transducer (m/s)
 
double beam_aperture_deg = 0.0
 Beamforming aperture angle.
 
int16_t gain_percent = 0
 Receiver gain (%)
 
bool chirp_enabled = false
 Chirp mode active.
 
uint16_t compression_type = 0
 Compression scheme (ZLIB, NONE, H264)
 
uint16_t range_compression = 0
 Range compression factor.
 
uint8_t sonar_type = 0
 Gemini type enum.
 
uint8_t platform_type = 0
 Specific model (1200ik, 720ik, etc.)
 
uint32_t state_flags = 0
 Sonar state/orientation flags.
 
uint16_t ping_flags = 0
 HF/LF, manual/auto flags.
 

Detailed Description

Processed ping metadata extracted from GLF::GMainImage.

Member Data Documentation

◆ beam_aperture_deg

double gemini_sonar_driver::glf_processor::PingMetadata::beam_aperture_deg = 0.0

Beamforming aperture angle.

◆ center_frequency_khz

double gemini_sonar_driver::glf_processor::PingMetadata::center_frequency_khz = 0.0

Carrier frequency (720 or 1200 kHz)

◆ chirp_enabled

bool gemini_sonar_driver::glf_processor::PingMetadata::chirp_enabled = false

Chirp mode active.

◆ compression_type

uint16_t gemini_sonar_driver::glf_processor::PingMetadata::compression_type = 0

Compression scheme (ZLIB, NONE, H264)

◆ end_bearing_deg

uint32_t gemini_sonar_driver::glf_processor::PingMetadata::end_bearing_deg = 0

End bearing angle.

◆ end_range_bin

uint32_t gemini_sonar_driver::glf_processor::PingMetadata::end_range_bin = 0

Last valid range bin.

◆ gain_percent

int16_t gemini_sonar_driver::glf_processor::PingMetadata::gain_percent = 0

Receiver gain (%)

◆ modulation_frequency

double gemini_sonar_driver::glf_processor::PingMetadata::modulation_frequency = 0.0

SAMPLE RATE of processed GLF data (kHz). This encodes the relationship between range setting and num samples. For 45m range with 1356 samples: ~22.6 kHz (33mm resolution)

◆ num_beams

uint32_t gemini_sonar_driver::glf_processor::PingMetadata::num_beams = 0

Number of beams in this ping.

◆ ping_flags

uint16_t gemini_sonar_driver::glf_processor::PingMetadata::ping_flags = 0

HF/LF, manual/auto flags.

◆ ping_number

uint32_t gemini_sonar_driver::glf_processor::PingMetadata::ping_number = 0

Sequential ping counter.

◆ platform_type

uint8_t gemini_sonar_driver::glf_processor::PingMetadata::platform_type = 0

Specific model (1200ik, 720ik, etc.)

◆ range_compression

uint16_t gemini_sonar_driver::glf_processor::PingMetadata::range_compression = 0

Range compression factor.

◆ samples_per_beam

uint32_t gemini_sonar_driver::glf_processor::PingMetadata::samples_per_beam = 0

Range bins per beam.

◆ sonar_type

uint8_t gemini_sonar_driver::glf_processor::PingMetadata::sonar_type = 0

Gemini type enum.

◆ sound_speed_ms

double gemini_sonar_driver::glf_processor::PingMetadata::sound_speed_ms = 0.0

Sound speed at transducer (m/s)

◆ start_bearing_deg

uint32_t gemini_sonar_driver::glf_processor::PingMetadata::start_bearing_deg = 0

Start bearing angle.

◆ start_range_bin

uint32_t gemini_sonar_driver::glf_processor::PingMetadata::start_range_bin = 0

First valid range bin (sample0)

◆ state_flags

uint32_t gemini_sonar_driver::glf_processor::PingMetadata::state_flags = 0

Sonar state/orientation flags.

◆ transmit_time_seconds

double gemini_sonar_driver::glf_processor::PingMetadata::transmit_time_seconds = 0.0

SDK transmit timestamp (seconds)


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