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

#include <lossless_map.h>

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

Public 成员函数

 LosslessMap (LosslessMapConfig *config)
 
 ~LosslessMap ()
 
void SetValue (const Eigen::Vector3d &coordinate, int zone_id, unsigned char intensity)
 Set the value of a pixel in the map, including all the resolution levels.
 
void SetValueLayer (const Eigen::Vector3d &coordinate, int zone_id, unsigned char intensity)
 Set the vlaue of a pixel in a layer in the map node.
 
void GetValue (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id, std::vector< unsigned char > *values)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.
 
void GetValueSafe (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id, std::vector< unsigned char > *values)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.
 
void GetVar (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id, std::vector< float > *vars)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.
 
void GetVarSafe (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id, std::vector< float > *vars)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.
 
void GetAlt (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id, std::vector< float > *alts)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.
 
void GetAltSafe (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id, std::vector< float > *alts)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.
 
void GetAltVar (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id, std::vector< float > *alt_vars)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.
 
void GetAltVarSafe (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id, std::vector< float > *alt_vars)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.
 
void GetCount (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id, std::vector< unsigned int > *counts)
 Get the number of samples in the map cell.
 
void GetCountSafe (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id, std::vector< unsigned int > *counts)
 Get the number of samples in the map cell thread safely.
 
