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

#include <semantic_map.h>

apollo::prediction::SemanticMap 的协作图:

Public 成员函数

 SemanticMap ()
 
virtual ~SemanticMap ()=default
 
void Init ()
 
void RunCurrFrame (const std::unordered_map< int, ObstacleHistory > &obstacle_id_history_map)
 
bool GetMapById (const int obstacle_id, cv::Mat *feature_map)
 

详细描述

在文件 semantic_map.h34 行定义.

构造及析构函数说明

◆ SemanticMap()

apollo::prediction::SemanticMap::SemanticMap ( )

在文件 semantic_map.cc57 行定义.

57{}

◆ ~SemanticMap()

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

成员函数说明

◆ GetMapById()

bool apollo::prediction::SemanticMap::GetMapById ( const int  obstacle_id,
cv::Mat *  feature_map 
)

在文件 semantic_map.cc396 行定义.

396 {
397 if (obstacle_id_history_map_.find(obstacle_id) ==
398 obstacle_id_history_map_.end()) {
399 return false;
400 }
401 const auto& obstacle_history = obstacle_id_history_map_[obstacle_id];
402
403 if (!ValidFeatureHistory(obstacle_history, curr_base_x_, curr_base_y_)) {
404 return false;
405 }
406
407 cv::Mat output_img =
408 CropByHistory(obstacle_id_history_map_[obstacle_id],
409 cv::Scalar(0, 0, 255), curr_base_x_, curr_base_y_);
410 output_img.copyTo(*feature_map);
411 return true;
412}

◆ Init()

void apollo::prediction::SemanticMap::Init ( )

在文件 semantic_map.cc59 行定义.

59 {
60 curr_img_ = cv::Mat(2000, 2000, CV_8UC3, cv::Scalar(0, 0, 0));
61 obstacle_id_history_map_.clear();
62#ifdef __aarch64__
63 affine_transformer_.Init(cv::Size(2000, 2000), CV_8UC3);
64#endif
65}

◆ RunCurrFrame()

void apollo::prediction::SemanticMap::RunCurrFrame ( const std::unordered_map< int, ObstacleHistory > &  obstacle_id_history_map)

在文件 semantic_map.cc67 行定义.

68 {
69 if (obstacle_id_history_map.find(FLAGS_ego_vehicle_id) ==
70 obstacle_id_history_map.end()) {
71 return;
72 }
73
74 ego_feature_ = obstacle_id_history_map.at(FLAGS_ego_vehicle_id).feature(0);
75 if (!FLAGS_enable_async_draw_base_image) {
76 double x = ego_feature_.position().x();
77 double y = ego_feature_.position().y();
78 curr_base_x_ = x - FLAGS_base_image_half_range;
79 curr_base_y_ = y - FLAGS_base_image_half_range;
80 DrawBaseMap(x, y, curr_base_x_, curr_base_y_);
81 base_img_.copyTo(curr_img_);
82 } else {
83 base_img_.copyTo(curr_img_);
84 curr_base_x_ = base_x_;
85 curr_base_y_ = base_y_;
86 task_future_ = cyber::Async(&SemanticMap::DrawBaseMapThread, this);
87 // This is only for the first frame without base image yet
88 if (!started_drawing_) {
89 started_drawing_ = true;
90 return;
91 }
92 }
93
94 // Draw ADC trajectory
95 if (FLAGS_enable_draw_adc_trajectory) {
96 DrawADCTrajectory(cv::Scalar(0, 255, 255),
97 curr_base_x_, curr_base_y_, &curr_img_);
98 }
99
100 // Draw all obstacles_history
101 for (const auto obstacle_id_history_pair : obstacle_id_history_map) {
102 DrawHistory(obstacle_id_history_pair.second, cv::Scalar(0, 255, 255),
103 curr_base_x_, curr_base_y_, &curr_img_);
104 }
105
106 obstacle_id_history_map_ = obstacle_id_history_map;
107
108 // Crop ego_vehicle for demo
109 if (FLAGS_img_show_semantic_map) {
110 cv::Mat output_img;
111 if (GetMapById(FLAGS_ego_vehicle_id, &output_img)) {
112 cv::namedWindow("Demo window", cv::WINDOW_NORMAL);
113 cv::imshow("Demo window", output_img);
114 cv::waitKey();
115 }
116 }
117}
bool GetMapById(const int obstacle_id, cv::Mat *feature_map)
optional apollo::common::Point3D position
Definition feature.proto:88

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