|
| 1 | +// Copyright 2024 The Autoware Contributors |
| 2 | +// |
| 3 | +// Licensed under the Apache License, Version 2.0 (the "License"); |
| 4 | +// you may not use this file except in compliance with the License. |
| 5 | +// You may obtain a copy of the License at |
| 6 | +// |
| 7 | +// http://www.apache.org/licenses/LICENSE-2.0 |
| 8 | +// |
| 9 | +// Unless required by applicable law or agreed to in writing, software |
| 10 | +// distributed under the License is distributed on an "AS IS" BASIS, |
| 11 | +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. |
| 12 | +// See the License for the specific language governing permissions and |
| 13 | +// limitations under the License. |
| 14 | +#include "traffic_light_visualization/traffic_light_roi_visualizer/shape_draw.hpp" |
| 15 | + |
| 16 | +#include "opencv2/core/types.hpp" |
| 17 | +#include "opencv2/highgui.hpp" |
| 18 | +#include "opencv2/imgproc.hpp" |
| 19 | + |
| 20 | +void drawShape( |
| 21 | + const DrawFunctionParams & params, const std::string & filename, bool flipHorizontally, |
| 22 | + bool flipVertically, int x_offset, int y_offset, double scale_factor) |
| 23 | +{ |
| 24 | + std::string filepath = |
| 25 | + ament_index_cpp::get_package_share_directory("traffic_light_visualization") + "/images/" + |
| 26 | + filename; |
| 27 | + cv::Mat shapeImg = cv::imread(filepath, cv::IMREAD_UNCHANGED); |
| 28 | + if (shapeImg.empty()) { |
| 29 | + std::cerr << "Failed to load image: " << filepath << std::endl; |
| 30 | + return; |
| 31 | + } |
| 32 | + |
| 33 | + if (flipHorizontally) { |
| 34 | + cv::flip(shapeImg, shapeImg, 1); // Flip horizontally |
| 35 | + } |
| 36 | + |
| 37 | + if (flipVertically) { |
| 38 | + cv::flip(shapeImg, shapeImg, 0); // Flip vertically |
| 39 | + } |
| 40 | + |
| 41 | + cv::resize( |
| 42 | + shapeImg, shapeImg, cv::Size(params.size, params.size), scale_factor, scale_factor, |
| 43 | + cv::INTER_AREA); |
| 44 | + |
| 45 | + // Calculate the center position including offsets |
| 46 | + cv::Point position( |
| 47 | + params.position.x + x_offset, params.position.y - shapeImg.rows / 2 + y_offset); |
| 48 | + |
| 49 | + // Check for image boundaries |
| 50 | + if ( |
| 51 | + position.x < 0 || position.y < 0 || position.x + shapeImg.cols > params.image.cols || |
| 52 | + position.y + shapeImg.rows > params.image.rows) { |
| 53 | + std::cerr << "Adjusted position is out of image bounds." << std::endl; |
| 54 | + return; |
| 55 | + } |
| 56 | + |
| 57 | + // Calculate the width of the text |
| 58 | + std::string probabilityText = |
| 59 | + std::to_string(static_cast<int>(round(params.probability * 100))) + "%"; |
| 60 | + int baseline = 0; |
| 61 | + cv::Size textSize = |
| 62 | + cv::getTextSize(probabilityText, cv::FONT_HERSHEY_SIMPLEX, 0.75, 2, &baseline); |
| 63 | + |
| 64 | + // Adjust the filled rectangle to be at the top edge and the correct width |
| 65 | + int filledRectWidth = |
| 66 | + shapeImg.cols + (filename != "unknown.png" ? textSize.width + 10 : 5); // Add some padding |
| 67 | + int filledRectHeight = shapeImg.rows + 10; // Add some padding |
| 68 | + |
| 69 | + cv::rectangle( |
| 70 | + params.image, cv::Rect(position.x - 2, position.y - 5, filledRectWidth, filledRectHeight), |
| 71 | + params.color, |
| 72 | + -1); // Filled rectangle |
| 73 | + |
| 74 | + // Create ROI on the destination image |
| 75 | + cv::Mat destinationROI = params.image(cv::Rect(position, cv::Size(shapeImg.cols, shapeImg.rows))); |
| 76 | + |
| 77 | + // Overlay the image onto the main image |
| 78 | + for (int y = 0; y < shapeImg.rows; ++y) { |
| 79 | + for (int x = 0; x < shapeImg.cols; ++x) { |
| 80 | + cv::Vec4b & pixel = shapeImg.at<cv::Vec4b>(y, x); |
| 81 | + if (pixel[3] != 0) { // Only non-transparent pixels |
| 82 | + destinationROI.at<cv::Vec3b>(y, x) = cv::Vec3b(pixel[0], pixel[1], pixel[2]); |
| 83 | + } |
| 84 | + } |
| 85 | + } |
| 86 | + |
| 87 | + // Position the probability text right next to the shape |
| 88 | + if (filename != "unknown.png") { |
| 89 | + cv::putText( |
| 90 | + params.image, probabilityText, |
| 91 | + cv::Point( |
| 92 | + position.x + shapeImg.cols + 5, position.y + shapeImg.rows / 2 + textSize.height / 2), |
| 93 | + cv::FONT_HERSHEY_SIMPLEX, 0.75, cv::Scalar(0, 0, 0), 2, cv::LINE_AA); |
| 94 | + } |
| 95 | +} |
| 96 | + |
| 97 | +void drawCircle(const DrawFunctionParams & params) |
| 98 | +{ |
| 99 | + int y_offset = params.size / 2 + 5; |
| 100 | + drawShape(params, "circle.png", false, false, 0, -y_offset); |
| 101 | +} |
| 102 | + |
| 103 | +void drawLeftArrow(const DrawFunctionParams & params) |
| 104 | +{ |
| 105 | + int y_offset = params.size / 2 + 5; |
| 106 | + drawShape(params, "left_arrow.png", false, false, 0, -y_offset); |
| 107 | +} |
| 108 | + |
| 109 | +void drawRightArrow(const DrawFunctionParams & params) |
| 110 | +{ |
| 111 | + int y_offset = params.size / 2 + 5; |
| 112 | + drawShape(params, "left_arrow.png", true, false, 0, -y_offset); |
| 113 | +} |
| 114 | + |
| 115 | +void drawStraightArrow(const DrawFunctionParams & params) |
| 116 | +{ |
| 117 | + int y_offset = params.size / 2 + 5; // This adjusts the base position upwards |
| 118 | + |
| 119 | + drawShape(params, "straight_arrow.png", false, false, 0, -y_offset); |
| 120 | +} |
| 121 | +void drawDownArrow(const DrawFunctionParams & params) |
| 122 | +{ |
| 123 | + int y_offset = params.size / 2 + 5; // This adjusts the base position upwards |
| 124 | + drawShape(params, "straight_arrow.png", false, true, 0, -y_offset); |
| 125 | +} |
| 126 | + |
| 127 | +void drawDownLeftArrow(const DrawFunctionParams & params) |
| 128 | +{ |
| 129 | + int y_offset = params.size / 2 + 5; |
| 130 | + drawShape(params, "down_left_arrow.png", false, false, 0, -y_offset); |
| 131 | +} |
| 132 | + |
| 133 | +void drawDownRightArrow(const DrawFunctionParams & params) |
| 134 | +{ |
| 135 | + int y_offset = params.size / 2 + 5; |
| 136 | + drawShape(params, "down_left_arrow.png", true, false, 0, -y_offset); |
| 137 | +} |
| 138 | + |
| 139 | +void drawCross(const DrawFunctionParams & params) |
| 140 | +{ |
| 141 | + int y_offset = params.size / 2 + 5; |
| 142 | + |
| 143 | + drawShape(params, "cross.png", false, false, 0, -y_offset); |
| 144 | +} |
| 145 | + |
| 146 | +void drawUnknown(const DrawFunctionParams & params) |
| 147 | +{ |
| 148 | + int y_offset = params.size / 2 + 5; |
| 149 | + drawShape(params, "unknown.png", false, false, 0, -y_offset); |
| 150 | +} |
| 151 | + |
| 152 | +void drawTrafficLightShape( |
| 153 | + cv::Mat & image, const std::string & shape, const cv::Point & position, const cv::Scalar & color, |
| 154 | + int size, float probability) |
| 155 | +{ |
| 156 | + static std::map<std::string, DrawFunction> shapeToFunction = { |
| 157 | + {"circle", drawCircle}, |
| 158 | + {"left", drawLeftArrow}, |
| 159 | + {"right", drawRightArrow}, |
| 160 | + {"straight", drawStraightArrow}, |
| 161 | + {"down", drawDownArrow}, |
| 162 | + {"down_left", drawDownLeftArrow}, |
| 163 | + {"down_right", drawDownRightArrow}, |
| 164 | + {"cross", drawCross}, |
| 165 | + {"unknown", drawUnknown}}; |
| 166 | + auto it = shapeToFunction.find(shape); |
| 167 | + if (it != shapeToFunction.end()) { |
| 168 | + DrawFunctionParams params{image, position, color, size, probability}; |
| 169 | + it->second(params); |
| 170 | + } else { |
| 171 | + std::cerr << "Unknown shape: " << shape << std::endl; |
| 172 | + } |
| 173 | +} |
0 commit comments