unsigned char GetValue (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.
 
unsigned char GetValueSafe (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.
 
float GetVar (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.
 
float GetVarSafe (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.
 
float GetAlt (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.
 
float GetAltSafe (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.
 
float GetAltVar (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.
 
float GetAltVarSafe (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id)
 Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.
 
unsigned int GetCount (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id)
 Get the number of samples in the map cell.
 
unsigned int GetCountSafe (const Eigen::Vector3d &coordinate, int zone_id, unsigned int resolution_id)
 Get the number of samples in the map cell thread safely.
 
void SetGroundHeightOffset (double height_offset)
 Set the ground height offset.
 
virtual void PreloadMapArea (const Eigen::Vector3d &location, const Eigen::Vector3d &trans_diff, unsigned int resolution_id, unsigned int zone_id)
 Preload map nodes for the next frame location calculation.
 
virtual bool LoadMapArea (const Eigen::Vector3d &seed_pt3d, unsigned int resolution_id, unsigned int zone_id, int filter_size_x, int filter_size_y)
 Load map nodes for the location calculate of this frame.
 
- Public 成员函数 继承自 apollo::localization::msf::BaseMap
 BaseMap (BaseMapConfig *map_config)
 The constructor.
 
virtual ~BaseMap ()
 The destructor.
 
virtual void InitMapNodeCaches (int cacheL1_size, int cahceL2_size)
 Init load threadpool and preload threadpool.
 
BaseMapNodeGetMapNode (const MapNodeIndex &index)
 Get the map node, if it's not in the cache, return false.
 
BaseMapNodeGetMapNodeSafe (const MapNodeIndex &index)
 Return the map node, if it's not in the cache, safely load it.
 
bool IsMapNodeExist (const MapNodeIndex &index) const
 Check if the map node in the cache.
 
bool SetMapFolderPath (const std::string folder_path)
 Set the directory of the map.
 
void AddDataset (const std::string dataset_path)
 Add a dataset path to the map config.
 
void AttachMapNodePool (BaseMapNodePool *p_map_node_pool)
 Attach map node pointer.
 
void WriteBinary (FILE *file)
 Write all the map nodes to a single binary file stream.
 
void LoadBinary (FILE *file, std::string map_folder_path="")
 Load all the map nodes from a single binary file stream.
 
const BaseMapConfigGetConfig () const
 Get the map config.
 
BaseMapConfigGetConfig ()
 Get the map config.
 

额外继承的成员函数

- Protected 成员函数 继承自 apollo::localization::msf::BaseMap
void LoadMapNodes (std::set< MapNodeIndex > *map_ids)
 Load map node by index.
 
void PreloadMapNodes (std::set< MapNodeIndex > *map_ids)
 Load map node by index.
 
void LoadMapNodeThreadSafety (MapNodeIndex index, bool is_reserved=false)
 Load map node by index, thread_safety.
 
- Protected 属性 继承自 apollo::localization::msf::BaseMap
BaseMapConfigmap_config_
 The map settings.
 
std::list< MapNodeIndexmap_nodes_disk_
 All the map nodes in the Map (in the disk).
 
MapNodeCache< MapNodeIndex, BaseMapNode >::DestroyFunc destroy_func_lvl1_
 
MapNodeCache< MapNodeIndex, BaseMapNode >::DestroyFunc destroy_func_lvl2_
 
MapNodeCache< MapNodeIndex, BaseMapNode > * map_node_cache_lvl1_
 The cache for map node preload.
 
MapNodeCache< MapNodeIndex, BaseMapNode > * map_node_cache_lvl2_
 brief The dynamic map node preloading thread pool pointer.
 
BaseMapNodePoolmap_node_pool_
 The map node memory pool pointer.
 
std::set< MapNodeIndexmap_preloading_task_index_
 @bried Keep the index of preloading nodes.
 
boost::recursive_mutex map_load_mutex_
 The mutex for preload map node.
 

详细描述

在文件 lossless_map.h28 行定义.

构造及析构函数说明

◆ LosslessMap()

apollo::localization::msf::LosslessMap::LosslessMap ( LosslessMapConfig config)
explicit

在文件 lossless_map.cc25 行定义.

25: BaseMap(config) {}
BaseMap(BaseMapConfig *map_config)
The constructor.
Definition base_map.cc:29

◆ ~LosslessMap()

apollo::localization::msf::LosslessMap::~LosslessMap ( )

在文件 lossless_map.cc27 行定义.

27{}

成员函数说明

◆ GetAlt() [1/2]

float apollo::localization::msf::LosslessMap::GetAlt ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.

在文件 lossless_map.cc186 行定义.

187 {
188 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
190 resolution_id, zone_id);
191 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
192 return node->GetAlt(coordinate);
193}
std::vector< float > map_resolutions_
The pixel resolutions in the map in meters.
BaseMapConfig * map_config_
The map settings.
Definition base_map.h:105
BaseMapNode * GetMapNode(const MapNodeIndex &index)
Get the map node, if it's not in the cache, return false.
Definition base_map.cc:61
static MapNodeIndex GetMapNodeIndex(const BaseMapConfig &option, const Eigen::Vector3d &coordinate, unsigned int resolution_id, int zone_id)
Construct a map node index, given a global coordinate, eigen version.
apollo::localization::msf::pyramid_map::MapNodeIndex MapNodeIndex

◆ GetAlt() [2/2]

void apollo::localization::msf::LosslessMap::GetAlt ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id,
std::vector< float > *  alts 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.

This function returns the value of each layer in the map cell.

在文件 lossless_map.cc90 行定义.

91 {
92 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
94 resolution_id, zone_id);
95 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
96 node->GetAlt(coordinate, alts);
97}

◆ GetAltSafe() [1/2]

float apollo::localization::msf::LosslessMap::GetAltSafe ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.

在文件 lossless_map.cc195 行定义.

196 {
197 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
199 resolution_id, zone_id);
200 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
201 return node->GetAlt(coordinate);
202}
BaseMapNode * GetMapNodeSafe(const MapNodeIndex &index)
Return the map node, if it's not in the cache, safely load it.
Definition base_map.cc:67

◆ GetAltSafe() [2/2]

void apollo::localization::msf::LosslessMap::GetAltSafe ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id,
std::vector< float > *  alts 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.

This function returns the value of each layer in the map cell.

在文件 lossless_map.cc99 行定义.

101 {
102 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
104 resolution_id, zone_id);
105 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
106 node->GetAlt(coordinate, alts);
107}

◆ GetAltVar() [1/2]

float apollo::localization::msf::LosslessMap::GetAltVar ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.

在文件 lossless_map.cc204 行定义.

205 {
206 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
208 resolution_id, zone_id);
209 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
210 return node->GetAltVar(coordinate);
211}

◆ GetAltVar() [2/2]

void apollo::localization::msf::LosslessMap::GetAltVar ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id,
std::vector< float > *  alt_vars 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.

This function returns the value of each layer in the map cell.

在文件 lossless_map.cc109 行定义.

111 {
112 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
114 resolution_id, zone_id);
115 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
116 node->GetAltVar(coordinate, alt_vars);
117}

◆ GetAltVarSafe() [1/2]

float apollo::localization::msf::LosslessMap::GetAltVarSafe ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.

在文件 lossless_map.cc213 行定义.

214 {
215 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
217 resolution_id, zone_id);
218 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
219 return node->GetAltVar(coordinate);
220}

