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

#include <ndt_map_node.h>

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

Public 成员函数

 NdtMapNode ()
 
 ~NdtMapNode ()
 
float GetMapResolutionZ () const
 Get the resolution of this map nodex.
 
Eigen::Vector3d GetCoordinate3D (unsigned int x, unsigned int y, int altitude_index) const
 Given the local x, y, altitude index, return the global coordinate.
 
Eigen::Vector3d GetCoordinateCenter3D (unsigned int x, unsigned int y, int altitude_index) const
 Given the local x, y, altitude index, return the global coordinate.
 
- Public 成员函数 继承自 apollo::localization::msf::BaseMapNode
 BaseMapNode (BaseMapMatrix *matrix, CompressionStrategy *strategy)
 Construct a map node.
 
virtual ~BaseMapNode ()
 Destruct a map node.
 
virtual void Init (const BaseMapConfig *map_config, const MapNodeIndex &index, bool create_map_cells=true)
 Initialize the map node.
 
virtual void InitMapMatrix (const BaseMapConfig *map_config)
 Initialize the map matrix.
 
virtual void Finalize ()
 call before deconstruction or reset.
 
virtual void ResetMapNode ()
 Reset map cells data.
 
bool Save ()
 Save the map node to the disk.
 
bool SaveIntensityImage () const
 Save intensity image of node.
 
bool Load ()
 Load the map node from the disk.
 
bool Load (const char *filename)
 
const BaseMapMatrixGetMapCellMatrix () const
 Get map cell matrix.
 
BaseMapMatrixGetMapCellMatrix ()
 
const BaseMapConfigGetMapConfig () const
 Get the map settings.
 
void SetMapNodeIndex (const MapNodeIndex &index)
 Set the map node index.
 
const MapNodeIndexGetMapNodeIndex () const
 Get the map node index.
 
void SetIsReserved (bool is_reserved)
 Set if the map node is reserved.
 
bool GetIsReserved () const
 Get if the map node is reserved.
 
bool GetIsChanged () const
 Get if the map data has changed.
 
void SetIsChanged (bool is)
 Set if the map node data has changed.
 
bool GetIsReady () const
 Get if the map node data is ready
 
const Eigen::Vector2d & GetLeftTopCorner () const
 Get the left top corner of the map node.
 
void SetLeftTopCorner (double x, double y)
 
float GetMapResolution () const
 Get the resolution of this map nodex.
 
bool GetCoordinate (const Eigen::Vector2d &coordinate, unsigned int *x, unsigned int *y) const
 Given the global coordinate, get the local 2D coordinate of the map cell matrix.
 
bool GetCoordinate (const Eigen::Vector3d &coordinate, unsigned int *x, unsigned int *y) const
 
Eigen::Vector2d GetCoordinate (unsigned int x, unsigned int y) const
 Given the local 2D coordinate, return the global coordinate, eigen version.
 

静态 Public 成员函数

static void Reduce (NdtMapNode *map_node, const NdtMapNode &map_node_new)
 Combine two map nodes (Reduce operation in mapreduce).
 
- 静态 Public 成员函数 继承自 apollo::localization::msf::BaseMapNode
static Eigen::Vector2d GetLeftTopCorner (const BaseMapConfig &option, const MapNodeIndex &index)
 

Public 属性

unsigned int num_valid_cells_
 The number of cells with elements.
 
unsigned int num_valid_single_cells_
 The number of single cells with elements.
 

额外继承的成员函数

- Protected 成员函数 继承自 apollo::localization::msf::BaseMapNode
virtual unsigned int LoadBinary (FILE *file)
 Load the map cell from a binary chunk.
 
virtual unsigned int CreateBinary (FILE *file) const
 Create the binary.
 
virtual unsigned int GetBinarySize () const
 Get the binary size of the object.
 
virtual unsigned int LoadHeaderBinary (unsigned char *buf)
 Load the map node header from a binary chunk.
 
virtual unsigned int CreateHeaderBinary (unsigned char *buf, unsigned int buf_size) const
 Create the binary header.
 
virtual unsigned int GetHeaderBinarySize () const
 Get the size of the header in bytes.
 
virtual unsigned int LoadBodyBinary (std::vector< unsigned char > *buf)
 Load the map node body from a binary chunk.
 
virtual unsigned int CreateBodyBinary (std::vector< unsigned char > *buf) const
 Create the binary body.
 
virtual unsigned int GetBodyBinarySize () const
 Get the size of the body in bytes.
 
bool SaveIntensityImage (const std::string &path) const
 Save intensity image of node.
 
- Protected 属性 继承自 apollo::localization::msf::BaseMapNode
const BaseMapConfigmap_config_ = nullptr
 The map settings.
 
MapNodeIndex index_
 The index of this node.
 
Eigen::Vector2d left_top_corner_
 The left top corner of the map node in the global coordinate system.
 
BaseMapMatrixmap_matrix_
 The data structure of the map datas, which is a matrix.
 
bool is_reserved_ = false
 If the node is reserved in map.
 
bool is_changed_ = false
 Has the map node been changed.
 
bool data_is_ready_ = false
 
unsigned int file_body_binary_size_ = 0
 The body binary size in file.
 
CompressionStrategycompression_strategy_ = nullptr
 @bried The compression strategy.
 
float min_altitude_ = 1e6
 The min altitude of point cloud in the node.
 

详细描述

在文件 ndt_map_node.h30 行定义.

构造及析构函数说明

◆ NdtMapNode()

apollo::localization::msf::NdtMapNode::NdtMapNode ( )

在文件 ndt_map_node.cc24 行定义.

24 : BaseMapNode(new NdtMapMatrix(), new ZlibStrategy()) {
27}
BaseMapNode(BaseMapMatrix *matrix, CompressionStrategy *strategy)
Construct a map node.
unsigned int num_valid_cells_
The number of cells with elements.
unsigned int num_valid_single_cells_
The number of single cells with elements.
apollo::localization::msf::pyramid_map::NdtMapMatrix NdtMapMatrix

◆ ~NdtMapNode()

apollo::localization::msf::NdtMapNode::~NdtMapNode ( )

在文件 ndt_map_node.cc28 行定义.

28{}

成员函数说明

◆ GetCoordinate3D()

Eigen::Vector3d apollo::localization::msf::NdtMapNode::GetCoordinate3D ( unsigned int  x,
unsigned int  y,
int  altitude_index 
) const

Given the local x, y, altitude index, return the global coordinate.

在文件 ndt_map_node.cc29 行定义.

30 {
31 const Eigen::Vector2d& left_top_corner = GetLeftTopCorner();
32 Eigen::Vector2d coord_2d;
33 coord_2d[0] =
34 left_top_corner[0] + (static_cast<double>(x)) * GetMapResolution();
35 coord_2d[1] =
36 left_top_corner[1] + (static_cast<double>(y)) * GetMapResolution();
37
38 double altitude =
40 Eigen::Vector3d coord_3d;
41 coord_3d[0] = coord_2d[0];
42 coord_3d[1] = coord_2d[1];
43 coord_3d[2] = altitude;
44
45 return coord_3d;
46}
const Eigen::Vector2d & GetLeftTopCorner() const
Get the left top corner of the map node.
float GetMapResolution() const
Get the resolution of this map nodex.
static float CalAltitude(const float resolution, const int altitude_index)
Calculate altitude from altitude index.
float GetMapResolutionZ() const
Get the resolution of this map nodex.

◆ GetCoordinateCenter3D()

Eigen::Vector3d apollo::localization::msf::NdtMapNode::GetCoordinateCenter3D ( unsigned int  x,
unsigned int  y,
int  altitude_index 
) const

Given the local x, y, altitude index, return the global coordinate.

在文件 ndt_map_node.cc48 行定义.

50 {
51 const Eigen::Vector2d& left_top_corner = GetLeftTopCorner();
52 Eigen::Vector2d coord_2d;
53 coord_2d[0] =
54 left_top_corner[0] + (static_cast<double>(x) + 0.5) * GetMapResolution();
55 coord_2d[1] =
56 left_top_corner[1] + (static_cast<double>(y) + 0.5) * GetMapResolution();
57
58 double altitude =
60 Eigen::Vector3d coord_3d;
61 coord_3d[0] = coord_2d[0];
62 coord_3d[1] = coord_2d[1];
63 coord_3d[2] = altitude;
64
65 return coord_3d;
66}

◆ GetMapResolutionZ()

float apollo::localization::msf::NdtMapNode::GetMapResolutionZ ( ) const
inline

Get the resolution of this map nodex.

在文件 ndt_map_node.h36 行定义.

36 {
37 return static_cast<const NdtMapConfig*>(map_config_)
38 ->map_resolutions_z_[index_.resolution_id_];
39 }
MapNodeIndex index_
The index of this node.
const BaseMapConfig * map_config_
The map settings.
unsigned int resolution_id_
The ID of the resolution.
apollo::localization::msf::pyramid_map::NdtMapConfig NdtMapConfig

◆ Reduce()

void apollo::localization::msf::NdtMapNode::Reduce ( NdtMapNode map_node,
const NdtMapNode map_node_new 
)
static

Combine two map nodes (Reduce operation in mapreduce).

The result is saved in map_node.

在文件 ndt_map_node.cc68 行定义.

68 {
69 assert(map_node->index_.m_ == map_node_new.index_.m_);
70 assert(map_node->index_.n_ == map_node_new.index_.n_);
71 assert(map_node->index_.resolution_id_ == map_node_new.index_.resolution_id_);
72 assert(map_node->index_.zone_id_ == map_node_new.index_.zone_id_);
74 static_cast<NdtMapMatrix*>(map_node->map_matrix_),
75 static_cast<const NdtMapMatrix&>(*map_node_new.map_matrix_));
76}
static void Reduce(NdtMapMatrix *cells, const NdtMapMatrix &cells_new)
Combine two NdtMapMatrix instances (Reduce).

类成员变量说明

◆ num_valid_cells_

unsigned int apollo::localization::msf::NdtMapNode::num_valid_cells_

The number of cells with elements.

在文件 ndt_map_node.h58 行定义.

◆ num_valid_single_cells_

unsigned int apollo::localization::msf::NdtMapNode::num_valid_single_cells_

The number of single cells with elements.

在文件 ndt_map_node.h60 行定义.


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