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

The data structure of the base map. 更多...

#include <base_map.h>

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

Public 成员函数

 BaseMap (BaseMapConfig *config)
 The constructor.
 
virtual ~BaseMap ()
 The destructor.
 
virtual void InitMapNodeCaches (int cacheL1_size, int cahceL2_size)
 
void AttachMapNodePool (BaseMapNodePool *p_map_node_pool)
 Attach map node pointer.
 
BaseMapNodeGetMapNode (const MapNodeIndex &index)
 Return 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)
 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 Release ()
 Release resources.
 
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.
 
void ComputeMd5ForAllMapNodes ()
 Compute md5 for all map node file in map.
 
bool CheckMap ()
 Check if map is normal.
 
bool CheckMapStrictly ()
 Check if map is normal(with map node checking).
 
const BaseMapConfigGetMapConfig () const
 Get the map config.
 
BaseMapConfigGetMapConfig ()
 Get the map config.
 
const std::vector< std::string > & GetAllMapNodePaths () const
 Get all map node paths.
 
const std::vector< std::string > & GetAllMapNodeMd5s () const
 Get all map node md5s.
 

Protected 成员函数

void GetAllMapIndexAndPath ()
 
MapNodeIndex GetMapIndexFromMapPath (const std::string &map_path)
 
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 (const MapNodeIndex &index, bool is_reserved=false)
 Load map node by index, thread_safety.
 
void CheckAndUpdateCache (std::set< MapNodeIndex > *map_ids)
 Check map node in L2 Cache.
 

Protected 属性

BaseMapConfigmap_config_ = nullptr
 The map settings.
 
MapNodeCache< MapNodeIndex, BaseMapNode >::DestroyFunc destroy_func_lvl1_
 
MapNodeCache< MapNodeIndex, BaseMapNode >::DestroyFunc destroy_func_lvl2_
 
std::unique_ptr< MapNodeCache< MapNodeIndex, BaseMapNode > > map_node_cache_lvl1_ = nullptr
 The cache for map node preload.
 
std::unique_ptr< MapNodeCache< MapNodeIndex, BaseMapNode > > map_node_cache_lvl2_ = nullptr
 brief The dynamic map node preloading thread pool pointer.
 
BaseMapNodePoolmap_node_pool_ = nullptr
 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.
 
std::vector< MapNodeIndexall_map_node_indices_
 All the map nodes in the Map (in the disk).
 
std::vector< std::string > all_map_node_paths_
 
std::vector< std::string > all_map_node_md5s_
 All the map nodes' md5 in the Map (in the disk).
 

详细描述

The data structure of the base map.

在文件 base_map.h38 行定义.

构造及析构函数说明

◆ BaseMap()

apollo::localization::msf::pyramid_map::BaseMap::BaseMap ( BaseMapConfig config)
explicit

The constructor.

在文件 base_map.cc32 行定义.

33 : map_config_(config),
34 map_node_cache_lvl1_(nullptr),
35 map_node_cache_lvl2_(nullptr),
36 map_node_pool_(nullptr) {}
BaseMapConfig * map_config_
The map settings.
Definition base_map.h:125
std::unique_ptr< MapNodeCache< MapNodeIndex, BaseMapNode > > map_node_cache_lvl2_
brief The dynamic map node preloading thread pool pointer.
Definition base_map.h:134
std::unique_ptr< MapNodeCache< MapNodeIndex, BaseMapNode > > map_node_cache_lvl1_
The cache for map node preload.
Definition base_map.h:131
BaseMapNodePool * map_node_pool_
The map node memory pool pointer.
Definition base_map.h:136

◆ ~BaseMap()

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

The destructor.

在文件 base_map.cc38 行定义.

38{}

成员函数说明

◆ AddDataset()

void apollo::localization::msf::pyramid_map::BaseMap::AddDataset ( const std::string  dataset_path)

Add a dataset path to the map config.

在文件 base_map.cc117 行定义.

117 {
118 map_config_->map_datasets_.push_back(dataset_path);
119 std::string config_path = map_config_->map_folder_path_ + "/config.xml";
120 map_config_->Save(config_path);
121}
std::vector< std::string > map_datasets_
The datasets that contributed to the map.
bool Save(const std::string &file_path)
Save the map option to a XML file.

