#ifndef UV_LED_DETECT_ADAPTIVE_H #define UV_LED_DETECT_ADAPTIVE_H #include #include #include #include #include #include #include #include // Include for std::fixed and std::setprecision #include // Include for std::tuple #include #include #include struct ROIData{ int numRois; std::vector numberDetectedPoints; std::vector thresholdValue; std::vector klDivergence; std::vector validRoi; }; namespace uvdar { class UVDARLedDetectAdaptive{ public: UVDARLedDetectAdaptive(int neighborhoodSize = 25, double point_similarity_threshold = 5.0, std::string adaptive_method = "Otsu", bool adaptive_debug = false); ~UVDARLedDetectAdaptive(); bool processImageAdaptive(const cv::Mat& inputImage, const std::vector& trackingPoints, std::vector& detectedPoints, const std::vector& standardPoints); void generateVisualizationAdaptive(const cv::Mat& inputImage,cv::Mat& visualization_image,const std::vector& detectedPoints); ROIData prepareAdaptiveDataForLogging(); const std::vector& getLastProcessedBinaryROIs() const { return lastProcessedBinaryROIs_; } const std::vector& getLastProcessedROIs() const { return lastProcessedROIs_; } private: std::vector applyAdaptiveThreshold(const cv::Mat& inputImage, const cv::Rect& roi); cv::Rect adjustROI(const cv::Rect& inputROI, const cv::Size& imageSize); cv::Rect calculateROI(const cv::Mat& image, const cv::Point& point, int neighborhoodSize); std::vector mergeOverlappingROIs(const std::vector& rois, const cv::Size& imageSize, double overlapThreshold); bool isOverlapping(const cv::Rect& roi1, const cv::Rect& roi2, double overlapThreshold); std::vector detectPointsFromRoi(const cv::Mat& mask, const cv::Rect& roi); bool isClose(const cv::Point& p1, const cv::Point& p2, double threshold); int adjustNeighborhoodSizeBasedOnArea(const cv::Mat& roiImage, const std::vector>& contours, int currentSize); std::vector mergePoints(const std::vector& adaptivePoints,const std::vector& standardPoints, double threshold); double calculateKLDivergence(const std::vector& segmentHist, const std::vector& overallHist, size_t limit); double calculateEntropy(const std::vector& histSegment); double calculateKLDivergence2(const cv::Mat& hist, const std::vector& Q, int start, int end); std::tuple findOptimalThresholdUsingKL(const cv::Mat& roiImage); std::tuple findOptimalThresholdUsingEntropy(const cv::Mat& roiImage); cv::Mat plotHistogram(const cv::Mat& image); void saveRoiImage(const cv::Mat& binaryRoi, const cv::Point& center, int index, int thresholdValue, double klDivergence); int neighborhoodSize_; int thresholdValue_; double minKLDivergence_; double point_similarity_threshold_; std::string adaptive_method_; bool adaptive_debug_; int roiIndex_; int MAX_SIZE = 50; int MIN_SIZE = 5; std::vector lastProcessedBinaryROIs_; std::vector lastProcessedROIs_; // For storing ROI positions std::vector allRoiDetectedPoints;// For storing ROI positions int numRois; std::vector numberDetectedPoints; std::vector thresholdValue; std::vector klDivergence; std::vector validRoi; int index = 0; }; } // namespace uvdar #endif // UV_LED_DETECT_ADAPTIVE_H