Skip to content

Commit 6e4fe3c

Browse files
tzhong518ktro2828pre-commit-ci[bot]
authored andcommitted
feat(traffic_light): output undetected traffic light as unknown (autowarefoundation#5934)
* fix: output undetected traffic light as unknown Signed-off-by: tzhong518 <sworgun@gmail.com> * Update perception/traffic_light_classifier/src/nodelet.cpp Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> * Update perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> * style(pre-commit): autofix * fix: unnecessary count Signed-off-by: tzhong518 <sworgun@gmail.com> * style(pre-commit): autofix * fix: improve readability Signed-off-by: tzhong518 <sworgun@gmail.com> * fix: index error Signed-off-by: tzhong518 <sworgun@gmail.com> * fix: append the undetected rois at the end so that the order can be easily kept Signed-off-by: tzhong518 <sworgun@gmail.com> * fix: false occlusion ratio for undetected signals Signed-off-by: tzhong518 <sworgun@gmail.com> --------- Signed-off-by: tzhong518 <sworgun@gmail.com> Co-authored-by: Kotaro Uetake <60615504+ktro2828@users.noreply.github.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent b363c98 commit 6e4fe3c

File tree

4 files changed

+63
-15
lines changed

4 files changed

+63
-15
lines changed

perception/traffic_light_classifier/src/nodelet.cpp

+24-6
Original file line numberDiff line numberDiff line change
@@ -13,6 +13,8 @@
1313
// limitations under the License.
1414
#include "traffic_light_classifier/nodelet.hpp"
1515

16+
#include <tier4_perception_msgs/msg/traffic_light_element.hpp>
17+
1618
#include <iostream>
1719
#include <memory>
1820
#include <utility>
@@ -98,16 +100,18 @@ void TrafficLightClassifierNodelet::imageRoiCallback(
98100
output_msg.signals.resize(input_rois_msg->rois.size());
99101

100102
std::vector<cv::Mat> images;
101-
size_t num_valid_roi = 0;
102103
std::vector<size_t> backlight_indices;
103104
for (size_t i = 0; i < input_rois_msg->rois.size(); i++) {
104-
// skip if not the expected type of roi
105+
// skip if the roi is not detected
106+
if (input_rois_msg->rois.at(i).roi.height == 0) {
107+
break;
108+
}
105109
if (input_rois_msg->rois.at(i).traffic_light_type != classify_traffic_light_type_) {
106110
continue;
107111
}
108-
output_msg.signals[num_valid_roi].traffic_light_id =
112+
output_msg.signals[images.size()].traffic_light_id =
109113
input_rois_msg->rois.at(i).traffic_light_id;
110-
output_msg.signals[num_valid_roi].traffic_light_type =
114+
output_msg.signals[images.size()].traffic_light_type =
111115
input_rois_msg->rois.at(i).traffic_light_type;
112116
const sensor_msgs::msg::RegionOfInterest & roi = input_rois_msg->rois.at(i).roi;
113117

@@ -116,15 +120,29 @@ void TrafficLightClassifierNodelet::imageRoiCallback(
116120
backlight_indices.emplace_back(i);
117121
}
118122
images.emplace_back(roi_img);
119-
num_valid_roi++;
120123
}
121-
output_msg.signals.resize(num_valid_roi);
122124

125+
output_msg.signals.resize(images.size());
123126
if (!classifier_ptr_->getTrafficSignals(images, output_msg)) {
124127
RCLCPP_ERROR(this->get_logger(), "failed classify image, abort callback");
125128
return;
126129
}
127130

131+
// append the undetected rois as unknown
132+
for (const auto & input_roi : input_rois_msg->rois) {
133+
if (input_roi.roi.height == 0 && input_roi.traffic_light_type == classify_traffic_light_type_) {
134+
tier4_perception_msgs::msg::TrafficSignal tlr_sig;
135+
tlr_sig.traffic_light_id = input_roi.traffic_light_id;
136+
tlr_sig.traffic_light_type = input_roi.traffic_light_type;
137+
tier4_perception_msgs::msg::TrafficLightElement element;
138+
element.color = tier4_perception_msgs::msg::TrafficLightElement::UNKNOWN;
139+
element.shape = tier4_perception_msgs::msg::TrafficLightElement::CIRCLE;
140+
element.confidence = 0.0;
141+
tlr_sig.elements.push_back(element);
142+
output_msg.signals.push_back(tlr_sig);
143+
}
144+
}
145+
128146
for (const auto & idx : backlight_indices) {
129147
auto & elements = output_msg.signals.at(idx).elements;
130148
for (auto & element : elements) {

perception/traffic_light_fine_detector/src/nodelet.cpp

+21-7
Original file line numberDiff line numberDiff line change
@@ -272,14 +272,28 @@ void TrafficLightFineDetectorNodelet::detectionMatch(
272272
}
273273

274274
out_rois.rois.clear();
275-
for (const auto & p : bestDetections) {
275+
std::vector<size_t> invalid_roi_id;
276+
for (const auto & [tlr_id, roi] : id2expectRoi) {
277+
// if matches, update the roi info
278+
if (!bestDetections.count(tlr_id)) {
279+
invalid_roi_id.emplace_back(tlr_id);
280+
continue;
281+
}
282+
TrafficLightRoi tlr;
283+
tlr.traffic_light_id = tlr_id;
284+
const auto & object = bestDetections.at(tlr_id);
285+
tlr.traffic_light_type = roi.traffic_light_type;
286+
tlr.roi.x_offset = object.x_offset;
287+
tlr.roi.y_offset = object.y_offset;
288+
tlr.roi.width = object.width;
289+
tlr.roi.height = object.height;
290+
out_rois.rois.push_back(tlr);
291+
}
292+
// append undetected rois at the end
293+
for (const auto & id : invalid_roi_id) {
276294
TrafficLightRoi tlr;
277-
tlr.traffic_light_id = p.first;
278-
tlr.traffic_light_type = id2expectRoi[p.first].traffic_light_type;
279-
tlr.roi.x_offset = p.second.x_offset;
280-
tlr.roi.y_offset = p.second.y_offset;
281-
tlr.roi.width = p.second.width;
282-
tlr.roi.height = p.second.height;
295+
tlr.traffic_light_id = id;
296+
tlr.traffic_light_type = id2expectRoi[id].traffic_light_type;
283297
out_rois.rois.push_back(tlr);
284298
}
285299
}

perception/traffic_light_occlusion_predictor/src/nodelet.cpp

+13-1
Original file line numberDiff line numberDiff line change
@@ -129,20 +129,26 @@ void TrafficLightOcclusionPredictorNodelet::syncCallback(
129129
const uint8_t traffic_light_type)
130130
{
131131
std::vector<int> occlusion_ratios;
132+
size_t not_detected_roi = 0;
132133
if (in_cloud_msg == nullptr || in_cam_info_msg == nullptr || in_roi_msg == nullptr) {
133134
occlusion_ratios.resize(in_signal_msg->signals.size(), 0);
134135
} else {
135136
tier4_perception_msgs::msg::TrafficLightRoiArray selected_roi_msg;
136137
selected_roi_msg.rois.reserve(in_roi_msg->rois.size());
137138
for (size_t i = 0; i < in_roi_msg->rois.size(); ++i) {
139+
// not detected roi
140+
if (in_roi_msg->rois[i].roi.height == 0) {
141+
not_detected_roi++;
142+
continue;
143+
}
138144
if (in_roi_msg->rois.at(i).traffic_light_type == traffic_light_type) {
139145
selected_roi_msg.rois.push_back(in_roi_msg->rois.at(i));
140146
}
141147
}
142148

143149
tier4_perception_msgs::msg::TrafficSignalArray out_msg = *in_signal_msg;
144150

145-
if (selected_roi_msg.rois.size() != in_signal_msg->signals.size()) {
151+
if (selected_roi_msg.rois.size() != in_signal_msg->signals.size() - not_detected_roi) {
146152
occlusion_ratios.resize(in_signal_msg->signals.size(), 0);
147153
} else {
148154
auto selected_roi_msg_ptr =
@@ -162,6 +168,12 @@ void TrafficLightOcclusionPredictorNodelet::syncCallback(
162168
traffic_light_utils::setSignalUnknown(out_msg_.signals.at(predicted_num + i), 0.0);
163169
}
164170
}
171+
172+
// push back not detected rois
173+
for (size_t i = occlusion_ratios.size(); i < in_signal_msg->signals.size(); ++i) {
174+
out_msg_.signals.push_back(in_signal_msg->signals[i]);
175+
}
176+
165177
subscribed_.at(traffic_light_type) = true;
166178

167179
if (std::all_of(subscribed_.begin(), subscribed_.end(), [](bool v) { return v; })) {

perception/traffic_light_occlusion_predictor/src/occlusion_predictor.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -88,6 +88,10 @@ void CloudOcclusionPredictor::predict(
8888
image_geometry::PinholeCameraModel pinhole_model;
8989
pinhole_model.fromCameraInfo(*camera_info_msg);
9090
for (size_t i = 0; i < rois_msg->rois.size(); i++) {
91+
// skip if no detection
92+
if (rois_msg->rois[i].roi.height == 0) {
93+
continue;
94+
}
9195
calcRoiVector3D(
9296
rois_msg->rois[i], pinhole_model, traffic_light_position_map, tf_camera2map, roi_tls[i],
9397
roi_brs[i]);
@@ -107,7 +111,7 @@ void CloudOcclusionPredictor::predict(
107111
lidar_rays_[static_cast<int>(ray.azimuth)][static_cast<int>(ray.elevation)].push_back(ray);
108112
}
109113
for (size_t i = 0; i < roi_tls.size(); i++) {
110-
occlusion_ratios[i] = predict(roi_tls[i], roi_brs[i]);
114+
occlusion_ratios[i] = rois_msg->rois[i].roi.height == 0 ? 0 : predict(roi_tls[i], roi_brs[i]);
111115
}
112116
}
113117

0 commit comments

Comments
 (0)