Apollo  6.0
Open source self driving car software
Public Member Functions | List of all members
apollo::localization::msf::LossyMap2D Class Reference

#include <lossy_map_2d.h>

Inheritance diagram for apollo::localization::msf::LossyMap2D:
Inheritance graph
Collaboration diagram for apollo::localization::msf::LossyMap2D:
Collaboration graph

Public Member Functions

 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. 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. More...
 
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. 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. More...
 
- Public Member Functions inherited from apollo::localization::msf::BaseMap
 BaseMap (BaseMapConfig *map_config)
 The constructor. More...
 
virtual ~BaseMap ()
 The destructor. More...
 
virtual void InitMapNodeCaches (int cacheL1_size, int cahceL2_size)
 Init load threadpool and preload threadpool. More...
 
BaseMapNodeGetMapNode (const MapNodeIndex &index)
 Get the map node, if it's not in the cache, return false. More...
 
BaseMapNodeGetMapNodeSafe (const MapNodeIndex &index)
 Return the map node, if it's not in the cache, safely load it. More...
 
bool IsMapNodeExist (const MapNodeIndex &index) const
 Check if the map node in the cache. More...
 
bool SetMapFolderPath (const std::string folder_path)
 Set the directory of the map. More...
 
void AddDataset (const std::string dataset_path)
 Add a dataset path to the map config. More...
 
void AttachMapNodePool (BaseMapNodePool *p_map_node_pool)
 Attach map node pointer. More...
 
void WriteBinary (FILE *file)
 Write all the map nodes to a single binary file stream. It's for binary streaming or packing. More...
 
void LoadBinary (FILE *file, std::string map_folder_path="")
 Load all the map nodes from a single binary file stream. It's for binary streaming or packing. More...
 
const BaseMapConfigGetConfig () const
 Get the map config. More...
 
BaseMapConfigGetConfig ()
 Get the map config. More...
 

Additional Inherited Members

- Protected Member Functions inherited from apollo::localization::msf::BaseMap
void LoadMapNodes (std::set< MapNodeIndex > *map_ids)
 Load map node by index. More...
 
void PreloadMapNodes (std::set< MapNodeIndex > *map_ids)
 Load map node by index. More...
 
void LoadMapNodeThreadSafety (MapNodeIndex index, bool is_reserved=false)
 Load map node by index, thread_safety. More...
 
- Protected Attributes inherited from apollo::localization::msf::BaseMap
BaseMapConfigmap_config_
 The map settings. More...
 
std::list< MapNodeIndexmap_nodes_disk_
 All the map nodes in the Map (in the disk). More...
 
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. More...
 
MapNodeCache< MapNodeIndex, BaseMapNode > * map_node_cache_lvl2_
 
BaseMapNodePoolmap_node_pool_
 The map node memory pool pointer. More...
 
std::set< MapNodeIndexmap_preloading_task_index_
 
boost::recursive_mutex map_load_mutex_
 The mutex for preload map node. More...
 

Constructor & Destructor Documentation

◆ LossyMap2D()

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

◆ ~LossyMap2D()

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

Member Function Documentation

◆ LoadMapArea()

virtual 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.

Reimplemented from apollo::localization::msf::BaseMap.

◆ PreloadMapArea()

virtual 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.

Reimplemented from apollo::localization::msf::BaseMap.


The documentation for this class was generated from the following file: