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

The data structure of a Node in the map. 更多...

#include <base_map_node.h>

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

Public 成员函数

 BaseMapNode (BaseMapMatrix *matrix, CompressionStrategy *strategy)
 Construct a map node.
 
virtual ~BaseMapNode ()
 Destruct a map node.
 
virtual void Init (const BaseMapConfig *map_config, const MapNodeIndex &index, bool create_map_cells=true)
 Initialize the map node.
 
virtual void InitMapMatrix (const BaseMapConfig *map_config)
 Initialize the map matrix.
 
virtual void Finalize ()
 call before deconstruction or reset.
 
virtual void ResetMapNode ()
 Reset map cells data.
 
bool Save ()
 Save the map node to the disk.
 
bool SaveIntensityImage () const
 Save intensity image of node.
 
bool Load ()
 Load the map node from the disk.
 
bool Load (const char *filename)
 
const BaseMapMatrixGetMapCellMatrix () const
 Get map cell matrix.
 
BaseMapMatrixGetMapCellMatrix ()
 
const BaseMapConfigGetMapConfig () const
 Get the map settings.
 
void SetMapNodeIndex (const MapNodeIndex &index)
 Set the map node index.
 
const MapNodeIndexGetMapNodeIndex () const
 Get the map node index.
 
void SetIsReserved (bool is_reserved)
 Set if the map node is reserved.
 
bool GetIsReserved () const
 Get if the map node is reserved.
 
bool GetIsChanged () const
 Get if the map data has changed.
 
void SetIsChanged (bool is)
 Set if the map node data has changed.
 
bool GetIsReady () const
 Get if the map node data is ready
 
const Eigen::Vector2d & GetLeftTopCorner () const
 Get the left top corner of the map node.
 
void SetLeftTopCorner (double x, double y)
 
float GetMapResolution () const
 Get the resolution of this map nodex.
 
bool GetCoordinate (const Eigen::Vector2d &coordinate, unsigned int *x, unsigned int *y) const
 Given the global coordinate, get the local 2D coordinate of the map cell matrix.
 
bool GetCoordinate (const Eigen::Vector3d &coordinate, unsigned int *x, unsigned int *y) const
 
Eigen::Vector2d GetCoordinate (unsigned int x, unsigned int y) const
 Given the local 2D coordinate, return the global coordinate, eigen version.
 

静态 Public 成员函数

static Eigen::Vector2d GetLeftTopCorner (const BaseMapConfig &option, const MapNodeIndex &index)
 

Protected 成员函数

virtual unsigned int LoadBinary (FILE *file)
 Load the map cell from a binary chunk.
 
virtual unsigned int CreateBinary (FILE *file) const
 Create the binary.
 
virtual unsigned int GetBinarySize () const
 Get the binary size of the object.
 
virtual unsigned int LoadHeaderBinary (unsigned char *buf)
 Load the map node header from a binary chunk.
 
virtual unsigned int CreateHeaderBinary (unsigned char *buf, unsigned int buf_size) const
 Create the binary header.
 
virtual unsigned int GetHeaderBinarySize () const
 Get the size of the header in bytes.
 
virtual unsigned int LoadBodyBinary (std::vector< unsigned char > *buf)
 Load the map node body from a binary chunk.
 
virtual unsigned int CreateBodyBinary (std::vector< unsigned char > *buf) const
 Create the binary body.
 
virtual unsigned int GetBodyBinarySize () const
 Get the size of the body in bytes.
 
bool SaveIntensityImage (const std::string &path) const
 Save intensity image of node.
 

Protected 属性

const BaseMapConfigmap_config_ = nullptr
 The map settings.
 
MapNodeIndex index_
 The index of this node.
 
Eigen::Vector2d left_top_corner_
 The left top corner of the map node in the global coordinate system.
 
BaseMapMatrixmap_matrix_
 The data structure of the map datas, which is a matrix.
 
