From b68b51cf397f40b29dc2bfae4882907f3656c7a0 Mon Sep 17 00:00:00 2001 From: Your Name Date: Wed, 17 Apr 2024 15:45:45 +0200 Subject: [PATCH] Added visualization thread with rois --- src/detector.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/src/detector.cpp b/src/detector.cpp index 514b69f..4ab35c7 100644 --- a/src/detector.cpp +++ b/src/detector.cpp @@ -584,9 +584,6 @@ class UVDARDetector : public nodelet::Nodelet{ //ROS_INFO_STREAM("[UVDARDetector]: Processing image with tracking points only."); processAdaptive(image, image_index, trackingPointsPerCamera[image_index]); - cv::Mat white_background = cv::Mat::ones(image->image.size(), image->image.type()) * 255; - uvda_[image_index]->generateVisualizationAdaptive(white_background,visualization_image,adaptive_detected_points_[image_index]); - //publishVisualizationImage(visualization_image); } } @@ -661,7 +658,12 @@ class UVDARDetector : public nodelet::Nodelet{ void VisualizationThread([[maybe_unused]] const ros::TimerEvent& te) { if (initialized_){ //generateVisualization(image_visualization_); - if ((image_visualization_.cols != 0) && (image_visualization_.rows != 0)){ + int image_index = 0; + cv::Mat visualization_image; + cv::Mat white_background = cv::Mat::ones(images_current_[image_index].size(),images_current_[image_index].type()) * 255; + uvda_[image_index]->generateVisualizationAdaptive(white_background,visualization_image,adaptive_detected_points_[image_index]); + //publishVisualizationImage(visualization_image); + if ((visualization_image.cols != 0) && (visualization_image.rows != 0)){ if (_publish_visualization_){ ROS_INFO_STREAM("[UVDARDetector]: Publishing visualization."); pub_visualization_->publish("uvdar_detection_visualization", 0.01, visualization_image, true); @@ -804,7 +806,6 @@ class UVDARDetector : public nodelet::Nodelet{ ros::Time initial_delay_start_; - cv::Mat visualization_image; std::vector timer_process_tracking_;