Apollo 10.0
自动驾驶开放平台
apollo::prediction::ObstaclesContainer类 参考

#include <obstacles_container.h>

类 apollo::prediction::ObstaclesContainer 继承关系图:
apollo::prediction::ObstaclesContainer 的协作图:

Public 成员函数

 ObstaclesContainer ()
 Constructor
 
 ObstaclesContainer (const SubmoduleOutput &submodule_output)
 Constructor from container output
 
virtual ~ObstaclesContainer ()=default
 Destructor
 
void Insert (const ::google::protobuf::Message &message) override
 Insert a data message into the container
 
void InsertPerceptionObstacle (const perception::PerceptionObstacle &perception_obstacle, const double timestamp)
 Insert an perception obstacle
 
void InsertFeatureProto (const Feature &feature)
 Insert a feature proto message into the container
 
void BuildLaneGraph ()
 Build lane graph for obstacles
 
void BuildJunctionFeature ()
 Build junction feature for obstacles
 
ObstacleGetObstacle (const int id)
 Get obstacle pointer
 
void Clear ()
 Clear obstacle container
 
void CleanUp ()
 
size_t NumOfObstacles ()
 
const apollo::perception::PerceptionObstacleGetPerceptionObstacle (const int id)
 
const std::vector< int > & curr_frame_movable_obstacle_ids ()
 Get movable obstacle IDs in the current frame
 
const std::vector< int > & curr_frame_unmovable_obstacle_ids ()
 Get unmovable obstacle IDs in the current frame
 
const std::vector< int > & curr_frame_considered_obstacle_ids ()
 Get non-ignore obstacle IDs in the current frame
 
void SetConsideredObstacleIds ()
 
std::vector< int > curr_frame_obstacle_ids ()
 Get current frame obstacle IDs in the current frame
 
double timestamp () const
 
SubmoduleOutput GetSubmoduleOutput (const size_t history_size, const apollo::cyber::Time &frame_start_time)
 
const Scenariocurr_scenario () const
 Get current scenario
 
ObstacleClustersGetClustersPtr () const
 Get the raw pointer of clusters_
 
JunctionAnalyzerGetJunctionAnalyzer ()
 
- Public 成员函数 继承自 apollo::prediction::Container
 Container ()=default
 Constructor
 
virtual ~Container ()=default
 Destructor
 

详细描述

在文件 obstacles_container.h39 行定义.

构造及析构函数说明

◆ ObstaclesContainer() [1/2]

apollo::prediction::ObstaclesContainer::ObstaclesContainer ( )

Constructor

在文件 obstacles_container.cc35 行定义.

36 : ptr_obstacles_(FLAGS_max_num_obstacles),
37 clusters_(new ObstacleClusters()) {}

◆ ObstaclesContainer() [2/2]

apollo::prediction::ObstaclesContainer::ObstaclesContainer ( const SubmoduleOutput submodule_output)
explicit

Constructor from container output

在文件 obstacles_container.cc39 行定义.

40 : ptr_obstacles_(FLAGS_max_num_obstacles),
41 clusters_(new ObstacleClusters()) {
42 for (const Obstacle& obstacle : submodule_output.curr_frame_obstacles()) {
43 // Deep copy of obstacle is needed for modification
44 std::unique_ptr<Obstacle> ptr_obstacle(new Obstacle(obstacle));
45 ptr_obstacle->SetJunctionAnalyzer(&junction_analyzer_);
46 ptr_obstacles_.Put(obstacle.id(), std::move(ptr_obstacle));
47 }
48
49 Obstacle ego_vehicle = submodule_output.GetEgoVehicle();
50 std::unique_ptr<Obstacle> ptr_ego_vehicle(
51 new Obstacle(std::move(ego_vehicle)));
52 ptr_ego_vehicle->SetJunctionAnalyzer(&junction_analyzer_);
53 ptr_obstacles_.Put(ego_vehicle.id(), std::move(ptr_ego_vehicle));
54
55 curr_frame_movable_obstacle_ids_ =
56 submodule_output.curr_frame_movable_obstacle_ids();
57 curr_frame_unmovable_obstacle_ids_ =
58 submodule_output.curr_frame_unmovable_obstacle_ids();
59 curr_frame_considered_obstacle_ids_ =
60 submodule_output.curr_frame_considered_obstacle_ids();
61 curr_scenario_ = submodule_output.curr_scenario();
62}