◆ GetAltVarSafe() [2/2]

void apollo::localization::msf::LosslessMap::GetAltVarSafe ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id,
std::vector< float > *  alt_vars 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.

This function returns the value of each layer in the map cell.

在文件 lossless_map.cc119 行定义.

121 {
122 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
124 resolution_id, zone_id);
125 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
126 node->GetAltVar(coordinate, alt_vars);
127}

◆ GetCount() [1/2]

unsigned int apollo::localization::msf::LosslessMap::GetCount ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id 
)

Get the number of samples in the map cell.

在文件 lossless_map.cc222 行定义.

223 {
224 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
226 resolution_id, zone_id);
227 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
228 return node->GetCount(coordinate);
229}

◆ GetCount() [2/2]

void apollo::localization::msf::LosslessMap::GetCount ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id,
std::vector< unsigned int > *  counts 
)

Get the number of samples in the map cell.

在文件 lossless_map.cc129 行定义.

131 {
132 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
134 resolution_id, zone_id);
135 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
136 node->GetCount(coordinate, counts);
137}

◆ GetCountSafe() [1/2]

unsigned int apollo::localization::msf::LosslessMap::GetCountSafe ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id 
)

Get the number of samples in the map cell thread safely.

在文件 lossless_map.cc231 行定义.

233 {
234 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
236 resolution_id, zone_id);
237 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
238 return node->GetCount(coordinate);
239}

◆ GetCountSafe() [2/2]

void apollo::localization::msf::LosslessMap::GetCountSafe ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id,
std::vector< unsigned int > *  counts 
)

Get the number of samples in the map cell thread safely.

在文件 lossless_map.cc139 行定义.

141 {
142 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
144 resolution_id, zone_id);
145 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
146 node->GetCount(coordinate, counts);
147}

◆ GetValue() [1/2]

unsigned char apollo::localization::msf::LosslessMap::GetValue ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.

在文件 lossless_map.cc149 行定义.

150 {
151 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
153 resolution_id, zone_id);
154 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
155 return node->GetValue(coordinate);
156}

◆ GetValue() [2/2]

void apollo::localization::msf::LosslessMap::GetValue ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id,
std::vector< unsigned char > *  values 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.

This function returns the value of each layer in the map cell.

在文件 lossless_map.cc51 行定义.

53 {
54 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
56 resolution_id, zone_id);
57 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
58 node->GetValue(coordinate, values);
59}

◆ GetValueSafe() [1/2]

unsigned char apollo::localization::msf::LosslessMap::GetValueSafe ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.

在文件 lossless_map.cc158 行定义.

160 {
161 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
163 resolution_id, zone_id);
164 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
165 return node->GetValue(coordinate);
166}

◆ GetValueSafe() [2/2]

void apollo::localization::msf::LosslessMap::GetValueSafe ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id,
std::vector< unsigned char > *  values 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.

This function returns the value of each layer in the map cell.

在文件 lossless_map.cc61 行定义.

63 {
64 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
66 resolution_id, zone_id);
67 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
68 node->GetValue(coordinate, values);
69}

◆ GetVar() [1/2]

float apollo::localization::msf::LosslessMap::GetVar ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.

在文件 lossless_map.cc168 行定义.

169 {
170 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
172 resolution_id, zone_id);
173 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
174 return node->GetVar(coordinate);
175}

◆ GetVar() [2/2]

void apollo::localization::msf::LosslessMap::GetVar ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id,
std::vector< float > *  vars 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache and return the value, if necessary.

This function returns the value of each layer in the map cell.

在文件 lossless_map.cc71 行定义.

72 {
73 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
75 resolution_id, zone_id);
76 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNode(index));
77 node->GetVar(coordinate, vars);
78}

◆ GetVarSafe() [1/2]

float apollo::localization::msf::LosslessMap::GetVarSafe ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.

在文件 lossless_map.cc177 行定义.

178 {
179 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
181 resolution_id, zone_id);
182 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
183 return node->GetVar(coordinate);
184}