◆ AttachMapNodePool()

void apollo::localization::msf::pyramid_map::BaseMap::AttachMapNodePool ( BaseMapNodePool p_map_node_pool)

Attach map node pointer.

在文件 base_map.cc53 行定义.

53 {
54 map_node_pool_ = map_node_pool;
55}

◆ CheckAndUpdateCache()

void apollo::localization::msf::pyramid_map::BaseMap::CheckAndUpdateCache ( std::set< MapNodeIndex > *  map_ids)
protected

Check map node in L2 Cache.

在文件 base_map.cc164 行定义.

164 {
165 std::set<MapNodeIndex>::iterator itr = map_ids->begin();
166 BaseMapNode* node = nullptr;
167 while (itr != map_ids->end()) {
168 boost::unique_lock<boost::recursive_mutex> lock(map_load_mutex_);
169 if (map_node_cache_lvl2_->Get(*itr, &node)) {
170 node->SetIsReserved(true);
171 map_node_cache_lvl1_->Put(*itr, node);
172 lock.unlock();
173 itr = map_ids->erase(itr);
174 } else {
175 lock.unlock();
176 ++itr;
177 }
178 }
179}
boost::recursive_mutex map_load_mutex_
The mutex for preload map node.
Definition base_map.h:140

◆ CheckMap()

bool apollo::localization::msf::pyramid_map::BaseMap::CheckMap ( )

Check if map is normal.

在文件 base_map.cc533 行定义.

533 {
535
536 for (unsigned int i = 0; i < all_map_node_paths_.size(); ++i) {
537 const std::string& path = all_map_node_paths_[i];
538 std::map<std::string, std::string>::iterator it =
539 map_config_->node_md5_map_.find(path);
540 if (it == map_config_->node_md5_map_.end()) {
541 return false;
542 }
543
544 if (it->second != all_map_node_md5s_[i]) {
545 return false;
546 }
547 }
548
549 return true;
550}
std::map< std::string, std::string > node_md5_map_
The map structure to store map node file name and its md5.
std::vector< std::string > all_map_node_md5s_
All the map nodes' md5 in the Map (in the disk).
Definition base_map.h:147
std::vector< std::string > all_map_node_paths_
Definition base_map.h:144
void ComputeMd5ForAllMapNodes()
Compute md5 for all map node file in map.
Definition base_map.cc:522

◆ CheckMapStrictly()

bool apollo::localization::msf::pyramid_map::BaseMap::CheckMapStrictly ( )

Check if map is normal(with map node checking).

在文件 base_map.cc552 行定义.

552 {
553 // TODO(fuxiangyu@baidu.com)
554 return true;
555}

◆ ComputeMd5ForAllMapNodes()

void apollo::localization::msf::pyramid_map::BaseMap::ComputeMd5ForAllMapNodes ( )

Compute md5 for all map node file in map.

在文件 base_map.cc522 行定义.

522 {
523 all_map_node_md5s_.clear();
525 for (unsigned int i = 0; i < all_map_node_paths_.size(); ++i) {
526 std::string path = map_config_->map_folder_path_ + all_map_node_paths_[i];
529 all_map_node_md5s_.push_back(md5);
530 }
531}
static void ComputeFileMd5(const std::string &file_path, unsigned char res[kUcharMd5Length])
Compute file md5 given a file path.

◆ GetAllMapIndexAndPath()

void apollo::localization::msf::pyramid_map::BaseMap::GetAllMapIndexAndPath ( )
protected

在文件 base_map.cc502 行定义.

502 {
503 std::string map_folder_path = map_config_->map_folder_path_;
504 boost::filesystem::path map_folder_path_boost(map_folder_path);
505 all_map_node_indices_.clear();
506 all_map_node_paths_.clear();
507 boost::filesystem::recursive_directory_iterator end_iter;
508 boost::filesystem::recursive_directory_iterator iter(map_folder_path_boost);
509 for (; iter != end_iter; ++iter) {
510 if (!boost::filesystem::is_directory(*iter)) {
511 if (iter->path().extension() == "") {
512 std::string path = iter->path().string();
513 path = path.substr(map_folder_path.length(), path.length());
514
515 all_map_node_paths_.push_back(path);
517 }
518 }
519 }
520}
std::vector< MapNodeIndex > all_map_node_indices_
All the map nodes in the Map (in the disk).
Definition base_map.h:143
MapNodeIndex GetMapIndexFromMapPath(const std::string &map_path)
Definition base_map.cc:490

