Apollo 10.0
自动驾驶开放平台
apollo::planning::Obstacle类 参考

This is the class that associates an Obstacle with its path properties. 更多...

#include <obstacle.h>

apollo::planning::Obstacle 的协作图:

Public 成员函数

 Obstacle ()=default
 
 Obstacle (const std::string &id, const perception::PerceptionObstacle &perception_obstacle, const prediction::ObstaclePriority::Priority &obstacle_priority, const bool is_static)
 
 Obstacle (const std::string &id, const perception::PerceptionObstacle &perception_obstacle, const prediction::Trajectory &trajectory, const prediction::ObstaclePriority::Priority &obstacle_priority, const bool is_static)
 
const std::string & Id () const
 
void SetId (const std::string &id)
 
double speed () const
 
int32_t PerceptionId () const
 
bool IsStatic () const
 
bool IsVirtual () const
 
common::TrajectoryPoint GetPointAtTime (const double time) const
 
common::math::Box2d GetBoundingBox (const common::TrajectoryPoint &point) const
 
const common::math::Box2dPerceptionBoundingBox () const
 
const common::math::Polygon2dPerceptionPolygon () const
 
const prediction::TrajectoryTrajectory () const
 
bool HasTrajectory () const
 
const perception::PerceptionObstaclePerception () const
 
bool IsCautionLevelObstacle () const
 
const ObjectDecisionType & LateralDecision () const
 return the merged lateral decision Lateral decision is one of {Nudge, Ignore}
 
const ObjectDecisionType & LongitudinalDecision () const
 return the merged longitudinal decision Longitudinal decision is one of {Stop, Yield, Follow, Overtake, Ignore}
 
std::string DebugString () const
 
void PrintPolygonCurve () const
 
const SLBoundaryPerceptionSLBoundary () const
 
const STBoundaryreference_line_st_boundary () const
 
const STBoundarypath_st_boundary () const
 
const std::vector< std::string > & decider_tags () const
 
const std::vector< ObjectDecisionType > & decisions () const
 
void AddLongitudinalDecision (const std::string &decider_tag, const ObjectDecisionType &decision)
 
void AddLateralDecision (const std::string &decider_tag, const ObjectDecisionType &decision)
 
bool HasLateralDecision () const
 
void set_path_st_boundary (const STBoundary &boundary)
 
bool is_path_st_boundary_initialized ()
 
void SetStBoundaryType (const STBoundary::BoundaryType type)
 
void EraseStBoundary ()
 
void EraseDecision ()
 
void SetReferenceLineStBoundary (const STBoundary &boundary)
 
void SetReferenceLineStBoundaryType (const STBoundary::BoundaryType type)
 
void EraseReferenceLineStBoundary ()
 
bool HasLongitudinalDecision () const
 
bool HasNonIgnoreDecision () const
 
double MinRadiusStopDistance (const common::VehicleParam &vehicle_param) const
 Calculate stop distance with the obstacle using the ADC's minimum turning radius
 
bool IsIgnore () const
 Check if this object can be safely ignored.
 
bool IsLongitudinalIgnore () const
 
bool IsLateralIgnore () const
 
void BuildReferenceLineStBoundary (const ReferenceLine &reference_line, const double adc_start_s)
 
void SetPerceptionSlBoundary (const SLBoundary &sl_boundary)
 
void SetBlockingObstacle (bool blocking)
 
bool IsBlockingObstacle () const
 
bool IsLaneBlocking () const
 
void CheckLaneBlocking (const ReferenceLine &reference_line)
 
bool IsLaneChangeBlocking () const
 
void SetLaneChangeBlocking (const bool is_distance_clear)
 
common::math::Polygon2d GetObstacleTrajectoryPolygon (const common::TrajectoryPoint &point) const
 

静态 Public 成员函数

static std::list< std::unique_ptr< Obstacle > > CreateObstacles (const prediction::PredictionObstacles &predictions)
 This is a helper function that can create obstacles from prediction data.
 
static std::unique_ptr< ObstacleCreateStaticVirtualObstacles (const std::string &id, const common::math::Box2d &obstacle_box)
 
static bool IsValidPerceptionObstacle (const perception::PerceptionObstacle &obstacle)
 
static bool IsValidTrajectoryPoint (const common::TrajectoryPoint &point)
 
static bool IsLongitudinalDecision (const ObjectDecisionType &decision)
 check if an ObjectDecisionType is a longitudinal decision.
 
static bool IsLateralDecision (const ObjectDecisionType &decision)
 check if an ObjectDecisionType is a lateral decision.
 

详细描述

This is the class that associates an Obstacle with its path properties.