◆ GetVarSafe() [2/2]

void apollo::localization::msf::LosslessMap::GetVarSafe ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned int  resolution_id,
std::vector< float > *  vars 
)

Given the 3D global coordinate, this function loads the corresponding map node in the cache thread safely and return the value, if necessary.

This function returns the value of each layer in the map cell.

在文件 lossless_map.cc80 行定义.

82 {
83 DCHECK_LT(resolution_id, map_config_->map_resolutions_.size());
85 resolution_id, zone_id);
86 LosslessMapNode* node = static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
87 node->GetVar(coordinate, vars);
88}

◆ LoadMapArea()

bool apollo::localization::msf::LosslessMap::LoadMapArea ( const Eigen::Vector3d &  seed_pt3d,
unsigned int  resolution_id,
unsigned int  zone_id,
int  filter_size_x,
int  filter_size_y 
)
virtual

Load map nodes for the location calculate of this frame.

If the forecasts are correct in last frame, these nodes will be all in cache, if not, then need to create loading tasks, and wait for the loading finish, in order to the nodes which the following calculate needed are all in the memory, eigen version.

重载 apollo::localization::msf::BaseMap .

在文件 lossless_map.cc248 行定义.

250 {
251 BaseMap::LoadMapArea(seed_pt3d, resolution_id, zone_id, filter_size_x,
252 filter_size_y);
253 return true;
254}
virtual bool LoadMapArea(const Eigen::Vector3d &seed_pt3d, unsigned int resolution_id, unsigned int zone_id, int filter_size_x, int filter_size_y)
Load map nodes for the location calculate of this frame.
Definition base_map.cc:407

◆ PreloadMapArea()

void apollo::localization::msf::LosslessMap::PreloadMapArea ( const Eigen::Vector3d &  location,
const Eigen::Vector3d &  trans_diff,
unsigned int  resolution_id,
unsigned int  zone_id 
)
virtual

Preload map nodes for the next frame location calculation.

It will forecasts the nodes by the direction of the car moving. Because the progress of loading will cost a long time (over 100ms), it must do this for a period of time in advance. After the index of nodes calculate finished, it will create loading tasks, but will not wait for the loading finished, eigen version.

重载 apollo::localization::msf::BaseMap .

在文件 lossless_map.cc241 行定义.

244 {
245 BaseMap::PreloadMapArea(location, trans_diff, resolution_id, zone_id);
246}
virtual void PreloadMapArea(const Eigen::Vector3d &location, const Eigen::Vector3d &trans_diff, unsigned int resolution_id, unsigned int zone_id)
Preload map nodes for the next frame location calculation.
Definition base_map.cc:268

◆ SetGroundHeightOffset()

void apollo::localization::msf::LosslessMap::SetGroundHeightOffset ( double  height_offset)

Set the ground height offset.

◆ SetValue()

void apollo::localization::msf::LosslessMap::SetValue ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned char  intensity 
)

Set the value of a pixel in the map, including all the resolution levels.

参数
<coordinate>The 3D global coordinate.
<intensity>The reflectance intensity.

在文件 lossless_map.cc29 行定义.

30 {
31 for (size_t i = 0; i < map_config_->map_resolutions_.size(); ++i) {
33 *map_config_, coordinate, static_cast<unsigned int>(i), zone_id);
34 LosslessMapNode* node =
35 static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
36 node->SetValue(coordinate, intensity);
37 }
38}

◆ SetValueLayer()

void apollo::localization::msf::LosslessMap::SetValueLayer ( const Eigen::Vector3d &  coordinate,
int  zone_id,
unsigned char  intensity 
)

Set the vlaue of a pixel in a layer in the map node.

参数
<coordinate>The 3D global coordinate. The z is used as the altitude for the layer match.
<intensity>The reflectance intensity.

在文件 lossless_map.cc40 行定义.

41 {
42 for (size_t i = 0; i < map_config_->map_resolutions_.size(); ++i) {
44 *map_config_, coordinate, static_cast<unsigned int>(i), zone_id);
45 LosslessMapNode* node =
46 static_cast<LosslessMapNode*>(GetMapNodeSafe(index));
47 node->SetValueLayer(coordinate, intensity);
48 }
49}

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