Skip to content

Commit

Permalink
Merge conflict solved
Browse files Browse the repository at this point in the history
  • Loading branch information
MarlonRiv committed Jul 22, 2024
2 parents 60ff9c1 + 59e2d3d commit e0a2594
Show file tree
Hide file tree
Showing 6 changed files with 1,670 additions and 170 deletions.
119 changes: 7 additions & 112 deletions include/detect/uv_led_detect_adaptive.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -106,49 +106,12 @@ const std::vector<cv::Point>& standardPoints) {
detectedPoints.insert(detectedPoints.end(), roiDetectedPoints.begin(), roiDetectedPoints.end());
}

/* // Process each tracking point
for (const auto& point : trackingPoints) {
// Apply adaptive thresholding to the ROI around the tracking point
//std::cout << "[UVDARLedDetectAdaptive]: PROCESSING TRACKING POINT: " << point << std::endl;
std::vector<cv::Point> roiDetectedPoints = applyAdaptiveThreshold(inputImage, point, neighborhoodSize_);
numRois++;
// Check if the detected points are empty
if (roiDetectedPoints.empty()){
//std::cout << "[UVDARLedDetectAdaptive]: EMPTY ROI DETECTED POINTS" << std::endl;
continue;
}
// Check each point for uniqueness before adding
//detectedPoints.insert(detectedPoints.end(), roiDetectedPoints.begin(), roiDetectedPoints.end());
// Check each point for uniqueness before adding
for (const auto& roiPoint : roiDetectedPoints) {
if (uniquePoints.insert(roiPoint).second) { // .second is true if the insertion is successful (i.e., the point is unique)
detectedPoints.push_back(roiPoint); // Insert only the unique point
}
}
} */

std::vector<cv::Point> final_detected_points = mergePoints(detectedPoints, standardPoints, point_similarity_threshold_);


/*
//Print the final detected points
for (int i = 0; i < final_detected_points.size(); i++) {
std::cout << "[UVDARLedDetectAdaptive]: Final detected point " << i << ": " << final_detected_points[i] << std::endl;
}
*/
detectedPoints = final_detected_points;
//standardPoints = final_detected_points;

//Fail if no points are detected TODO
//if (final_detected_points.size() == 0){
// return false;
//}

return true;//if successful
return true;
}
//}

