Skip to content

test(traffic_light_map_based_detector): add integration test#12396

Merged
interimadd merged 3 commits intoautowarefoundation:mainfrom
interimadd:add-integration-test-for-traffic-light-map-based-detector
Apr 1, 2026
Merged

test(traffic_light_map_based_detector): add integration test#12396
interimadd merged 3 commits intoautowarefoundation:mainfrom
interimadd:add-integration-test-for-traffic-light-map-based-detector

Conversation

@interimadd
Copy link
Copy Markdown
Contributor

@interimadd interimadd commented Mar 31, 2026

Description

Add an integration test for autoware_traffic_light_map_based_detector node (MapBasedDetector).

This test verifies the end-to-end pipeline: publishing a lanelet map with a traffic light regulatory element, a route, TF, and camera info, then asserting that the node correctly produces ROIs (both output/rois with vibration margin and expect/rois without).

The following diagram illustrates the test setup — camera placement, traffic light position, and the expected ROI projection:

image

Related links

Parent Issue:

  • N/A

How was this PR tested?

1. All tests pass

colcon build --packages-select autoware_traffic_light_map_based_detector --cmake-args -DCMAKE_BUILD_TYPE=Release
colcon test --packages-select autoware_traffic_light_map_based_detector --event-handlers console_cohesion+
# 100% tests passed, 0 tests failed out of 6

2. Test coverage

Coverage was measured using lcov with a Debug build instrumented with --coverage flags.

Summary

File Line Coverage Function Coverage
traffic_light_map_based_detector_node.cpp 82.1% (238/290) 90.9% (10/11)
traffic_light_map_based_detector_process.cpp 96.4% (53/55) 100% (10/10)
Total 83.9% (291/347) 90.9% (20/22)

Notes

  • traffic_light_map_based_detector_process.cpp (utility functions) achieves 96.4% line coverage, with the existing test_utils covering the remaining utility paths
  • traffic_light_map_based_detector_node.cpp reaches 82.1% line coverage — the uncovered lines are primarily error handling paths (e.g., TF lookup failure, empty camera info) and the all_traffic_lights fallback path when no route is available

Notes for reviewers

This is a specification test added before refactoring to prevent regressions. It captures the current behavior of the node as-is, so that any unintended changes during refactoring are caught immediately. This test is intended to be removed after the refactoring is complete and replaced by unit tests for the extracted logic classes.

Interface changes

None.

Effects on system behavior

None. This PR only adds tests.

Signed-off-by: Takahisa.Ishikawa <takahisa.ishikawa@tier4.jp>
@github-actions github-actions bot added the component:perception Advanced sensor data processing and environment understanding. (auto-assigned) label Mar 31, 2026
@github-actions
Copy link
Copy Markdown

github-actions bot commented Mar 31, 2026

Thank you for contributing to the Autoware project!

🚧 If your pull request is in progress, switch it to draft mode.

Please ensure:

@interimadd interimadd added the run:build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci) label Mar 31, 2026
@codecov
Copy link
Copy Markdown

codecov bot commented Mar 31, 2026

Codecov Report

✅ All modified and coverable lines are covered by tests.
✅ Project coverage is 19.00%. Comparing base (24bf6eb) to head (b0950ff).
⚠️ Report is 1 commits behind head on main.

Additional details and impacted files
@@            Coverage Diff             @@
##             main   #12396      +/-   ##
==========================================
+ Coverage   18.46%   19.00%   +0.53%     
==========================================
  Files        1888     1894       +6     
  Lines      129807   130625     +818     
  Branches    45966    48149    +2183     
==========================================
+ Hits        23968    24822     +854     
- Misses      86102    86570     +468     
+ Partials    19737    19233     -504     
Flag Coverage Δ *Carryforward flag
daily 21.00% <ø> (ø) Carriedforward from 6f4e694
daily-cuda 18.56% <ø> (ø) Carriedforward from 6f4e694
daily-humble-amd64-cuda 18.36% <ø> (-0.08%) ⬇️ Carriedforward from 6f4e694
daily-humble-amd64-nocuda 20.87% <ø> (-0.10%) ⬇️ Carriedforward from 6f4e694
daily-jazzy-amd64-nocuda ?
differential 2.63% <ø> (?)
differential-cuda 17.56% <ø> (?)
total-cuda 18.56% <ø> (ø) Carriedforward from 6f4e694
total-humble-cuda 18.36% <ø> (-0.09%) ⬇️ Carriedforward from 6f4e694

*This pull request uses carry forward flags. Click here to find out more.

☔ View full report in Codecov by Sentry.
📢 Have feedback on the report? Share it here.

🚀 New features to boost your workflow:
  • ❄️ Test Analytics: Detect flaky tests, report on failures, and find test suite problems.

@interimadd interimadd marked this pull request as ready for review March 31, 2026 09:27
Copy link
Copy Markdown
Contributor

@a-maumau a-maumau left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM!

I have a comment for the code which not that much important.

Also, for the PR comment's figure, it seems it has some typo.
The linestring for a traffic light should be placed at bottom of actual traffic light position.
So the traffic light's height is from z=3.5 to z=4.5:

traffic light
     /