◆ GetAllMapNodeMd5s()

const std::vector< std::string > & apollo::localization::msf::pyramid_map::BaseMap::GetAllMapNodeMd5s ( ) const
inline

Get all map node md5s.

在文件 base_map.h105 行定义.

105 {
106 return all_map_node_md5s_;
107 }

◆ GetAllMapNodePaths()

const std::vector< std::string > & apollo::localization::msf::pyramid_map::BaseMap::GetAllMapNodePaths ( ) const
inline

Get all map node paths.

在文件 base_map.h101 行定义.

101 {
102 return all_map_node_paths_;
103 }

◆ GetMapConfig() [1/2]

BaseMapConfig & apollo::localization::msf::pyramid_map::BaseMap::GetMapConfig ( )
inline

Get the map config.

在文件 base_map.h99 行定义.

99{ return *map_config_; }

◆ GetMapConfig() [2/2]

const BaseMapConfig & apollo::localization::msf::pyramid_map::BaseMap::GetMapConfig ( ) const
inline

Get the map config.

在文件 base_map.h97 行定义.

97{ return *map_config_; }

◆ GetMapIndexFromMapPath()

MapNodeIndex apollo::localization::msf::pyramid_map::BaseMap::GetMapIndexFromMapPath ( const std::string &  map_path)
protected

在文件 base_map.cc490 行定义.

490 {
491 MapNodeIndex index;
492 char buf[100];
493 sscanf(map_path.c_str(), "/%03u/%05s/%02d/%08u/%08u", &index.resolution_id_,
494 buf, &index.zone_id_, &index.m_, &index.n_);
495 std::string zone = buf;
496 if (zone == "south") {
497 index.zone_id_ = -index.zone_id_;
498 }
499 return index;
500}
apollo::localization::msf::pyramid_map::MapNodeIndex MapNodeIndex

◆ GetMapNode()

BaseMapNode * apollo::localization::msf::pyramid_map::BaseMap::GetMapNode ( const MapNodeIndex index)

Return the map node, if it's not in the cache, return false.

在文件 base_map.cc57 行定义.

57 {
58 BaseMapNode* node = nullptr;
59 map_node_cache_lvl1_->Get(index, &node);
60 return node;
61}

◆ GetMapNodeSafe()

BaseMapNode * apollo::localization::msf::pyramid_map::BaseMap::GetMapNodeSafe ( const MapNodeIndex index)

Return the map node, if it's not in the cache, safely load it.

在文件 base_map.cc63 行定义.

63 {
64 BaseMapNode* node = nullptr;
65 // try get from cacheL1
66 boost::unique_lock<boost::recursive_mutex> lock1(map_load_mutex_);
67 bool success = map_node_cache_lvl1_->Get(index, &node);
68 if (success) {
69 lock1.unlock();
70 return node;
71 }
72 lock1.unlock();
73
74 // try get from cacheL2
75 boost::unique_lock<boost::recursive_mutex> lock2(map_load_mutex_);
76 success = map_node_cache_lvl2_->Get(index, &node);
77 if (success) {
78 node->SetIsReserved(true);
79 map_node_cache_lvl1_->Put(index, node);
80 lock2.unlock();
81 return node;
82 }
83 lock2.unlock();
84
85 // load from disk
86 std::cerr << "GetMapNodeSafe: This node don't exist in cache! " << std::endl
87 << "load this node from disk now!" << index << std::endl;
88
89 LoadMapNodeThreadSafety(index, true);
90
91 boost::unique_lock<boost::recursive_mutex> lock3(map_load_mutex_);
92 map_node_cache_lvl2_->Get(index, &node);
93 map_node_cache_lvl1_->Put(index, node);
94 lock3.unlock();
95
96 return node;
97}
void LoadMapNodeThreadSafety(const MapNodeIndex &index, bool is_reserved=false)
Load map node by index, thread_safety.
Definition base_map.cc:228

