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

#include <lossy_map_2d.h>

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

Public 成员函数

 LossyMap2D (LossyMapConfig2D *config)
 
 ~LossyMap2D ()
 
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.
 

详细描述

在文件 lossy_map_2d.h26 行定义.

构造及析构函数说明

◆ LossyMap2D()

apollo::localization::msf::LossyMap2D::LossyMap2D ( LossyMapConfig2D config)
explicit

在文件 lossy_map_2d.cc23 行定义.

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

◆ ~LossyMap2D()

apollo::localization::msf::LossyMap2D::~LossyMap2D ( )

在文件 lossy_map_2d.cc25 行定义.

25{}

成员函数说明

◆ LoadMapArea()

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

在文件 lossy_map_2d.cc34 行定义.

36 {
37 BaseMap::LoadMapArea(seed_pt3d, resolution_id, zone_id, filter_size_x,
38 filter_size_y);
39 return true;
40}
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::LossyMap2D::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 .

在文件 lossy_map_2d.cc27 行定义.

30 {
31 BaseMap::PreloadMapArea(location, trans_diff, resolution_id, zone_id);
32}
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

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