An obstacle's path properties relative to a path. The s and l values are examples of path properties. The decision of an obstacle is also associated with a path.

The decisions have two categories: lateral decision and longitudinal decision. Lateral decision includes: nudge, ignore. Lateral decision safety priority: nudge > ignore. Longitudinal decision includes: stop, yield, follow, overtake, ignore. Decision safety priorities order: stop > yield >= follow > overtake > ignore

Ignore decision belongs to both lateral decision and longitudinal decision, and it has the lowest priority.

在文件 obstacle.h62 行定义.

构造及析构函数说明

◆ Obstacle() [1/3]

apollo::planning::Obstacle::Obstacle ( )
default

◆ Obstacle() [2/3]

apollo::planning::Obstacle::Obstacle ( const std::string &  id,
const perception::PerceptionObstacle perception_obstacle,
const prediction::ObstaclePriority::Priority obstacle_priority,
const bool  is_static 
)

在文件 obstacle.cc63 行定义.

67 : id_(id),
68 perception_id_(perception_obstacle.id()),
69 perception_obstacle_(perception_obstacle),
70 perception_bounding_box_({perception_obstacle_.position().x(),
71 perception_obstacle_.position().y()},
72 perception_obstacle_.theta(),
73 perception_obstacle_.length(),
74 perception_obstacle_.width()) {
75 is_caution_level_obstacle_ = (obstacle_priority == ObstaclePriority::CAUTION);
76 std::vector<common::math::Vec2d> polygon_points;
77 if (FLAGS_use_navigation_mode ||
78 perception_obstacle.polygon_point_size() <= 2) {
79 perception_bounding_box_.GetAllCorners(&polygon_points);
80 } else {
81 ACHECK(perception_obstacle.polygon_point_size() > 2)
82 << "object " << id << "has less than 3 polygon points";
83 for (const auto& point : perception_obstacle.polygon_point()) {
84 polygon_points.emplace_back(point.x(), point.y());
85 }
86 }
88 &perception_polygon_))
89 << "object[" << id << "] polygon is not a valid convex hull.\n"
90 << perception_obstacle.DebugString();
91
92 is_static_ = (is_static || obstacle_priority == ObstaclePriority::IGNORE);
93 is_virtual_ = (perception_obstacle.id() < 0);
94 speed_ = std::hypot(perception_obstacle.velocity().x(),
95 perception_obstacle.velocity().y());
96}
void GetAllCorners(std::vector< Vec2d > *const corners) const
Getter of the corners of the box
Definition box2d.cc:140
static bool ComputeConvexHull(const std::vector< Vec2d > &points, Polygon2d *const polygon, bool check_area=true)
Compute the convex hull of a group of points.
Definition polygon2d.cc:340
#define ACHECK(cond)
Definition log.h:80
optional apollo::common::Point3D position

◆ Obstacle() [3/3]

apollo::planning::Obstacle::Obstacle ( const std::string &  id,
const perception::PerceptionObstacle perception_obstacle,
const prediction::Trajectory trajectory,
const prediction::ObstaclePriority::Priority obstacle_priority,
const bool  is_static 
)

在文件 obstacle.cc98 行定义.

103 : Obstacle(id, perception_obstacle, obstacle_priority, is_static) {
104 trajectory_ = trajectory;
105 auto& trajectory_points = *trajectory_.mutable_trajectory_point();
106 double cumulative_s = 0.0;
107 if (trajectory_points.size() > 0) {
108 trajectory_points[0].mutable_path_point()->set_s(0.0);
109 }
110 for (int i = 1; i < trajectory_points.size(); ++i) {
111 const auto& prev = trajectory_points[i - 1];
112 const auto& cur = trajectory_points[i];
113 if (prev.relative_time() >= cur.relative_time()) {
114 AERROR << "prediction time is not increasing."
115 << "current point: " << cur.ShortDebugString()
116 << "previous point: " << prev.ShortDebugString();
117 }
118 cumulative_s +=
119 common::util::DistanceXY(prev.path_point(), cur.path_point());
120 trajectory_points[i].mutable_path_point()->set_s(cumulative_s);
121 }
122}
#define AERROR
Definition log.h:44
double DistanceXY(const U &u, const V &v)
calculate the distance beteween Point u and Point v, which are all have member function x() and y() i...
Definition util.h:97

成员函数说明

◆ AddLateralDecision()

void apollo::planning::Obstacle::AddLateralDecision ( const std::string &  decider_tag,
const ObjectDecisionType &  decision 
)

在文件 obstacle.cc661 行定义.

