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

The options of the reflectance map. 更多...

#include <base_map_config.h>

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

Public 成员函数

 BaseMapConfig (const std::string &map_version="0.1")
 The constructor gives the default map settings.
 
virtual ~BaseMapConfig ()
 The deconstructor.
 
bool Save (const std::string &file_path)
 Save the map option to a XML file.
 
bool Load (const std::string &file_path)
 Load the map option from a XML file.
 
void SetMapVersion (const std::string &map_version)
 Set map_version.
 
void SetMapNodeSize (unsigned int size_x, unsigned int size_y)
 Set map_node_size.
 
void SetGroundHeightOffset (float map_ground_height_offset)
 Set map_ground_height_offset.
 
void SetIsCompression (bool map_is_compression)
 Set map_is_compression.
 
void ResizeMapRange ()
 Resize map range by range and resolutions.
 
void SetSingleResolutions (float resolution=0.125)
 Set single resolutions.
 
void SetMultiResolutions ()
 Set multi resolutions.
 
void SetNodeMd5Map (const std::map< std::string, std::string > &node_md5_map)
 Set node_md5_map.
 
void AddNodeMd5 (const std::string &node_path, const std::string &md5)
 Add a node md5 pair.
 
MapVersion GetMapVersion () const
 Get map version.
 

Public 属性

std::string map_version_ = ""
 The version of map.
 
std::vector< float > map_resolutions_
 The pixel resolutions in the map in meters.
 
unsigned int map_node_size_x_ = 0
 The map node size in pixels.
 
unsigned int map_node_size_y_ = 0
 The map node size in pixels.
 
Rect2D< double > map_range_
 The minimum and maximum UTM range in the map.
 
float map_ground_height_offset_ = 0.0f
 Velodyne's height to the ground.
 
bool map_is_compression_ = false
 Enable the compression.
 
std::string map_folder_path_ = ""
 The map folder path.
 
std::vector< std::string > map_datasets_
 The datasets that contributed to the map.
 
std::map< std::string, std::string > node_md5_map_
 The map structure to store map node file name and its md5.
 
std::string coordinate_type_ = ""
 

Protected 成员函数

virtual bool CreateXml (boost::property_tree::ptree *config) const
 Create the XML structure.
 
virtual bool LoadXml (const boost::property_tree::ptree &config)
 Load the map options from a XML structure.
 

详细描述

The options of the reflectance map.

在文件 base_map_config.h42 行定义.

构造及析构函数说明

◆ BaseMapConfig()

apollo::localization::msf::pyramid_map::BaseMapConfig::BaseMapConfig ( const std::string &  map_version = "0.1")
explicit

The constructor gives the default map settings.

在文件 base_map_config.cc29 行定义.

29 {
30 map_version_ = map_version;
31 coordinate_type_ = "UTM";
32 map_resolutions_.push_back(0.125);
33 map_node_size_x_ = 1024; // in pixels
34 map_node_size_y_ = 1024; // in pixels
35 map_range_ = Rect2D<double>(0, 0, 1000448.0, 10000384.0); // in meters
38 map_folder_path_ = ".";
39}
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.
Rect2D< double > map_range_
The minimum and maximum UTM range in the map.
float map_ground_height_offset_
Velodyne's height to the ground.
unsigned int map_node_size_x_
The map node size in pixels.

◆ ~BaseMapConfig()

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

The deconstructor.

在文件 base_map_config.cc41 行定义.

41{}

成员函数说明

◆ AddNodeMd5()

void apollo::localization::msf::pyramid_map::BaseMapConfig::AddNodeMd5 ( const std::string &  node_path,
const std::string &  md5 
)

Add a node md5 pair.

在文件 base_map_config.cc252 行定义.

253 {
254 node_md5_map_[node_path] = md5;
255}
std::map< std::string, std::string > node_md5_map_
The map structure to store map node file name and its md5.

◆ CreateXml()

bool apollo::localization::msf::pyramid_map::BaseMapConfig::CreateXml ( boost::property_tree::ptree *  config) const
protectedvirtual

Create the XML structure.

apollo::localization::msf::pyramid_map::NdtMapConfig , 以及 apollo::localization::msf::pyramid_map::PyramidMapConfig 重载.

在文件 base_map_config.cc66 行定义.

