121 {
122 if (nullptr == os_light) {
123 return false;
124 }
125 if (nullptr == *os_light) {
126 return false;
127 }
128 if (!x2v_traffic_light) {
130 return false;
131 }
132 return true;
133 }
134 if (junction_id != x2v_traffic_light->hdmap_junction_id()) {
135 AWARN <<
"current junction id " << junction_id
136 << ", received the junction id "
137 << x2v_traffic_light->hdmap_junction_id();
138 return false;
139 }
140 std::shared_ptr<OSLight> os_traffic_light = nullptr;
142 return false;
143 }
144 int num_os_traffic_light = os_traffic_light->road_traffic_light_size();
145 if (0 == num_os_traffic_light) {
146 AERROR <<
"Ignored no traffic light contained after conventor.";
147 return false;
148 }
149 std::shared_ptr<OSLight> sim_traffic_light_data = nullptr;
150
151 auto cur_junction_id = x2v_traffic_light->intersection_id();
152 auto tmp_os_traffic_light = std::make_shared<OSLight>();
153 tmp_os_traffic_light->CopyFrom(*os_traffic_light);
154
155 tmp_os_traffic_light->clear_road_traffic_light();
156 for (int i = 0; i < num_os_traffic_light; i++) {
157 auto os_current_light = os_traffic_light->mutable_road_traffic_light(i);
159 AERROR <<
"Traffic light proc failed";
160 continue;
161 }
162 if (os_current_light->single_traffic_light_size() > 0) {
163 auto tmp_os_current_light =
164 tmp_os_traffic_light->add_road_traffic_light();
165 tmp_os_current_light->CopyFrom(*(os_current_light));
166 }
167 }
168 tmp_os_traffic_light->set_confidence(
IsRushHour() ? 0.5 : 1.0);
169 AINFO <<
"all traffic light send to os BEFORE is: "
170 << os_traffic_light->DebugString();
171 if (0 == tmp_os_traffic_light->road_traffic_light_size()) {
172 return false;
173 }
174 cur_junction_id = x2v_traffic_light->intersection_id();
175 tmp_os_traffic_light->set_intersection_id(cur_junction_id);
176
177 if (cur_junction_id != intersection_id_) {
178 AINFO <<
"Enter New Juncion: " << cur_junction_id;
179 oslight_ = nullptr;
180 intersection_id_ = cur_junction_id;
181 int num_traffic_light = tmp_os_traffic_light->road_traffic_light_size();
182 for (int i = 0; i < num_traffic_light; i++) {
183 auto remaining_time = tmp_os_traffic_light->road_traffic_light(i)
184 .single_traffic_light(0)
185 .color_remaining_time_s();
186 remaining_time_[i] = remaining_time;
187 msg_timestamp_[i] = x2v_traffic_light->header().timestamp_sec();
188 }
189 } else {
190 ADEBUG <<
"Same Juncion: " << cur_junction_id;
191 if (flag_u_turn) {
192 for (unsigned int i = 0; i < kBufferSize; i++) {
193 msg_timestamp_[i] = 0.0;
194 remaining_time_[i] = -1;
195 }
196 oslight_ = nullptr;
197 }
198 int num_traffic_light = tmp_os_traffic_light->road_traffic_light_size();
199 for (int i = 0; i < num_traffic_light; i++) {
200 auto remaining_time = tmp_os_traffic_light->road_traffic_light(i)
201 .single_traffic_light(0)
202 .color_remaining_time_s();
203 if ((remaining_time_[i] != remaining_time)) {
204 remaining_time_[i] = remaining_time;
205 msg_timestamp_[i] = x2v_traffic_light->header().timestamp_sec();
206 }
207 }
208 if (!!oslight_) {
209 int road_valid_size =
210 std::min(oslight_->road_traffic_light_size(),
211 tmp_os_traffic_light->road_traffic_light_size());
212 for (int i = 0; i < road_valid_size; i++) {
213 const auto &last_msg_road = oslight_->road_traffic_light(i);
214 auto current_msg_road =
215 tmp_os_traffic_light->mutable_road_traffic_light(i);
216 int single_valid_size =
217 std::min(last_msg_road.single_traffic_light_size(),
218 current_msg_road->single_traffic_light_size());
219 for (int j = 0; j < single_valid_size; j++) {
220 const auto &last_msg_single_traffic_light =
221 last_msg_road.single_traffic_light(j);
222 auto current_msg_single_traffic_light =
223 current_msg_road->mutable_single_traffic_light(j);
224 if (last_msg_single_traffic_light.color() ==
225 current_msg_single_traffic_light->color()) {
226 if (current_msg_single_traffic_light->color_remaining_time_s() >
227 last_msg_single_traffic_light.color_remaining_time_s()) {
228 AINFO <<
"correct the remaining time";
229 current_msg_single_traffic_light->set_color_remaining_time_s(
230 last_msg_single_traffic_light.color_remaining_time_s());
231 }
232 }
233 }
234 }
235 }
236 }
237 oslight_ = std::make_shared<::apollo::v2x::IntersectionTrafficLightData>();
238 oslight_->CopyFrom(*tmp_os_traffic_light);
239 (*os_light)->CopyFrom(*tmp_os_traffic_light);
240 return true;
241}
bool TrafficLightProc(const std::shared_ptr<::apollo::hdmap::HDMap > &hdmap, double distance, ::apollo::v2x::RoadTrafficLight *msg)
static bool LightObu2Sys(const ObuLight &obu_light, std::shared_ptr< OSLight > *os_light)
const char *const kUnknownJunctionId