662 {
663 DCHECK(IsLateralDecision(decision))
664 << "Decision: " << decision.ShortDebugString()
665 << " is not a lateral decision";
666 lateral_decision_ = MergeLateralDecision(lateral_decision_, decision);
667 ADEBUG << decider_tag << " added obstacle " << Id()
668 << " a lateral decision: " << decision.ShortDebugString()
669 << ". The merged decision is: "
670 << lateral_decision_.ShortDebugString();
671 decisions_.push_back(decision);
672 decider_tags_.push_back(decider_tag);
673}
static bool IsLateralDecision(const ObjectDecisionType &decision)
check if an ObjectDecisionType is a lateral decision.
Definition obstacle.cc:533
const std::string & Id() const
Definition obstacle.h:75
#define ADEBUG
Definition log.h:41

◆ AddLongitudinalDecision()

void apollo::planning::Obstacle::AddLongitudinalDecision ( const std::string &  decider_tag,
const ObjectDecisionType &  decision 
)

在文件 obstacle.cc646 行定义.

647 {
648 DCHECK(IsLongitudinalDecision(decision))
649 << "Decision: " << decision.ShortDebugString()
650 << " is not a longitudinal decision";
651 longitudinal_decision_ =
652 MergeLongitudinalDecision(longitudinal_decision_, decision);
653 ADEBUG << decider_tag << " added obstacle " << Id()
654 << " longitudinal decision: " << decision.ShortDebugString()
655 << ". The merged decision is: "
656 << longitudinal_decision_.ShortDebugString();
657 decisions_.push_back(decision);
658 decider_tags_.push_back(decider_tag);
659}
static bool IsLongitudinalDecision(const ObjectDecisionType &decision)
check if an ObjectDecisionType is a longitudinal decision.
Definition obstacle.cc:537

◆ BuildReferenceLineStBoundary()

void apollo::planning::Obstacle::BuildReferenceLineStBoundary ( const ReferenceLine reference_line,
const double  adc_start_s 
)

在文件 obstacle.cc316 行定义.

317 {
318 const auto& adc_param =
319 VehicleConfigHelper::Instance()->GetConfig().vehicle_param();
320 const double half_adc_width = adc_param.width() / 2;
321 if (is_static_ || trajectory_.trajectory_point().empty()) {
322 std::vector<std::pair<STPoint, STPoint>> point_pairs;
323 double start_s = sl_boundary_.start_s();
324 double end_s = sl_boundary_.end_s();
325 if (end_s - start_s < kStBoundaryDeltaS) {
326 end_s = start_s + kStBoundaryDeltaS;
327 }
328 if (!reference_line.IsBlockRoad(perception_bounding_box_, half_adc_width)) {
329 return;
330 }
331 point_pairs.emplace_back(STPoint(start_s - adc_start_s, 0.0),
332 STPoint(end_s - adc_start_s, 0.0));
333 point_pairs.emplace_back(STPoint(start_s - adc_start_s, FLAGS_st_max_t),
334 STPoint(end_s - adc_start_s, FLAGS_st_max_t));
335 reference_line_st_boundary_ = STBoundary(point_pairs);
336 } else {
337 if (BuildTrajectoryStBoundary(reference_line, adc_start_s,
338 &reference_line_st_boundary_)) {
339 ADEBUG << "Found st_boundary for obstacle " << id_;
340 ADEBUG << "st_boundary: min_t = " << reference_line_st_boundary_.min_t()
341 << ", max_t = " << reference_line_st_boundary_.max_t()
342 << ", min_s = " << reference_line_st_boundary_.min_s()
343 << ", max_s = " << reference_line_st_boundary_.max_s();
344 } else {
345 ADEBUG << "No st_boundary for obstacle " << id_;
346 }
347 }
348}
repeated apollo::common::TrajectoryPoint trajectory_point
Definition feature.proto:78

◆ CheckLaneBlocking()

void apollo::planning::Obstacle::CheckLaneBlocking ( const ReferenceLine reference_line)

在文件 obstacle.cc739 行定义.

739 {
740 if (!IsStatic()) {
741 is_lane_blocking_ = false;
742 return;
743 }
744 DCHECK(sl_boundary_.has_start_s());
745 DCHECK(sl_boundary_.has_end_s());
746 DCHECK(sl_boundary_.has_start_l());
747 DCHECK(sl_boundary_.has_end_l());
748
749 if (sl_boundary_.start_l() * sl_boundary_.end_l() < 0.0) {
750 is_lane_blocking_ = true;
751 return;
752 }
753
754 const double driving_width = reference_line.GetDrivingWidth(sl_boundary_);
756
757 if (reference_line.IsOnLane(sl_boundary_) &&
758 driving_width <
759 vehicle_param.width() + FLAGS_static_obstacle_nudge_l_buffer) {
760 is_lane_blocking_ = true;
761 return;
762 }
763
764 is_lane_blocking_ = false;
765}
static const VehicleConfig & GetConfig()
Get the current vehicle configuration.
optional VehicleParam vehicle_param