◆ ~ObstaclesContainer()

virtual apollo::prediction::ObstaclesContainer::~ObstaclesContainer ( )
virtualdefault

Destructor

成员函数说明

◆ BuildJunctionFeature()

void apollo::prediction::ObstaclesContainer::BuildJunctionFeature ( )

Build junction feature for obstacles

在文件 obstacles_container.cc312 行定义.

312 {
313 // Go through every obstacle in the current frame, after some
314 // sanity checks, build junction features for those that are in junction.
315 for (const int id : curr_frame_considered_obstacle_ids_) {
316 Obstacle* obstacle_ptr = GetObstacle(id);
317 if (obstacle_ptr == nullptr) {
318 AERROR << "Null obstacle found.";
319 continue;
320 }
321 const std::string& junction_id = junction_analyzer_.GetJunctionId();
322 if (obstacle_ptr->IsInJunction(junction_id)) {
323 AINFO << "Build junction feature for obstacle [" << obstacle_ptr->id()
324 << "] in junction [" << junction_id << "]";
325 obstacle_ptr->BuildJunctionFeature();
326 }
327 }
328}
const std::string & GetJunctionId()
Get junction ID
Obstacle * GetObstacle(const int id)
Get obstacle pointer
#define AERROR
Definition log.h:44
#define AINFO
Definition log.h:42

◆ BuildLaneGraph()

void apollo::prediction::ObstaclesContainer::BuildLaneGraph ( )

Build lane graph for obstacles

在文件 obstacles_container.cc281 行定义.

281 {
282 // Go through every obstacle in the current frame, after some
283 // sanity checks, build lane graph for non-junction cases.
284 for (const int id : curr_frame_considered_obstacle_ids_) {
285 Obstacle* obstacle_ptr = GetObstacle(id);
286 if (obstacle_ptr == nullptr) {
287 AERROR << "Null obstacle found.";
288 continue;
289 }
290 if (FLAGS_prediction_offline_mode !=
292 ADEBUG << "Building Lane Graph.";
293 obstacle_ptr->BuildLaneGraph();
294 obstacle_ptr->BuildLaneGraphFromLeftToRight();
295 } else {
296 ADEBUG << "Building ordered Lane Graph.";
297 ADEBUG << "Building lane graph for id = " << id;
298 obstacle_ptr->BuildLaneGraphFromLeftToRight();
299 }
300 obstacle_ptr->SetNearbyObstacles();
301 }
302
303 Obstacle* ego_vehicle_ptr = GetObstacle(FLAGS_ego_vehicle_id);
304 if (ego_vehicle_ptr == nullptr) {
305 AERROR << "Ego vehicle not inserted";
306 return;
307 }
308 ego_vehicle_ptr->BuildLaneGraph();
309 ego_vehicle_ptr->SetNearbyObstacles();
310}
#define ADEBUG
Definition log.h:41

◆ CleanUp()

void apollo::prediction::ObstaclesContainer::CleanUp ( )

在文件 obstacles_container.cc64 行定义.

64 {
65 // Clean up the history and get the PerceptionObstacles
66 curr_frame_movable_obstacle_ids_.clear();
67 curr_frame_unmovable_obstacle_ids_.clear();
68 curr_frame_considered_obstacle_ids_.clear();
69}

◆ Clear()

void apollo::prediction::ObstaclesContainer::Clear ( )

Clear obstacle container

在文件 obstacles_container.cc177 行定义.

177 {
178 ptr_obstacles_.Clear();
179 timestamp_ = -1.0;
180}

◆ curr_frame_considered_obstacle_ids()

const std::vector< int > & apollo::prediction::ObstaclesContainer::curr_frame_considered_obstacle_ids ( )

Get non-ignore obstacle IDs in the current frame

返回
Non-ignore obstacle IDs in the current frame

在文件 obstacles_container.cc192 行定义.

192 {
193 return curr_frame_considered_obstacle_ids_;
194}

◆ curr_frame_movable_obstacle_ids()