bool is_reserved_ = false
 If the node is reserved in map.
 
bool is_changed_ = false
 Has the map node been changed.
 
bool data_is_ready_ = false
 
unsigned int file_body_binary_size_ = 0
 The body binary size in file.
 
CompressionStrategycompression_strategy_ = nullptr
 @bried The compression strategy.
 
float min_altitude_ = 1e6
 The min altitude of point cloud in the node.
 

详细描述

The data structure of a Node in the map.

在文件 base_map_node.h32 行定义.

构造及析构函数说明

◆ BaseMapNode()

apollo::localization::msf::BaseMapNode::BaseMapNode ( BaseMapMatrix matrix,
CompressionStrategy strategy 
)

Construct a map node.

在文件 base_map_node.cc30 行定义.

31 : map_matrix_(matrix), compression_strategy_(strategy) {}
BaseMapMatrix * map_matrix_
The data structure of the map datas, which is a matrix.
CompressionStrategy * compression_strategy_
@bried The compression strategy.

◆ ~BaseMapNode()

apollo::localization::msf::BaseMapNode::~BaseMapNode ( )
virtual

Destruct a map node.

在文件 base_map_node.cc33 行定义.

33 {
34 if (map_matrix_ != nullptr) {
35 delete map_matrix_;
36 }
37 if (compression_strategy_ != nullptr) {
39 }
40}

成员函数说明

◆ CreateBinary()

unsigned int apollo::localization::msf::BaseMapNode::CreateBinary ( FILE *  file) const
protectedvirtual

Create the binary.

Serialization of the object.

参数
<return>The the used size of binary is returned.

在文件 base_map_node.cc204 行定义.

204 {
205 unsigned int buf_size = GetBinarySize();
206 std::vector<unsigned char> buffer;
207 buffer.resize(buf_size);
208
209 unsigned int binary_size = 0;
210 std::vector<unsigned char> body_buffer;
211 CreateBodyBinary(&body_buffer);
212 // CHECK_EQ(processed_size, buf_size);
213
214 // Create header
215 unsigned int header_size = GetHeaderBinarySize();
216 unsigned int processed_size = CreateHeaderBinary(&buffer[0], buf_size);
217 CHECK_EQ(processed_size, header_size);
218
219 unsigned int buffer_bias = processed_size;
220 buf_size -= processed_size;
221 binary_size += processed_size;
222 // Create body
223 CHECK_GE(buf_size, body_buffer.size());
224 memcpy(&buffer[buffer_bias], &body_buffer[0], body_buffer.size());
225 binary_size += static_cast<unsigned int>(body_buffer.size());
226 fwrite(&buffer[0], 1, binary_size, file);
227 return binary_size;
228}
virtual unsigned int CreateHeaderBinary(unsigned char *buf, unsigned int buf_size) const
Create the binary header.
virtual unsigned int CreateBodyBinary(std::vector< unsigned char > *buf) const
Create the binary body.
virtual unsigned int GetBinarySize() const
Get the binary size of the object.
virtual unsigned int GetHeaderBinarySize() const
Get the size of the header in bytes.

◆ CreateBodyBinary()

unsigned int apollo::localization::msf::BaseMapNode::CreateBodyBinary ( std::vector< unsigned char > *  buf) const
protectedvirtual

Create the binary body.

参数
<buf,buf_size>The buffer and its size.
<return>The required or the used size of is returned.

在文件 base_map_node.cc310 行定义.