◆ CreateObstacles()

std::list< std::unique_ptr< Obstacle > > apollo::planning::Obstacle::CreateObstacles ( const prediction::PredictionObstacles predictions)
static

This is a helper function that can create obstacles from prediction data.

The original prediction may have multiple trajectories for each obstacle. But this function will create one obstacle for each trajectory.

参数
predictionsThe prediction results
返回
obstacles The output obstacles saved in a list of unique_ptr.

在文件 obstacle.cc197 行定义.

198 {
199 std::list<std::unique_ptr<Obstacle>> obstacles;
200 for (const auto& prediction_obstacle : predictions.prediction_obstacle()) {
201 if (!IsValidPerceptionObstacle(prediction_obstacle.perception_obstacle())) {
202 AERROR << "Invalid perception obstacle: "
203 << prediction_obstacle.perception_obstacle().DebugString();
204 continue;
205 }
206 const auto perception_id =
207 std::to_string(prediction_obstacle.perception_obstacle().id());
208 if (prediction_obstacle.trajectory().empty()) {
209 obstacles.emplace_back(
210 new Obstacle(perception_id, prediction_obstacle.perception_obstacle(),
211 prediction_obstacle.priority().priority(),
212 prediction_obstacle.is_static()));
213 continue;
214 }
215
216 int trajectory_index = 0;
217 for (const auto& trajectory : prediction_obstacle.trajectory()) {
218 bool is_valid_trajectory = true;
219 for (const auto& point : trajectory.trajectory_point()) {
220 if (!IsValidTrajectoryPoint(point)) {
221 AERROR << "obj:" << perception_id
222 << " TrajectoryPoint: " << trajectory.ShortDebugString()
223 << " is NOT valid.";
224 is_valid_trajectory = false;
225 break;
226 }
227 }
228 if (!is_valid_trajectory) {
229 continue;
230 }
231
232 const std::string obstacle_id =
233 absl::StrCat(perception_id, "_", trajectory_index);
234 obstacles.emplace_back(
235 new Obstacle(obstacle_id, prediction_obstacle.perception_obstacle(),
236 trajectory, prediction_obstacle.priority().priority(),
237 prediction_obstacle.is_static()));
238 ++trajectory_index;
239 }
240 }
241 return obstacles;
242}
static bool IsValidTrajectoryPoint(const common::TrajectoryPoint &point)
Definition obstacle.cc:278
static bool IsValidPerceptionObstacle(const perception::PerceptionObstacle &obstacle)
Definition obstacle.cc:167

◆ CreateStaticVirtualObstacles()

std::unique_ptr< Obstacle > apollo::planning::Obstacle::CreateStaticVirtualObstacles ( const std::string &  id,
const common::math::Box2d obstacle_box 
)
static

在文件 obstacle.cc244 行定义.

