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

#include <ndt_map_node.h>

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

Public 成员函数

 NdtMapNode ()
 
 ~NdtMapNode ()
 
void Init (const BaseMapConfig *map_config)
 Initialize the map node.
 
void Init (const BaseMapConfig *map_config, const MapNodeIndex &index, bool create_map_cells=true)
 
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::pyramid_map::BaseMapNode
 BaseMapNode ()
 Construct a map node.
 
 BaseMapNode (BaseMapMatrix *matrix, CompressionStrategy *strategy)
 Construct a map node.
 
virtual ~BaseMapNode ()
 Destruct a 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 SaveAltitudeImage () const
 Save altitude image of node.
 
bool Load ()
 Load the map node from the disk.
 
bool Load (const char *filename)
 
virtual 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.
 
virtual bool GetCoordinate (const Eigen::Vector3d &coordinate, unsigned int *x, unsigned int *y) const
 
virtual Eigen::Vector2d GetCoordinate (unsigned int x, unsigned int y) const
 Given the local 2D coordinate, return the global coordinate.
 
void SetMapNodeIndex (const MapNodeIndex &index)
 Set the map node index.
 
bool SaveIntensityImage (const std::string &path) const
 Save intensity image of node.
 
bool SaveAltitudeImage (const std::string &path) const
 Save altitude image of node.
 
const BaseMapMatrixGetMapCellMatrix () const
 Get map cell matrix.
 
BaseMapMatrixGetMapCellMatrix ()
 
const BaseMapConfigGetMapConfig () const
 Get the map settings.
 
const BaseMapNodeConfigGetMapNodeConfig () const
 Get the map node config.
 
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
 
void SetLeftTopCorner (double x, double y)
 Set the left top corner of the map node.
 
float GetMapResolution () const
 Get the resolution of this map nodex.
 

静态 Public 成员函数

static void Reduce (NdtMapNode *map_node, const NdtMapNode &map_node_new)
 Combine two map nodes (Reduce operation in mapreduce).
 
- 静态 Public 成员函数 继承自 apollo::localization::msf::pyramid_map::BaseMapNode
static Eigen::Vector2d ComputeLeftTopCorner (const BaseMapConfig &config, const MapNodeIndex &index)
 
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::pyramid_map::BaseMapNode
bool CreateMapDirectory (const std::string &path) const
 Try to create the map directory.
 
bool CreateMapDirectoryRecursively (const std::vector< std::string > &paths) const
 Try to create the map directory recursively.
 
bool CheckMapDirectoryRecursively (const std::vector< std::string > &paths) const
 Try to check the map directory recursively.
 
virtual bool LoadBinary (FILE *file)
 Load the map cell from a binary chunk.
 
virtual bool CreateBinary (FILE *file) const
 Create the binary.
 
virtual size_t GetBinarySize () const
 Get the binary size of the object.
 
virtual size_t LoadHeaderBinary (const unsigned char *buf)
 Load the map node header from a binary chunk.
 
virtual size_t CreateHeaderBinary (unsigned char *buf, size_t buf_size) const
 Create the binary header.
 
virtual size_t GetHeaderBinarySize () const
 Get the size of the header in bytes.
 
virtual size_t LoadBodyBinary (std::vector< unsigned char > *buf)
 Load the map node body from a binary chunk.
 
virtual size_t CreateBodyBinary (std::vector< unsigned char > *buf) const
 Create the binary body.
 
virtual size_t GetBodyBinarySize () const
 Get the size of the body in bytes.
 
- Protected 属性 继承自 apollo::localization::msf::pyramid_map::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.
 
std::shared_ptr< BaseMapNodeConfigmap_node_config_ = nullptr
 The map node config.
 
std::shared_ptr< BaseMapMatrixmap_matrix_ = nullptr
 The data structure of the map datas, which is a matrix.
 
std::shared_ptr< BaseMapMatrixHandlermap_matrix_handler_ = nullptr
 The class to load and create map matrix binary.
 
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
 
size_t file_body_binary_size_ = 0
 The body binary size in file.
 
size_t uncompressed_file_body_size_ = 0
 
std::shared_ptr< CompressionStrategycompression_strategy_ = nullptr
 @bried The compression strategy.
 

详细描述

在文件 ndt_map_node.h31 行定义.

构造及析构函数说明

◆ NdtMapNode()

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

在文件 ndt_map_node.cc27 行定义.

27{}

◆ ~NdtMapNode()

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

在文件 ndt_map_node.cc28 行定义.

28{}

成员函数说明

◆ GetCoordinate3D()

Eigen::Vector3d apollo::localization::msf::pyramid_map::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.cc75 行定义.