───┌─┐  ^
   │●│  |
   │●│  |  1 m
   │●│  |
   └─┘  v  _____
                ^
                |  3.5 m
z = 0 __________v

https://docs.pilot.auto/reference-design/common/map-requirements/vector-map-requirements/category_traffic_light/#vm-04-02-%E4%BF%A1%E5%8F%B7%E6%A9%9F%E3%81%AE%E4%BD%8D%E7%BD%AE%E3%81%A8%E3%82%B5%E3%82%A4%E3%82%BA

Comment on lines +298 to +311
EXPECT_EQ(rois[0].traffic_light_id, traffic_light_linestring_id_);
EXPECT_NEAR(rois[0].roi.x_offset, 301, 1);
EXPECT_NEAR(rois[0].roi.y_offset, 140, 1);
EXPECT_NEAR(rois[0].roi.width, 37, 1);
EXPECT_NEAR(rois[0].roi.height, 39, 1);

// expect/rois has zero vibration offset, so exact integer values from geometry
auto expect_rois = getExpectRois();
ASSERT_EQ(expect_rois.size(), 1u);
EXPECT_EQ(expect_rois[0].traffic_light_id, traffic_light_linestring_id_);
EXPECT_EQ(expect_rois[0].roi.x_offset, 310u);
EXPECT_EQ(expect_rois[0].roi.y_offset, 150u);
EXPECT_EQ(expect_rois[0].roi.width, 20u);
EXPECT_EQ(expect_rois[0].roi.height, 20u);
Copy link
Copy Markdown
Contributor

@a-maumau a-maumau Apr 1, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Following comment may be too much for just checking the code, but I will leave it here.

We can leave the value as for some reference to do some sanity check (detect the logical or numerical changes), but we can compute the actual value quite easily for an ideal camera like following. So it would be better to leave some comments for the (likely a) magic numbers.

camera at (0, 0, 0), looking at +x

// world -> camera
// downfward is y+ in camera coordinate
top left    : (20.0,  0.5, 3.5 + 1.0) -> (-0.5, -4.5, 20.0)
right bottom: (20.0, -0.5, 3.5)       -> ( 0.5, -3.5, 20.0)

for ideal camera
c_x = 320
c_y = 240

u = f_x * (x_opt / z_opt) + c_x
v = f_y * (y_opt / z_opt) + c_y

------------------------------------------------------------------------------
without margin (expect ROI)

top left point:
    u_top_left = f_x * (x_opt / z_opt) + c_x = 400 * (-0.5 / 20) + 320 = 310
    v_top_left = f_y * (y_opt / z_opt) + c_y = 400 * (-4.5 / 20) + 240 = 150

bottom right point
    u_bottom_right = f_x * (x_opt / z_opt) + c_x = 400 * (0.5 / 20) + 320 = 330
    v_bottom_right = f_y * (y_opt / z_opt) + c_y = 400 * (-3.5 / 20) + 240 = 170

(x, y, w, h) -> (310, 150, 20, 20)

------------------------------------------------------------------------------
with margin (rough ROI)

margin def.:
    margin_x = (margin_yaw / 2) * depth + margin_width / 2
    margin_y = (margin_pitch / 2) * depth + margin_height / 2
    margin_z = margin_depth / 2

margin_x = (0.01745 / 2) * 20.0 + (0.5 / 2) = 0.4245
margin_y = (0.01745 / 2) * 20.0 + (0.5 / 2) = 0.4245
margin_z = 0.5 / 2 = 0.25

top left point (tl_camera_optical - margin):
    u_top_left = 400 * ((-0.5 - 0.4245) / (20 - 0.25)) + 320 ≒ 301.276
    v_top_left = 400 * ((-4.5 - 0.4245) / (20 - 0.25)) + 240 ≒ 140.263

bottom right point (tl_camera_optical + margin):
    u_bottom_right = 400 * ((0.5 + 0.4245) / (20 + 0.25)) + 320 ≒ 338.262
    v_bottom_right = 400 * ((-3.5 + 0.4245) / (20 + 0.25)) + 240 ≒ 179.249

(x, y, w, h) -> (301.276, 140.263, 36.986 38.986) ≒ (301, 140, 37, 39)

Takahisa.Ishikawa and others added 2 commits April 1, 2026 15:57
…ion comments to integration test

Signed-off-by: Takahisa.Ishikawa <takahisa.ishikawa@tier4.jp>
@interimadd
Copy link
Copy Markdown
Contributor Author

@a-maumau
Thank you for your review!
I misunderstood definition of traffic light position. I have fixed the figure in PR description and added comment to the test code.

@interimadd interimadd enabled auto-merge (squash) April 1, 2026 07:00
@interimadd interimadd merged commit d6ff08d into autowarefoundation:main Apr 1, 2026
62 checks passed
@github-project-automation github-project-automation bot moved this from To Triage to Done in Software Working Group Apr 1, 2026
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

component:perception Advanced sensor data processing and environment understanding. (auto-assigned) run:build-and-test-differential Mark to enable build-and-test-differential workflow. (used-by-ci)

Projects

Status: Done

Development

Successfully merging this pull request may close these issues.

2 participants