◆ InitMapNodeCaches()

void apollo::localization::msf::pyramid_map::BaseMap::InitMapNodeCaches ( int  cacheL1_size,
int  cahceL2_size 
)
virtual

在文件 base_map.cc40 行定义.

40 {
43 std::placeholders::_1);
46 std::placeholders::_1);
47 map_node_cache_lvl1_.reset(new MapNodeCache<MapNodeIndex, BaseMapNode>(
48 cacheL1_size, destroy_func_lvl1_));
49 map_node_cache_lvl2_.reset(new MapNodeCache<MapNodeIndex, BaseMapNode>(
50 cahceL2_size, destroy_func_lvl2_));
51}
static bool CacheL2Destroy(Element *value)
static bool CacheL1Destroy(Element *value)
MapNodeCache< MapNodeIndex, BaseMapNode >::DestroyFunc destroy_func_lvl1_
Definition base_map.h:127
MapNodeCache< MapNodeIndex, BaseMapNode >::DestroyFunc destroy_func_lvl2_
Definition base_map.h:128

◆ IsMapNodeExist()

bool apollo::localization::msf::pyramid_map::BaseMap::IsMapNodeExist ( const MapNodeIndex index)

Check if the map node in the cache.

在文件 base_map.cc99 行定义.

99 {
100 boost::unique_lock<boost::recursive_mutex> lock(map_load_mutex_);
101 bool if_exist = map_node_cache_lvl1_->IsExist(index);
102 lock.unlock();
103 return if_exist;
104}

◆ LoadMapArea()

bool apollo::localization::msf::pyramid_map::BaseMap::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.

top left

top center

top right

middle left

middle center

middle right

bottom left

bottom center

bottom right

在文件 base_map.cc394 行定义.

396 {
397 if (map_node_pool_ == nullptr) {
398 std::cerr << "Map node pool is nullptr!" << std::endl;
399 return false;
400 }
401 std::set<MapNodeIndex> map_ids;
402 float map_pixel_resolution =
403 this->map_config_->map_resolutions_[resolution_id];
405 Eigen::Vector3d pt_top_left;
406 pt_top_left[0] = seed_pt3d[0] -
407 (static_cast<float>(this->map_config_->map_node_size_x_) *
408 map_pixel_resolution / 2.0) -
409 static_cast<float>(filter_size_x / 2) * map_pixel_resolution;
410 pt_top_left[1] = seed_pt3d[1] -
411 (static_cast<float>(this->map_config_->map_node_size_y_) *
412 map_pixel_resolution / 2.0) -
413 static_cast<float>(filter_size_y / 2) * map_pixel_resolution;
414 pt_top_left[2] = 0;
416 resolution_id, zone_id);
417 map_ids.insert(map_id);
419 Eigen::Vector3d pt_top_center;
420 pt_top_center[0] = seed_pt3d[0];
421 pt_top_center[1] = pt_top_left[1];
422 pt_top_center[2] = 0;
423 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, pt_top_center,
424 resolution_id, zone_id);
425 map_ids.insert(map_id);
427 Eigen::Vector3d pt_top_right;
428 pt_top_right[0] =
429 seed_pt3d[0] +
430 (static_cast<float>(this->map_config_->map_node_size_x_) *
431 map_pixel_resolution / 2.0) +
432 static_cast<float>(filter_size_x / 2) * map_pixel_resolution;
433 pt_top_right[1] = pt_top_left[1];
434 pt_top_left[2] = 0;
435 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, pt_top_right,
436 resolution_id, zone_id);
437 map_ids.insert(map_id);
439 Eigen::Vector3d pt_middle_left;
440 pt_middle_left[0] = pt_top_left[0];
441 pt_middle_left[1] = seed_pt3d[1];
442 pt_middle_left[2] = 0;
443 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, pt_middle_left,
444 resolution_id, zone_id);
445 map_ids.insert(map_id);
447 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, seed_pt3d, resolution_id,
448 zone_id);
449 map_ids.insert(map_id);
451 Eigen::Vector3d pt_middle_right;
452 pt_middle_right[0] = pt_top_right[0];
453 pt_middle_right[1] = seed_pt3d[1];
454 pt_middle_right[2] = 0;
455 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, pt_middle_right,
456 resolution_id, zone_id);
457 map_ids.insert(map_id);
459 Eigen::Vector3d pt_bottom_left;
460 pt_bottom_left[0] = pt_top_left[0];
461 pt_bottom_left[1] =
462 seed_pt3d[1] +
463 (static_cast<float>(this->map_config_->map_node_size_y_) *
464 map_pixel_resolution / 2.0) +
465 static_cast<float>(filter_size_y / 2) * map_pixel_resolution;
466 pt_bottom_left[2] = 0;
467 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, pt_bottom_left,
468 resolution_id, zone_id);
469 map_ids.insert(map_id);
471 Eigen::Vector3d pt_bottom_center;
472 pt_bottom_center[0] = seed_pt3d[0];
473 pt_bottom_center[1] = pt_bottom_left[1];
474 pt_bottom_center[2] = 0;
475 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, pt_bottom_center,
476 resolution_id, zone_id);
477 map_ids.insert(map_id);
479 Eigen::Vector3d pt_bottom_right;
480 pt_bottom_right[0] = pt_top_right[0];
481 pt_bottom_right[1] = pt_bottom_left[1];
482 pt_bottom_right[2] = 0;
483 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, pt_bottom_right,
484 resolution_id, zone_id);
485 map_ids.insert(map_id);
486 this->LoadMapNodes(&map_ids);
487 return true;
488}
unsigned int map_node_size_y_
The map node size in pixels.
std::vector< float > map_resolutions_
The pixel resolutions in the map in meters.
unsigned int map_node_size_x_
The map node size in pixels.
void LoadMapNodes(std::set< MapNodeIndex > *map_ids)
Load map node by index.
Definition base_map.cc:123
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.

