File tree 1 file changed +2
-10
lines changed
perception/traffic_light_multi_camera_fusion/src
1 file changed +2
-10
lines changed Original file line number Diff line number Diff line change @@ -82,16 +82,8 @@ int compareRecord(const traffic_light::FusionRecord & r1, const traffic_light::F
82
82
int visible_score_1 = calVisibleScore (r1);
83
83
int visible_score_2 = calVisibleScore (r2);
84
84
if (visible_score_1 == visible_score_2) {
85
- double sum_1 = 0 ;
86
- for_each (r1.signal .elements .begin (), r1.signal .elements .end (), [&sum_1](const auto & elem) {
87
- sum_1 = sum_1 + elem.confidence ;
88
- });
89
- double sum_2 = 0 ;
90
- for_each (r2.signal .elements .begin (), r2.signal .elements .end (), [&sum_2](const auto & elem) {
91
- sum_2 = sum_2 + elem.confidence ;
92
- });
93
- double confidence_1 = sum_1 / r1.signal .elements .size ();
94
- double confidence_2 = sum_2 / r2.signal .elements .size ();
85
+ double confidence_1 = r1.signal .elements [0 ].confidence ;
86
+ double confidence_2 = r2.signal .elements [0 ].confidence ;
95
87
return confidence_1 < confidence_2 ? -1 : 1 ;
96
88
} else {
97
89
return visible_score_1 < visible_score_2 ? -1 : 1 ;
You can’t perform that action at this time.
0 commit comments