Skip to content

Commit

Permalink
fix(traffic_light_roi_visualizer): show unknown results correctly (au…
Browse files Browse the repository at this point in the history
…towarefoundation#9467)

fix: show unknown results correctly

Signed-off-by: tzhong518 <[email protected]>
  • Loading branch information
tzhong518 authored Nov 29, 2024
1 parent e4f8414 commit ac7fa10
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -201,16 +201,18 @@ void TrafficLightRoiVisualizerNode::imageRoughRoiCallback(
// bbox drawing
cv_ptr = cv_bridge::toCvCopy(input_image_msg, sensor_msgs::image_encodings::RGB8);
for (auto tl_rough_roi : input_tl_rough_roi_msg->rois) {
// visualize rough roi
createRect(cv_ptr->image, tl_rough_roi, cv::Scalar(0, 255, 0));

// note: a signal will still be output even if it is undetected
// Its position and size will be set as 0 and the color will be set as unknown
// So a rough roi will always have correspond roi a correspond traffic signal
ClassificationResult result;
bool has_correspond_traffic_signal =
getClassificationResult(tl_rough_roi.traffic_light_id, *input_traffic_signals_msg, result);
tier4_perception_msgs::msg::TrafficLightRoi tl_roi;
bool has_correspond_roi =
getRoiFromId(tl_rough_roi.traffic_light_id, input_tl_roi_msg, tl_roi);

createRect(cv_ptr->image, tl_rough_roi, extractShapeInfo(result.label).color);

if (has_correspond_roi && has_correspond_traffic_signal) {
// has fine detection and classification results
createRect(cv_ptr->image, tl_roi, result);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,10 @@ void drawShape(
cv::Mat & image, const std::vector<ShapeImgParam> & params, int size, const cv::Point & position,
const cv::Scalar & color, float probability)
{
// skip if the roi position is set as (0,0), which means it is undetected
if (position.x == 0 && position.y == 0) {
return;
}
// load concatenated shape image
const auto shape_img = loadShapeImage(params, size);

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

const cv::Point rect_position(position.x, position.y - fill_rect_h);

if (
rect_position.x < 0 || rect_position.y < 0 || rect_position.x + fill_rect_w > image.cols ||
position.y > image.rows) {
// TODO(KhalilSelyan): This error message may flood the terminal logs, so commented out
// temporarily. Need to consider a better way.

// std::cerr << "Adjusted position is out of image bounds." << std::endl;
std::cerr << "Adjusted position is out of image bounds." << std::endl;
return;
}
cv::Rect rectangle(rect_position.x, rect_position.y, fill_rect_w, fill_rect_h);
Expand Down

0 comments on commit ac7fa10

Please sign in to comment.