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

The data structure of the map cells in a map node. 更多...

#include <base_map_matrix.h>

类 apollo::localization::msf::pyramid_map::BaseMapMatrix 继承关系图:
apollo::localization::msf::pyramid_map::BaseMapMatrix 的协作图:

Public 成员函数

 BaseMapMatrix ()
 The default constructor.
 
virtual ~BaseMapMatrix ()
 The deconstructor.
 
 BaseMapMatrix (const BaseMapMatrix &map_matrix)
 The copy constructor.
 
virtual void Init (const BaseMapConfig &config)=0
 Initialize the map matrix.
 
virtual void Reset ()=0
 Reset map cells data.
 
virtual bool GetIntensityImg (cv::Mat *intensity_img) const
 get intensity image of node.
 
virtual bool GetAltitudeImg (cv::Mat *altitude_img) const
 get altitude image of node.
 

详细描述

The data structure of the map cells in a map node.

在文件 base_map_matrix.h30 行定义.

构造及析构函数说明

◆ BaseMapMatrix() [1/2]

apollo::localization::msf::pyramid_map::BaseMapMatrix::BaseMapMatrix ( )

The default constructor.

在文件 base_map_matrix.cc24 行定义.

24{}

◆ ~BaseMapMatrix()

apollo::localization::msf::pyramid_map::BaseMapMatrix::~BaseMapMatrix ( )
virtual

The deconstructor.

在文件 base_map_matrix.cc26 行定义.

26{}

◆ BaseMapMatrix() [2/2]

apollo::localization::msf::pyramid_map::BaseMapMatrix::BaseMapMatrix ( const BaseMapMatrix map_matrix)
explicit

The copy constructor.

在文件 base_map_matrix.cc28 行定义.

28{}

成员函数说明

◆ GetAltitudeImg()

bool apollo::localization::msf::pyramid_map::BaseMapMatrix::GetAltitudeImg ( cv::Mat *  altitude_img) const
virtual

get altitude image of node.

apollo::localization::msf::pyramid_map::PyramidMapMatrix 重载.

在文件 base_map_matrix.cc34 行定义.

34 {
35 return false;
36}

◆ GetIntensityImg()

bool apollo::localization::msf::pyramid_map::BaseMapMatrix::GetIntensityImg ( cv::Mat *  intensity_img) const
virtual

get intensity image of node.

apollo::localization::msf::pyramid_map::NdtMapMatrix , 以及 apollo::localization::msf::pyramid_map::PyramidMapMatrix 重载.

在文件 base_map_matrix.cc30 行定义.

30 {
31 return false;
32}

◆ Init()

virtual void apollo::localization::msf::pyramid_map::BaseMapMatrix::Init ( const BaseMapConfig config)
pure virtual

◆ Reset()

virtual void apollo::localization::msf::pyramid_map::BaseMapMatrix::Reset ( )
pure virtual

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