245 {
246 // create a "virtual" perception_obstacle
247 perception::PerceptionObstacle perception_obstacle;
248 // simulator needs a valid integer
249 size_t negative_id = std::hash<std::string>{}(id);
250 // set the first bit to 1 so negative_id became negative number
251 negative_id |= (0x1 << 31);
252 perception_obstacle.set_id(static_cast<int32_t>(negative_id));
253 perception_obstacle.mutable_position()->set_x(obstacle_box.center().x());
254 perception_obstacle.mutable_position()->set_y(obstacle_box.center().y());
255 perception_obstacle.set_theta(obstacle_box.heading());
256 perception_obstacle.mutable_velocity()->set_x(0);
257 perception_obstacle.mutable_velocity()->set_y(0);
258 perception_obstacle.set_length(obstacle_box.length());
259 perception_obstacle.set_width(obstacle_box.width());
260 perception_obstacle.set_height(FLAGS_virtual_stop_wall_height);
261 perception_obstacle.set_type(
263 perception_obstacle.set_tracking_time(1.0);
264
265 std::vector<common::math::Vec2d> corner_points;
266 obstacle_box.GetAllCorners(&corner_points);
267 for (const auto& corner_point : corner_points) {
268 auto* point = perception_obstacle.add_polygon_point();
269 point->set_x(corner_point.x());
270 point->set_y(corner_point.y());
271 }
272 auto* obstacle =
273 new Obstacle(id, perception_obstacle, ObstaclePriority::NORMAL, true);
274 obstacle->is_virtual_ = true;
275 return std::unique_ptr<Obstacle>(obstacle);
276}

◆ DebugString()

std::string apollo::planning::Obstacle::DebugString ( ) const

在文件 obstacle.cc675 行定义.

675 {
676 std::stringstream ss;
677 ss << "Obstacle id: " << id_;
678 for (size_t i = 0; i < decisions_.size(); ++i) {
679 ss << " decision: " << decisions_[i].DebugString() << ", made by "
680 << decider_tags_[i];
681 }
682 if (lateral_decision_.object_tag_case() !=
683 ObjectDecisionType::OBJECT_TAG_NOT_SET) {
684 ss << "lateral decision: " << lateral_decision_.ShortDebugString();
685 }
686 if (longitudinal_decision_.object_tag_case() !=
687 ObjectDecisionType::OBJECT_TAG_NOT_SET) {
688 ss << "longitudinal decision: "
689 << longitudinal_decision_.ShortDebugString();
690 }
691 return ss.str();
692}

◆ decider_tags()

const std::vector< std::string > & apollo::planning::Obstacle::decider_tags ( ) const

在文件 obstacle.cc525 行定义.

525 {
526 return decider_tags_;
527}

◆ decisions()

const std::vector< ObjectDecisionType > & apollo::planning::Obstacle::decisions ( ) const

在文件 obstacle.cc529 行定义.

529 {
530 return decisions_;
531}

◆ EraseDecision()

void apollo::planning::Obstacle::EraseDecision ( )

在文件 obstacle.cc709 行定义.

709 {
710 lateral_decision_.Clear();
711 longitudinal_decision_.Clear();
712 decider_tags_.clear();
713}

◆ EraseReferenceLineStBoundary()

void apollo::planning::Obstacle::EraseReferenceLineStBoundary ( )

在文件 obstacle.cc724 行定义.

724 {
725 reference_line_st_boundary_ = STBoundary();
726}

◆ EraseStBoundary()

void apollo::planning::Obstacle::EraseStBoundary ( )

在文件 obstacle.cc707 行定义.

707{ path_st_boundary_ = STBoundary(); }

◆ GetBoundingBox()

common::math::Box2d apollo::planning::Obstacle::GetBoundingBox ( const common::TrajectoryPoint point) const

在文件 obstacle.cc159 行定义.

160 {
161 return common::math::Box2d({point.path_point().x(), point.path_point().y()},
162 point.path_point().theta(),
163 perception_obstacle_.length(),
164 perception_obstacle_.width());
165}

◆ GetObstacleTrajectoryPolygon()

common::math::Polygon2d apollo::planning::Obstacle::GetObstacleTrajectoryPolygon ( const common::TrajectoryPoint point) const

在文件 obstacle.cc773 行定义.

774 {
775 double delta_heading =
776 point.path_point().theta() - perception_obstacle_.theta();
777 double cos_delta_heading = cos(delta_heading);
778 double sin_delta_heading = sin(delta_heading);
779 std::vector<common::math::Vec2d> polygon_point;
780 polygon_point.reserve(perception_polygon_.points().size());
781
782 for (auto& iter : perception_polygon_.points()) {
783 double relative_x = iter.x() - perception_obstacle_.position().x();
784 double relative_y = iter.y() - perception_obstacle_.position().y();
785 double x = relative_x * cos_delta_heading - relative_y * sin_delta_heading +
786 point.path_point().x();
787 double y = relative_x * sin_delta_heading + relative_y * cos_delta_heading +
788 point.path_point().y();
789 polygon_point.emplace_back(x, y);
790 }
791
792 common::math::Polygon2d trajectory_point_polygon(polygon_point);
793 return trajectory_point_polygon;
794}
const std::vector< Vec2d > & points() const
Get the vertices of the polygon.
Definition polygon2d.h:65
float cos(Angle16 a)
Definition angle.cc:42
float sin(Angle16 a)
Definition angle.cc:25

◆ GetPointAtTime()

common::TrajectoryPoint apollo::planning::Obstacle::GetPointAtTime ( const double  time) const

在文件 obstacle.cc124 行定义.

125 {
126 const auto& points = trajectory_.trajectory_point();
127 if (points.size() < 2) {
128 common::TrajectoryPoint point;
129 point.mutable_path_point()->set_x(perception_obstacle_.position().x());
130 point.mutable_path_point()->set_y(perception_obstacle_.position().y());
131 point.mutable_path_point()->set_z(perception_obstacle_.position().z());
132 point.mutable_path_point()->set_theta(perception_obstacle_.theta());
133 point.mutable_path_point()->set_s(0.0);
134 point.mutable_path_point()->set_kappa(0.0);
135 point.mutable_path_point()->set_dkappa(0.0);
136 point.mutable_path_point()->set_ddkappa(0.0);
137 point.set_v(0.0);
138 point.set_a(0.0);
139 point.set_relative_time(0.0);
140 return point;
141 } else {
142 auto comp = [](const common::TrajectoryPoint p, const double time) {
143 return p.relative_time() < time;
144 };
145
146 auto it_lower =
147 std::lower_bound(points.begin(), points.end(), relative_time, comp);
148
149 if (it_lower == points.begin()) {
150 return *points.begin();
151 } else if (it_lower == points.end()) {
152 return *points.rbegin();
153 }
155 *(it_lower - 1), *it_lower, relative_time);
156 }
157}
SLPoint InterpolateUsingLinearApproximation(const SLPoint &p0, const SLPoint &p1, const double w)