Expand Down Expand Up @@ -179,7 +142,7 @@ std::vector<cv::Point> UVDARLedDetectAdaptive::applyAdaptiveThreshold(const cv::


// Compute and plot histograms
/* cv::Mat histOriginal = plotHistogram(grayImage); */
cv::Mat histOriginal = plotHistogram(grayImage);


/* cv::Mat grayImage;
Expand Down Expand Up @@ -211,7 +174,6 @@ std::vector<cv::Point> UVDARLedDetectAdaptive::applyAdaptiveThreshold(const cv::
// Create unsharp mask by subtracting the blurred version from the original image
cv::Mat unsharpMask = grayImage - blurred;

//saveRoiImage(unsharpMask, point, roiIndex_++, 0, 0.0);
// Apply the unsharp mask to the original image to enhance edges
cv::Mat enhancedImage;
cv::addWeighted(grayImage, 0.25, unsharpMask, 1.75, 0, enhancedImage);
Expand All @@ -226,15 +188,8 @@ std::vector<cv::Point> UVDARLedDetectAdaptive::applyAdaptiveThreshold(const cv::
fs::create_directories(outputDir);



//saveRoiImage(histOriginal, 0, roiIndex_++, 0, 0.0);
//saveRoiImage(histEnhanced, 0, roiIndex_++, 0, 0.0);

cv::Mat binaryRoi;
//cv::adaptiveThreshold(roiImage, binaryRoi, 255, cv::ADAPTIVE_THRESH_GAUSSIAN_C, cv::THRESH_BINARY, 11, 2);

//Print the adaptive method
//std::cout << "[UVDARLedDetectAdaptive]: ADAPTIVE METHOD: " << adaptive_method_ << std::endl;
cv::Mat binaryRoiOriginal;
if( adaptive_method_ == "Otsu" || adaptive_method_ == "otsu"){
//Apply Otsu's thresholding with the enhanced ROI
Expand All @@ -248,14 +203,13 @@ std::vector<cv::Point> UVDARLedDetectAdaptive::applyAdaptiveThreshold(const cv::
else{
//std::cout << "[UVDARLedDetectAdaptive]: APPLYING KL DIVERGENCE" << std::endl;
auto [thresholdValue, minKLDivergence] = findOptimalThresholdUsingKL(enhancedImage);
//Using entropy
//auto [thresholdValue, minKLDivergence] = findOptimalThresholdUsingEntropy(enhancedImage);
thresholdValue_ = thresholdValue;
minKLDivergence_ = minKLDivergence;
cv::threshold(enhancedImage,binaryRoi, thresholdValue_, 255, cv::THRESH_BINARY);
}



//Save the original and enhanced images
/* cv::imwrite(outputDir + "/im_" + std::to_string(index) + ".png", grayImage); */
index++;
Expand Down Expand Up @@ -342,11 +296,9 @@ std::vector<cv::Point> UVDARLedDetectAdaptive::applyAdaptiveThreshold(const cv::
else{
klDivergence.push_back(minKLDivergence_);
}
//klDivergence.push_back(minKLDivergence);
validRoi.push_back(0);

//Return empty roiDetectedPoints

std::vector<cv::Point> empty_roiDetectedPoints = {};
return empty_roiDetectedPoints;
//Clear the lastProcessedROIs_ and lastProcessedBinaryROIs_ vectors
Expand All @@ -357,8 +309,6 @@ std::vector<cv::Point> UVDARLedDetectAdaptive::applyAdaptiveThreshold(const cv::
lastProcessedROIs_.push_back(roi); // Store the ROI for visualization
// Store the binary ROI (For debugging/visualization)
lastProcessedBinaryROIs_.push_back(binaryRoi);
//saveRoiImage(binaryRoi, point, roiIndex_++, thresholdValue_, 1.0);
//std::cout << "[UVDARLedDetectAdaptive]: ADDING ROI DETECTED POINTS: " << roiDetectedPoints.size() << std::endl;


numberDetectedPoints.push_back(roiDetectedPoints.size());
Expand Down Expand Up @@ -404,9 +354,6 @@ std::vector<cv::Rect> UVDARLedDetectAdaptive::mergeOverlappingROIs(const std::ve
for (int j = i + 1; j < rois.size(); j++) {
if (merged[j]) continue;
if (isOverlapping(currentROI, rois[j], overlapThreshold)) {
//Print debug message
//std::cout << "[UVDARLedDetectAdaptive]: MERGING OVERLAPPING ROIS" << std::endl;
// Collect the corners of both rectangles
std::vector<cv::Point> corners;
corners.push_back(cv::Point(currentROI.x, currentROI.y));
corners.push_back(cv::Point(currentROI.x + currentROI.width, currentROI.y + currentROI.height));
Expand Down Expand Up @@ -449,8 +396,6 @@ int UVDARLedDetectAdaptive::adjustNeighborhoodSizeBasedOnArea(const cv::Mat& roi
// Print the area ratio
std::cout << "[UVDARLedDetectAdaptive]: AREA RATIO: " << areaRatio << std::endl;

// Revised adjustment calculation
// Example adjustment: scale currentSize based on deviation from a desired area ratio
const double targetAreaRatioSparse = 0.1, targetAreaRatioDense = 0.5;
double adjustmentFactor = 0.5; // Proportion of currentSize to adjust by, needs tuning

Expand Down Expand Up @@ -486,9 +431,6 @@ std::vector<cv::Point> UVDARLedDetectAdaptive::detectPointsFromRoi(const cv::Mat
cv::Mat labels;
int numComponents = cv::connectedComponents(mask, labels, 8, CV_32S);


//printf("Number of components: %d\n", numComponents);

// Iterate through components to calculate centroid
for (int i = 1; i < numComponents; i++) { // Start from 1 to ignore the background
cv::Mat componentMask = (labels == i);
Expand Down Expand Up @@ -557,8 +499,6 @@ std::vector<cv::Point> UVDARLedDetectAdaptive::mergePoints(const std::vector<cv:
}
}

//Print final size of combined points
//std::cout << "[UVDARLedDetectAdaptive]: COMBINED POINTS SIZE: " << combinedPoints.size() << std::endl;

return combinedPoints;
}
Expand Down Expand Up @@ -595,16 +535,6 @@ std::vector<cv::Point> UVDARLedDetectAdaptive::mergePoints(const std::vector<cv:
}
return klDivergence;

/* double klDivergence = 0.0;
double epsilon = 1e-10; // Small value to avoid log(0)
for (size_t i = 0; i < limit && i < segmentHist.size() && i < overallHist.size(); ++i) {
if (segmentHist[i] > 0 && overallHist[i] > 0) {
klDivergence += overallHist[i] * log((overallHist[i] + epsilon) / (segmentHist[i] + epsilon));
}
}
return klDivergence; */

}


Expand All @@ -630,16 +560,11 @@ std::tuple<int, double> UVDARLedDetectAdaptive::findOptimalThresholdUsingKL(cons
* optimalThreshold: The optimal threshold
*/

//Print shape of roiImage
//std::cout << "[UVDARLedDetectAdaptive]: ROI IMAGE SHAPE: " << roiImage.size() << std::endl;
// Assuming 'roiImage' is already in a binary form (0s and 1s)

int countZeros = cv::countNonZero(roiImage);
int totalPixels = roiImage.total();
int countOnes = totalPixels - countZeros;

//Print the count of zeros and ones
//std::cout << "[UVDARLedDetectAdaptive]: COUNT OF ZEROS: " << countZeros << std::endl;
//std::cout << "[UVDARLedDetectAdaptive]: COUNT OF ONES: " << countOnes << std::endl;


// Calculate the histogram of the ROI image
Expand All @@ -656,7 +581,6 @@ std::tuple<int, double> UVDARLedDetectAdaptive::findOptimalThresholdUsingKL(cons
int optimalThreshold = 0;


// Convert cv::Mat hist to std::vector<double> for easier manipulation
std::vector<double> Q(histSize);
for (int i = 0; i < histSize; ++i) {
Q[i] = hist.at<float>(i);
Expand Down Expand Up @@ -684,26 +608,11 @@ std::tuple<int, double> UVDARLedDetectAdaptive::findOptimalThresholdUsingKL(cons
double klDivBelow = calculateKLDivergence(normalizedP_below, Q, t + 1);
double klDivAbove = calculateKLDivergence(normalizedP_above, Q, histSize - t - 1);

/* std::cout << "Threshold: " << t << std::endl;
std::cout << "Sum Below: " << sumBelow << ", Sum Above: " << sumAbove << std::endl;
std::cout << "Normalized P_below: ";
for (double p : normalizedP_below) std::cout << p << " ";
std::cout << std::endl;
std::cout << "Normalized P_above: ";
for (double p : normalizedP_above) std::cout << p << " ";
std::cout << std::endl;
//Print the KL divergence
std::cout << "[UVDARLedDetectAdaptive]: KL DIVERGENCE BELOW: " << klDivBelow << std::endl;
std::cout << "[UVDARLedDetectAdaptive]: KL DIVERGENCE ABOVE: " << klDivAbove << std::endl; */


double totalKLDiv = klDivBelow + klDivAbove;

if (totalKLDiv < minKLDivergence && totalKLDiv > 0.0) {
//Print found better threshold
//std::cout << "[UVDARLedDetectAdaptive]: FOUND BETTER THRESHOLD: " << t << std::endl;
//std::cout << "[UVDARLedDetectAdaptive]: MIN KL DIVERGENCE: " << totalKLDiv << std::endl;


minKLDivergence = totalKLDiv;
optimalThreshold = t;
Expand All @@ -712,10 +621,6 @@ std::tuple<int, double> UVDARLedDetectAdaptive::findOptimalThresholdUsingKL(cons

}

//Print the minKLDivergence and optimalThreshold
//std::cout << "[UVDARLedDetectAdaptive]: MIN KL DIVERGENCE: " << minKLDivergence << std::endl;
//std::cout << "[UVDARLedDetectAdaptive]: OPTIMAL THRESHOLD: " << optimalThreshold << std::endl;


return std::make_tuple(optimalThreshold, minKLDivergence);

Expand Down Expand Up @@ -760,8 +665,6 @@ std::tuple<int, double> UVDARLedDetectAdaptive::findOptimalThresholdUsingEntropy
}
}

//std::cout << "[UVDARLedDetectAdaptive]: MAX ENTROPY: " << maxEntropy << std::endl;
//std::cout << "[UVDARLedDetectAdaptive]: OPTIMAL THRESHOLD: " << optimalThreshold << std::endl;

return std::make_tuple(optimalThreshold, maxEntropy);
}
Expand Down Expand Up @@ -806,15 +709,7 @@ void UVDARLedDetectAdaptive::generateVisualizationAdaptive(const cv::Mat& inputI
binaryRoi.copyTo(visualization_image(roi));

// Optionally draw a rectangle around the ROI
cv::rectangle(visualization_image, roi, cv::Scalar(0, 255, 0)); // Green rectangle


// // Draw detected points within this ROI
//for (const auto& point : detectedPoints) {
// cv::circle(visualization_image, point, 3, cv::Scalar(0, 0, 255), -1); // Red circle for each point
//}


cv::rectangle(visualization_image, roi, cv::Scalar(0, 255, 0)); // Green rectangle

}
}
Expand Down
Loading

0 comments on commit e0a2594

Please sign in to comment.