Skip to content

Commit ac7fa10

Browse files
authored
fix(traffic_light_roi_visualizer): show unknown results correctly (#9467)
fix: show unknown results correctly Signed-off-by: tzhong518 <sworgun@gmail.com>
1 parent e4f8414 commit ac7fa10

File tree

2 files changed

+10
-5
lines changed

2 files changed

+10
-5
lines changed

perception/autoware_traffic_light_visualization/src/traffic_light_roi_visualizer/node.cpp

+5-3
Original file line numberDiff line numberDiff line change
@@ -201,16 +201,18 @@ void TrafficLightRoiVisualizerNode::imageRoughRoiCallback(
201201
// bbox drawing
202202
cv_ptr = cv_bridge::toCvCopy(input_image_msg, sensor_msgs::image_encodings::RGB8);
203203
for (auto tl_rough_roi : input_tl_rough_roi_msg->rois) {
204-
// visualize rough roi
205-
createRect(cv_ptr->image, tl_rough_roi, cv::Scalar(0, 255, 0));
206-
204+
// note: a signal will still be output even if it is undetected
205+
// Its position and size will be set as 0 and the color will be set as unknown
206+
// So a rough roi will always have correspond roi a correspond traffic signal
207207
ClassificationResult result;
208208
bool has_correspond_traffic_signal =
209209
getClassificationResult(tl_rough_roi.traffic_light_id, *input_traffic_signals_msg, result);
210210
tier4_perception_msgs::msg::TrafficLightRoi tl_roi;
211211
bool has_correspond_roi =
212212
getRoiFromId(tl_rough_roi.traffic_light_id, input_tl_roi_msg, tl_roi);
213213

214+
createRect(cv_ptr->image, tl_rough_roi, extractShapeInfo(result.label).color);
215+
214216
if (has_correspond_roi && has_correspond_traffic_signal) {
215217
// has fine detection and classification results
216218
createRect(cv_ptr->image, tl_roi, result);

perception/autoware_traffic_light_visualization/src/traffic_light_roi_visualizer/shape_draw.cpp

+5-2
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,10 @@ void drawShape(
2929
cv::Mat & image, const std::vector<ShapeImgParam> & params, int size, const cv::Point & position,
3030
const cv::Scalar & color, float probability)
3131
{
32+
// skip if the roi position is set as (0,0), which means it is undetected
33+
if (position.x == 0 && position.y == 0) {
34+
return;
35+
}
3236
// load concatenated shape image
3337
const auto shape_img = loadShapeImage(params, size);
3438

@@ -42,14 +46,13 @@ void drawShape(
4246
const int fill_rect_h = std::max(shape_img.rows, text_size.height) + 10;
4347

4448
const cv::Point rect_position(position.x, position.y - fill_rect_h);
45-
4649
if (
4750
rect_position.x < 0 || rect_position.y < 0 || rect_position.x + fill_rect_w > image.cols ||
4851
position.y > image.rows) {
4952
// TODO(KhalilSelyan): This error message may flood the terminal logs, so commented out
5053
// temporarily. Need to consider a better way.
5154

52-
// std::cerr << "Adjusted position is out of image bounds." << std::endl;
55+
std::cerr << "Adjusted position is out of image bounds." << std::endl;
5356
return;
5457
}
5558
cv::Rect rectangle(rect_position.x, rect_position.y, fill_rect_w, fill_rect_h);

0 commit comments

Comments
 (0)