|
| 1 | +// Copyright 2025 TIER IV, Inc. |
| 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 | + |
| 15 | +#include "traffic_light_selector_node.hpp" |
| 16 | + |
| 17 | +#include <opencv2/core/types.hpp> |
| 18 | +#include <opencv2/opencv.hpp> |
| 19 | + |
| 20 | +#include <sensor_msgs/msg/region_of_interest.hpp> |
| 21 | + |
| 22 | +#include <map> |
| 23 | +#include <memory> |
| 24 | +#include <vector> |
| 25 | + |
| 26 | +namespace autoware::traffic_light |
| 27 | +{ |
| 28 | + |
| 29 | +TrafficLightSelectorNode::TrafficLightSelectorNode(const rclcpp::NodeOptions & node_options) |
| 30 | +: rclcpp::Node("traffic_light_selector_node", node_options), |
| 31 | + tf_buffer_(get_clock()), |
| 32 | + tf_listener_(tf_buffer_), |
| 33 | + detected_rois_sub_(this, "input/detected_rois", rclcpp::QoS{1}.get_rmw_qos_profile()), |
| 34 | + rough_rois_sub_(this, "input/rough_rois", rclcpp::QoS{1}.get_rmw_qos_profile()), |
| 35 | + expected_rois_sub_(this, "input/expect_rois", rclcpp::QoS{1}.get_rmw_qos_profile()), |
| 36 | + sync_(SyncPolicy(10), detected_rois_sub_, rough_rois_sub_, expected_rois_sub_) |
| 37 | +{ |
| 38 | + { |
| 39 | + stop_watch_ptr_ = |
| 40 | + std::make_unique<autoware::universe_utils::StopWatch<std::chrono::milliseconds>>(); |
| 41 | + debug_publisher_ = |
| 42 | + std::make_unique<autoware::universe_utils::DebugPublisher>(this, this->get_name()); |
| 43 | + stop_watch_ptr_->tic("cyclic_time"); |
| 44 | + stop_watch_ptr_->tic("processing_time"); |
| 45 | + } |
| 46 | + |
| 47 | + max_iou_threshold_ = declare_parameter<double>("max_iou_threshold"); |
| 48 | + using std::placeholders::_1; |
| 49 | + using std::placeholders::_2; |
| 50 | + using std::placeholders::_3; |
| 51 | + sync_.registerCallback(std::bind(&TrafficLightSelectorNode::objectsCallback, this, _1, _2, _3)); |
| 52 | + |
| 53 | + camera_info_sub_ = create_subscription<sensor_msgs::msg::CameraInfo>( |
| 54 | + "input/camera_info", rclcpp::SensorDataQoS(), |
| 55 | + std::bind(&TrafficLightSelectorNode::cameraInfoCallback, this, _1)); |
| 56 | + // Publisher |
| 57 | + pub_traffic_light_rois_ = |
| 58 | + create_publisher<TrafficLightRoiArray>("output/traffic_rois", rclcpp::QoS{1}); |
| 59 | +} |
| 60 | + |
| 61 | +void TrafficLightSelectorNode::cameraInfoCallback( |
| 62 | + const sensor_msgs::msg::CameraInfo::ConstSharedPtr input_msg) |
| 63 | +{ |
| 64 | + if (camera_info_subscribed_) { |
| 65 | + return; |
| 66 | + } |
| 67 | + RCLCPP_INFO(get_logger(), "camera_info received"); |
| 68 | + image_width_ = input_msg->width; |
| 69 | + image_height_ = input_msg->height; |
| 70 | + camera_info_subscribed_ = true; |
| 71 | +} |
| 72 | + |
| 73 | +void TrafficLightSelectorNode::objectsCallback( |
| 74 | + const DetectedObjectsWithFeature::ConstSharedPtr & detected_traffic_light_msg, |
| 75 | + const TrafficLightRoiArray::ConstSharedPtr & rough_rois_msg, |
| 76 | + const TrafficLightRoiArray::ConstSharedPtr & expected_rois_msg) |
| 77 | +{ |
| 78 | + stop_watch_ptr_->toc("processing_time", true); |
| 79 | + if (!camera_info_subscribed_) { |
| 80 | + return; |
| 81 | + } |
| 82 | + std::map<int, sensor_msgs::msg::RegionOfInterest> rough_rois_map; |
| 83 | + for (const auto & roi : rough_rois_msg->rois) { |
| 84 | + rough_rois_map[roi.traffic_light_id] = roi.roi; |
| 85 | + } |
| 86 | + // TODO(badai-nguyen): implement this function on CUDA or refactor the code |
| 87 | + |
| 88 | + TrafficLightRoiArray output; |
| 89 | + output.header = detected_traffic_light_msg->header; |
| 90 | + float max_matching_score = 0.0; |
| 91 | + int det_roi_shift_x = 0; |
| 92 | + int det_roi_shift_y = 0; |
| 93 | + std::vector<sensor_msgs::msg::RegionOfInterest> det_rois; |
| 94 | + std::vector<sensor_msgs::msg::RegionOfInterest> expect_rois; |
| 95 | + for (const auto & detected_roi : detected_traffic_light_msg->feature_objects) { |
| 96 | + det_rois.push_back(detected_roi.feature.roi); |
| 97 | + } |
| 98 | + for (const auto & expected_roi : expected_rois_msg->rois) { |
| 99 | + expect_rois.push_back(expected_roi.roi); |
| 100 | + } |
| 101 | + cv::Mat expect_roi_img = |
| 102 | + utils::createBinaryImageFromRois(expect_rois, cv::Size(image_width_, image_height_)); |
| 103 | + cv::Mat det_roi_img = |
| 104 | + utils::createBinaryImageFromRois(det_rois, cv::Size(image_width_, image_height_)); |
| 105 | + // for (const auto expect_roi : expect_rois) { |
| 106 | + for (const auto & expect_traffic_roi : expected_rois_msg->rois) { |
| 107 | + const auto & expect_roi = expect_traffic_roi.roi; |
| 108 | + auto traffic_light_id = expect_traffic_roi.traffic_light_id; |
| 109 | + const auto & rough_roi = rough_rois_map[traffic_light_id]; |
| 110 | + |
| 111 | + for (const auto & detected_roi : det_rois) { |
| 112 | + // check if the detected roi is inside the rough roi |
| 113 | + if (!utils::isInsideRoughRoi(detected_roi, rough_roi)) { |
| 114 | + continue; |
| 115 | + } |
| 116 | + int dx = static_cast<int>(detected_roi.x_offset) - static_cast<int>(expect_roi.x_offset); |
| 117 | + int dy = static_cast<int>(detected_roi.y_offset) - static_cast<int>(expect_roi.y_offset); |
| 118 | + cv::Mat det_roi_shifted = utils::shiftAndPaddingImage(det_roi_img, dx, dy); |
| 119 | + double iou = utils::getIoUOf2BinaryImages(expect_roi_img, det_roi_shifted); |
| 120 | + if (iou > max_matching_score) { |
| 121 | + max_matching_score = iou; |
| 122 | + det_roi_shift_x = dx; |
| 123 | + det_roi_shift_y = dy; |
| 124 | + } |
| 125 | + } |
| 126 | + } |
| 127 | + |
| 128 | + for (const auto & expect_roi : expected_rois_msg->rois) { |
| 129 | + // check max IOU after shift |
| 130 | + double max_iou = -1.0; |
| 131 | + sensor_msgs::msg::RegionOfInterest max_iou_roi; |
| 132 | + for (const auto & detected_roi : detected_traffic_light_msg->feature_objects) { |
| 133 | + // shift detected roi by det_roi_shift_x, det_roi_shift_y and calculate IOU |
| 134 | + sensor_msgs::msg::RegionOfInterest detected_roi_shifted = detected_roi.feature.roi; |
| 135 | + // fit top lef corner of detected roi to inside of image |
| 136 | + detected_roi_shifted.x_offset = std::clamp( |
| 137 | + static_cast<int>(detected_roi.feature.roi.x_offset) - det_roi_shift_x, 0, |
| 138 | + static_cast<int>(image_width_ - detected_roi.feature.roi.width)); |
| 139 | + detected_roi_shifted.y_offset = std::clamp( |
| 140 | + static_cast<int>(detected_roi.feature.roi.y_offset) - det_roi_shift_y, 0, |
| 141 | + static_cast<int>(image_height_ - detected_roi.feature.roi.height)); |
| 142 | + |
| 143 | + double iou = utils::getGenIoU(expect_roi.roi, detected_roi_shifted); |
| 144 | + if (iou > max_iou) { |
| 145 | + max_iou = iou; |
| 146 | + max_iou_roi = detected_roi.feature.roi; |
| 147 | + } |
| 148 | + } |
| 149 | + if (max_iou > max_iou_threshold_) { |
| 150 | + TrafficLightRoi traffic_light_roi; |
| 151 | + traffic_light_roi.traffic_light_id = expect_roi.traffic_light_id; |
| 152 | + traffic_light_roi.traffic_light_type = expect_roi.traffic_light_type; |
| 153 | + traffic_light_roi.roi = max_iou_roi; |
| 154 | + output.rois.push_back(traffic_light_roi); |
| 155 | + } else { |
| 156 | + TrafficLightRoi traffic_light_roi; |
| 157 | + traffic_light_roi.traffic_light_id = expect_roi.traffic_light_id; |
| 158 | + traffic_light_roi.traffic_light_type = expect_roi.traffic_light_type; |
| 159 | + output.rois.push_back(traffic_light_roi); |
| 160 | + } |
| 161 | + } |
| 162 | + pub_traffic_light_rois_->publish(output); |
| 163 | + if (debug_publisher_) { |
| 164 | + const double processing_time_ms = stop_watch_ptr_->toc("processing_time", true); |
| 165 | + const double cyclic_time_ms = stop_watch_ptr_->toc("cyclic_time", true); |
| 166 | + const double pipeline_latency_ms = |
| 167 | + std::chrono::duration<double, std::milli>( |
| 168 | + std::chrono::nanoseconds((this->get_clock()->now() - output.header.stamp).nanoseconds())) |
| 169 | + .count(); |
| 170 | + debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>( |
| 171 | + "debug/cyclic_time_ms", cyclic_time_ms); |
| 172 | + debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>( |
| 173 | + "debug/processing_time_ms", processing_time_ms); |
| 174 | + debug_publisher_->publish<tier4_debug_msgs::msg::Float64Stamped>( |
| 175 | + "debug/pipeline_latency_ms", pipeline_latency_ms); |
| 176 | + } |
| 177 | + return; |
| 178 | +} |
| 179 | +} // namespace autoware::traffic_light |
| 180 | + |
| 181 | +#include "rclcpp_components/register_node_macro.hpp" |
| 182 | +RCLCPP_COMPONENTS_REGISTER_NODE(autoware::traffic_light::TrafficLightSelectorNode) |
0 commit comments