@@ -303,7 +303,11 @@ void CrosswalkTrafficLightEstimatorNode::setCrosswalkTrafficSignal(
303
303
output_traffic_signal_element.color = color;
304
304
output_traffic_signal_element.shape = TrafficSignalElement::CIRCLE;
305
305
output_traffic_signal_element.confidence = 1.0 ;
306
- output.traffic_light_groups [idx].elements [0 ] = output_traffic_signal_element;
306
+ if (output.traffic_light_groups [idx].elements .empty ()) {
307
+ output.traffic_light_groups [idx].elements .push_back (output_traffic_signal_element);
308
+ } else {
309
+ output.traffic_light_groups [idx].elements [0 ] = output_traffic_signal_element;
310
+ }
307
311
continue ;
308
312
}
309
313
updateFlashingState (signal ); // check if it is flashing
@@ -325,6 +329,10 @@ void CrosswalkTrafficLightEstimatorNode::setCrosswalkTrafficSignal(
325
329
bool CrosswalkTrafficLightEstimatorNode::isInvalidDetectionStatus (
326
330
const TrafficSignal & signal) const
327
331
{
332
+ // invalid if elements is empty
333
+ if (signal .elements .empty ()) {
334
+ return true ;
335
+ }
328
336
// check occlusion, backlight(shape is unknown) and no detection(shape is circle)
329
337
if (
330
338
signal .elements .front ().color == TrafficSignalElement::UNKNOWN &&
@@ -347,6 +355,7 @@ void CrosswalkTrafficLightEstimatorNode::updateFlashingState(const TrafficSignal
347
355
348
356
// flashing green
349
357
if (
358
+ !signal .elements .empty () &&
350
359
signal .elements .front ().color == TrafficSignalElement::UNKNOWN &&
351
360
signal .elements .front ().confidence != 0 && // not due to occlusion
352
361
current_color_state_.at (id) != TrafficSignalElement::UNKNOWN) {
0 commit comments