diff --git a/perception/autoware_crosswalk_traffic_light_estimator/src/node.cpp b/perception/autoware_crosswalk_traffic_light_estimator/src/node.cpp index d7cc6c725edfd..8e301c1bd0b60 100644 --- a/perception/autoware_crosswalk_traffic_light_estimator/src/node.cpp +++ b/perception/autoware_crosswalk_traffic_light_estimator/src/node.cpp @@ -303,7 +303,11 @@ void CrosswalkTrafficLightEstimatorNode::setCrosswalkTrafficSignal( output_traffic_signal_element.color = color; output_traffic_signal_element.shape = TrafficSignalElement::CIRCLE; output_traffic_signal_element.confidence = 1.0; - output.traffic_light_groups[idx].elements[0] = output_traffic_signal_element; + if (output.traffic_light_groups[idx].elements.empty()) { + output.traffic_light_groups[idx].elements.push_back(output_traffic_signal_element); + } else { + output.traffic_light_groups[idx].elements[0] = output_traffic_signal_element; + } continue; } updateFlashingState(signal); // check if it is flashing @@ -325,6 +329,10 @@ void CrosswalkTrafficLightEstimatorNode::setCrosswalkTrafficSignal( bool CrosswalkTrafficLightEstimatorNode::isInvalidDetectionStatus( const TrafficSignal & signal) const { + // invalid if elements is empty + if (signal.elements.empty()) { + return true; + } // check occlusion, backlight(shape is unknown) and no detection(shape is circle) if ( signal.elements.front().color == TrafficSignalElement::UNKNOWN && @@ -347,7 +355,7 @@ void CrosswalkTrafficLightEstimatorNode::updateFlashingState(const TrafficSignal // flashing green if ( - signal.elements.front().color == TrafficSignalElement::UNKNOWN && + !signal.elements.empty() && signal.elements.front().color == TrafficSignalElement::UNKNOWN && signal.elements.front().confidence != 0 && // not due to occlusion current_color_state_.at(id) != TrafficSignalElement::UNKNOWN) { is_flashing_.at(id) = true;