◆ LoadMapNodes()

void apollo::localization::msf::pyramid_map::BaseMap::LoadMapNodes ( std::set< MapNodeIndex > *  map_ids)
protected

Load map node by index.

在文件 base_map.cc123 行定义.

123 {
124 if (map_ids->size() > map_node_cache_lvl1_->Capacity()) {
125 std::cerr << "map_ids's size is bigger than cache's capacity" << std::endl;
126 return;
127 }
128
129 // check in cacheL1
130 std::set<MapNodeIndex>::iterator itr = map_ids->begin();
131 while (itr != map_ids->end()) {
132 boost::unique_lock<boost::recursive_mutex> lock1(map_load_mutex_);
133 if (map_node_cache_lvl1_->IsExist(*itr)) {
134 // fresh LRU list
135 map_node_cache_lvl2_->IsExist(*itr);
136 lock1.unlock();
137 itr = map_ids->erase(itr);
138 } else {
139 lock1.unlock();
140 ++itr;
141 }
142 }
143 // check and update cache
144 CheckAndUpdateCache(map_ids);
145 // load from disk sync
146 std::vector<std::future<void>> load_futures_;
147 itr = map_ids->begin();
148 while (itr != map_ids->end()) {
149 AERROR << "Preload map node failed!";
150 load_futures_.emplace_back(
151 cyber::Async(&BaseMap::LoadMapNodeThreadSafety, this, *itr, true));
152 ++itr;
153 }
154
155 for (auto& future : load_futures_) {
156 if (future.valid()) {
157 future.get();
158 }
159 }
160 // check in cacheL2 again
161 CheckAndUpdateCache(map_ids);
162}
void CheckAndUpdateCache(std::set< MapNodeIndex > *map_ids)
Check map node in L2 Cache.
Definition base_map.cc:164
#define AERROR
Definition log.h:44

◆ LoadMapNodeThreadSafety()

void apollo::localization::msf::pyramid_map::BaseMap::LoadMapNodeThreadSafety ( const MapNodeIndex index,
bool  is_reserved = false 
)
protected

Load map node by index, thread_safety.

在文件 base_map.cc228 行定义.

