Apollo 10.0
自动驾驶开放平台
apollo::localization::msf::VisualizationEngine类 参考

The engine to draw all elements for visualization. 更多...

#include <visualization_engine.h>

apollo::localization::msf::VisualizationEngine 的协作图:

Public 成员函数

 VisualizationEngine ()
 
 ~VisualizationEngine ()=default
 
bool Init (const std::string &map_folder, const std::string &map_visual_folder, const VisualMapParam &map_param, const unsigned int resolution_id, const int zone_id, const Eigen::Affine3d &extrinsic, const unsigned int loc_info_num=1)
 
void Visualize (::apollo::common::EigenVector< LocalizatonInfo > &&loc_infos, const ::apollo::common::EigenVector3dVec &cloud)
 
void SetAutoPlay (bool auto_play)
 

详细描述

The engine to draw all elements for visualization.

在文件 visualization_engine.h163 行定义.

构造及析构函数说明

◆ VisualizationEngine()

apollo::localization::msf::VisualizationEngine::VisualizationEngine ( )

在文件 visualization_engine.cc82 行定义.

83 : map_image_cache_(20),
84 image_window_(1024, 1024, CV_8UC3, cv::Scalar(0, 0, 0)),
85 big_window_(3072, 3072, CV_8UC3),
86 tips_window_(48, 1024, CV_8UC3, cv::Scalar(0, 0, 0)) {}

◆ ~VisualizationEngine()

apollo::localization::msf::VisualizationEngine::~VisualizationEngine ( )
default

成员函数说明

◆ Init()

bool apollo::localization::msf::VisualizationEngine::Init ( const std::string &  map_folder,
const std::string &  map_visual_folder,
const VisualMapParam map_param,
const unsigned int  resolution_id,
const int  zone_id,
const Eigen::Affine3d &  extrinsic,
const unsigned int  loc_info_num = 1 
)

在文件 visualization_engine.cc88 行定义.

94 {
95 map_folder_ = map_folder;
96 map_visual_folder_ = map_visual_folder;
97 map_param_ = map_param;
98 velodyne_extrinsic_ = extrinsic;
99 loc_info_num_ = loc_info_num;
100 expected_car_loc_id_ = loc_info_num;
101
102 trajectory_groups_.resize(loc_info_num_);
103
104 for (unsigned int i = 0; i < loc_info_num_; i++) {
105 cv::Mat tem_mat = cv::imread(car_img_path[i % 3]);
106 if (tem_mat.empty()) {
107 is_draw_car_ = false;
108 break;
109 }
110 car_img_mats_.push_back(tem_mat);
111 }
112
113 if (resolution_id_ >= map_param_.map_resolutions.size()) {
114 AERROR << "Invalid resolution id.";
115 return false;
116 }
117
118 zone_id_ = zone_id;
119 resolution_id_ = resolution_id;
120
121 cloud_img_ =
122 cv::Mat(cv::Size(map_param_.map_node_size_x, map_param_.map_node_size_y),
123 CV_8UC3);
124 cloud_img_mask_ =
125 cv::Mat(cv::Size(map_param_.map_node_size_x, map_param_.map_node_size_y),
126 CV_8UC1);
127
128 Preprocess(map_folder, map_visual_folder);
129
130 std::string params_file = image_visual_resolution_path_ + "/param.txt";
131 bool success = InitOtherParams(params_file);
132 if (!success) {
133 AERROR << "Init other params failed.";
134 }
135
136 cv::namedWindow(window_name_, cv::WINDOW_NORMAL);
137 cv::resizeWindow(window_name_, 1024, 1024);
138
139 is_init_ = true;
140
141 return true;
142}
#define AERROR
Definition log.h:44
unsigned int map_node_size_y
The map node size in pixels.
std::vector< float > map_resolutions
The pixel resolutions in the map in meters.
unsigned int map_node_size_x
The map node size in pixels.

◆ SetAutoPlay()

void apollo::localization::msf::VisualizationEngine::SetAutoPlay ( bool  auto_play)

在文件 visualization_engine.cc176 行定义.

176 {
177 auto_play_ = auto_play;
178}

◆ Visualize()

void apollo::localization::msf::VisualizationEngine::Visualize ( ::apollo::common::EigenVector< LocalizatonInfo > &&  loc_infos,
const ::apollo::common::EigenVector3dVec cloud 
)

在文件 visualization_engine.cc144 行定义.

146 {
147 if (!is_init_) {
148 AERROR << "Visualziation should be init first.";
149 return;
150 }
151
152 if (loc_infos.size() != loc_info_num_) {
153 AERROR << "Please check the localization info num.";
154 return;
155 }
156
157 cur_loc_infos_ = std::move(loc_infos);
158
159 if (!UpdateCarLocId(expected_car_loc_id_)) {
160 if (!UpdateCarLocId(car_loc_id_)) {
161 if (!UpdateCarLocId()) {
162 return;
163 }
164 } else {
165 if (expected_car_loc_id_ == loc_info_num_) {
166 expected_car_loc_id_ = car_loc_id_;
167 }
168 }
169 }
170
171 UpdateTrajectoryGroups();
172 cloud_ = cloud;
173 Draw();
174}

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