const std::vector< int > & apollo::prediction::ObstaclesContainer::curr_frame_movable_obstacle_ids ( )

Get movable obstacle IDs in the current frame

返回
Movable obstacle IDs in the current frame

在文件 obstacles_container.cc182 行定义.

182 {
183 return curr_frame_movable_obstacle_ids_;
184}

◆ curr_frame_obstacle_ids()

std::vector< int > apollo::prediction::ObstaclesContainer::curr_frame_obstacle_ids ( )

Get current frame obstacle IDs in the current frame

返回
Current frame obstacle IDs in the current frame

在文件 obstacles_container.cc212 行定义.

212 {
213 std::vector<int> curr_frame_obs_ids = curr_frame_movable_obstacle_ids_;
214 curr_frame_obs_ids.insert(curr_frame_obs_ids.end(),
215 curr_frame_unmovable_obstacle_ids_.begin(),
216 curr_frame_unmovable_obstacle_ids_.end());
217 return curr_frame_obs_ids;
218}

◆ curr_frame_unmovable_obstacle_ids()

const std::vector< int > & apollo::prediction::ObstaclesContainer::curr_frame_unmovable_obstacle_ids ( )

Get unmovable obstacle IDs in the current frame

返回
unmovable obstacle IDs in the current frame

在文件 obstacles_container.cc187 行定义.

187 {
188 return curr_frame_unmovable_obstacle_ids_;
189}

◆ curr_scenario()

const Scenario & apollo::prediction::ObstaclesContainer::curr_scenario ( ) const

Get current scenario

在文件 obstacles_container.cc371 行定义.

371 {
372 return curr_scenario_;
373}

◆ GetClustersPtr()

ObstacleClusters * apollo::prediction::ObstaclesContainer::GetClustersPtr ( ) const

Get the raw pointer of clusters_

在文件 obstacles_container.cc375 行定义.

375 {
376 return clusters_.get();
377}

◆ GetJunctionAnalyzer()

JunctionAnalyzer * apollo::prediction::ObstaclesContainer::GetJunctionAnalyzer ( )

在文件 obstacles_container.cc378 行定义.

378 {
379 return &junction_analyzer_;
380}

◆ GetObstacle()

Obstacle * apollo::prediction::ObstaclesContainer::GetObstacle ( const int  id)

Get obstacle pointer

参数
ObstacleID
返回
Obstacle pointer

在文件 obstacles_container.cc161 行定义.

161 {
162 auto ptr_obstacle = ptr_obstacles_.GetSilently(id);
163 if (ptr_obstacle != nullptr) {
164 return ptr_obstacle->get();
165 }
166 return nullptr;
167}

◆ GetPerceptionObstacle()

const apollo::perception::PerceptionObstacle & apollo::prediction::ObstaclesContainer::GetPerceptionObstacle ( const int  id)

◆ GetSubmoduleOutput()

SubmoduleOutput apollo::prediction::ObstaclesContainer::GetSubmoduleOutput ( const size_t  history_size,
const apollo::cyber::Time frame_start_time 
)

在文件 obstacles_container.cc341 行定义.

342 {
343 SubmoduleOutput container_output;
344 for (int id : curr_frame_considered_obstacle_ids_) {
345 Obstacle* obstacle = GetObstacle(id);
346 if (obstacle == nullptr) {
347 AERROR << "Nullptr found for obstacle [" << id << "]";
348 continue;
349 }
350 obstacle->TrimHistory(history_size);
351 obstacle->ClearOldInformation();
352 container_output.InsertObstacle(std::move(*obstacle));
353 }
354
355 Obstacle* ego_obstacle = GetObstacle(FLAGS_ego_vehicle_id);
356 if (ego_obstacle != nullptr) {
357 container_output.InsertEgoVehicle(std::move(*ego_obstacle));
358 }
359
360 container_output.set_curr_frame_movable_obstacle_ids(
361 curr_frame_movable_obstacle_ids_);
362 container_output.set_curr_frame_unmovable_obstacle_ids(
363 curr_frame_unmovable_obstacle_ids_);
364 container_output.set_curr_frame_considered_obstacle_ids(
365 curr_frame_considered_obstacle_ids_);
366 container_output.set_frame_start_time(frame_start_time);
367
368 return container_output;
369}