66 {
67 config->put("map.map_config.version", map_version_);
68 config->put("map.map_config.coordnate_type", coordinate_type_);
69 config->put("map.map_config.node_size.x", map_node_size_x_);
70 config->put("map.map_config.node_size.y", map_node_size_y_);
71 config->put("map.map_config.range.min_x", map_range_.GetMinX());
72 config->put("map.map_config.range.min_y", map_range_.GetMinY());
73 config->put("map.map_config.range.max_x", map_range_.GetMaxX());
74 config->put("map.map_config.range.max_y", map_range_.GetMaxY());
75 config->put("map.map_config.compression", map_is_compression_);
76 config->put("map.map_runtime.map_ground_height_offset",
78 for (size_t i = 0; i < map_resolutions_.size(); ++i) {
79 config->add("map.map_config.resolutions.resolution", map_resolutions_[i]);
80 }
81
82 for (size_t i = 0; i < map_datasets_.size(); ++i) {
83 config->add("map.map_record.datasets.dataset", map_datasets_[i]);
84 }
85
86 // added md5 check info
87 std::map<std::string, std::string>::const_iterator iter;
88 for (iter = node_md5_map_.begin(); iter != node_md5_map_.end(); ++iter) {
89 boost::property_tree::ptree child;
90 child.put("path", iter->first);
91 child.put("md5", iter->second);
92 config->add_child("map.check_info.nodes.node", child);
93 }
94
95 return true;
96}
T GetMaxY() const
Get the max y of the rectangle.
Definition rect2d.h:88
T GetMaxX() const
Get the max x of the rectangle.
Definition rect2d.h:83
T GetMinX() const
Get the min x of the rectangle.
Definition rect2d.h:73
T GetMinY() const
Get the min y of the rectangle.
Definition rect2d.h:78
std::vector< std::string > map_datasets_
The datasets that contributed to the map.

◆ GetMapVersion()

MapVersion apollo::localization::msf::pyramid_map::BaseMapConfig::GetMapVersion ( ) const

Get map version.

在文件 base_map_config.cc270 行定义.

270 {
271 if (map_version_ == "lossy_full_alt" || map_version_ == "lossy_map") {
273 }
274
275 if (map_version_ == "0.21" || map_version_ == "lossless_map") {
277 }
278
279 if (map_version_ == "pyramid_lossy_map") {
281 }
282
283 if (map_version_ == "pyramid_lossless_map") {
285 }
286
287 return MapVersion::UNKNOWN;
288}

◆ Load()

bool apollo::localization::msf::pyramid_map::BaseMapConfig::Load ( const std::string &  file_path)

Load the map option from a XML file.

在文件 base_map_config.cc54 行定义.

54 {
55 boost::property_tree::ptree config;
56 boost::property_tree::read_xml(file_path, config);
57 bool success = LoadXml(config);
58
59 if (success) {
60 AINFO << "Loaded the map configuration from: " << file_path;
61 return true;
62 }
63 return false;
64}
virtual bool LoadXml(const boost::property_tree::ptree &config)
Load the map options from a XML structure.
#define AINFO
Definition log.h:42

◆ LoadXml()

bool apollo::localization::msf::pyramid_map::BaseMapConfig::LoadXml ( const boost::property_tree::ptree &  config)
protectedvirtual

Load the map options from a XML structure.

apollo::localization::msf::pyramid_map::PyramidMapConfig 重载.

在文件 base_map_config.cc98 行定义.

98 {
99 map_resolutions_.clear();
100 map_datasets_.clear();
101 node_md5_map_.clear();
102
103 auto map_version = config.get_optional<std::string>("map.map_config.version");
104 if (map_version) {
105 map_version_ = map_version.get();
106 }
107 auto coordinate_type =
108 config.get_optional<std::string>("map.map_config.coordinate_type");
109 if (coordinate_type) {
110 coordinate_type_ = coordinate_type.get();
111 }
112 auto map_node_size_x =
113 config.get_optional<unsigned int>("map.map_config.node_size.x");
114 if (map_node_size_x) {
115 map_node_size_x_ = map_node_size_x.get();
116 }
117
118 auto map_node_size_y =
119 config.get_optional<unsigned int>("map.map_config.node_size.y");
120 if (map_node_size_y) {
121 map_node_size_y_ = map_node_size_y.get();
122 }
123 double min_x = 0.0;
124 auto tmp_min_x = config.get_optional<double>("map.map_config.range.min_x");
125 if (tmp_min_x) {
126 min_x = tmp_min_x.get();
127 }
128 double min_y = 0.0;
129 auto tmp_min_y = config.get_optional<double>("map.map_config.range.min_y");
130 if (tmp_min_y) {
131 min_y = tmp_min_y.get();
132 }
133 double max_x = 0.0;
134 auto tmp_max_x = config.get_optional<double>("map.map_config.range.max_x");
135 if (tmp_max_x) {
136 max_x = tmp_max_x.get();
137 }
138 double max_y = 0.0;
139 auto tmp_max_y = config.get_optional<double>("map.map_config.range.max_y");
140 if (tmp_max_y) {
141 max_y = tmp_max_y.get();
142 }
143 map_range_ = Rect2D<double>(min_x, min_y, max_x, max_y);
144 auto map_ground_height_offset =
145 config.get_optional<float>("map.map_runtime.map_ground_height_offset");
146 if (map_ground_height_offset) {
147 map_ground_height_offset_ = map_ground_height_offset.get();
148 }
149 auto map_is_compression =
150 config.get_optional<bool>("map.map_config.compression");
151 if (map_is_compression) {
152 map_is_compression_ = map_is_compression.get();
153 }
154
155 auto resolutions = config.get_child_optional("map.map_config.resolutions");
156 if (resolutions) {
157 std::for_each(resolutions->begin(), resolutions->end(),
158 [this](const boost::property_tree::ptree::value_type &v) {
159 map_resolutions_.push_back(
160 static_cast<float>(atof(v.second.data().c_str())));
161 AINFO << "Resolution: " << v.second.data();
162 });
163 } else {
164 return false;
165 }
166
167 auto datasets = config.get_child_optional("map.map_record.datasets");
168 if (datasets) {
169 for (const boost::property_tree::ptree::value_type &v : *datasets) {
170 map_datasets_.push_back(v.second.data());
171 AINFO << "Dataset: " << v.second.data();
172 }
173 }
174
175 // load md5 check info
176 auto nodes = config.get_child_optional("map.check_info.nodes");
177 if (nodes) {
178 for (const boost::property_tree::ptree::value_type &v : *nodes) {
179 const boost::property_tree::ptree &child = v.second;
180 auto path = child.get_optional<std::string>("path");
181 auto md5 = child.get_optional<std::string>("md5");
182 if (!path || !md5) {
183 AERROR << "Lack path or md5.";
184 return false;
185 }
186 node_md5_map_[*path] = *md5;
187 }
188 }
189
190 return true;
191}
#define AERROR
Definition log.h:44

◆ ResizeMapRange()

void apollo::localization::msf::pyramid_map::BaseMapConfig::ResizeMapRange ( )

Resize map range by range and resolutions.

在文件 base_map_config.cc197 行定义.

197 {
198 double min_x = 0;
199 double min_y = 0;
200 double max_x = 0;
201 double max_y = 0;
202
203 double max_resolutions =
204 *std::max_element(map_resolutions_.begin(), map_resolutions_.end());
205 int n = 0;
206 while (min_x >= map_range_.GetMinX()) {
207 ++n;
208 min_x -= n * map_node_size_x_ * max_resolutions;
209 }
210 n = 0;
211 while (min_y >= map_range_.GetMinY()) {
212 ++n;
213 min_y -= n * map_node_size_y_ * max_resolutions;
214 }
215 n = 0;
216 while (max_x <= map_range_.GetMaxX()) {
217 ++n;
218 max_x += n * map_node_size_x_ * max_resolutions;
219 }
220 n = 0;
221 while (max_y <= map_range_.GetMaxY()) {
222 ++n;
223 max_y += n * map_node_size_y_ * max_resolutions;
224 }
225 map_range_ = Rect2D<double>(min_x, min_y, max_x, max_y);
226}

◆ Save()

bool apollo::localization::msf::pyramid_map::BaseMapConfig::Save ( const std::string &  file_path)

Save the map option to a XML file.

在文件 base_map_config.cc43 行定义.

43 {
44 boost::property_tree::ptree config;
45 bool success = CreateXml(&config);
46 if (success) {
47 boost::property_tree::write_xml(file_path, config);
48 AINFO << "Saved the map configuration to: " << file_path;
49 return true;
50 }
51 return false;
52}
virtual bool CreateXml(boost::property_tree::ptree *config) const
Create the XML structure.

◆ SetGroundHeightOffset()

void apollo::localization::msf::pyramid_map::BaseMapConfig::SetGroundHeightOffset ( float  map_ground_height_offset)

Set map_ground_height_offset.

在文件 base_map_config.cc262 行定义.

262 {
263 map_ground_height_offset_ = map_ground_height_offset;
264}

◆ SetIsCompression()

void apollo::localization::msf::pyramid_map::BaseMapConfig::SetIsCompression ( bool  map_is_compression)

Set map_is_compression.

在文件 base_map_config.cc266 行定义.

266 {
267 map_is_compression_ = map_is_compression;
268}

◆ SetMapNodeSize()

void apollo::localization::msf::pyramid_map::BaseMapConfig::SetMapNodeSize ( unsigned int  size_x,
unsigned int  size_y 
)

Set map_node_size.

在文件 base_map_config.cc257 行定义.

257 {
258 map_node_size_x_ = size_x;
259 map_node_size_y_ = size_y;
260}

◆ SetMapVersion()

void apollo::localization::msf::pyramid_map::BaseMapConfig::SetMapVersion ( const std::string &  map_version)

Set map_version.

在文件 base_map_config.cc193 行定义.

193 {
194 map_version_ = map_version;
195}

◆ SetMultiResolutions()

void apollo::localization::msf::pyramid_map::BaseMapConfig::SetMultiResolutions ( )

Set multi resolutions.

在文件 base_map_config.cc233 行定义.

233 {
234 map_resolutions_.clear();
235 map_resolutions_.push_back(0.03125);
236 map_resolutions_.push_back(0.0625);
237 map_resolutions_.push_back(0.125);
238 map_resolutions_.push_back(0.25);
239 map_resolutions_.push_back(0.5);
240 map_resolutions_.push_back(1);
241 map_resolutions_.push_back(2);
242 map_resolutions_.push_back(4);
243 map_resolutions_.push_back(8);
244 map_resolutions_.push_back(16);
245}

◆ SetNodeMd5Map()

void apollo::localization::msf::pyramid_map::BaseMapConfig::SetNodeMd5Map ( const std::map< std::string, std::string > &  node_md5_map)

Set node_md5_map.

在文件 base_map_config.cc247 行定义.

248 {
249 node_md5_map_ = node_md5_map;
250}

◆ SetSingleResolutions()

void apollo::localization::msf::pyramid_map::BaseMapConfig::SetSingleResolutions ( float  resolution = 0.125)

Set single resolutions.

在文件 base_map_config.cc228 行定义.

228 {
229 map_resolutions_.clear();
230 map_resolutions_.push_back(resolution);
231}

类成员变量说明

◆ coordinate_type_

std::string apollo::localization::msf::pyramid_map::BaseMapConfig::coordinate_type_ = ""

在文件 base_map_config.h101 行定义.

◆ map_datasets_

std::vector<std::string> apollo::localization::msf::pyramid_map::BaseMapConfig::map_datasets_

The datasets that contributed to the map.

在文件 base_map_config.h96 行定义.

◆ map_folder_path_

std::string apollo::localization::msf::pyramid_map::BaseMapConfig::map_folder_path_ = ""

The map folder path.

在文件 base_map_config.h94 行定义.

◆ map_ground_height_offset_

float apollo::localization::msf::pyramid_map::BaseMapConfig::map_ground_height_offset_ = 0.0f

Velodyne's height to the ground.

Estimate the Velodyne's height based on the ground height.

在文件 base_map_config.h89 行定义.

◆ map_is_compression_

bool apollo::localization::msf::pyramid_map::BaseMapConfig::map_is_compression_ = false

Enable the compression.

在文件 base_map_config.h91 行定义.

◆ map_node_size_x_

unsigned int apollo::localization::msf::pyramid_map::BaseMapConfig::map_node_size_x_ = 0

The map node size in pixels.

在文件 base_map_config.h78 行定义.

◆ map_node_size_y_

unsigned int apollo::localization::msf::pyramid_map::BaseMapConfig::map_node_size_y_ = 0

The map node size in pixels.

在文件 base_map_config.h80 行定义.

◆ map_range_

Rect2D<double> apollo::localization::msf::pyramid_map::BaseMapConfig::map_range_

The minimum and maximum UTM range in the map.

The x direction is the easting in UTM coordinate. The y direction is the northing in UTM coordinate.

在文件 base_map_config.h85 行定义.

◆ map_resolutions_

std::vector<float> apollo::localization::msf::pyramid_map::BaseMapConfig::map_resolutions_

The pixel resolutions in the map in meters.

在文件 base_map_config.h76 行定义.

◆ map_version_

std::string apollo::localization::msf::pyramid_map::BaseMapConfig::map_version_ = ""

The version of map.

在文件 base_map_config.h74 行定义.

◆ node_md5_map_

std::map<std::string, std::string> apollo::localization::msf::pyramid_map::BaseMapConfig::node_md5_map_

The map structure to store map node file name and its md5.

key:map node file name; value: md5 of map node file.

在文件 base_map_config.h99 行定义.


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