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

#include <visualization_manager.h>

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

Public 成员函数

 VisualizationManager ()
 
 ~VisualizationManager ()
 
bool Init (const std::string &map_folder, const std::string &map_visual_folder, const Eigen::Affine3d &velodyne_extrinsic, const VisualMapParam &map_param)
 
bool Init (const VisualizationManagerParams &params)
 
void AddLidarFrame (const LidarVisFrame &lidar_frame)
 
void AddGNSSLocMessage (const LocalizationMsg &gnss_loc_msg)
 
void AddLidarLocMessage (const LocalizationMsg &lidar_loc_msg)
 
void AddFusionLocMessage (const LocalizationMsg &fusion_loc_msg)
 
void StartVisualization ()
 
void StopVisualization ()
 

静态 Public 成员函数

static VisualizationManagerGetInstance ()
 

详细描述

在文件 visualization_manager.h149 行定义.

构造及析构函数说明

◆ VisualizationManager()

apollo::localization::msf::VisualizationManager::VisualizationManager ( )

在文件 visualization_manager.cc278 行定义.

279 : visual_engine_(),
280 stop_visualization_(false),
281 lidar_frame_buffer_(10),
282 gnss_loc_info_buffer_(20),
283 lidar_loc_info_buffer_(40),
284 fusion_loc_info_buffer_(400) {}

◆ ~VisualizationManager()

apollo::localization::msf::VisualizationManager::~VisualizationManager ( )

在文件 visualization_manager.cc286 行定义.

286 {
287 if (!(stop_visualization_.load())) {
288 stop_visualization_ = true;
289 visual_thread_.join();
290 }
291}

成员函数说明

◆ AddFusionLocMessage()

void apollo::localization::msf::VisualizationManager::AddFusionLocMessage ( const LocalizationMsg fusion_loc_msg)

在文件 visualization_manager.cc353 行定义.

354 {
355 AINFO << "AddFusionLocMessage.";
356 fusion_loc_info_buffer_.PushNewMessage(fusion_loc_msg.timestamp,
357 fusion_loc_msg);
358}
#define AINFO
Definition log.h:42

◆ AddGNSSLocMessage()

void apollo::localization::msf::VisualizationManager::AddGNSSLocMessage ( const LocalizationMsg gnss_loc_msg)

在文件 visualization_manager.cc341 行定义.

342 {
343 AINFO << "AddGNSSLocMessage.";
344 gnss_loc_info_buffer_.PushNewMessage(gnss_loc_msg.timestamp, gnss_loc_msg);
345}

◆ AddLidarFrame()

void apollo::localization::msf::VisualizationManager::AddLidarFrame ( const LidarVisFrame lidar_frame)

在文件 visualization_manager.cc333 行定义.

333 {
334 AINFO << "AddLidarFrame.";
335 static int id = 0;
336 AINFO << "id." << id;
337 lidar_frame_buffer_.PushNewMessage(lidar_frame.timestamp, lidar_frame);
338 id++;
339}

◆ AddLidarLocMessage()

void apollo::localization::msf::VisualizationManager::AddLidarLocMessage ( const LocalizationMsg lidar_loc_msg)

在文件 visualization_manager.cc347 行定义.

348 {
349 AINFO << "AddLidarLocMessage.";
350 lidar_loc_info_buffer_.PushNewMessage(lidar_loc_msg.timestamp, lidar_loc_msg);
351}

◆ GetInstance()

static VisualizationManager & apollo::localization::msf::VisualizationManager::GetInstance ( )
inlinestatic

在文件 visualization_manager.h156 行定义.

156 {
157 static VisualizationManager visual_manage;
158 return visual_manage;
159 }

◆ Init() [1/2]

bool apollo::localization::msf::VisualizationManager::Init ( const std::string &  map_folder,
const std::string &  map_visual_folder,
const Eigen::Affine3d &  velodyne_extrinsic,
const VisualMapParam map_param 
)

在文件 visualization_manager.cc293 行定义.

296 {
297 AINFO << "Get zone id.";
298 unsigned int resolution_id = 0;
299 int zone_id = 0;
300
301 bool success = GetZoneIdFromMapFolder(map_folder, resolution_id, &zone_id);
302 if (!success) {
303 AERROR << "Get zone id failed.";
304 return false;
305 }
306 AINFO << "Get zone id succeed.";
307
308 AINFO << "Init visualization engine.";
309 success = visual_engine_.Init(map_folder, map_visual_folder, map_param,
310 resolution_id, zone_id, velodyne_extrinsic,
312 if (!success) {
313 AERROR << "Visualization engine init failed.";
314 return false;
315 }
316 AINFO << "Visualization engine init succeed.";
317
318 visual_engine_.SetAutoPlay(true);
319
320 return true;
321}
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)
#define AERROR
Definition log.h:44
#define LOC_INFO_NUM

◆ Init() [2/2]

bool apollo::localization::msf::VisualizationManager::Init ( const VisualizationManagerParams params)

在文件 visualization_manager.cc323 行定义.

323 {
324 lidar_frame_buffer_.SetCapacity(params.lidar_frame_buffer_capacity);
325 gnss_loc_info_buffer_.SetCapacity(params.gnss_loc_info_buffer_capacity);
326 lidar_loc_info_buffer_.SetCapacity(params.lidar_loc_info_buffer_capacity);
327 fusion_loc_info_buffer_.SetCapacity(params.fusion_loc_info_buffer_capacity);
328
329 return Init(params.map_folder, params.map_visual_folder,
330 params.velodyne_extrinsic, params.map_param);
331}
bool Init(const std::string &map_folder, const std::string &map_visual_folder, const Eigen::Affine3d &velodyne_extrinsic, const VisualMapParam &map_param)

◆ StartVisualization()

void apollo::localization::msf::VisualizationManager::StartVisualization ( )

在文件 visualization_manager.cc360 行定义.

360 {
361 visual_thread_ = std::thread(&VisualizationManager::DoVisualize, this);
362}

◆ StopVisualization()

void apollo::localization::msf::VisualizationManager::StopVisualization ( )

在文件 visualization_manager.cc364 行定义.

364 {
365 stop_visualization_ = true;
366 visual_thread_.join();
367}

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