◆ Insert()

void apollo::prediction::ObstaclesContainer::Insert ( const ::google::protobuf::Message &  message)
overridevirtual

Insert a data message into the container

参数
Datamessage to be inserted in protobuf

实现了 apollo::prediction::Container.

在文件 obstacles_container.cc73 行定义.

73 {
74 PerceptionObstacles perception_obstacles;
75 perception_obstacles.CopyFrom(
76 dynamic_cast<const PerceptionObstacles&>(message));
77
78 // Get the new timestamp and update it in the class
79 // - If it's more than 10sec later than the most recent one, clear the
80 // obstacle history.
81 // - If it's not a valid time (earlier than history), continue.
82 // - Also consider the offline_mode case.
83 double timestamp = 0.0;
84 if (perception_obstacles.has_header() &&
85 perception_obstacles.header().has_timestamp_sec()) {
86 timestamp = perception_obstacles.header().timestamp_sec();
87 }
88 if (std::fabs(timestamp - timestamp_) > FLAGS_replay_timestamp_gap) {
89 ptr_obstacles_.Clear();
90 ADEBUG << "Replay mode is enabled.";
91 } else if (timestamp <= timestamp_) {
92 AERROR << "Invalid timestamp curr [" << timestamp << "] v.s. prev ["
93 << timestamp_ << "].";
94 return;
95 }
96
97 switch (FLAGS_prediction_offline_mode) {
98 case 1: {
99 if (std::fabs(timestamp - timestamp_) > FLAGS_replay_timestamp_gap ||
100 FeatureOutput::Size() > FLAGS_max_num_dump_feature) {
102 }
103 break;
104 }
105 case 2: {
106 if (std::fabs(timestamp - timestamp_) > FLAGS_replay_timestamp_gap ||
108 FLAGS_max_num_dump_dataforlearn) {
110 }
111 break;
112 }
113 case 3: {
114 if (std::fabs(timestamp - timestamp_) > FLAGS_replay_timestamp_gap ||
116 FLAGS_max_num_dump_feature) {
118 }
119 break;
120 }
121 case 4: {
122 if (std::fabs(timestamp - timestamp_) > FLAGS_replay_timestamp_gap ||
123 FeatureOutput::SizeOfFrameEnv() > FLAGS_max_num_dump_feature) {
125 }
126 break;
127 }
128 case 5: {
129 if (std::fabs(timestamp - timestamp_) > FLAGS_replay_timestamp_gap ||
130 FeatureOutput::SizeOfFrameEnv() > FLAGS_max_num_dump_feature) {
132 }
133 break;
134 }
135 default: {
136 // No data dump
138 break;
139 }
140 }
141
142 timestamp_ = timestamp;
143 ADEBUG << "Current timestamp is [" << std::fixed << std::setprecision(6)
144 << timestamp_ << "]";
145
146 // Set up the ObstacleClusters:
147 // Insert the Obstacles one by one
148 for (const PerceptionObstacle& perception_obstacle :
149 perception_obstacles.perception_obstacle()) {
150 ADEBUG << "Perception obstacle [" << perception_obstacle.id() << "] "
151 << "was detected";
152 InsertPerceptionObstacle(perception_obstacle, timestamp_);
153 ADEBUG << "Perception obstacle [" << perception_obstacle.id() << "] "
154 << "was inserted";
155 }
156
158 clusters_->SortObstacles();
159}
static void WriteDataForLearning()
Write DataForLearning features to a file
static int SizeOfPredictionResult()
Get the size of prediction results.
static int Size()
Get feature size
static int SizeOfFrameEnv()
Get the size of frame env.
static void WriteDataForTuning()
Write DataForTuning features to a file
static int SizeOfDataForLearning()
Get the size of data_for_learning features.
static void WriteFrameEnv()
Write frame env to a file
static void WriteFeatureProto()
Write features to a file
static void WritePredictionResult()
Write PredictionResult to a file
void InsertPerceptionObstacle(const perception::PerceptionObstacle &perception_obstacle, const double timestamp)
Insert an perception obstacle

◆ InsertFeatureProto()

void apollo::prediction::ObstaclesContainer::InsertFeatureProto ( const Feature feature)

