work nice with a larger area + add comments on QRcode.cpp

This commit is contained in:
Thomas BONNIER 2024-12-19 11:55:56 +01:00
parent 8dbd79d5a4
commit 32a0ba5fd5
2 changed files with 88 additions and 0 deletions

View File

@ -50,3 +50,80 @@
``` ```
2. The node will process frames from the camera, detect ArUco markers, and display their positions in the arena frame. 2. The node will process frames from the camera, detect ArUco markers, and display their positions in the arena frame.
### Additional Information
#### Dependencies
Ensure you have the following dependencies installed:
- ROS
- OpenCV
- yaml-cpp
#### Building the Package
1. Navigate to your catkin workspace:
```bash
cd ~/catkin_ws
```
2. Build the package:
```bash
catkin build test
```
3. Source the workspace:
```bash
source devel/setup.bash
```
#### Running the Nodes
1. Start the ROS master node:
```bash
roscore
```
2. In a new terminal, run the desired node as described in the steps above.
#### Troubleshooting
- If the camera is not detected, ensure it is properly connected and recognized by the system.
- If not enough markers are detected, try adjusting the lighting conditions or the camera position.
- Ensure all configuration files (`camera_parameters.yml`, `arena_config.yml`, `arena_transformation.yml`) are correctly formatted and located in the appropriate directory.
#### Example Configuration Files
`camera_parameters.yml`:
```yaml
camera_matrix: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [fx, 0, cx, 0, fy, cy, 0, 0, 1]
distortion_coefficients: !!opencv-matrix
rows: 1
cols: 5
dt: d
data: [k1, k2, p1, p2, k3]
```
`arena_config.yml`:
```yaml
markers:
- id: 1
position: [0, 0]
- id: 2
position: [0, 1]
- id: 3
position: [0, 2]
```
`arena_transformation.yml`:
```yaml
transformation_matrix: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [1, 0, 0, 0, 1, 0, 0, 0, 1]
```

View File

@ -7,10 +7,12 @@
#include <thread> #include <thread>
#include <yaml-cpp/yaml.h> #include <yaml-cpp/yaml.h>
// Global variables for camera parameters and marker positions
cv::Mat cameraMatrix, distCoeffs; cv::Mat cameraMatrix, distCoeffs;
std::map<int, cv::Point2f> markerPositions; std::map<int, cv::Point2f> markerPositions;
cv::Mat transformationMatrix; cv::Mat transformationMatrix;
// Function to load marker positions from a YAML file
void loadMarkerPositions(const std::string& filename) void loadMarkerPositions(const std::string& filename)
{ {
try try
@ -29,6 +31,7 @@ void loadMarkerPositions(const std::string& filename)
} }
} }
// Function to load the transformation matrix from a YAML file
void loadTransformationMatrix(const std::string& filename) void loadTransformationMatrix(const std::string& filename)
{ {
cv::FileStorage fs(filename, cv::FileStorage::READ); cv::FileStorage fs(filename, cv::FileStorage::READ);
@ -41,6 +44,7 @@ void loadTransformationMatrix(const std::string& filename)
fs.release(); fs.release();
} }
// Function to apply gamma correction to an image
cv::Mat gammaCorrection(const cv::Mat& image, double gamma = 0.4) cv::Mat gammaCorrection(const cv::Mat& image, double gamma = 0.4)
{ {
cv::Mat lookUpTable(1, 256, CV_8U); cv::Mat lookUpTable(1, 256, CV_8U);
@ -53,6 +57,7 @@ cv::Mat gammaCorrection(const cv::Mat& image, double gamma = 0.4)
return corrected; return corrected;
} }
// Function to upscale an image
cv::Mat upscaleImage(const cv::Mat& image, double scaleFactor = 3.0) cv::Mat upscaleImage(const cv::Mat& image, double scaleFactor = 3.0)
{ {
cv::Mat upscaled; cv::Mat upscaled;
@ -60,6 +65,7 @@ cv::Mat upscaleImage(const cv::Mat& image, double scaleFactor = 3.0)
return upscaled; return upscaled;
} }
// Function to sharpen an image
cv::Mat sharpenImage(const cv::Mat& image) 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 sharpeningKernel = (cv::Mat_<float>(3, 3) << 0, -1, 0, -1, 5, -1, 0, -1, 0);
@ -68,6 +74,7 @@ cv::Mat sharpenImage(const cv::Mat& image)
return sharpened; return sharpened;
} }
// Function to reduce noise in an image
cv::Mat reduceNoise(const cv::Mat& image) cv::Mat reduceNoise(const cv::Mat& image)
{ {
cv::Mat denoised; cv::Mat denoised;
@ -75,6 +82,7 @@ cv::Mat reduceNoise(const cv::Mat& image)
return denoised; return denoised;
} }
// Function to enhance an image by applying various processing steps
cv::Mat enhanceImage(const cv::Mat& image) cv::Mat enhanceImage(const cv::Mat& image)
{ {
// Apply gamma correction // Apply gamma correction
@ -95,6 +103,7 @@ cv::Mat enhanceImage(const cv::Mat& image)
return enhanced; return enhanced;
} }
// Function to process a frame and detect ArUco markers
void processFrame(cv::Mat& frame) void processFrame(cv::Mat& frame)
{ {
// Apply image processing steps // Apply image processing steps
@ -195,6 +204,7 @@ void processFrame(cv::Mat& frame)
cv::waitKey(1); cv::waitKey(1);
} }
// Thread function to continuously capture and process frames from the camera
void frameProcessingThread() void frameProcessingThread()
{ {
cv::VideoCapture cap(0, cv::CAP_V4L2); // Open the default camera with V4L2 backend cv::VideoCapture cap(0, cv::CAP_V4L2); // Open the default camera with V4L2 backend
@ -225,6 +235,7 @@ void frameProcessingThread()
} }
} }
// Main function
int main(int argc, char** argv) int main(int argc, char** argv)
{ {
ros::init(argc, argv, "aruco_detector"); ros::init(argc, argv, "aruco_detector");