◆ HasLateralDecision()

bool apollo::planning::Obstacle::HasLateralDecision ( ) const

在文件 obstacle.cc631 行定义.

631 {
632 return lateral_decision_.object_tag_case() !=
633 ObjectDecisionType::OBJECT_TAG_NOT_SET;
634}

◆ HasLongitudinalDecision()

bool apollo::planning::Obstacle::HasLongitudinalDecision ( ) const

在文件 obstacle.cc636 行定义.

636 {
637 return longitudinal_decision_.object_tag_case() !=
638 ObjectDecisionType::OBJECT_TAG_NOT_SET;
639}

◆ HasNonIgnoreDecision()

bool apollo::planning::Obstacle::HasNonIgnoreDecision ( ) const

在文件 obstacle.cc641 行定义.

641 {
642 return (HasLateralDecision() && !IsLateralIgnore()) ||
644}
bool IsLongitudinalIgnore() const
Definition obstacle.cc:589
bool HasLongitudinalDecision() const
Definition obstacle.cc:636
bool IsLateralIgnore() const
Definition obstacle.cc:593
bool HasLateralDecision() const
Definition obstacle.cc:631

◆ HasTrajectory()

bool apollo::planning::Obstacle::HasTrajectory ( ) const
inline

在文件 obstacle.h98 行定义.

98 {
99 return !(trajectory_.trajectory_point().empty());
100 }

◆ Id()

const std::string & apollo::planning::Obstacle::Id ( ) const
inline

在文件 obstacle.h75 行定义.

75{ return id_; }

◆ is_path_st_boundary_initialized()

bool apollo::planning::Obstacle::is_path_st_boundary_initialized ( )
inline

在文件 obstacle.h165 行定义.

165 {
166 return path_st_boundary_initialized_;
167 }

◆ IsBlockingObstacle()

bool apollo::planning::Obstacle::IsBlockingObstacle ( ) const
inline

在文件 obstacle.h217 行定义.

217{ return is_blocking_obstacle_; }

◆ IsCautionLevelObstacle()

bool apollo::planning::Obstacle::IsCautionLevelObstacle ( ) const
inline

在文件 obstacle.h124 行定义.

124 {
125 return is_caution_level_obstacle_;
126 }

◆ IsIgnore()

bool apollo::planning::Obstacle::IsIgnore ( ) const

Check if this object can be safely ignored.

The object will be ignored if the lateral decision is ignore and the longitudinal decision is ignore return longitudinal_decision_ == ignore && lateral_decision == ignore.

在文件 obstacle.cc585 行定义.

585 {
587}

◆ IsLaneBlocking()

bool apollo::planning::Obstacle::IsLaneBlocking ( ) const
inline

在文件 obstacle.h222 行定义.

222{ return is_lane_blocking_; }

◆ IsLaneChangeBlocking()

bool apollo::planning::Obstacle::IsLaneChangeBlocking ( ) const
inline

在文件 obstacle.h224 行定义.

224{ return is_lane_change_blocking_; }

◆ IsLateralDecision()

bool apollo::planning::Obstacle::IsLateralDecision ( const ObjectDecisionType &  decision)
static

check if an ObjectDecisionType is a lateral decision.

在文件 obstacle.cc533 行定义.

533 {
534 return decision.has_ignore() || decision.has_nudge();
535}

◆ IsLateralIgnore()

bool apollo::planning::Obstacle::IsLateralIgnore ( ) const

在文件 obstacle.cc593 行定义.

593 {
594 return lateral_decision_.has_ignore();
595}

◆ IsLongitudinalDecision()

bool apollo::planning::Obstacle::IsLongitudinalDecision ( const ObjectDecisionType &  decision)
static

check if an ObjectDecisionType is a longitudinal decision.

在文件 obstacle.cc537 行定义.

537 {
538 return decision.has_ignore() || decision.has_stop() || decision.has_yield() ||
539 decision.has_follow() || decision.has_overtake();
540}

