Apollo 10.0
自动驾驶开放平台
hdmap_common.cc
浏览该文件的文档.
1/* Copyright 2017 The Apollo Authors. All Rights Reserved.
2
3Licensed under the Apache License, Version 2.0 (the "License");
4you may not use this file except in compliance with the License.
5You may obtain a copy of the License at
6
7 http://www.apache.org/licenses/LICENSE-2.0
8
9Unless required by applicable law or agreed to in writing, software
10distributed under the License is distributed on an "AS IS" BASIS,
11WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12See the License for the specific language governing permissions and
13limitations under the License.
14=========================================================================*/
15
17
18#include <algorithm>
19#include <limits>
20
21#include "cyber/common/log.h"
26
27namespace apollo {
28namespace hdmap {
29namespace {
32
33// Minimum error in lane segmentation.
34// const double kSegmentationEpsilon = 0.2;
35
36// Minimum distance to remove duplicated points.
37constexpr double kDuplicatedPointsEpsilon = 1e-7;
38
39// Margin for comparation
40constexpr double kEpsilon = 0.1;
41
42void RemoveDuplicates(std::vector<Vec2d> *points) {
43 RETURN_IF_NULL(points);
44
45 int count = 0;
46 const double limit = kDuplicatedPointsEpsilon * kDuplicatedPointsEpsilon;
47 for (const auto &point : *points) {
48 if (count == 0 || point.DistanceSquareTo((*points)[count - 1]) > limit) {
49 (*points)[count++] = point;
50 }
51 }
52 points->resize(count);
53}
54
55void PointsFromCurve(const Curve &input_curve, std::vector<Vec2d> *points) {
56 RETURN_IF_NULL(points);
57 points->clear();
58
59 for (const auto &curve : input_curve.segment()) {
60 if (curve.has_line_segment()) {
61 for (const auto &point : curve.line_segment().point()) {
62 points->emplace_back(point.x(), point.y());
63 }
64 } else {
65 AERROR << "Can not handle curve type.";
66 }
67 }
68 RemoveDuplicates(points);
69}
70
71apollo::common::math::Polygon2d ConvertToPolygon2d(const Polygon &polygon) {
72 std::vector<Vec2d> points;
73 points.reserve(polygon.point_size());
74 for (const auto &point : polygon.point()) {
75 points.emplace_back(point.x(), point.y());
76 }
77 RemoveDuplicates(&points);
78 while (points.size() >= 2 && points[0].DistanceTo(points.back()) <=
80 points.pop_back();
81 }
83}
84
85void SegmentsFromCurve(
86 const Curve &curve,
87 std::vector<apollo::common::math::LineSegment2d> *segments) {
88 RETURN_IF_NULL(segments);
89
90 std::vector<Vec2d> points;
91 PointsFromCurve(curve, &points);
92 for (size_t i = 0; i + 1 < points.size(); ++i) {
93 segments->emplace_back(points[i], points[i + 1]);
94 }
95}
96
97PointENU PointFromVec2d(const Vec2d &point) {
98 PointENU pt;
99 pt.set_x(point.x());
100 pt.set_y(point.y());
101 return pt;
102}
103
104} // namespace
105
106LaneInfo::LaneInfo(const Lane &lane) : lane_(lane) { Init(); }
107
108void LaneInfo::Init() {
109 PointsFromCurve(lane_.central_curve(), &points_);
110 CHECK_GE(points_.size(), 2U);
111 segments_.clear();
112 accumulated_s_.clear();
113 unit_directions_.clear();
114 headings_.clear();
115
116 double s = 0;
117 for (size_t i = 0; i + 1 < points_.size(); ++i) {
118 segments_.emplace_back(points_[i], points_[i + 1]);
119 accumulated_s_.push_back(s);
120 unit_directions_.push_back(segments_.back().unit_direction());
121 s += segments_.back().length();
122 }
123
124 accumulated_s_.push_back(s);
125 total_length_ = s;
126 ACHECK(!unit_directions_.empty());
127 unit_directions_.push_back(unit_directions_.back());
128 for (const auto &direction : unit_directions_) {
129 headings_.push_back(direction.Angle());
130 }
131 for (const auto &overlap_id : lane_.overlap_id()) {
132 overlap_ids_.emplace_back(overlap_id.id());
133 }
134 ACHECK(!segments_.empty());
135
136 sampled_left_width_.clear();
137 sampled_right_width_.clear();
138 for (const auto &sample : lane_.left_sample()) {
139 sampled_left_width_.emplace_back(sample.s(), sample.width());
140 }
141 for (const auto &sample : lane_.right_sample()) {
142 sampled_right_width_.emplace_back(sample.s(), sample.width());
143 }
144
145 if (lane_.has_type()) {
146 if (lane_.type() == Lane::CITY_DRIVING) {
147 for (const auto &p : sampled_left_width_) {
148 if (p.second < FLAGS_half_vehicle_width) {
149 AERROR
150 << "lane[id = " << lane_.id().DebugString()
151 << "]. sampled_left_width_[" << p.second
152 << "] is too small. It should be larger than half vehicle width["
153 << FLAGS_half_vehicle_width << "].";
154 }
155 }
156 for (const auto &p : sampled_right_width_) {
157 if (p.second < FLAGS_half_vehicle_width) {
158 AERROR
159 << "lane[id = " << lane_.id().DebugString()
160 << "]. sampled_right_width_[" << p.second
161 << "] is too small. It should be larger than half vehicle width["
162 << FLAGS_half_vehicle_width << "].";
163 }
164 }
165 } else if (lane_.type() == Lane::NONE) {
166 AERROR << "lane_[id = " << lane_.id().DebugString() << "] type is NONE.";
167 }
168 } else {
169 AERROR << "lane_[id = " << lane_.id().DebugString() << "] has NO type.";
170 }
171
172 sampled_left_road_width_.clear();
173 sampled_right_road_width_.clear();
174 for (const auto &sample : lane_.left_road_sample()) {
175 sampled_left_road_width_.emplace_back(sample.s(), sample.width());
176 }
177 for (const auto &sample : lane_.right_road_sample()) {
178 sampled_right_road_width_.emplace_back(sample.s(), sample.width());
179 }
180
181 CreateKDTree();
182}
183
184void LaneInfo::GetWidth(const double s, double *left_width,
185 double *right_width) const {
186 if (left_width != nullptr) {
187 *left_width = GetWidthFromSample(sampled_left_width_, s);
188 }
189 if (right_width != nullptr) {
190 *right_width = GetWidthFromSample(sampled_right_width_, s);
191 }
192}
193
194double LaneInfo::Heading(const double s) const {
195 if (accumulated_s_.empty()) {
196 return 0.0;
197 }
198 const double kEpsilon = 0.001;
199 if (s + kEpsilon < accumulated_s_.front()) {
200 AWARN << "s:" << s << " should be >= " << accumulated_s_.front();
201 return headings_.front();
202 }
203 if (s - kEpsilon > accumulated_s_.back()) {
204 AWARN << "s:" << s << " should be <= " << accumulated_s_.back();
205 return headings_.back();
206 }
207
208 auto iter = std::lower_bound(accumulated_s_.begin(), accumulated_s_.end(), s);
209 int index = static_cast<int>(std::distance(accumulated_s_.begin(), iter));
210 if (index == 0 || *iter - s <= common::math::kMathEpsilon) {
211 return headings_[index];
212 }
213 return common::math::slerp(headings_[index - 1], accumulated_s_[index - 1],
214 headings_[index], accumulated_s_[index], s);
215}
216
217double LaneInfo::Curvature(const double s) const {
218 if (points_.size() < 2U) {
219 AERROR << "Not enough points to compute curvature.";
220 return 0.0;
221 }
222 const double kEpsilon = 0.001;
223 if (s + kEpsilon < accumulated_s_.front()) {
224 AERROR << "s:" << s << " should be >= " << accumulated_s_.front();
225 return 0.0;
226 }
227 if (s > accumulated_s_.back() + kEpsilon) {
228 AERROR << "s:" << s << " should be <= " << accumulated_s_.back();
229 return 0.0;
230 }
231
232 auto iter = std::lower_bound(accumulated_s_.begin(), accumulated_s_.end(), s);
233 if (iter == accumulated_s_.end()) {
234 ADEBUG << "Reach the end of lane.";
235 return 0.0;
236 }
237 int index = static_cast<int>(std::distance(accumulated_s_.begin(), iter));
238 if (index == 0) {
239 ADEBUG << "Reach the beginning of lane";
240 return 0.0;
241 }
242 return (headings_[index] - headings_[index - 1]) /
243 (accumulated_s_[index] - accumulated_s_[index - 1] + kEpsilon);
244}
245
246double LaneInfo::GetWidth(const double s) const {
247 double left_width = 0.0;
248 double right_width = 0.0;
249 GetWidth(s, &left_width, &right_width);
250 return left_width + right_width;
251}
252
253double LaneInfo::GetEffectiveWidth(const double s) const {
254 double left_width = 0.0;
255 double right_width = 0.0;
256 GetWidth(s, &left_width, &right_width);
257 return 2 * std::min(left_width, right_width);
258}
259
260void LaneInfo::GetRoadWidth(const double s, double *left_width,
261 double *right_width) const {
262 if (left_width != nullptr) {
263 *left_width = GetWidthFromSample(sampled_left_road_width_, s);
264 }
265 if (right_width != nullptr) {
266 *right_width = GetWidthFromSample(sampled_right_road_width_, s);
267 }
268}
269
270double LaneInfo::GetRoadWidth(const double s) const {
271 double left_width = 0.0;
272 double right_width = 0.0;
273 GetRoadWidth(s, &left_width, &right_width);
274 return left_width + right_width;
275}
276
277double LaneInfo::GetWidthFromSample(
278 const std::vector<LaneInfo::SampledWidth> &samples, const double s) const {
279 if (samples.empty()) {
280 return 0.0;
281 }
282 if (s <= samples[0].first) {
283 return samples[0].second;
284 }
285 if (s >= samples.back().first) {
286 return samples.back().second;
287 }
288 int low = 0;
289 int high = static_cast<int>(samples.size());
290 while (low + 1 < high) {
291 const int mid = (low + high) >> 1;
292 if (samples[mid].first <= s) {
293 low = mid;
294 } else {
295 high = mid;
296 }
297 }
298 const LaneInfo::SampledWidth &sample1 = samples[low];
299 const LaneInfo::SampledWidth &sample2 = samples[high];
300 const double ratio = (sample2.first - s) / (sample2.first - sample1.first);
301 return sample1.second * ratio + sample2.second * (1.0 - ratio);
302}
303
304bool LaneInfo::IsOnLane(const Vec2d &point) const {
305 double accumulate_s = 0.0;
306 double lateral = 0.0;
307 if (!GetProjection(point, &accumulate_s, &lateral)) {
308 return false;
309 }
310
311 if (accumulate_s > (total_length() + kEpsilon) ||
312 (accumulate_s + kEpsilon) < 0.0) {
313 return false;
314 }
315
316 double left_width = 0.0;
317 double right_width = 0.0;
318 GetWidth(accumulate_s, &left_width, &right_width);
319 if (lateral < left_width && lateral > -right_width) {
320 return true;
321 }
322 return false;
323}
324
326 std::vector<Vec2d> corners;
327 box.GetAllCorners(&corners);
328 for (const auto &corner : corners) {
329 if (!IsOnLane(corner)) {
330 return false;
331 }
332 }
333 return true;
334}
335
336PointENU LaneInfo::GetSmoothPoint(double s) const {
337 PointENU point;
338 RETURN_VAL_IF(points_.size() < 2, point);
339 if (s <= 0.0) {
340 return PointFromVec2d(points_[0]);
341 }
342
343 if (s >= total_length()) {
344 return PointFromVec2d(points_.back());
345 }
346
347 const auto low_itr =
348 std::lower_bound(accumulated_s_.begin(), accumulated_s_.end(), s);
349 RETURN_VAL_IF(low_itr == accumulated_s_.end(), point);
350 size_t index = low_itr - accumulated_s_.begin();
351 double delta_s = *low_itr - s;
353 return PointFromVec2d(points_[index]);
354 }
355
356 auto smooth_point = points_[index] - unit_directions_[index - 1] * delta_s;
357
358 return PointFromVec2d(smooth_point);
359}
360
361double LaneInfo::DistanceTo(const Vec2d &point) const {
362 const auto segment_box = lane_segment_kdtree_->GetNearestObject(point);
363 RETURN_VAL_IF_NULL(segment_box, 0.0);
364 return segment_box->DistanceTo(point);
365}
366
367double LaneInfo::DistanceTo(const Vec2d &point, Vec2d *map_point,
368 double *s_offset, int *s_offset_index) const {
369 RETURN_VAL_IF_NULL(map_point, 0.0);
370 RETURN_VAL_IF_NULL(s_offset, 0.0);
371 RETURN_VAL_IF_NULL(s_offset_index, 0.0);
372
373 const auto segment_box = lane_segment_kdtree_->GetNearestObject(point);
374 RETURN_VAL_IF_NULL(segment_box, 0.0);
375 int index = segment_box->id();
376 double distance = segments_[index].DistanceTo(point, map_point);
377 *s_offset_index = index;
378 *s_offset =
379 accumulated_s_[index] + segments_[index].start().DistanceTo(*map_point);
380 return distance;
381}
382
383PointENU LaneInfo::GetNearestPoint(const Vec2d &point, double *distance) const {
384 PointENU empty_point;
385 RETURN_VAL_IF_NULL(distance, empty_point);
386
387 const auto segment_box = lane_segment_kdtree_->GetNearestObject(point);
388 RETURN_VAL_IF_NULL(segment_box, empty_point);
389 int index = segment_box->id();
390 Vec2d nearest_point;
391 *distance = segments_[index].DistanceTo(point, &nearest_point);
392
393 return PointFromVec2d(nearest_point);
394}
395
396bool LaneInfo::GetProjection(const Vec2d &point, double *accumulate_s,
397 double *lateral) const {
399 RETURN_VAL_IF_NULL(lateral, false);
400
401 if (segments_.empty()) {
402 return false;
403 }
404 double min_dist = std::numeric_limits<double>::infinity();
405 int seg_num = static_cast<int>(segments_.size());
406 int min_index = 0;
407 for (int i = 0; i < seg_num; ++i) {
408 const double distance = segments_[i].DistanceSquareTo(point);
409 if (distance < min_dist) {
410 min_index = i;
411 min_dist = distance;
412 }
413 }
414 min_dist = std::sqrt(min_dist);
415 const auto &nearest_seg = segments_[min_index];
416 const auto prod = nearest_seg.ProductOntoUnit(point);
417 const auto proj = nearest_seg.ProjectOntoUnit(point);
418 if (min_index == 0) {
419 *accumulate_s = std::min(proj, nearest_seg.length());
420 if (proj < 0) {
421 *lateral = prod;
422 } else {
423 *lateral = (prod > 0.0 ? 1 : -1) * min_dist;
424 }
425 } else if (min_index == seg_num - 1) {
426 *accumulate_s = accumulated_s_[min_index] + std::max(0.0, proj);
427 if (proj > 0) {
428 *lateral = prod;
429 } else {
430 *lateral = (prod > 0.0 ? 1 : -1) * min_dist;
431 }
432 } else {
433 *accumulate_s = accumulated_s_[min_index] +
434 std::max(0.0, std::min(proj, nearest_seg.length()));
435 *lateral = (prod > 0.0 ? 1 : -1) * min_dist;
436 }
437 return true;
438}
439
440bool LaneInfo::GetProjection(const Vec2d &point, const double heading,
441 double *accumulate_s, double *lateral) const {
443 RETURN_VAL_IF_NULL(lateral, false);
444
445 if (segments_.empty()) {
446 return false;
447 }
448 double min_dist = std::numeric_limits<double>::infinity();
449 int seg_num = static_cast<int>(segments_.size());
450 int min_index = 0;
451 for (int i = 0; i < seg_num; ++i) {
452 if (abs(common::math::AngleDiff(segments_[i].heading(), heading)) >= M_PI_2)
453 continue;
454 const double distance = segments_[i].DistanceSquareTo(point);
455 if (distance < min_dist) {
456 min_index = i;
457 min_dist = distance;
458 }
459 }
460 min_dist = std::sqrt(min_dist);
461 const auto &nearest_seg = segments_[min_index];
462 const auto prod = nearest_seg.ProductOntoUnit(point);
463 const auto proj = nearest_seg.ProjectOntoUnit(point);
464 if (min_index == 0) {
465 *accumulate_s = std::min(proj, nearest_seg.length());
466 if (proj < 0) {
467 *lateral = prod;
468 } else {
469 *lateral = (prod > 0.0 ? 1 : -1) * min_dist;
470 }
471 } else if (min_index == seg_num - 1) {
472 *accumulate_s = accumulated_s_[min_index] + std::max(0.0, proj);
473 if (proj > 0) {
474 *lateral = prod;
475 } else {
476 *lateral = (prod > 0.0 ? 1 : -1) * min_dist;
477 }
478 } else {
479 *accumulate_s = accumulated_s_[min_index] +
480 std::max(0.0, std::min(proj, nearest_seg.length()));
481 *lateral = (prod > 0.0 ? 1 : -1) * min_dist;
482 }
483 return true;
484}
485
486void LaneInfo::PostProcess(const HDMapImpl &map_instance) {
487 UpdateOverlaps(map_instance);
488}
489
490void LaneInfo::UpdateOverlaps(const HDMapImpl &map_instance) {
491 for (const auto &overlap_id : overlap_ids_) {
492 const auto &overlap_ptr =
493 map_instance.GetOverlapById(MakeMapId(overlap_id));
494 if (overlap_ptr == nullptr) {
495 continue;
496 }
497 overlaps_.emplace_back(overlap_ptr);
498 for (const auto &object : overlap_ptr->overlap().object()) {
499 const auto &object_id = object.id().id();
500 if (object_id == lane_.id().id()) {
501 continue;
502 }
503 const auto &object_map_id = MakeMapId(object_id);
504 if (map_instance.GetLaneById(object_map_id) != nullptr) {
505 cross_lanes_.emplace_back(overlap_ptr);
506 }
507 if (map_instance.GetSignalById(object_map_id) != nullptr) {
508 signals_.emplace_back(overlap_ptr);
509 }
510 if (map_instance.GetBarrierGateById(object_map_id) != nullptr) {
511 barrier_gates_.emplace_back(overlap_ptr);
512 }
513 if (map_instance.GetYieldSignById(object_map_id) != nullptr) {
514 yield_signs_.emplace_back(overlap_ptr);
515 }
516 if (map_instance.GetStopSignById(object_map_id) != nullptr) {
517 stop_signs_.emplace_back(overlap_ptr);
518 }
519 if (map_instance.GetCrosswalkById(object_map_id) != nullptr) {
520 crosswalks_.emplace_back(overlap_ptr);
521 }
522 if (map_instance.GetJunctionById(object_map_id) != nullptr) {
523 junctions_.emplace_back(overlap_ptr);
524 }
525 if (map_instance.GetClearAreaById(object_map_id) != nullptr) {
526 clear_areas_.emplace_back(overlap_ptr);
527 }
528 if (map_instance.GetSpeedBumpById(object_map_id) != nullptr) {
529 speed_bumps_.emplace_back(overlap_ptr);
530 }
531 if (map_instance.GetParkingSpaceById(object_map_id) != nullptr) {
532 parking_spaces_.emplace_back(overlap_ptr);
533 }
534 if (map_instance.GetPNCJunctionById(object_map_id) != nullptr) {
535 pnc_junctions_.emplace_back(overlap_ptr);
536 }
537 if (map_instance.GetAreaById(object_map_id) != nullptr) {
538 areas_.emplace_back(overlap_ptr);
539 }
540 }
541 }
542}
543
544void LaneInfo::CreateKDTree() {
546 params.max_leaf_dimension = 5.0; // meters.
547 params.max_leaf_size = 16;
548
549 segment_box_list_.clear();
550 for (size_t id = 0; id < segments_.size(); ++id) {
551 const auto &segment = segments_[id];
552 segment_box_list_.emplace_back(
553 apollo::common::math::AABox2d(segment.start(), segment.end()), this,
554 &segment, id);
555 }
556 lane_segment_kdtree_.reset(new LaneSegmentKDTree(segment_box_list_, params));
557}
558
559JunctionInfo::JunctionInfo(const Junction &junction) : junction_(junction) {
560 Init();
561}
562
563void JunctionInfo::Init() {
564 polygon_ = ConvertToPolygon2d(junction_.polygon());
565 CHECK_GT(polygon_.num_points(), 2);
566
567 for (const auto &overlap_id : junction_.overlap_id()) {
568 overlap_ids_.emplace_back(overlap_id);
569 }
570}
571
572void JunctionInfo::PostProcess(const HDMapImpl &map_instance) {
573 UpdateOverlaps(map_instance);
574}
575
576void JunctionInfo::UpdateOverlaps(const HDMapImpl &map_instance) {
577 for (const auto &overlap_id : overlap_ids_) {
578 const auto &overlap_ptr = map_instance.GetOverlapById(overlap_id);
579 if (overlap_ptr == nullptr) {
580 continue;
581 }
582
583 for (const auto &object : overlap_ptr->overlap().object()) {
584 const auto &object_id = object.id().id();
585 if (object_id == id().id()) {
586 continue;
587 }
588
589 if (object.has_stop_sign_overlap_info()) {
590 overlap_stop_sign_ids_.push_back(object.id());
591 }
592 }
593 }
594}
595
596AreaInfo::AreaInfo(const Area &ad_area) : ad_area_(ad_area) { Init(); }
597
598void AreaInfo::Init() {
599 polygon_ = ConvertToPolygon2d(ad_area_.polygon());
600 CHECK_GT(polygon_.num_points(), 2);
601
602 for (const auto &overlap_id : ad_area_.overlap_id()) {
603 overlap_ids_.emplace_back(overlap_id);
604 }
605}
606
607void AreaInfo::PostProcess(const HDMapImpl &map_instance) {
608 UpdateOverlaps(map_instance);
609}
610
611void AreaInfo::UpdateOverlaps(const HDMapImpl &map_instance) {
612 for (const auto &overlap_id : overlap_ids_) {
613 const auto &overlap_ptr = map_instance.GetOverlapById(overlap_id);
614 if (overlap_ptr == nullptr) {
615 continue;
616 }
617
618 for (const auto &object : overlap_ptr->overlap().object()) {
619 const auto &object_id = object.id().id();
620 if (object_id == id().id()) {
621 continue;
622 }
623
624 if (object.has_area_overlap_info()) {
625 auto area =
626 map_instance.GetAreaById(map_instance.CreateHDMapId(object_id));
627 if (area->type() == Area::UnDriveable)
628 overlap_undriveable_areas_.push_back(area);
629 }
630 }
631 }
632}
633
634SignalInfo::SignalInfo(const Signal &signal) : signal_(signal) { Init(); }
635
636void SignalInfo::Init() {
637 for (const auto &stop_line : signal_.stop_line()) {
638 SegmentsFromCurve(stop_line, &segments_);
639 }
640 ACHECK(!segments_.empty());
641 std::vector<Vec2d> points;
642 for (const auto &segment : segments_) {
643 points.emplace_back(segment.start());
644 points.emplace_back(segment.end());
645 }
646 CHECK_GT(points.size(), 0U);
647}
648
650 : barrier_gate_(barrier_gate) {
651 Init();
652}
653
654void BarrierGateInfo::Init() {
655 for (const auto &stop_line : barrier_gate_.stop_line()) {
656 SegmentsFromCurve(stop_line, &segments_);
657 }
658 ACHECK(!segments_.empty());
659 std::vector<Vec2d> points;
660 for (const auto &segment : segments_) {
661 points.emplace_back(segment.start());
662 points.emplace_back(segment.end());
663 }
664 CHECK_GT(points.size(), 0U);
665}
666
668 : crosswalk_(crosswalk) {
669 Init();
670}
671
672void CrosswalkInfo::Init() {
673 polygon_ = ConvertToPolygon2d(crosswalk_.polygon());
674 CHECK_GT(polygon_.num_points(), 2);
675}
676
677StopSignInfo::StopSignInfo(const StopSign &stop_sign) : stop_sign_(stop_sign) {
678 init();
679}
680
681void StopSignInfo::init() {
682 for (const auto &stop_line : stop_sign_.stop_line()) {
683 SegmentsFromCurve(stop_line, &segments_);
684 }
685 ACHECK(!segments_.empty());
686
687 for (const auto &overlap_id : stop_sign_.overlap_id()) {
688 overlap_ids_.emplace_back(overlap_id);
689 }
690}
691
692void StopSignInfo::PostProcess(const HDMapImpl &map_instance) {
693 UpdateOverlaps(map_instance);
694}
695
696void StopSignInfo::UpdateOverlaps(const HDMapImpl &map_instance) {
697 for (const auto &overlap_id : overlap_ids_) {
698 const auto &overlap_ptr = map_instance.GetOverlapById(overlap_id);
699 if (overlap_ptr == nullptr) {
700 continue;
701 }
702
703 for (const auto &object : overlap_ptr->overlap().object()) {
704 const auto &object_id = object.id().id();
705 if (object_id == id().id()) {
706 continue;
707 }
708
709 if (object.has_junction_overlap_info()) {
710 overlap_junction_ids_.push_back(object.id());
711 } else if (object.has_lane_overlap_info()) {
712 overlap_lane_ids_.push_back(object.id());
713 }
714 }
715 }
716 if (overlap_junction_ids_.empty()) {
717 AWARN << "stop sign " << id().id() << "has no overlap with any junction.";
718 }
719}
720
722 : yield_sign_(yield_sign) {
723 Init();
724}
725
726void YieldSignInfo::Init() {
727 for (const auto &stop_line : yield_sign_.stop_line()) {
728 SegmentsFromCurve(stop_line, &segments_);
729 }
730 // segments_from_curve(yield_sign_.stop_line(), &segments_);
731 ACHECK(!segments_.empty());
732}
733
735 : clear_area_(clear_area) {
736 Init();
737}
738
739void ClearAreaInfo::Init() {
740 polygon_ = ConvertToPolygon2d(clear_area_.polygon());
741 CHECK_GT(polygon_.num_points(), 2);
742}
743
745 : speed_bump_(speed_bump) {
746 Init();
747}
748
749void SpeedBumpInfo::Init() {
750 for (const auto &stop_line : speed_bump_.position()) {
751 SegmentsFromCurve(stop_line, &segments_);
752 }
753 ACHECK(!segments_.empty());
754}
755
756OverlapInfo::OverlapInfo(const Overlap &overlap) : overlap_(overlap) {}
757
758const ObjectOverlapInfo *OverlapInfo::GetObjectOverlapInfo(const Id &id) const {
759 for (const auto &object : overlap_.object()) {
760 if (object.id().id() == id.id()) {
761 return &object;
762 }
763 }
764 return nullptr;
765}
766
767RoadInfo::RoadInfo(const Road &road) : road_(road) {
768 for (const auto &section : road_.section()) {
769 sections_.push_back(section);
770 road_boundaries_.push_back(section.boundary());
771 }
772}
773
774const std::vector<RoadBoundary> &RoadInfo::GetBoundaries() const {
775 return road_boundaries_;
776}
777
779 : parking_space_(parking_space) {
780 Init();
781}
782
783void ParkingSpaceInfo::Init() {
784 polygon_ = ConvertToPolygon2d(parking_space_.polygon());
785 CHECK_GT(polygon_.num_points(), 2);
786}
787
789 : junction_(pnc_junction) {
790 Init();
791}
792
793void PNCJunctionInfo::Init() {
794 polygon_ = ConvertToPolygon2d(junction_.polygon());
795 CHECK_GT(polygon_.num_points(), 2);
796
797 for (const auto &overlap_id : junction_.overlap_id()) {
798 overlap_ids_.emplace_back(overlap_id);
799 }
800}
801
802RSUInfo::RSUInfo(const RSU &rsu) : _rsu(rsu) {}
803
804} // namespace hdmap
805} // namespace apollo
Implements a class of (undirected) axes-aligned bounding boxes in 2-D.
Definition aabox2d.h:42
Rectangular (undirected) bounding box in 2-D.
Definition box2d.h:52
void GetAllCorners(std::vector< Vec2d > *const corners) const
Getter of the corners of the box
Definition box2d.cc:140
The class of polygon in 2-D.
Definition polygon2d.h:42
int num_points() const
Get the number of vertices of the polygon.
Definition polygon2d.h:79
Implements a class of 2-dimensional vectors.
Definition vec2d.h:42
const Area & area() const
AreaInfo(const Area &ad_area)
BarrierGateInfo(const BarrierGate &barrier_gate)
ClearAreaInfo(const ClearArea &clear_area)
CrosswalkInfo(const Crosswalk &crosswalk)
High-precision map loader implement.
Definition hdmap_impl.h:59
JunctionInfo(const Junction &junction)
std::pair< double, double > SampledWidth
double Heading(const double s) const
void GetRoadWidth(const double s, double *left_width, double *right_width) const
apollo::common::PointENU GetSmoothPoint(double s) const
void GetWidth(const double s, double *left_width, double *right_width) const
double GetEffectiveWidth(const double s) const
LaneInfo(const Lane &lane)
const Id & id() const
apollo::common::PointENU GetNearestPoint(const apollo::common::math::Vec2d &point, double *distance) const
double Curvature(const double s) const
bool GetProjection(const apollo::common::math::Vec2d &point, double *accumulate_s, double *lateral) const
double total_length() const
bool IsOnLane(const apollo::common::math::Vec2d &point) const
double DistanceTo(const apollo::common::math::Vec2d &point) const
const std::vector< double > & accumulate_s() const
OverlapInfo(const Overlap &overlap)
const ObjectOverlapInfo * GetObjectOverlapInfo(const Id &id) const
PNCJunctionInfo(const PNCJunction &pnc_junction)
ParkingSpaceInfo(const ParkingSpace &parkingspace)
RSUInfo(const RSU &rsu)
RoadInfo(const Road &road)
const std::vector< RoadBoundary > & GetBoundaries() const
SignalInfo(const Signal &signal)
SpeedBumpInfo(const SpeedBump &speed_bump)
StopSignInfo(const StopSign &stop_sign)
YieldSignInfo(const YieldSign &yield_sign)
Linear interpolation functions.
#define RETURN_VAL_IF_NULL(ptr, val)
Definition log.h:98
#define RETURN_IF_NULL(ptr)
Definition log.h:90
#define ACHECK(cond)
Definition log.h:80
#define RETURN_VAL_IF(condition, val)
Definition log.h:114
#define ADEBUG
Definition log.h:41
#define AERROR
Definition log.h:44
#define AWARN
Definition log.h:43
Math-related util functions.
constexpr double kMathEpsilon
Definition vec2d.h:35
double AngleDiff(const double from, const double to)
Calculate the difference between angle from and to
Definition math_utils.cc:61
double slerp(const double a0, const double t0, const double a1, const double t1, const double t)
Spherical linear interpolation between two angles.
apollo::hdmap::Id MakeMapId(const std::string &id)
create a Map ID given a string.
Definition hdmap_util.h:85
apollo::common::math::AABoxKDTree2d< LaneSegmentBox > LaneSegmentKDTree
class register implement
Definition arena_queue.h:37
Contains parameters of axis-aligned bounding box.
int max_leaf_size
The maximum number of items in one leaf node.
double max_leaf_dimension
The maximum dimension size of leaf node.
required Polygon polygon
optional Type type
optional string id
Definition map_id.proto:7
optional Curve central_curve
optional LaneType type
repeated RoadSection section