229 {
230 BaseMapNode* map_node = nullptr;
231 while (map_node == nullptr) {
232 map_node = map_node_pool_->AllocMapNode();
233 if (map_node == nullptr) {
234 boost::unique_lock<boost::recursive_mutex> lock(map_load_mutex_);
235 BaseMapNode* node_remove = map_node_cache_lvl2_->ClearOne();
236 lock.unlock();
237 if (node_remove) {
238 map_node_pool_->FreeMapNode(node_remove);
239 }
240 }
241 }
242 map_node->SetMapNodeIndex(index);
243
244 if (!map_node->Load()) {
245 AINFO << "Created map node: " << index;
246 } else {
247 AINFO << "Loaded map node: " << index;
248 }
249 map_node->SetIsReserved(is_reserved);
250 boost::unique_lock<boost::recursive_mutex> lock(map_load_mutex_);
251 BaseMapNode* node_remove = map_node_cache_lvl2_->Put(index, map_node);
252 // if the node already added into cacheL2, erase it from preloading set
253 auto itr = map_preloading_task_index_.find(index);
254 if (itr != map_preloading_task_index_.end()) {
256 }
257 lock.unlock();
258 if (node_remove) {
259 map_node_pool_->FreeMapNode(node_remove);
260 }
261}
BaseMapNode * AllocMapNode()
Get a MapNode object from memory pool.
void FreeMapNode(BaseMapNode *map_node)
Release MapNode object to memory pool.
std::set< MapNodeIndex > map_preloading_task_index_
@bried Keep the index of preloading nodes.
Definition base_map.h:138
#define AINFO
Definition log.h:42

◆ PreloadMapArea()

void apollo::localization::msf::pyramid_map::BaseMap::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.

top left

top center

top right

middle left

middle center

middle right

bottom left

bottom center

bottom right

在文件 base_map.cc263 行定义.