311 {
312 if (compression_strategy_ == nullptr) {
313 unsigned int body_size = GetBodyBinarySize();
314 buf->resize(body_size);
315 map_matrix_->CreateBinary(&((*buf)[0]), body_size);
316 file_body_binary_size_ = static_cast<unsigned int>(buf->size());
317 return static_cast<unsigned int>(buf->size());
318 }
319 std::vector<unsigned char> buf_uncompressed;
320 // Compute the uncompression binary body size
321 unsigned int body_size = GetBodyBinarySize();
322 buf_uncompressed.resize(body_size);
323 map_matrix_->CreateBinary(&buf_uncompressed[0], body_size);
324 compression_strategy_->Encode(&buf_uncompressed, buf);
325 file_body_binary_size_ = static_cast<unsigned int>(buf->size());
326 return static_cast<unsigned int>(buf->size());
327}
virtual unsigned int CreateBinary(unsigned char *buf, unsigned int buf_size) const =0
Create the binary.
unsigned int file_body_binary_size_
The body binary size in file.
virtual unsigned int GetBodyBinarySize() const
Get the size of the body in bytes.
virtual int Encode(BufferStr *buf, BufferStr *buf_compressed)=0

◆ CreateHeaderBinary()

unsigned int apollo::localization::msf::BaseMapNode::CreateHeaderBinary ( unsigned char *  buf,
unsigned int  buf_size 
) const
protectedvirtual

Create the binary header.

参数
<buf,buf_size>The buffer and its size.
<return>The required or the used size of is returned.

在文件 base_map_node.cc254 行定义.

255 {
256 unsigned int target_size = GetHeaderBinarySize();
257 if (buf_size >= target_size) {
258 unsigned int* p = reinterpret_cast<unsigned int*>(buf);
260 ++p;
261 int* pp = reinterpret_cast<int*>(p);
262 *pp = index_.zone_id_;
263 ++pp;
264 p = reinterpret_cast<unsigned int*>(pp);
265 *p = index_.m_;
266 ++p;
267 *p = index_.n_;
268 ++p;
269 *p = file_body_binary_size_; // Set it before call this function!
270 }
271 return target_size;
272}
MapNodeIndex index_
The index of this node.
unsigned int m_
The map node ID at the northing direction.
unsigned int n_
The map node ID at the easting direction.
unsigned int resolution_id_
The ID of the resolution.

◆ Finalize()

void apollo::localization::msf::BaseMapNode::Finalize ( )
virtual

call before deconstruction or reset.

在文件 base_map_node.cc60 行定义.

60 {
61 if (is_changed_) {
62 Save();
63 AERROR << "Save Map Node to disk: " << index_ << ".";
64 }
65}
bool is_changed_
Has the map node been changed.
bool Save()
Save the map node to the disk.
#define AERROR
Definition log.h:44

◆ GetBinarySize()

unsigned int apollo::localization::msf::BaseMapNode::GetBinarySize ( ) const
protectedvirtual

Get the binary size of the object.

在文件 base_map_node.cc230 行定义.

230 {
231 // It is uncompressed binary size.
233}

◆ GetBodyBinarySize()

unsigned int apollo::localization::msf::BaseMapNode::GetBodyBinarySize ( ) const
protectedvirtual

Get the size of the body in bytes.

在文件 base_map_node.cc329 行定义.

329 {
330 return map_matrix_->GetBinarySize();
331}
virtual unsigned int GetBinarySize() const =0
Get the binary size of the object.

◆ GetCoordinate() [1/3]

bool apollo::localization::msf::BaseMapNode::GetCoordinate ( const Eigen::Vector2d &  coordinate,
unsigned int *  x,
unsigned int *  y 
) const

Given the global coordinate, get the local 2D coordinate of the map cell matrix.

<return> If global coordinate (x, y) belongs to this map node.

Given the local 2D coordinate, return the global coordinate.

Given the global coordinate, get the local 2D coordinate of the map cell matrix. <return> If global coordinate (x, y) belongs to this map node, eigen version.

在文件 base_map_node.cc352 行定义.

