Skip to content

Commit

Permalink
Latest change after thesis
Browse files Browse the repository at this point in the history
  • Loading branch information
MarlonRiv committed Jul 22, 2024
1 parent b016597 commit 60ff9c1
Show file tree
Hide file tree
Showing 10 changed files with 2,169 additions and 663 deletions.
Binary file added heading_decoding.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
48 changes: 30 additions & 18 deletions include/detect/uv_led_detect_adaptive.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,15 @@ const std::vector<cv::Point>& standardPoints) {

// Use a set to store unique points
std::set<cv::Point, PointComparator> uniquePoints;

std::string outputDir = "/home/rivermar/Desktop/MRS_Master_Project/pres_images";

// Ensure the output directory exists
fs::create_directories(outputDir);

/* cv::imwrite(outputDir + "/im_" + std::to_string(index) + ".png", inputImage); */

index++;
// Reset detected points
detectedPoints.clear();
lastProcessedBinaryROIs_.clear();
Expand Down Expand Up @@ -171,7 +179,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 @@ -209,10 +217,10 @@ std::vector<cv::Point> UVDARLedDetectAdaptive::applyAdaptiveThreshold(const cv::
cv::addWeighted(grayImage, 0.25, unsharpMask, 1.75, 0, enhancedImage);


cv::Mat histEnhanced = plotHistogram(enhancedImage);
/* cv::Mat histEnhanced = plotHistogram(enhancedImage); */

// Specify the output directory
std::string outputDir = "/home/rivermar/Desktop/MRS_Master_Project/roi_images";
std::string outputDir = "/home/rivermar/Desktop/MRS_Master_Project/pres_images";

// Ensure the output directory exists
fs::create_directories(outputDir);
Expand Down Expand Up @@ -249,21 +257,22 @@ std::vector<cv::Point> UVDARLedDetectAdaptive::applyAdaptiveThreshold(const cv::


//Save the original and enhanced images
cv::imwrite(outputDir + "/im_" + std::to_string(index) + ".png", grayImage);
index++;
// Save the histograms adding an index for each histogram
cv::imwrite(outputDir + "/im_" + std::to_string(index) + ".png", histOriginal);
index++;
//Save the binary ROI using the original image
cv::imwrite(outputDir + "/im_" + std::to_string(index) + ".png", binaryRoiOriginal);
/* cv::imwrite(outputDir + "/im_" + std::to_string(index) + ".png", grayImage); */
index++;

/* // Save the histograms adding an index for each histogram */
/* cv::imwrite(outputDir + "/im_" + std::to_string(index) + ".png", histOriginal); */
/* index++; */
/* //Save the binary ROI using the original image */
/* cv::imwrite(outputDir + "/im_" + std::to_string(index) + ".png", binaryRoiOriginal); */
/* index++; */
//Save the enhanced image
cv::imwrite(outputDir + "/im_" + std::to_string(index) + ".png", enhancedImage);
index++;
cv::imwrite(outputDir + "/im_" + std::to_string(index) + ".png", histEnhanced);
/* cv::imwrite(outputDir + "/im_" + std::to_string(index) + ".png", enhancedImage); */
index++;
//Save the binary ROI
cv::imwrite(outputDir + "/im_" + std::to_string(index) + ".png", binaryRoi);
/* cv::imwrite(outputDir + "/im_" + std::to_string(index) + ".png", histEnhanced); */
/* index++; */
/* //Save the binary ROI */
/* cv::imwrite(outputDir + "/im_" + std::to_string(index) + ".png", binaryRoi); */
index++;

// Find contours in the binary ROI
Expand Down Expand Up @@ -308,9 +317,12 @@ std::vector<cv::Point> UVDARLedDetectAdaptive::applyAdaptiveThreshold(const cv::

// Detect points within this ROI
std::vector<cv::Point> roiDetectedPoints = detectPointsFromRoi(binaryRoi, roi);
/* //Save the binary ROI */
/* cv::imwrite(outputDir + "/im_" + std::to_string(index) + ".png", binaryRoi); */
index++;

if (adaptive_debug_){
//Print the number of detected points
//Print the number of detected points
std::cout << "[UVDARLedDetectAdaptive]: ROI NUMBER OF DETECTED POINTS: " << roiDetectedPoints.size() << std::endl;
}

Expand Down Expand Up @@ -884,7 +896,7 @@ void UVDARLedDetectAdaptive::saveRoiImage(const cv::Mat& binaryRoi, const cv::Po
std::string fullPath = fs::path(outputDir) / filename;

// Save the image
cv::imwrite(fullPath, binaryRoi);
/* cv::imwrite(fullPath, binaryRoi); */
}
//}

Expand Down Expand Up @@ -912,4 +924,4 @@ ROIData UVDARLedDetectAdaptive::prepareAdaptiveDataForLogging() {
}


} // namespace uvdar
} // namespace uvdar
4 changes: 2 additions & 2 deletions include/detect/uv_led_detect_adaptive.h
Original file line number Diff line number Diff line change
Expand Up @@ -95,10 +95,10 @@ class UVDARLedDetectAdaptive{
std::vector<float> klDivergence;
std::vector<int> validRoi;
int index = 0;

int index_g = 0;

};

} // namespace uvdar

#endif // UV_LED_DETECT_ADAPTIVE_H
#endif // UV_LED_DETECT_ADAPTIVE_H
2 changes: 1 addition & 1 deletion launch/rosbag.launch
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@
<param name="publish" type="bool" value="$(arg publish)"/>
<param name="justReport" type="bool" value="true"/>
<param name="threshold" type="int" value="$(arg threshold)"/>
<param name="adaptive_threshold" type="bool" value="false"/>
<param name="adaptive_threshold" type="bool" value="true"/>
<param name="adaptive_method" type="string" value="otsu"/>
<param name="adaptive_debug" type="bool" value="true"/>

Expand Down
5 changes: 3 additions & 2 deletions scripts/.tmuxinator.yml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ windows:
- rqtviz:
layout: even-vertical
panes:
- waitForRos; sleep 3; rosbag record -O ~/Desktop/MRS_Master_Project/rosbags/good_sequence/diff_power_18m_th150_topics.bag /uav7/uvdar_bluefox/left/image_raw /uav7/uvdar/points_seen_left /uav7/uvdar/blinkers_seen_back /uav7/uvdar/ami_all_seq_info_back
# - waitForRos; sleep 3; rosbag record -O ~/Desktop/MRS_Master_Project/rosbags/good_sequence/diff_power_18m_th150_topics.bag /uav7/uvdar_bluefox/left/image_raw /uav7/uvdar/points_seen_left /uav7/uvdar/blinkers_seen_back /uav7/uvdar/ami_all_seq_info_back
#- rosbag record -O rosbags/first/omta_38.bag -e "(.*)_camp"
# - rosbag record -O rosbags/first/omta_39.bag -e "(.*)_camp"
# - rosbag record -O rosbags/first/4dht_38.bag -e "(.*)_camp"
Expand All @@ -36,7 +36,8 @@ windows:
# - waitForRos; sleep 3; rosbag play --clock ~/experiments/20_04/two_tx/two_tx/rx/occlusion_1/rx.bag
# - waitForRos; sleep 3; rosbag play --clock ~/experiments/20_04/two_tx/two_tx/rx/occlusion_2/rx.bag
# - waitForRos; rosbag play --clock ~/experiments/20_04/tumult/tumult/rx/rx.bag
- waitForRos; sleep 3; rosbag play --clock ~/Desktop/MRS_Master_Project/experiments/diff_power_18m_0615.bag
- waitForRos; sleep 3; rosbag play --clock ~/Desktop/MRS_Master_Project/experiments/diff_power_5m_0615.bag

# - waitForRos; sleep 3; rosbag play --clock ~/experiments/19_04/demo_first/rx1/all_three/rx1.bag

- topics:
Expand Down
Loading

0 comments on commit 60ff9c1

Please sign in to comment.