Jim Ostrowski | ff0f5e4 | 2022-01-22 01:35:31 -0800 | [diff] [blame] | 1 | #include <map> |
| 2 | #include <opencv2/calib3d.hpp> |
| 3 | #include <opencv2/features2d.hpp> |
| 4 | #include <opencv2/highgui/highgui.hpp> |
| 5 | #include <opencv2/imgproc.hpp> |
| 6 | #include <random> |
| 7 | |
| 8 | #include "aos/events/shm_event_loop.h" |
| 9 | #include "aos/init.h" |
| 10 | #include "aos/time/time.h" |
Jim Ostrowski | 977850f | 2022-01-22 21:04:22 -0800 | [diff] [blame^] | 11 | #include "frc971/vision/vision_generated.h" |
Jim Ostrowski | ff0f5e4 | 2022-01-22 01:35:31 -0800 | [diff] [blame] | 12 | #include "y2022/vision/blob_detector.h" |
| 13 | |
| 14 | DEFINE_string(capture, "", |
| 15 | "If set, capture a single image and save it to this filename."); |
| 16 | DEFINE_string(channel, "/camera", "Channel name for the image."); |
| 17 | DEFINE_string(config, "config.json", "Path to the config file to use."); |
| 18 | DEFINE_string(png_dir, |
| 19 | "/home/jim/code/FRC/971-Robot-Code/y2020/vision/LED_Ring_exp", |
| 20 | "Path to a set of images to display."); |
| 21 | DEFINE_bool(show_features, true, "Show the blobs."); |
| 22 | |
| 23 | namespace y2022 { |
| 24 | namespace vision { |
| 25 | namespace { |
| 26 | |
| 27 | aos::Fetcher<frc971::vision::CameraImage> image_fetcher; |
| 28 | |
| 29 | bool DisplayLoop() { |
| 30 | int64_t image_timestamp = 0; |
| 31 | const frc971::vision::CameraImage *image; |
| 32 | // Read next image |
| 33 | if (!image_fetcher.FetchNext()) { |
| 34 | VLOG(2) << "Couldn't fetch next image"; |
| 35 | return true; |
| 36 | } |
| 37 | |
| 38 | image = image_fetcher.get(); |
| 39 | CHECK(image != nullptr) << "Couldn't read image"; |
| 40 | image_timestamp = image->monotonic_timestamp_ns(); |
| 41 | VLOG(2) << "Got image at timestamp: " << image_timestamp; |
| 42 | |
| 43 | // Create color image: |
| 44 | cv::Mat image_color_mat(cv::Size(image->cols(), image->rows()), CV_8UC2, |
| 45 | (void *)image->data()->data()); |
| 46 | cv::Mat rgb_image(cv::Size(image->cols(), image->rows()), CV_8UC3); |
| 47 | cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV); |
| 48 | |
| 49 | if (!FLAGS_capture.empty()) { |
| 50 | cv::imwrite(FLAGS_capture, rgb_image); |
| 51 | return false; |
| 52 | } |
| 53 | |
| 54 | cv::Mat binarized_image, ret_image; |
| 55 | std::vector<std::vector<cv::Point>> unfiltered_blobs, filtered_blobs, |
| 56 | blob_stats; |
| 57 | BlobDetector::ExtractBlobs(rgb_image, binarized_image, ret_image, |
| 58 | filtered_blobs, unfiltered_blobs, blob_stats); |
| 59 | |
| 60 | LOG(INFO) << image->monotonic_timestamp_ns() |
| 61 | << ": # blobs: " << filtered_blobs.size(); |
| 62 | |
| 63 | // Downsize for viewing |
| 64 | cv::resize(rgb_image, rgb_image, |
| 65 | cv::Size(rgb_image.cols / 2, rgb_image.rows / 2), |
| 66 | cv::INTER_LINEAR); |
| 67 | |
| 68 | cv::imshow("image", rgb_image); |
| 69 | cv::imshow("blobs", ret_image); |
| 70 | |
| 71 | int keystroke = cv::waitKey(1); |
| 72 | if ((keystroke & 0xFF) == static_cast<int>('c')) { |
| 73 | // Convert again, to get clean image |
| 74 | cv::cvtColor(image_color_mat, rgb_image, cv::COLOR_YUV2BGR_YUYV); |
| 75 | std::stringstream name; |
| 76 | name << "capture-" << aos::realtime_clock::now() << ".png"; |
| 77 | cv::imwrite(name.str(), rgb_image); |
| 78 | LOG(INFO) << "Saved image file: " << name.str(); |
| 79 | } else if ((keystroke & 0xFF) == static_cast<int>('q')) { |
| 80 | return false; |
| 81 | } |
| 82 | return true; |
| 83 | } |
| 84 | |
| 85 | void ViewerMain() { |
| 86 | aos::FlatbufferDetachedBuffer<aos::Configuration> config = |
| 87 | aos::configuration::ReadConfig(FLAGS_config); |
| 88 | |
| 89 | aos::ShmEventLoop event_loop(&config.message()); |
| 90 | |
| 91 | image_fetcher = |
| 92 | event_loop.MakeFetcher<frc971::vision::CameraImage>(FLAGS_channel); |
| 93 | |
| 94 | // Run the display loop |
| 95 | event_loop.AddPhasedLoop( |
| 96 | [&event_loop](int) { |
| 97 | if (!DisplayLoop()) { |
| 98 | LOG(INFO) << "Calling event_loop Exit"; |
| 99 | event_loop.Exit(); |
| 100 | }; |
| 101 | }, |
| 102 | ::std::chrono::milliseconds(100)); |
| 103 | |
| 104 | event_loop.Run(); |
| 105 | |
| 106 | image_fetcher = aos::Fetcher<frc971::vision::CameraImage>(); |
| 107 | } |
| 108 | |
| 109 | void ViewerLocal() { |
| 110 | std::vector<cv::String> file_list; |
| 111 | cv::glob(FLAGS_png_dir + "/*.png", file_list, false); |
| 112 | for (auto file : file_list) { |
| 113 | LOG(INFO) << "Reading file " << file; |
| 114 | cv::Mat rgb_image = cv::imread(file.c_str()); |
| 115 | std::vector<std::vector<cv::Point>> filtered_blobs, unfiltered_blobs, |
| 116 | blob_stats; |
| 117 | cv::Mat binarized_image = |
| 118 | cv::Mat::zeros(cv::Size(rgb_image.cols, rgb_image.rows), CV_8UC1); |
| 119 | cv::Mat ret_image = |
| 120 | cv::Mat::zeros(cv::Size(rgb_image.cols, rgb_image.rows), CV_8UC3); |
| 121 | |
| 122 | BlobDetector::ExtractBlobs(rgb_image, binarized_image, ret_image, |
| 123 | filtered_blobs, unfiltered_blobs, blob_stats); |
| 124 | |
| 125 | LOG(INFO) << ": # blobs: " << filtered_blobs.size() << " (# removed: " |
| 126 | << unfiltered_blobs.size() - filtered_blobs.size() << ")"; |
| 127 | cv::imshow("image", rgb_image); |
| 128 | cv::imshow("blobs", ret_image); |
| 129 | |
| 130 | int keystroke = cv::waitKey(1000); |
| 131 | if ((keystroke & 0xFF) == static_cast<int>('q')) { |
| 132 | return; |
| 133 | } |
| 134 | } |
| 135 | } |
| 136 | } // namespace |
| 137 | } // namespace vision |
| 138 | } // namespace y2022 |
| 139 | |
| 140 | // Quick and lightweight viewer for images |
| 141 | int main(int argc, char **argv) { |
| 142 | aos::InitGoogle(&argc, &argv); |
| 143 | if (FLAGS_png_dir != "") |
| 144 | y2022::vision::ViewerLocal(); |
| 145 | else |
| 146 | y2022::vision::ViewerMain(); |
| 147 | } |