test last session

This commit is contained in:
Thomas BONNIER 2024-12-19 11:25:19 +01:00
parent 20841f7d60
commit ebf1f7480f
2 changed files with 121 additions and 16 deletions

View File

@ -41,16 +41,58 @@ void loadTransformationMatrix(const std::string& filename)
fs.release();
}
cv::Mat gammaCorrection(const cv::Mat& image, double gamma = 0.4)
{
cv::Mat lookUpTable(1, 256, CV_8U);
uchar* p = lookUpTable.ptr();
for (int i = 0; i < 256; ++i)
p[i] = cv::saturate_cast<uchar>(pow(i / 255.0, 1.0 / gamma) * 255.0);
cv::Mat corrected;
cv::LUT(image, lookUpTable, corrected);
return corrected;
}
cv::Mat upscaleImage(const cv::Mat& image, double scaleFactor = 3.0)
{
cv::Mat upscaled;
cv::resize(image, upscaled, cv::Size(), scaleFactor, scaleFactor, cv::INTER_LINEAR);
return upscaled;
}
cv::Mat sharpenImage(const cv::Mat& image)
{
cv::Mat sharpeningKernel = (cv::Mat_<float>(3, 3) << 0, -1, 0, -1, 5, -1, 0, -1, 0);
cv::Mat sharpened;
cv::filter2D(image, sharpened, -1, sharpeningKernel);
return sharpened;
}
cv::Mat reduceNoise(const cv::Mat& image)
{
cv::Mat denoised;
cv::GaussianBlur(image, denoised, cv::Size(5, 5), 0);
return denoised;
}
cv::Mat enhanceImage(const cv::Mat& image)
{
cv::Mat gray, blurred, equalized, thresholded, sharpened;
cv::cvtColor(image, gray, cv::COLOR_BGR2GRAY);
cv::GaussianBlur(gray, blurred, cv::Size(5, 5), 0);
cv::equalizeHist(blurred, equalized);
cv::adaptiveThreshold(equalized, thresholded, 255, cv::ADAPTIVE_THRESH_GAUSSIAN_C, cv::THRESH_BINARY, 11, 2);
cv::Mat sharpeningKernel = (cv::Mat_<float>(3, 3) << 0, -1, 0, -1, 5, -1, 0, -1, 0);
cv::filter2D(thresholded, sharpened, -1, sharpeningKernel);
return sharpened;
// Apply gamma correction
cv::Mat enhanced = gammaCorrection(image);
// Sharpen
enhanced = sharpenImage(enhanced);
// Upscale
enhanced = upscaleImage(enhanced, 3.0);
// Sharpen again after upscaling
enhanced = sharpenImage(enhanced);
// Reduce noise
enhanced = reduceNoise(enhanced);
return enhanced;
}
void processFrame(cv::Mat& frame)

View File

@ -33,14 +33,67 @@ void saveTransformationMatrix(const std::string& filename, const cv::Mat& transf
fs.release();
}
cv::Mat gammaCorrection(const cv::Mat& image, double gamma = 0.4)
{
cv::Mat lookUpTable(1, 256, CV_8U);
uchar* p = lookUpTable.ptr();
for (int i = 0; i < 256; ++i)
p[i] = cv::saturate_cast<uchar>(pow(i / 255.0, 1.0 / gamma) * 255.0);
cv::Mat corrected;
cv::LUT(image, lookUpTable, corrected);
return corrected;
}
cv::Mat upscaleImage(const cv::Mat& image, double scaleFactor = 3.0)
{
cv::Mat upscaled;
cv::resize(image, upscaled, cv::Size(), scaleFactor, scaleFactor, cv::INTER_LINEAR);
return upscaled;
}
cv::Mat downscaleImage(const cv::Mat& image, double scaleFactor)
{
if (scaleFactor <= 0)
throw std::invalid_argument("Scale factor must be greater than 0.");
cv::Mat downscaled;
cv::resize(image, downscaled, cv::Size(), scaleFactor, scaleFactor, cv::INTER_LINEAR);
return downscaled;
}
cv::Mat sharpenImage(const cv::Mat& image)
{
cv::Mat sharpeningKernel = (cv::Mat_<float>(3, 3) << 0, -1, 0, -1, 5, -1, 0, -1, 0);
cv::Mat sharpened;
cv::filter2D(image, sharpened, -1, sharpeningKernel);
return sharpened;
}
cv::Mat reduceNoise(const cv::Mat& image)
{
cv::Mat denoised;
cv::GaussianBlur(image, denoised, cv::Size(5, 5), 0);
return denoised;
}
cv::Mat enhanceImage(const cv::Mat& image)
{
cv::Mat gray, blurred, equalized, thresholded;
cv::cvtColor(image, gray, cv::COLOR_BGR2GRAY);
cv::GaussianBlur(gray, blurred, cv::Size(5, 5), 0);
cv::equalizeHist(blurred, equalized);
cv::adaptiveThreshold(equalized, thresholded, 255, cv::ADAPTIVE_THRESH_GAUSSIAN_C, cv::THRESH_BINARY, 11, 2);
return thresholded;
// Apply gamma correction
cv::Mat enhanced = gammaCorrection(image);
// Sharpen
enhanced = sharpenImage(enhanced);
// Upscale
enhanced = upscaleImage(enhanced, 3.0);
// Sharpen again after upscaling
enhanced = sharpenImage(enhanced);
// Reduce noise
enhanced = reduceNoise(enhanced);
return enhanced;
}
void loadMarkerPositions(const std::string& filename)
@ -78,7 +131,17 @@ void processFrame(cv::Mat& frame, std::map<int, cv::Point2f>& markerPositions, c
// Apply image processing steps
cv::Mat processedFrame = enhanceImage(frame);
// Create ArUco marker detector
// Create ArUco marker detector with modified parameters
cv::Ptr<cv::aruco::DetectorParameters> parameters = cv::aruco::DetectorParameters::create();
parameters->adaptiveThreshWinSizeMin = 3;
parameters->adaptiveThreshWinSizeMax = 23;
parameters->adaptiveThreshWinSizeStep = 5;
parameters->minMarkerPerimeterRate = 0.005;
parameters->maxMarkerPerimeterRate = 3.0;
parameters->perspectiveRemoveIgnoredMarginPerCell = 0.05;
parameters->cornerRefinementMethod = cv::aruco::CORNER_REFINE_SUBPIX;
parameters->polygonalApproxAccuracyRate = 0.025;
cv::Ptr<cv::aruco::Dictionary> dictionary =
cv::aruco::getPredefinedDictionary(cv::aruco::DICT_4X4_50);
std::vector<int> markerIds;
@ -86,7 +149,7 @@ void processFrame(cv::Mat& frame, std::map<int, cv::Point2f>& markerPositions, c
std::vector<cv::Vec3d> rvecs, tvecs;
// Detect markers in the image
cv::aruco::detectMarkers(processedFrame, dictionary, markerCorners, markerIds);
cv::aruco::detectMarkers(processedFrame, dictionary, markerCorners, markerIds, parameters);
// Draw detected markers
if (!markerIds.empty())