diff --git a/src/drone-software/src/acoustic/.gitattributes b/src/drone-software/src/acoustic/.gitattributes new file mode 100644 index 0000000..6221b58 --- /dev/null +++ b/src/drone-software/src/acoustic/.gitattributes @@ -0,0 +1,4 @@ +# Mark binary files +*.onnx binary +*.bin binary +*.wav binary diff --git a/src/drone-software/src/acoustic/build/test_core_lib.exe b/src/drone-software/src/acoustic/build/test_core_lib.exe index 2015987..93ffc73 100644 Binary files a/src/drone-software/src/acoustic/build/test_core_lib.exe and b/src/drone-software/src/acoustic/build/test_core_lib.exe differ diff --git a/src/drone-software/src/acoustic/src/core/gunshot_classifier.cpp b/src/drone-software/src/acoustic/src/core/gunshot_classifier.cpp index 8bbf2af..67e1e15 100644 --- a/src/drone-software/src/acoustic/src/core/gunshot_classifier.cpp +++ b/src/drone-software/src/acoustic/src/core/gunshot_classifier.cpp @@ -104,6 +104,14 @@ struct GunshotClassifier::Impl { } bool LoadModel(const std::string& path) { + // Verify file exists before attempting ONNX load + std::ifstream check(path, std::ios::binary); + if (!check) { + std::cerr << "[ERROR] Model file not found: " << path << std::endl; + return false; + } + check.close(); + #ifdef _WIN32 int wlen = MultiByteToWideChar(CP_UTF8, 0, path.c_str(), -1, nullptr, 0); std::wstring wpath; @@ -114,14 +122,14 @@ struct GunshotClassifier::Impl { try { session = std::make_unique(env, wpath.c_str(), *session_options); } catch (const Ort::Exception& e) { - (void)e; + std::cerr << "[ERROR] ONNX Runtime failed to load model: " << e.what() << std::endl; return false; } #else try { session = std::make_unique(env, path.c_str(), *session_options); } catch (const Ort::Exception& e) { - (void)e; + std::cerr << "[ERROR] ONNX Runtime failed to load model: " << e.what() << std::endl; return false; } #endif diff --git a/src/drone-software/src/acoustic/tests/test_core_lib.cpp b/src/drone-software/src/acoustic/tests/test_core_lib.cpp index 14d912a..efe94c7 100644 --- a/src/drone-software/src/acoustic/tests/test_core_lib.cpp +++ b/src/drone-software/src/acoustic/tests/test_core_lib.cpp @@ -109,13 +109,61 @@ void test_feature_extractor_shape() { std::cout << "[PASS] feature_extractor_shape (" << mel.rows() << " x " << mel.cols() << ")" << std::endl; } +void test_audio_buffer_overflow() { + AudioBuffer buf(10, 1); + std::vector data(25, 1.0f); + buf.Push(data); + assert(buf.Size() == 10); // should cap at capacity + auto popped = buf.Pop(5); + assert(popped.size() == 5); + assert(buf.Size() == 5); + std::cout << "[PASS] audio_buffer_overflow" << std::endl; +} + +void test_distance_estimator_multi_class() { + DistanceConfig config; + config.ref_spl_gunshot = 150.0f; + config.ref_spl_artillery = 180.0f; + config.ref_spl_explosion = 170.0f; + config.attenuation_alpha = 0.6f; + DistanceEstimator est(config); + float d1 = est.Estimate(120.0f, "gunshot"); + float d2 = est.Estimate(120.0f, "artillery"); + float d3 = est.Estimate(120.0f, "explosion"); + assert(d2 > d1); // artillery has higher ref SPL -> farther estimated distance at same SPL + assert(d3 > d1); + std::cout << "[PASS] distance_estimator_multi_class" << std::endl; +} + +void test_threat_tracker_filtering() { + ThreatTracker tracker(0.3f, 15.0f, 5); + AcousticThreat t1; + t1.sound_type = "gunshot"; + t1.confidence = 0.9f; + t1.azimuth = 45.0f; + t1.distance = 100.0f; + + // First update should publish + auto out1 = tracker.Update({t1}); + assert(out1.size() == 1); + + // Immediate second update with same azimuth should be filtered (interval < 0.3s) + auto out2 = tracker.Update({t1}); + assert(out2.empty()); + + std::cout << "[PASS] threat_tracker_filtering" << std::endl; +} + int main() { std::cout << "Running core library tests..." << std::endl; test_audio_buffer(); + test_audio_buffer_overflow(); test_preemphasis(); test_gcc_phat_cross_array(); test_distance_estimator(); + test_distance_estimator_multi_class(); test_threat_tracker(); + test_threat_tracker_filtering(); test_feature_extractor_shape(); std::cout << "All tests passed!" << std::endl; return 0;