265 {
266 if (map_node_pool_ == nullptr) {
267 std::cerr << "Map node pool is nullptr!" << std::endl;
268 return;
269 }
270 int x_direction = trans_diff[0] > 0 ? 1 : -1;
271 int y_direction = trans_diff[1] > 0 ? 1 : -1;
272 std::set<MapNodeIndex> map_ids;
273 float map_pixel_resolution =
274 this->map_config_->map_resolutions_[resolution_id];
276 Eigen::Vector3d pt_top_left;
277 pt_top_left[0] =
278 location[0] - (static_cast<float>(this->map_config_->map_node_size_x_) *
279 map_pixel_resolution / 2.0f);
280 pt_top_left[1] =
281 location[1] - (static_cast<float>(this->map_config_->map_node_size_y_) *
282 map_pixel_resolution / 2.0f);
283 pt_top_left[2] = 0;
285 resolution_id, zone_id);
286 map_ids.insert(map_id);
288 Eigen::Vector3d pt_top_center;
289 pt_top_center[0] = location[0];
290 pt_top_center[1] = pt_top_left[1];
291 pt_top_center[2] = 0;
292 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, pt_top_center,
293 resolution_id, zone_id);
294 map_ids.insert(map_id);
296 Eigen::Vector3d pt_top_right;
297 pt_top_right[0] =
298 location[0] + (static_cast<float>(this->map_config_->map_node_size_x_) *
299 map_pixel_resolution / 2.0f);
300 pt_top_right[1] = pt_top_left[1];
301 pt_top_right[2] = 0;
302 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, pt_top_right,
303 resolution_id, zone_id);
304 map_ids.insert(map_id);
306 Eigen::Vector3d pt_middle_left;
307 pt_middle_left[0] = pt_top_left[0];
308 pt_middle_left[1] = location[1];
309 pt_middle_left[2] = 0;
310 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, pt_middle_left,
311 resolution_id, zone_id);
312 map_ids.insert(map_id);
314 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, location, resolution_id,
315 zone_id);
316 map_ids.insert(map_id);
318 Eigen::Vector3d pt_middle_right;
319 pt_middle_right[0] = pt_top_right[0];
320 pt_middle_right[1] = pt_middle_left[1];
321 pt_middle_right[2] = 0;
322 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, pt_middle_right,
323 resolution_id, zone_id);
324 map_ids.insert(map_id);
326 Eigen::Vector3d pt_bottom_left;
327 pt_bottom_left[0] = pt_top_left[0];
328 pt_bottom_left[1] =
329 location[1] + (static_cast<float>(this->map_config_->map_node_size_y_) *
330 map_pixel_resolution / 2.0);
331 pt_bottom_left[2] = 0;
332 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, pt_bottom_left,
333 resolution_id, zone_id);
334 map_ids.insert(map_id);
336 Eigen::Vector3d pt_bottom_center;
337 pt_bottom_center[0] = pt_top_center[0];
338 pt_bottom_center[1] = pt_bottom_left[1];
339 pt_bottom_center[2] = 0;
340 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, pt_bottom_center,
341 resolution_id, zone_id);
342 map_ids.insert(map_id);
344 Eigen::Vector3d pt_bottom_right;
345 pt_bottom_right[0] = pt_top_right[0];
346 pt_bottom_right[1] = pt_bottom_left[1];
347 pt_bottom_right[2] = 0;
348 map_id = MapNodeIndex::GetMapNodeIndex(*map_config_, pt_bottom_right,
349 resolution_id, zone_id);
350 map_ids.insert(map_id);
351 for (int i = -1; i < 2; ++i) {
352 Eigen::Vector3d pt;
353 pt[0] = location[0] + x_direction * 1.5 *
355 map_pixel_resolution;
356 pt[1] = location[1] + static_cast<double>(i) *
358 map_pixel_resolution;
359 pt[2] = 0;
360 map_id =
361 MapNodeIndex::GetMapNodeIndex(*map_config_, pt, resolution_id, zone_id);
362 map_ids.insert(map_id);
363 }
364 for (int i = -1; i < 2; ++i) {
365 Eigen::Vector3d pt;
366 pt[0] = location[0] + static_cast<double>(i) *
368 map_pixel_resolution;
369 pt[1] = location[1] + y_direction * 1.5 *
371 map_pixel_resolution;
372 pt[2] = 0;
373 map_id =
374 MapNodeIndex::GetMapNodeIndex(*map_config_, pt, resolution_id, zone_id);
375 map_ids.insert(map_id);
376 }
377 {
378 Eigen::Vector3d pt;
379 pt[0] = location[0] + x_direction * 1.5 *
381 map_pixel_resolution;
382 pt[1] = location[1] + y_direction * 1.5 *
384 map_pixel_resolution;
385 pt[2] = 0;
386 map_id =
387 MapNodeIndex::GetMapNodeIndex(*map_config_, pt, resolution_id, zone_id);
388 map_ids.insert(map_id);
389 }
390
391 this->PreloadMapNodes(&map_ids);
392}
void PreloadMapNodes(std::set< MapNodeIndex > *map_ids)
Load map node by index.
Definition base_map.cc:181

◆ PreloadMapNodes()

void apollo::localization::msf::pyramid_map::BaseMap::PreloadMapNodes ( std::set< MapNodeIndex > *  map_ids)
protected

Load map node by index.

在文件 base_map.cc181 行定义.

181 {
182 if (map_ids->size() > map_node_cache_lvl2_->Capacity()) {
183 AERROR << "map_ids's size is bigger than cache's capacity";
184 return;
185 }
186 // check in cacheL2
187 std::set<MapNodeIndex>::iterator itr = map_ids->begin();
188 bool is_exist = false;
189 while (itr != map_ids->end()) {
190 boost::unique_lock<boost::recursive_mutex> lock1(map_load_mutex_);
191 is_exist = map_node_cache_lvl2_->IsExist(*itr);
192 lock1.unlock();
193 if (is_exist) {
194 itr = map_ids->erase(itr);
195 } else {
196 ++itr;
197 }
198 }
199 // check whether in already preloading index set
200 itr = map_ids->begin();
201 auto preloading_itr = map_preloading_task_index_.end();
202 while (itr != map_ids->end()) {
203 boost::unique_lock<boost::recursive_mutex> lock2(map_load_mutex_);
204 preloading_itr = map_preloading_task_index_.find(*itr);
205 lock2.unlock();
206 if (preloading_itr != map_preloading_task_index_.end()) {
207 // already preloading
208 itr = map_ids->erase(itr);
209 } else {
210 ++itr;
211 }
212 }
213 // load form disk sync
214 std::vector<std::future<void>> preload_futures;
215 itr = map_ids->begin();
216 AINFO << "Preload map node size: " << map_ids->size();
217 while (itr != map_ids->end()) {
218 AINFO << "Preload map node: " << *itr << std::endl;
219 boost::unique_lock<boost::recursive_mutex> lock3(map_load_mutex_);
220 map_preloading_task_index_.insert(*itr);
221 lock3.unlock();
222 preload_futures.emplace_back(
223 cyber::Async(&BaseMap::LoadMapNodeThreadSafety, this, *itr, false));
224 ++itr;
225 }
226}

