@ -83,32 +83,25 @@ private:
}
void init_pipeline ( ) {
PipelineParams p ;
p . feature . sample_rate = params_ . sample_rate ;
p . feature . n_mels = 64 ;
p . feature . n_fft = 2048 ;
p . feature . hop_length = 512 ;
p . feature . f_min = 0.0f ;
p . feature . f_max = 8000.0f ;
p . feature . preemphasis = 0.97f ;
p . model_path = params_ . model_path ;
p . label_map_path = params_ . label_map_path ;
p . sample_rate = params_ . sample_rate ;
p . mic_geometry . num_mics = params_ . n_channels ;
p . mic_geometry . layout = " cross " ;
p . mic_geometry . spacing = 0.15f ;
pipeline_ = std : : make_unique < Pipeline > ( p ) ;
if ( ! pipeline_ - > init ( ) ) {
ROS_ERROR ( " Pipeline initialization failed " ) ;
}
PipelineConfig config ;
config . sample_rate = static_cast < uint32_t > ( params_ . sample_rate ) ;
config . chunk_duration = params_ . chunk_duration ;
config . hop_duration = params_ . hop_duration ;
config . n_mels = 64 ;
config . classifier . model_path = params_ . model_path ;
config . classifier . label_map_path = params_ . label_map_path ;
config . classifier . threshold = 0.7f ;
config . classifier . smoothing_window = 3 ;
config . mic_array . num_mics = static_cast < uint32_t > ( params_ . n_channels ) ;
config . mic_array . layout = " cross " ;
config . mic_array . spacing = 0.15f ;
pipeline_ = std : : make_unique < Pipeline > ( config ) ;
}
void init_source ( ) {
if ( source_type_ = = " mic_array " ) {
audio_sub_ = nh_ . subscribe ( params_ . mobile_phone_topic . empty ( )
? " /microphone_array/audio "
: " /microphone_array/audio " ,
10 , & AcousticNode : : on_mic_array_audio , this ) ;
audio_sub_ = nh_ . subscribe ( " /microphone_array/audio " , 10 ,
& AcousticNode : : on_mic_array_audio , this ) ;
} else if ( source_type_ = = " mobile_phone " ) {
audio_sub_ = nh_ . subscribe ( params_ . mobile_phone_topic , 10 ,
& AcousticNode : : on_mobile_phone_audio , this ) ;
@ -122,33 +115,37 @@ private:
}
}
// Convert multi-channel vector-of-vectors to flat interleaved format
std : : vector < float > flatten_audio ( const std : : vector < std : : vector < float > > & audio , int channels ) {
if ( audio . empty ( ) | | channels = = 0 ) return { } ;
size_t samples = audio [ 0 ] . size ( ) ;
std : : vector < float > flat ( samples * channels ) ;
for ( size_t s = 0 ; s < samples ; + + s ) {
for ( int ch = 0 ; ch < channels ; + + ch ) {
flat [ s * channels + ch ] = ( ch < static_cast < int > ( audio . size ( ) ) & & s < audio [ ch ] . size ( ) )
? audio [ ch ] [ s ] : 0.0f ;
}
}
return flat ;
}
void on_mic_array_audio ( const std_msgs : : Float32MultiArray : : ConstPtr & msg ) {
// Parse layout from dim: [channels, samples]
if ( msg - > layout . dim . size ( ) < 2 ) return ;
int channels = msg - > layout . dim [ 0 ] . size ;
int samples = msg - > layout . dim [ 1 ] . size ;
int channels = static_cast < int > ( msg - > layout . dim [ 0 ] . size ) ;
int samples = static_cast < int > ( msg - > layout . dim [ 1 ] . size ) ;
if ( channels = = 0 | | samples = = 0 ) return ;
std : : vector < std : : vector < float > > audio ( channels , std : : vector < float > ( samples ) ) ;
for ( int ch = 0 ; ch < channels ; + + ch ) {
for ( int s = 0 ; s < samples ; + + s ) {
audio [ ch ] [ s ] = msg - > data [ ch * samples + s ] ;
}
}
std : : vector < TrackedThreat > threats ;
if ( channels = = 1 ) {
pipeline_ - > process_single_channel ( audio [ 0 ] , threats ) ;
} else {
pipeline_ - > process ( audio , threats ) ;
}
// Publish threats via threat_publisher (would be called by main loop)
// Assuming data is interleaved or [channels x samples] row-major
std : : vector < float > flat ( msg - > data . begin ( ) , msg - > data . end ( ) ) ;
auto frame = pipeline_ - > Process ( flat ) ;
( void ) frame ; // Would be published by threat_publisher in main loop
}
void on_mobile_phone_audio ( const std_msgs : : Float32MultiArray : : ConstPtr & msg ) {
if ( msg - > data . empty ( ) ) return ;
std : : vector < TrackedThreat > threats ;
pipeline_ - > process_single_channel ( msg - > data , threats ) ;
std : : vector < float > flat ( msg - > data . begin ( ) , msg - > data . end ( ) ) ;
auto frame = pipeline_ - > Process ( flat ) ;
( void ) frame ;
}
void process_wav_source ( ) {
@ -161,12 +158,9 @@ private:
ros : : shutdown ( ) ;
return ;
}
std : : vector < TrackedThreat > threats ;
if ( wav_source_ - > num_channels ( ) = = 1 ) {
pipeline_ - > process_single_channel ( audio [ 0 ] , threats ) ;
} else {
pipeline_ - > process ( audio , threats ) ;
}
auto flat = flatten_audio ( audio , static_cast < int > ( wav_source_ - > num_channels ( ) ) ) ;
auto frame = pipeline_ - > Process ( flat ) ;
( void ) frame ;
}
} ;