Insert a feature proto message into the container

参数
featureproto message

在文件 obstacles_container.cc261 行定义.

261 {
262 if (!feature.has_id()) {
263 AERROR << "Invalid feature, no ID found.";
264 return;
265 }
266 int id = feature.id();
267 auto obstacle_ptr = GetObstacleWithLRUUpdate(id);
268 if (obstacle_ptr != nullptr) {
269 obstacle_ptr->InsertFeature(feature);
270 } else {
271 auto ptr_obstacle = Obstacle::Create(feature, clusters_.get());
272 if (ptr_obstacle == nullptr) {
273 AERROR << "Failed to insert obstacle into container";
274 return;
275 }
276 ptr_obstacle->SetJunctionAnalyzer(&junction_analyzer_);
277 ptr_obstacles_.Put(id, std::move(ptr_obstacle));
278 }
279}
static std::unique_ptr< Obstacle > Create(const perception::PerceptionObstacle &perception_obstacle, const double timestamp, const int prediction_id, ObstacleClusters *clusters_ptr)
Constructor
Definition obstacle.cc:1406

◆ InsertPerceptionObstacle()

void apollo::prediction::ObstaclesContainer::InsertPerceptionObstacle ( const perception::PerceptionObstacle perception_obstacle,
const double  timestamp 
)

Insert an perception obstacle

参数
Perceptionobstacle Timestamp

在文件 obstacles_container.cc220 行定义.

221 {
222 // Sanity checks.
223 int id = perception_obstacle.id();
224 if (id < FLAGS_ego_vehicle_id) {
225 AERROR << "Invalid ID [" << id << "]";
226 return;
227 }
228 if (!IsMovable(perception_obstacle)) {
229 ADEBUG << "Perception obstacle [" << perception_obstacle.id()
230 << "] is unmovable.";
231 curr_frame_unmovable_obstacle_ids_.push_back(id);
232 return;
233 }
234
235 // Insert the obstacle and also update the LRUCache.
236 auto obstacle_ptr = GetObstacleWithLRUUpdate(id);
237 if (obstacle_ptr != nullptr) {
238 ADEBUG << "Current time = " << std::fixed << std::setprecision(6)
239 << timestamp;
240 obstacle_ptr->Insert(perception_obstacle, timestamp, id);
241 ADEBUG << "Refresh obstacle [" << id << "]";
242 } else {
243 auto ptr_obstacle =
244 Obstacle::Create(perception_obstacle, timestamp, id, clusters_.get());
245 if (ptr_obstacle == nullptr) {
246 AERROR << "Failed to insert obstacle into container";
247 return;
248 }
249 ptr_obstacle->SetJunctionAnalyzer(&junction_analyzer_);
250 ptr_obstacles_.Put(id, std::move(ptr_obstacle));
251 ADEBUG << "Insert obstacle [" << id << "]";
252 }
253
254 if (FLAGS_prediction_offline_mode ==
256 id != FLAGS_ego_vehicle_id) {
257 curr_frame_movable_obstacle_ids_.push_back(id);
258 }
259}

◆ NumOfObstacles()

size_t apollo::prediction::ObstaclesContainer::NumOfObstacles ( )
inline

在文件 obstacles_container.h101 行定义.

101{ return ptr_obstacles_.size(); }

◆ SetConsideredObstacleIds()

void apollo::prediction::ObstaclesContainer::SetConsideredObstacleIds ( )

在文件 obstacles_container.cc196 行定义.

196 {
197 curr_frame_considered_obstacle_ids_.clear();
198 for (const int id : curr_frame_movable_obstacle_ids_) {
199 Obstacle* obstacle_ptr = GetObstacle(id);
200 if (obstacle_ptr == nullptr) {
201 AERROR << "Null obstacle found.";
202 continue;
203 }
204 if (obstacle_ptr->ToIgnore()) {
205 ADEBUG << "Ignore obstacle [" << obstacle_ptr->id() << "]";
206 continue;
207 }
208 curr_frame_considered_obstacle_ids_.push_back(id);
209 }
210}

◆ timestamp()

double apollo::prediction::ObstaclesContainer::timestamp ( ) const

在文件 obstacles_container.cc339 行定义.

339{ return timestamp_; }

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