◆ IsLongitudinalIgnore()

bool apollo::planning::Obstacle::IsLongitudinalIgnore ( ) const

在文件 obstacle.cc589 行定义.

589 {
590 return longitudinal_decision_.has_ignore();
591}

◆ IsStatic()

bool apollo::planning::Obstacle::IsStatic ( ) const
inline

在文件 obstacle.h82 行定义.

82{ return is_static_; }

◆ IsValidPerceptionObstacle()

bool apollo::planning::Obstacle::IsValidPerceptionObstacle ( const perception::PerceptionObstacle obstacle)
static

在文件 obstacle.cc167 行定义.

167 {
168 if (obstacle.length() <= 0.0) {
169 AERROR << "invalid obstacle length:" << obstacle.length();
170 return false;
171 }
172 if (obstacle.width() <= 0.0) {
173 AERROR << "invalid obstacle width:" << obstacle.width();
174 return false;
175 }
176 if (obstacle.height() <= 0.0) {
177 AERROR << "invalid obstacle height:" << obstacle.height();
178 return false;
179 }
180 if (obstacle.has_velocity()) {
181 if (std::isnan(obstacle.velocity().x()) ||
182 std::isnan(obstacle.velocity().y())) {
183 AERROR << "invalid obstacle velocity:"
184 << obstacle.velocity().DebugString();
185 return false;
186 }
187 }
188 for (auto pt : obstacle.polygon_point()) {
189 if (std::isnan(pt.x()) || std::isnan(pt.y())) {
190 AERROR << "invalid obstacle polygon point:" << pt.DebugString();
191 return false;
192 }
193 }
194 return true;
195}

◆ IsValidTrajectoryPoint()

bool apollo::planning::Obstacle::IsValidTrajectoryPoint ( const common::TrajectoryPoint point)
static

在文件 obstacle.cc278 行定义.

278 {
279 return !((!point.has_path_point()) || std::isnan(point.path_point().x()) ||
280 std::isnan(point.path_point().y()) ||
281 std::isnan(point.path_point().z()) ||
282 std::isnan(point.path_point().kappa()) ||
283 std::isnan(point.path_point().s()) ||
284 std::isnan(point.path_point().dkappa()) ||
285 std::isnan(point.path_point().ddkappa()) || std::isnan(point.v()) ||
286 std::isnan(point.a()) || std::isnan(point.relative_time()));
287}

◆ IsVirtual()

bool apollo::planning::Obstacle::IsVirtual ( ) const
inline

在文件 obstacle.h83 行定义.

83{ return is_virtual_; }

◆ LateralDecision()

const ObjectDecisionType & apollo::planning::Obstacle::LateralDecision ( ) const

return the merged lateral decision Lateral decision is one of {Nudge, Ignore}

在文件 obstacle.cc581 行定义.

581 {
582 return lateral_decision_;
583}

◆ LongitudinalDecision()

const ObjectDecisionType & apollo::planning::Obstacle::LongitudinalDecision ( ) const

return the merged longitudinal decision Longitudinal decision is one of {Stop, Yield, Follow, Overtake, Ignore}

在文件 obstacle.cc577 行定义.

577 {
578 return longitudinal_decision_;
579}

◆ MinRadiusStopDistance()

double apollo::planning::Obstacle::MinRadiusStopDistance ( const common::VehicleParam vehicle_param) const

Calculate stop distance with the obstacle using the ADC's minimum turning radius

在文件 obstacle.cc293 行定义.

294 {
295 if (min_radius_stop_distance_ > 0) {
296 return min_radius_stop_distance_;
297 }
298 static constexpr double stop_distance_buffer = 0.5;
299 const double min_turn_radius = VehicleConfigHelper::MinSafeTurnRadius();
300 double lateral_diff =
301 vehicle_param.width() / 2.0 + std::max(std::fabs(sl_boundary_.start_l()),
302 std::fabs(sl_boundary_.end_l()));
303 const double kEpison = 1e-5;
304 lateral_diff = std::min(lateral_diff, min_turn_radius - kEpison);
305 double stop_distance =
306 std::sqrt(std::fabs(min_turn_radius * min_turn_radius -
307 (min_turn_radius - lateral_diff) *
308 (min_turn_radius - lateral_diff))) +
309 stop_distance_buffer;
310 stop_distance -= vehicle_param.front_edge_to_center();
311 stop_distance = std::min(stop_distance, FLAGS_max_stop_distance_obstacle);
312 stop_distance = std::max(stop_distance, FLAGS_min_stop_distance_obstacle);
313 return stop_distance;
314}
static double MinSafeTurnRadius()
Get the safe turning radius when the vehicle is turning with maximum steering angle.