76 {
77 const Eigen::Vector2d& left_top_corner = GetLeftTopCorner();
78 Eigen::Vector2d coord_2d;
79 coord_2d[0] =
80 left_top_corner[0] + (static_cast<double>(x)) * GetMapResolution();
81 coord_2d[1] =
82 left_top_corner[1] + (static_cast<double>(y)) * GetMapResolution();
83
84 double altitude =
86 Eigen::Vector3d coord_3d;
87 coord_3d[0] = coord_2d[0];
88 coord_3d[1] = coord_2d[1];
89 coord_3d[2] = altitude;
90
91 return coord_3d;
92}
const Eigen::Vector2d & GetLeftTopCorner() const
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::pyramid_map::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.cc94 行定义.

96 {
97 const Eigen::Vector2d& left_top_corner = GetLeftTopCorner();
98 Eigen::Vector2d coord_2d;
99 coord_2d[0] =
100 left_top_corner[0] + (static_cast<double>(x) + 0.5) * GetMapResolution();
101 coord_2d[1] =
102 left_top_corner[1] + (static_cast<double>(y) + 0.5) * GetMapResolution();
103
104 double altitude =
106 Eigen::Vector3d coord_3d;
107 coord_3d[0] = coord_2d[0];
108 coord_3d[1] = coord_2d[1];
109 coord_3d[2] = altitude;
110
111 return coord_3d;
112}

◆ GetMapResolutionZ()

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

Get the resolution of this map nodex.

在文件 ndt_map_node.h41 行定义.

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

◆ Init() [1/2]

void apollo::localization::msf::pyramid_map::NdtMapNode::Init ( const BaseMapConfig map_config)
virtual

Initialize the map node.

Call this function first before use it!

实现了 apollo::localization::msf::pyramid_map::BaseMapNode.

在文件 ndt_map_node.cc30 行定义.

30 {
31 map_config_ = map_config;
32
33 map_node_config_.reset(new NdtMapNodeConfig());
35 map_node_config_->has_map_version_ = false;
36 map_node_config_->has_body_md5_ = false;
37 is_reserved_ = false;
38 data_is_ready_ = false;
39 is_changed_ = false;
42
43 map_matrix_.reset(new NdtMapMatrix());
46 compression_strategy_.reset(new ZlibStrategy());
48}
std::shared_ptr< CompressionStrategy > compression_strategy_
@bried The compression strategy.
bool is_changed_
Has the map node been changed.
bool is_reserved_
If the node is reserved in map.
std::shared_ptr< BaseMapMatrixHandler > map_matrix_handler_
The class to load and create map matrix binary.
std::shared_ptr< BaseMapMatrix > map_matrix_
The data structure of the map datas, which is a matrix.
std::shared_ptr< BaseMapNodeConfig > map_node_config_
The map node config.
virtual void InitMapMatrix(const BaseMapConfig *map_config)
Initialize the map matrix.
unsigned int num_valid_single_cells_
The number of single cells with elements.
unsigned int num_valid_cells_
The number of cells with elements.
apollo::localization::msf::pyramid_map::NdtMapMatrix NdtMapMatrix

◆ Init() [2/2]

void apollo::localization::msf::pyramid_map::NdtMapNode::Init ( const BaseMapConfig map_config,
const MapNodeIndex index,
bool  create_map_cells = true 
)
virtual

实现了 apollo::localization::msf::pyramid_map::BaseMapNode.

在文件 ndt_map_node.cc49 行定义.

50 {
51 map_config_ = map_config;
52
53 map_node_config_.reset(new NdtMapNodeConfig());
54 map_node_config_->node_index_ = index;
58 map_node_config_->has_map_version_ = false;
59 map_node_config_->has_body_md5_ = false;
60 is_reserved_ = false;
61 data_is_ready_ = false;
62 is_changed_ = false;
65
66 map_matrix_.reset(new NdtMapMatrix());
69 compression_strategy_.reset(new ZlibStrategy());
70 if (create_map_cells) {
72 }
73}
static Eigen::Vector2d ComputeLeftTopCorner(const BaseMapConfig &config, const MapNodeIndex &index)
Eigen::Vector2d left_top_corner_
The left top corner of the map node in the global coordinate system.

◆ Reduce()

void apollo::localization::msf::pyramid_map::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.cc114 行定义.

114 {
115 assert(map_node->index_.m_ == map_node_new.index_.m_);
116 assert(map_node->index_.n_ == map_node_new.index_.n_);
117 assert(map_node->index_.resolution_id_ == map_node_new.index_.resolution_id_);
118 assert(map_node->index_.zone_id_ == map_node_new.index_.zone_id_);
120 static_cast<NdtMapMatrix*>(map_node->map_matrix_.get()),
121 static_cast<const NdtMapMatrix&>(*map_node_new.map_matrix_));
122}
static void Reduce(NdtMapMatrix *cells, const NdtMapMatrix &cells_new)
Combine two NdtMapMatrix instances (Reduce).

类成员变量说明

◆ num_valid_cells_

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

The number of cells with elements.

在文件 ndt_map_node.h63 行定义.

◆ num_valid_single_cells_

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

The number of single cells with elements.

在文件 ndt_map_node.h65 行定义.


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