37constexpr double kDuplicatedPointsEpsilon = 1e-7;
40constexpr double kEpsilon = 0.1;
42void RemoveDuplicates(std::vector<Vec2d> *points) {
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;
52 points->resize(count);
55void PointsFromCurve(
const Curve &input_curve, std::vector<Vec2d> *points) {
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());
65 AERROR <<
"Can not handle curve type.";
68 RemoveDuplicates(points);
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());
77 RemoveDuplicates(&points);
78 while (points.size() >= 2 && points[0].DistanceTo(points.back()) <=
85void SegmentsFromCurve(
87 std::vector<apollo::common::math::LineSegment2d> *segments) {
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]);
97PointENU PointFromVec2d(
const Vec2d &point) {
108void LaneInfo::Init() {
110 CHECK_GE(points_.size(), 2U);
112 accumulated_s_.clear();
113 unit_directions_.clear();
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();
124 accumulated_s_.push_back(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());
131 for (
const auto &overlap_id : lane_.overlap_id()) {
132 overlap_ids_.emplace_back(overlap_id.id());
134 ACHECK(!segments_.empty());
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());
141 for (
const auto &sample : lane_.right_sample()) {
142 sampled_right_width_.emplace_back(sample.s(), sample.width());
145 if (lane_.has_type()) {
147 for (
const auto &p : sampled_left_width_) {
148 if (p.second < FLAGS_half_vehicle_width) {
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 <<
"].";
156 for (
const auto &p : sampled_right_width_) {
157 if (p.second < FLAGS_half_vehicle_width) {
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 <<
"].";
166 AERROR <<
"lane_[id = " << lane_.
id().DebugString() <<
"] type is NONE.";
169 AERROR <<
"lane_[id = " << lane_.
id().DebugString() <<
"] has NO type.";
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());
177 for (
const auto &sample : lane_.right_road_sample()) {
178 sampled_right_road_width_.emplace_back(sample.s(), sample.width());
185 double *right_width)
const {
186 if (left_width !=
nullptr) {
187 *left_width = GetWidthFromSample(sampled_left_width_, s);
189 if (right_width !=
nullptr) {
190 *right_width = GetWidthFromSample(sampled_right_width_, s);
195 if (accumulated_s_.empty()) {
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();
203 if (s - kEpsilon > accumulated_s_.back()) {
204 AWARN <<
"s:" << s <<
" should be <= " << accumulated_s_.back();
205 return headings_.back();
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));
211 return headings_[index];
214 headings_[index], accumulated_s_[index], s);
218 if (points_.size() < 2U) {
219 AERROR <<
"Not enough points to compute curvature.";
222 const double kEpsilon = 0.001;
223 if (s + kEpsilon < accumulated_s_.front()) {
224 AERROR <<
"s:" << s <<
" should be >= " << accumulated_s_.front();
227 if (s > accumulated_s_.back() + kEpsilon) {
228 AERROR <<
"s:" << s <<
" should be <= " << accumulated_s_.back();
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.";
237 int index =
static_cast<int>(std::distance(accumulated_s_.begin(), iter));
239 ADEBUG <<
"Reach the beginning of lane";
242 return (headings_[index] - headings_[index - 1]) /
243 (accumulated_s_[index] - accumulated_s_[index - 1] + kEpsilon);
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;
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);
261 double *right_width)
const {
262 if (left_width !=
nullptr) {
263 *left_width = GetWidthFromSample(sampled_left_road_width_, s);
265 if (right_width !=
nullptr) {
266 *right_width = GetWidthFromSample(sampled_right_road_width_, s);
271 double left_width = 0.0;
272 double right_width = 0.0;
274 return left_width + right_width;
277double LaneInfo::GetWidthFromSample(
278 const std::vector<LaneInfo::SampledWidth> &samples,
const double s)
const {
279 if (samples.empty()) {
282 if (s <= samples[0].first) {
283 return samples[0].second;
285 if (s >= samples.back().first) {
286 return samples.back().second;
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) {
300 const double ratio = (sample2.first - s) / (sample2.first - sample1.first);
301 return sample1.second * ratio + sample2.second * (1.0 - ratio);
306 double lateral = 0.0;
316 double left_width = 0.0;
317 double right_width = 0.0;
319 if (lateral < left_width && lateral > -right_width) {
326 std::vector<Vec2d> corners;
328 for (
const auto &corner : corners) {
340 return PointFromVec2d(points_[0]);
344 return PointFromVec2d(points_.back());
348 std::lower_bound(accumulated_s_.begin(), accumulated_s_.end(), s);
350 size_t index = low_itr - accumulated_s_.begin();
351 double delta_s = *low_itr - s;
353 return PointFromVec2d(points_[index]);
356 auto smooth_point = points_[index] - unit_directions_[index - 1] * delta_s;
358 return PointFromVec2d(smooth_point);
362 const auto segment_box = lane_segment_kdtree_->GetNearestObject(point);
364 return segment_box->DistanceTo(point);
368 double *s_offset,
int *s_offset_index)
const {
373 const auto segment_box = lane_segment_kdtree_->GetNearestObject(point);
375 int index = segment_box->id();
376 double distance = segments_[index].DistanceTo(point, map_point);
377 *s_offset_index = index;
379 accumulated_s_[index] + segments_[index].start().DistanceTo(*map_point);
384 PointENU empty_point;
387 const auto segment_box = lane_segment_kdtree_->GetNearestObject(point);
389 int index = segment_box->id();
391 *distance = segments_[index].DistanceTo(point, &nearest_point);
393 return PointFromVec2d(nearest_point);
397 double *lateral)
const {
401 if (segments_.empty()) {
404 double min_dist = std::numeric_limits<double>::infinity();
405 int seg_num =
static_cast<int>(segments_.size());
407 for (
int i = 0; i < seg_num; ++i) {
408 const double distance = segments_[i].DistanceSquareTo(point);
409 if (distance < min_dist) {
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) {
423 *lateral = (prod > 0.0 ? 1 : -1) * min_dist;
425 }
else if (min_index == seg_num - 1) {
426 *
accumulate_s = accumulated_s_[min_index] + std::max(0.0, proj);
430 *lateral = (prod > 0.0 ? 1 : -1) * min_dist;
434 std::max(0.0, std::min(proj, nearest_seg.length()));
435 *lateral = (prod > 0.0 ? 1 : -1) * min_dist;
441 double *accumulate_s,
double *lateral)
const {
445 if (segments_.empty()) {
448 double min_dist = std::numeric_limits<double>::infinity();
449 int seg_num =
static_cast<int>(segments_.size());
451 for (
int i = 0; i < seg_num; ++i) {
454 const double distance = segments_[i].DistanceSquareTo(point);
455 if (distance < min_dist) {
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) {
469 *lateral = (prod > 0.0 ? 1 : -1) * min_dist;
471 }
else if (min_index == seg_num - 1) {
472 *
accumulate_s = accumulated_s_[min_index] + std::max(0.0, proj);
476 *lateral = (prod > 0.0 ? 1 : -1) * min_dist;
480 std::max(0.0, std::min(proj, nearest_seg.length()));
481 *lateral = (prod > 0.0 ? 1 : -1) * min_dist;
486void LaneInfo::PostProcess(
const HDMapImpl &map_instance) {
487 UpdateOverlaps(map_instance);
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) {
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()) {
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);
507 if (map_instance.GetSignalById(object_map_id) !=
nullptr) {
508 signals_.emplace_back(overlap_ptr);
510 if (map_instance.GetBarrierGateById(object_map_id) !=
nullptr) {
511 barrier_gates_.emplace_back(overlap_ptr);
513 if (map_instance.GetYieldSignById(object_map_id) !=
nullptr) {
514 yield_signs_.emplace_back(overlap_ptr);
516 if (map_instance.GetStopSignById(object_map_id) !=
nullptr) {
517 stop_signs_.emplace_back(overlap_ptr);
519 if (map_instance.GetCrosswalkById(object_map_id) !=
nullptr) {
520 crosswalks_.emplace_back(overlap_ptr);
522 if (map_instance.GetJunctionById(object_map_id) !=
nullptr) {
523 junctions_.emplace_back(overlap_ptr);
525 if (map_instance.GetClearAreaById(object_map_id) !=
nullptr) {
526 clear_areas_.emplace_back(overlap_ptr);
528 if (map_instance.GetSpeedBumpById(object_map_id) !=
nullptr) {
529 speed_bumps_.emplace_back(overlap_ptr);
531 if (map_instance.GetParkingSpaceById(object_map_id) !=
nullptr) {
532 parking_spaces_.emplace_back(overlap_ptr);
534 if (map_instance.GetPNCJunctionById(object_map_id) !=
nullptr) {
535 pnc_junctions_.emplace_back(overlap_ptr);
537 if (map_instance.GetAreaById(object_map_id) !=
nullptr) {
538 areas_.emplace_back(overlap_ptr);
544void LaneInfo::CreateKDTree() {
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(
563void JunctionInfo::Init() {
564 polygon_ = ConvertToPolygon2d(junction_.
polygon());
567 for (
const auto &overlap_id : junction_.overlap_id()) {
568 overlap_ids_.emplace_back(overlap_id);
572void JunctionInfo::PostProcess(
const HDMapImpl &map_instance) {
573 UpdateOverlaps(map_instance);
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) {
583 for (
const auto &
object : overlap_ptr->overlap().object()) {
584 const auto &object_id =
object.id().id();
585 if (object_id ==
id().
id()) {
589 if (
object.has_stop_sign_overlap_info()) {
590 overlap_stop_sign_ids_.push_back(
object.
id());
598void AreaInfo::Init() {
599 polygon_ = ConvertToPolygon2d(ad_area_.
polygon());
602 for (
const auto &overlap_id : ad_area_.overlap_id()) {
603 overlap_ids_.emplace_back(overlap_id);
607void AreaInfo::PostProcess(
const HDMapImpl &map_instance) {
608 UpdateOverlaps(map_instance);
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) {
618 for (
const auto &
object : overlap_ptr->overlap().object()) {
619 const auto &object_id =
object.id().id();
620 if (object_id ==
id().
id()) {
624 if (
object.has_area_overlap_info()) {
626 map_instance.GetAreaById(map_instance.CreateHDMapId(object_id));
628 overlap_undriveable_areas_.push_back(
area);
636void SignalInfo::Init() {
637 for (
const auto &stop_line : signal_.stop_line()) {
638 SegmentsFromCurve(stop_line, &segments_);
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());
646 CHECK_GT(points.size(), 0U);
650 : barrier_gate_(barrier_gate) {
654void BarrierGateInfo::Init() {
655 for (
const auto &stop_line : barrier_gate_.stop_line()) {
656 SegmentsFromCurve(stop_line, &segments_);
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());
664 CHECK_GT(points.size(), 0U);
668 : crosswalk_(crosswalk) {
672void CrosswalkInfo::Init() {
673 polygon_ = ConvertToPolygon2d(crosswalk_.
polygon());
681void StopSignInfo::init() {
682 for (
const auto &stop_line : stop_sign_.stop_line()) {
683 SegmentsFromCurve(stop_line, &segments_);
685 ACHECK(!segments_.empty());
687 for (
const auto &overlap_id : stop_sign_.overlap_id()) {
688 overlap_ids_.emplace_back(overlap_id);
692void StopSignInfo::PostProcess(
const HDMapImpl &map_instance) {
693 UpdateOverlaps(map_instance);
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) {
703 for (
const auto &
object : overlap_ptr->overlap().object()) {
704 const auto &object_id =
object.id().id();
705 if (object_id ==
id().
id()) {
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());
716 if (overlap_junction_ids_.empty()) {
717 AWARN <<
"stop sign " <<
id().
id() <<
"has no overlap with any junction.";
722 : yield_sign_(yield_sign) {
726void YieldSignInfo::Init() {
727 for (
const auto &stop_line : yield_sign_.stop_line()) {
728 SegmentsFromCurve(stop_line, &segments_);
731 ACHECK(!segments_.empty());
735 : clear_area_(clear_area) {
739void ClearAreaInfo::Init() {
740 polygon_ = ConvertToPolygon2d(clear_area_.
polygon());
745 : speed_bump_(speed_bump) {
749void SpeedBumpInfo::Init() {
750 for (
const auto &stop_line : speed_bump_.position()) {
751 SegmentsFromCurve(stop_line, &segments_);
753 ACHECK(!segments_.empty());
759 for (
const auto &
object : overlap_.object()) {
760 if (
object.
id().id() ==
id.id()) {
768 for (
const auto §ion : road_.
section()) {
769 sections_.push_back(section);
770 road_boundaries_.push_back(section.boundary());
775 return road_boundaries_;
779 : parking_space_(parking_space) {
783void ParkingSpaceInfo::Init() {
784 polygon_ = ConvertToPolygon2d(parking_space_.
polygon());
789 : junction_(pnc_junction) {
793void PNCJunctionInfo::Init() {
794 polygon_ = ConvertToPolygon2d(junction_.
polygon());
797 for (
const auto &overlap_id : junction_.overlap_id()) {
798 overlap_ids_.emplace_back(overlap_id);
Implements a class of (undirected) axes-aligned bounding boxes in 2-D.
Rectangular (undirected) bounding box in 2-D.
void GetAllCorners(std::vector< Vec2d > *const corners) const
Getter of the corners of the box
The class of polygon in 2-D.
int num_points() const
Get the number of vertices of the polygon.
Implements a class of 2-dimensional vectors.
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.
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)
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)
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)
#define RETURN_IF_NULL(ptr)
#define RETURN_VAL_IF(condition, val)
Math-related util functions.
constexpr double kMathEpsilon
double AngleDiff(const double from, const double to)
Calculate the difference between angle from and to
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.
apollo::common::math::AABoxKDTree2d< LaneSegmentBox > LaneSegmentKDTree
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.
optional Curve central_curve
repeated RoadSection section