◆ Release()

void apollo::localization::msf::pyramid_map::BaseMap::Release ( )

Release resources.

◆ SetMapFolderPath()

bool apollo::localization::msf::pyramid_map::BaseMap::SetMapFolderPath ( const std::string  folder_path)

Set the directory of the map.

在文件 base_map.cc106 行定义.

106 {
107 map_config_->map_folder_path_ = folder_path;
108 // Try to load the config
109 std::string config_path = map_config_->map_folder_path_ + "/config.xml";
110 if (cyber::common::PathExists(config_path)) {
111 map_config_->Load(config_path);
112 return true;
113 }
114 return false;
115}
bool Load(const std::string &file_path)
Load the map option from a XML file.
bool PathExists(const std::string &path)
Check if the path exists.
Definition file.cc:195

类成员变量说明

◆ all_map_node_indices_

std::vector<MapNodeIndex> apollo::localization::msf::pyramid_map::BaseMap::all_map_node_indices_
protected

All the map nodes in the Map (in the disk).

在文件 base_map.h143 行定义.

◆ all_map_node_md5s_

std::vector<std::string> apollo::localization::msf::pyramid_map::BaseMap::all_map_node_md5s_
protected

All the map nodes' md5 in the Map (in the disk).

在文件 base_map.h147 行定义.

◆ all_map_node_paths_

std::vector<std::string> apollo::localization::msf::pyramid_map::BaseMap::all_map_node_paths_
protected

在文件 base_map.h144 行定义.

◆ destroy_func_lvl1_

MapNodeCache<MapNodeIndex,BaseMapNode>::DestroyFunc apollo::localization::msf::pyramid_map::BaseMap::destroy_func_lvl1_
protected

在文件 base_map.h127 行定义.

◆ destroy_func_lvl2_

MapNodeCache<MapNodeIndex,BaseMapNode>::DestroyFunc apollo::localization::msf::pyramid_map::BaseMap::destroy_func_lvl2_
protected

在文件 base_map.h128 行定义.

◆ map_config_

BaseMapConfig* apollo::localization::msf::pyramid_map::BaseMap::map_config_ = nullptr
protected

The map settings.

在文件 base_map.h125 行定义.

◆ map_load_mutex_

boost::recursive_mutex apollo::localization::msf::pyramid_map::BaseMap::map_load_mutex_
protected

The mutex for preload map node.

在文件 base_map.h140 行定义.

◆ map_node_cache_lvl1_

std::unique_ptr<MapNodeCache<MapNodeIndex, BaseMapNode> > apollo::localization::msf::pyramid_map::BaseMap::map_node_cache_lvl1_ = nullptr
protected

The cache for map node preload.

在文件 base_map.h131 行定义.

◆ map_node_cache_lvl2_

std::unique_ptr<MapNodeCache<MapNodeIndex, BaseMapNode> > apollo::localization::msf::pyramid_map::BaseMap::map_node_cache_lvl2_ = nullptr
protected

brief The dynamic map node preloading thread pool pointer.

在文件 base_map.h134 行定义.

◆ map_node_pool_

BaseMapNodePool* apollo::localization::msf::pyramid_map::BaseMap::map_node_pool_ = nullptr
protected

The map node memory pool pointer.

在文件 base_map.h136 行定义.

◆ map_preloading_task_index_

std::set<MapNodeIndex> apollo::localization::msf::pyramid_map::BaseMap::map_preloading_task_index_
protected

@bried Keep the index of preloading nodes.

在文件 base_map.h138 行定义.


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