353 {
354 const Eigen::Vector2d& left_top_corner = GetLeftTopCorner();
355 int off_x = static_cast<int>((coordinate[0] - left_top_corner[0]) /
357 int off_y = static_cast<int>((coordinate[1] - left_top_corner[1]) /
359 if (off_x >= 0 &&
360 off_x < static_cast<int>(this->map_config_->map_node_size_x_) &&
361 off_y >= 0 &&
362 off_y < static_cast<int>(this->map_config_->map_node_size_y_)) {
363 *x = static_cast<unsigned int>(off_x);
364 *y = static_cast<unsigned int>(off_y);
365 return true;
366 } else {
367 return false;
368 }
369}
unsigned int map_node_size_y_
The map node size in pixels.
unsigned int map_node_size_x_
The map node size in pixels.
const Eigen::Vector2d & GetLeftTopCorner() const
Get the left top corner of the map node.
const BaseMapConfig * map_config_
The map settings.
float GetMapResolution() const
Get the resolution of this map nodex.

◆ GetCoordinate() [2/3]

bool apollo::localization::msf::BaseMapNode::GetCoordinate ( const Eigen::Vector3d &  coordinate,
unsigned int *  x,
unsigned int *  y 
) const

在文件 base_map_node.cc379 行定义.

380 {
381 Eigen::Vector2d coord2d(coordinate[0], coordinate[1]);
382 return GetCoordinate(coord2d, x, y);
383}
bool GetCoordinate(const Eigen::Vector2d &coordinate, unsigned int *x, unsigned int *y) const
Given the global coordinate, get the local 2D coordinate of the map cell matrix.

◆ GetCoordinate() [3/3]

Eigen::Vector2d apollo::localization::msf::BaseMapNode::GetCoordinate ( unsigned int  x,
unsigned int  y 
) const

Given the local 2D coordinate, return the global coordinate, eigen version.

在文件 base_map_node.cc394 行定义.

395 {
396 const Eigen::Vector2d& left_top_corner = GetLeftTopCorner();
397 Eigen::Vector2d coord(
398 left_top_corner[0] + static_cast<float>(x) * GetMapResolution(),
399 left_top_corner[1] + static_cast<float>(y) * GetMapResolution());
400 return coord;
401}

◆ GetHeaderBinarySize()

unsigned int apollo::localization::msf::BaseMapNode::GetHeaderBinarySize ( ) const
protectedvirtual

Get the size of the header in bytes.

在文件 base_map_node.cc274 行定义.

274 {
275 return static_cast<int>(sizeof(unsigned int) // index_.resolution_id_
276 + sizeof(int) // index_.zone_id_
277 + sizeof(unsigned int) // index_.m_
278 + sizeof(unsigned int) // index_.n_
279 + sizeof(unsigned int)); // the body size in file.
280}

◆ GetIsChanged()

bool apollo::localization::msf::BaseMapNode::GetIsChanged ( ) const
inline

Get if the map data has changed.

在文件 base_map_node.h75 行定义.

75{ return is_changed_; }

◆ GetIsReady()

bool apollo::localization::msf::BaseMapNode::GetIsReady ( ) const
inline

Get if the map node data is ready

在文件 base_map_node.h79 行定义.

◆ GetIsReserved()

bool apollo::localization::msf::BaseMapNode::GetIsReserved ( ) const
inline

Get if the map node is reserved.

在文件 base_map_node.h73 行定义.

73{ return is_reserved_; }
bool is_reserved_
If the node is reserved in map.

◆ GetLeftTopCorner() [1/2]

const Eigen::Vector2d & apollo::localization::msf::BaseMapNode::GetLeftTopCorner ( ) const
inline

Get the left top corner of the map node.

在文件 base_map_node.h86 行定义.

86 {
87 return left_top_corner_;
88 }
Eigen::Vector2d left_top_corner_
The left top corner of the map node in the global coordinate system.

◆ GetLeftTopCorner() [2/2]

Eigen::Vector2d apollo::localization::msf::BaseMapNode::GetLeftTopCorner ( const BaseMapConfig option,
const MapNodeIndex index 
)
static

在文件 base_map_node.cc415 行定义.

416 {
417 Eigen::Vector2d coord;
418 coord[0] = config.map_range_.GetMinX() +
419 static_cast<float>(config.map_node_size_x_) *
420 config.map_resolutions_[index.resolution_id_] *
421 static_cast<float>(index.n_);
422 coord[1] = config.map_range_.GetMinY() +
423 static_cast<float>(config.map_node_size_y_) *
424 config.map_resolutions_[index.resolution_id_] *
425 static_cast<float>(index.m_);
426 DCHECK_LT(coord[0], config.map_range_.GetMaxX());
427 DCHECK_LT(coord[1], config.map_range_.GetMaxY());
428 return coord;
429}

◆ GetMapCellMatrix() [1/2]

BaseMapMatrix & apollo::localization::msf::BaseMapNode::GetMapCellMatrix ( )
inline

在文件 base_map_node.h62 行定义.

62{ return *map_matrix_; }

◆ GetMapCellMatrix() [2/2]

const BaseMapMatrix & apollo::localization::msf::BaseMapNode::GetMapCellMatrix ( ) const
inline

Get map cell matrix.

在文件 base_map_node.h60 行定义.

60{ return *map_matrix_; }

◆ GetMapConfig()

const BaseMapConfig & apollo::localization::msf::BaseMapNode::GetMapConfig ( ) const
inline

Get the map settings.

在文件 base_map_node.h65 行定义.

65{ return *map_config_; }

◆ GetMapNodeIndex()

const MapNodeIndex & apollo::localization::msf::BaseMapNode::GetMapNodeIndex ( ) const
inline

Get the map node index.

在文件 base_map_node.h69 行定义.

69{ return index_; }

◆ GetMapResolution()

float apollo::localization::msf::BaseMapNode::GetMapResolution ( ) const
inline

Get the resolution of this map nodex.

在文件 base_map_node.h98 行定义.

98 {
100 }
std::vector< float > map_resolutions_
The pixel resolutions in the map in meters.

◆ Init()

void apollo::localization::msf::BaseMapNode::Init ( const BaseMapConfig map_config,
const MapNodeIndex index,
bool  create_map_cells = true 
)
virtual

Initialize the map node.

Call this function first before use it!

在文件 base_map_node.cc42 行定义.

43 {
44 map_config_ = map_config;
45 index_ = index;
47 is_reserved_ = false;
48 data_is_ready_ = false;
49 is_changed_ = false;
50 if (create_map_cells) {
52 }
53}
virtual void InitMapMatrix(const BaseMapConfig *map_config)
Initialize the map matrix.

◆ InitMapMatrix()

void apollo::localization::msf::BaseMapNode::InitMapMatrix ( const BaseMapConfig map_config)
virtual

Initialize the map matrix.

在文件 base_map_node.cc55 行定义.

55 {
56 map_config_ = map_config;
57 map_matrix_->Init(map_config);
58}
virtual void Init(const BaseMapConfig *config)=0
Initialize the map matrix.

◆ Load() [1/2]

bool apollo::localization::msf::BaseMapNode::Load ( )

Load the map node from the disk.

在文件 base_map_node.cc131 行定义.

131 {
132 char buf[1024];
133 std::string path = map_config_->map_folder_path_;
134 if (!DirectoryExists(path)) {
135 return false;
136 }
137 path = path + "/map";
138 if (!DirectoryExists(path)) {
139 return false;
140 }
141 snprintf(buf, sizeof(buf), "/%03u", index_.resolution_id_);
142 path = path + buf;
143 if (!DirectoryExists(path)) {
144 return false;
145 }
146 if (index_.zone_id_ > 0) {
147 path = path + "/north";
148 } else {
149 path = path + "/south";
150 }
151 if (!DirectoryExists(path)) {
152 return false;
153 }
154 snprintf(buf, sizeof(buf), "/%02d", abs(index_.zone_id_));
155 path = path + buf;
156 if (!DirectoryExists(path)) {
157 return false;
158 }
159 snprintf(buf, sizeof(buf), "/%08u", index_.m_);
160 path = path + buf;
161 if (!DirectoryExists(path)) {
162 return false;
163 }
164 snprintf(buf, sizeof(buf), "/%08u", index_.n_);
165 path = path + buf;
166
167 return Load(path.c_str());
168}
std::string map_folder_path_
The map folder path.
bool Load()
Load the map node from the disk.
bool DirectoryExists(const std::string &directory_path)
Check if the directory specified by directory_path exists and is indeed a directory.
Definition file.cc:207

◆ Load() [2/2]

bool apollo::localization::msf::BaseMapNode::Load ( const char *  filename)

在文件 base_map_node.cc170 行定义.

170 {
171 data_is_ready_ = false;
172 // char buf[1024];
173
174 FILE* file = fopen(filename, "rb");
175 if (file) {
176 LoadBinary(file);
177 fclose(file);
178 is_changed_ = false;
179 data_is_ready_ = true;
180 return true;
181 } else {
182 AERROR << "Can't find the file: " << filename;
183 return false;
184 }
185}
virtual unsigned int LoadBinary(FILE *file)
Load the map cell from a binary chunk.

◆ LoadBinary()

unsigned int apollo::localization::msf::BaseMapNode::LoadBinary ( FILE *  file)
protectedvirtual

Load the map cell from a binary chunk.

参数
<return>The size read (the real size of object).

在文件 base_map_node.cc187 行定义.

187 {
188 // Load the header
189 unsigned int header_size = GetHeaderBinarySize();
190 std::vector<unsigned char> buf(header_size);
191 size_t read_size = fread(&buf[0], 1, header_size, file);
192 CHECK_EQ(read_size, header_size);
193 unsigned int processed_size = LoadHeaderBinary(&buf[0]);
194 CHECK_EQ(processed_size, header_size);
195
196 // Load the body
197 buf.resize(file_body_binary_size_);
198 read_size = fread(&buf[0], 1, file_body_binary_size_, file);
199 CHECK_EQ(read_size, file_body_binary_size_);
200 processed_size += LoadBodyBinary(&buf);
201 return processed_size;
202}
virtual unsigned int LoadHeaderBinary(unsigned char *buf)
Load the map node header from a binary chunk.
virtual unsigned int LoadBodyBinary(std::vector< unsigned char > *buf)
Load the map node body from a binary chunk.

◆ LoadBodyBinary()

unsigned int apollo::localization::msf::BaseMapNode::LoadBodyBinary ( std::vector< unsigned char > *  buf)
protectedvirtual

Load the map node body from a binary chunk.

参数
<return>The size read (the real size of body).

在文件 base_map_node.cc294 行定义.

294 {
295 if (compression_strategy_ == nullptr) {
296 return map_matrix_->LoadBinary(&((*buf)[0]));
297 }
298 std::vector<unsigned char> buf_uncompressed;
299 int ret = compression_strategy_->Decode(buf, &buf_uncompressed);
300 if (ret < 0) {
301 AERROR << "compression Decode error: " << ret;
302 return 0;
303 }
304 AERROR << "map node compress ratio: "
305 << static_cast<float>(buf->size()) /
306 static_cast<float>(buf_uncompressed.size());
307 return map_matrix_->LoadBinary(&buf_uncompressed[0]);
308}
virtual unsigned int LoadBinary(unsigned char *buf)=0
Load the map cell from a binary chunk.
virtual int Decode(BufferStr *buf, BufferStr *buf_uncompressed)=0

◆ LoadHeaderBinary()

unsigned int apollo::localization::msf::BaseMapNode::LoadHeaderBinary ( unsigned char *  buf)
protectedvirtual

Load the map node header from a binary chunk.

参数
<return>The size read (the real size of header).

在文件 base_map_node.cc235 行定义.

235 {
236 unsigned int target_size = GetHeaderBinarySize();
237 unsigned int* p = reinterpret_cast<unsigned int*>(buf);
239 ++p;
240 int* pp = reinterpret_cast<int*>(p);
241 index_.zone_id_ = *pp;
242 ++pp;
243 p = reinterpret_cast<unsigned int*>(pp);
244 index_.m_ = *p;
245 ++p;
246 index_.n_ = *p;
247 ++p;
248 // left_top_corner_ = GetLeftTopCorner(*map_config_, index_);
251 return target_size;
252}

◆ ResetMapNode()

void apollo::localization::msf::BaseMapNode::ResetMapNode ( )
virtual

Reset map cells data.

在文件 base_map_node.cc67 行定义.

67 {
68 is_changed_ = false;
69 data_is_ready_ = false;
70 is_reserved_ = false;
72}
virtual void Reset(const BaseMapConfig *config)=0
Reset map cells data.

◆ Save()

bool apollo::localization::msf::BaseMapNode::Save ( )

Save the map node to the disk.

在文件 base_map_node.cc80 行定义.

80 {
82 char buf[1024];
83 std::string path = map_config_->map_folder_path_;
84 if (!EnsureDirectory(path)) {
85 return false;
86 }
87 path = path + "/map";
88 if (!EnsureDirectory(path)) {
89 return false;
90 }
91 snprintf(buf, sizeof(buf), "/%03u", index_.resolution_id_);
92 path = path + buf;
93 if (!EnsureDirectory(path)) {
94 return false;
95 }
96 if (index_.zone_id_ > 0) {
97 path = path + "/north";
98 } else {
99 path = path + "/south";
100 }
101 if (!EnsureDirectory(path)) {
102 return false;
103 }
104 snprintf(buf, sizeof(buf), "/%02d", abs(index_.zone_id_));
105 path = path + buf;
106 if (!EnsureDirectory(path)) {
107 return false;
108 }
109 snprintf(buf, sizeof(buf), "/%08u", index_.m_);
110 path = path + buf;
111 if (!EnsureDirectory(path)) {
112 return false;
113 }
114 snprintf(buf, sizeof(buf), "/%08u", index_.n_);
115 path = path + buf;
116
117 AINFO << "Save node: " << path;
118
119 FILE* file = fopen(path.c_str(), "wb");
120 if (file) {
121 CreateBinary(file);
122 fclose(file);
123 is_changed_ = false;
124 return true;
125 } else {
126 AERROR << "Can't write to file: " << path << ".";
127 return false;
128 }
129}
virtual unsigned int CreateBinary(FILE *file) const
Create the binary.
bool SaveIntensityImage() const
Save intensity image of node.
#define AINFO
Definition log.h:42
bool EnsureDirectory(const std::string &directory_path)
Check if a specified directory specified by directory_path exists.
Definition file.cc:299

◆ SaveIntensityImage() [1/2]

bool apollo::localization::msf::BaseMapNode::SaveIntensityImage ( ) const

Save intensity image of node.

在文件 base_map_node.cc431 行定义.

431 {
432 char buf[1024];
433 std::string path = map_config_->map_folder_path_;
434 if (!EnsureDirectory(path)) {
435 return false;
436 }
437 path = path + "/image";
438 if (!EnsureDirectory(path)) {
439 return false;
440 }
441 snprintf(buf, sizeof(buf), "/%03u", index_.resolution_id_);
442 path = path + buf;
443 if (!EnsureDirectory(path)) {
444 return false;
445 }
446 if (index_.zone_id_ > 0) {
447 path = path + "/north";
448 } else {
449 path = path + "/south";
450 }
451 if (!EnsureDirectory(path)) {
452 return false;
453 }
454 snprintf(buf, sizeof(buf), "/%02d", abs(index_.zone_id_));
455 path = path + buf;
456 if (!EnsureDirectory(path)) {
457 return false;
458 }
459 snprintf(buf, sizeof(buf), "/%08u", index_.m_);
460 path = path + buf;
461 if (!EnsureDirectory(path)) {
462 return false;
463 }
464 snprintf(buf, sizeof(buf), "/%08u.png", index_.n_);
465 path = path + buf;
466 bool success0 = SaveIntensityImage(path);
467 return success0;
468}

◆ SaveIntensityImage() [2/2]

bool apollo::localization::msf::BaseMapNode::SaveIntensityImage ( const std::string &  path) const
protected

Save intensity image of node.

在文件 base_map_node.cc470 行定义.

470 {
471 cv::Mat image;
473 bool success = cv::imwrite(path, image);
474 return success;
475}
virtual void GetIntensityImg(cv::Mat *intensity_img) const =0
get intensity image of node.

◆ SetIsChanged()

void apollo::localization::msf::BaseMapNode::SetIsChanged ( bool  is)
inline

Set if the map node data has changed.

在文件 base_map_node.h77 行定义.

77{ is_changed_ = is; }

◆ SetIsReserved()

void apollo::localization::msf::BaseMapNode::SetIsReserved ( bool  is_reserved)
inline

Set if the map node is reserved.

在文件 base_map_node.h71 行定义.

71{ is_reserved_ = is_reserved; }

◆ SetLeftTopCorner()

void apollo::localization::msf::BaseMapNode::SetLeftTopCorner ( double  x,
double  y 
)
inline

在文件 base_map_node.h90 行定义.

90 {
91 // left_top_corner_[0] = x;
92 // left_top_corner_[1] = y;
93
94 left_top_corner_[0] = x;
95 left_top_corner_[1] = y;
96 }

◆ SetMapNodeIndex()

void apollo::localization::msf::BaseMapNode::SetMapNodeIndex ( const MapNodeIndex index)
inline

Set the map node index.

在文件 base_map_node.h67 行定义.

67{ index_ = index; }

类成员变量说明

◆ compression_strategy_

CompressionStrategy* apollo::localization::msf::BaseMapNode::compression_strategy_ = nullptr
protected

@bried The compression strategy.

在文件 base_map_node.h189 行定义.

◆ data_is_ready_

bool apollo::localization::msf::BaseMapNode::data_is_ready_ = false
protected

在文件 base_map_node.h184 行定义.

◆ file_body_binary_size_

unsigned int apollo::localization::msf::BaseMapNode::file_body_binary_size_ = 0
mutableprotected

The body binary size in file.

It's useful when reading and writing files.

在文件 base_map_node.h187 行定义.

◆ index_

MapNodeIndex apollo::localization::msf::BaseMapNode::index_
protected

The index of this node.

在文件 base_map_node.h172 行定义.

◆ is_changed_

bool apollo::localization::msf::BaseMapNode::is_changed_ = false
protected

Has the map node been changed.

在文件 base_map_node.h182 行定义.

◆ is_reserved_

bool apollo::localization::msf::BaseMapNode::is_reserved_ = false
protected

If the node is reserved in map.

在文件 base_map_node.h180 行定义.

◆ left_top_corner_

Eigen::Vector2d apollo::localization::msf::BaseMapNode::left_top_corner_
protected

The left top corner of the map node in the global coordinate system.

在文件 base_map_node.h176 行定义.

◆ map_config_

const BaseMapConfig* apollo::localization::msf::BaseMapNode::map_config_ = nullptr
protected

The map settings.

在文件 base_map_node.h170 行定义.

◆ map_matrix_

BaseMapMatrix* apollo::localization::msf::BaseMapNode::map_matrix_
protected

The data structure of the map datas, which is a matrix.

在文件 base_map_node.h178 行定义.

◆ min_altitude_

float apollo::localization::msf::BaseMapNode::min_altitude_ = 1e6
protected

The min altitude of point cloud in the node.

在文件 base_map_node.h191 行定义.


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