◆ path_st_boundary()

const STBoundary & apollo::planning::Obstacle::path_st_boundary ( ) const

在文件 obstacle.cc521 行定义.

521 {
522 return path_st_boundary_;
523}

◆ Perception()

const perception::PerceptionObstacle & apollo::planning::Obstacle::Perception ( ) const
inline

在文件 obstacle.h102 行定义.

102 {
103 return perception_obstacle_;
104 }

◆ PerceptionBoundingBox()

const common::math::Box2d & apollo::planning::Obstacle::PerceptionBoundingBox ( ) const
inline

在文件 obstacle.h90 行定义.

90 {
91 return perception_bounding_box_;
92 }

◆ PerceptionId()

int32_t apollo::planning::Obstacle::PerceptionId ( ) const
inline

在文件 obstacle.h80 行定义.

80{ return perception_id_; }

◆ PerceptionPolygon()

const common::math::Polygon2d & apollo::planning::Obstacle::PerceptionPolygon ( ) const
inline

在文件 obstacle.h93 行定义.

93 {
94 return perception_polygon_;
95 }

◆ PerceptionSLBoundary()

const SLBoundary & apollo::planning::Obstacle::PerceptionSLBoundary ( ) const

在文件 obstacle.cc694 行定义.

694 {
695 return sl_boundary_;
696}

◆ PrintPolygonCurve()

void apollo::planning::Obstacle::PrintPolygonCurve ( ) const

在文件 obstacle.cc796 行定义.

796 {
797 if (perception_polygon_.points().size() < 1) {
798 return;
799 }
800
801 PrintCurves print_curve;
802 for (const auto& p : perception_polygon_.points()) {
803 print_curve.AddPoint(id_ + "_ObsPolygon", p.x(), p.y());
804 }
805 print_curve.AddPoint(id_ + "_ObsPolygon", perception_polygon_.points()[0].x(),
806 perception_polygon_.points()[0].y());
807 print_curve.PrintToLog();
808}

◆ reference_line_st_boundary()

const STBoundary & apollo::planning::Obstacle::reference_line_st_boundary ( ) const

在文件 obstacle.cc517 行定义.

517 {
518 return reference_line_st_boundary_;
519}

◆ set_path_st_boundary()

void apollo::planning::Obstacle::set_path_st_boundary ( const STBoundary boundary)

在文件 obstacle.cc698 行定义.

698 {
699 path_st_boundary_ = boundary;
700 path_st_boundary_initialized_ = true;
701}

◆ SetBlockingObstacle()

void apollo::planning::Obstacle::SetBlockingObstacle ( bool  blocking)
inline

在文件 obstacle.h216 行定义.

216{ is_blocking_obstacle_ = blocking; }

◆ SetId()

void apollo::planning::Obstacle::SetId ( const std::string &  id)
inline

在文件 obstacle.h76 行定义.

76{ id_ = id; }

◆ SetLaneChangeBlocking()

void apollo::planning::Obstacle::SetLaneChangeBlocking ( const bool  is_distance_clear)

在文件 obstacle.cc767 行定义.

767 {
768 is_lane_change_blocking_ = is_distance_clear;
769}

◆ SetPerceptionSlBoundary()

void apollo::planning::Obstacle::SetPerceptionSlBoundary ( const SLBoundary sl_boundary)

在文件 obstacle.cc289 行定义.

289 {
290 sl_boundary_ = sl_boundary;
291}

◆ SetReferenceLineStBoundary()

void apollo::planning::Obstacle::SetReferenceLineStBoundary ( const STBoundary boundary)

在文件 obstacle.cc715 行定义.

715 {
716 reference_line_st_boundary_ = boundary;
717}

◆ SetReferenceLineStBoundaryType()

void apollo::planning::Obstacle::SetReferenceLineStBoundaryType ( const STBoundary::BoundaryType  type)

在文件 obstacle.cc719 行定义.

720 {
721 reference_line_st_boundary_.SetBoundaryType(type);
722}
void SetBoundaryType(const BoundaryType &boundary_type)

◆ SetStBoundaryType()

void apollo::planning::Obstacle::SetStBoundaryType ( const STBoundary::BoundaryType  type)

在文件 obstacle.cc703 行定义.

703 {
704 path_st_boundary_.SetBoundaryType(type);
705}

◆ speed()

double apollo::planning::Obstacle::speed ( ) const
inline

在文件 obstacle.h78 行定义.

78{ return speed_; }

◆ Trajectory()

const prediction::Trajectory & apollo::planning::Obstacle::Trajectory ( ) const
inline

在文件 obstacle.h96 行定义.

96{ return trajectory_; }

该类的文档由以下文件生成: