Apollo  6.0
Open source self driving car software
base_map_node.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2019 The Apollo Authors. All Rights Reserved.
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *****************************************************************************/
16 #pragma once
17 
18 #include <memory>
19 #include <string>
20 #include <vector>
21 
22 #include "Eigen/Core"
23 
30 
31 namespace apollo {
32 namespace localization {
33 namespace msf {
34 namespace pyramid_map {
35 
37 class BaseMapNode {
38  public:
40  BaseMapNode();
42  BaseMapNode(BaseMapMatrix* matrix, CompressionStrategy* strategy);
44  virtual ~BaseMapNode();
45 
47  virtual void Init(const BaseMapConfig* map_config) = 0;
48  virtual void Init(const BaseMapConfig* map_config, const MapNodeIndex& index,
49  bool create_map_cells = true) = 0;
50 
52  virtual void InitMapMatrix(const BaseMapConfig* map_config);
54  virtual void Finalize();
56  virtual void ResetMapNode();
57 
59  bool Save();
61  bool SaveIntensityImage() const;
63  bool SaveAltitudeImage() const;
65  bool Load();
66  bool Load(const char* filename);
67 
71  virtual bool GetCoordinate(const Eigen::Vector2d& coordinate, unsigned int* x,
72  unsigned int* y) const;
73  virtual bool GetCoordinate(const Eigen::Vector3d& coordinate, unsigned int* x,
74  unsigned int* y) const;
76  virtual Eigen::Vector2d GetCoordinate(unsigned int x, unsigned int y) const;
77 
79  void SetMapNodeIndex(const MapNodeIndex& index);
80 
82  bool SaveIntensityImage(const std::string& path) const;
84  bool SaveAltitudeImage(const std::string& path) const;
85 
87  const MapNodeIndex& index);
88 
90  inline const BaseMapMatrix& GetMapCellMatrix() const { return *map_matrix_; }
92 
94  inline const BaseMapConfig& GetMapConfig() const { return *map_config_; }
95 
97  inline const BaseMapNodeConfig& GetMapNodeConfig() const {
98  return *map_node_config_;
99  }
100 
102  inline const MapNodeIndex& GetMapNodeIndex() const {
103  return map_node_config_->node_index_;
104  }
105 
107  inline void SetIsReserved(bool is_reserved) { is_reserved_ = is_reserved; }
108 
110  inline bool GetIsReserved() const { return is_reserved_; }
111 
113  inline bool GetIsChanged() const { return is_changed_; }
114 
116  inline void SetIsChanged(bool is) { is_changed_ = is; }
117 
119  inline bool GetIsReady() const { return data_is_ready_; }
120 
121  inline const Eigen::Vector2d& GetLeftTopCorner() const {
122  return left_top_corner_;
123  }
124 
126  inline void SetLeftTopCorner(double x, double y) {
127  left_top_corner_[0] = x;
128  left_top_corner_[1] = y;
129  }
130 
132  inline float GetMapResolution() const {
133  return this->map_config_
134  ->map_resolutions_[map_node_config_->node_index_.resolution_id_];
135  }
136 
137  static Eigen::Vector2d GetLeftTopCorner(const BaseMapConfig& option,
138  const MapNodeIndex& index);
139 
140  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
141 
142  protected:
144  bool CreateMapDirectory(const std::string& path) const;
147  const std::vector<std::string>& paths) const;
150  const std::vector<std::string>& paths) const;
151 
154  virtual bool LoadBinary(FILE* file);
157  virtual bool CreateBinary(FILE* file) const;
159  virtual size_t GetBinarySize() const;
160 
164  virtual size_t LoadHeaderBinary(const unsigned char* buf);
169  virtual size_t CreateHeaderBinary(unsigned char* buf, size_t buf_size) const;
171  virtual size_t GetHeaderBinarySize() const;
172 
176  virtual size_t LoadBodyBinary(std::vector<unsigned char>* buf);
181  virtual size_t CreateBodyBinary(std::vector<unsigned char>* buf) const;
183  virtual size_t GetBodyBinarySize() const;
184 
186  const BaseMapConfig* map_config_ = nullptr;
187 
190 
194 
196  std::shared_ptr<BaseMapNodeConfig> map_node_config_ = nullptr;
198  std::shared_ptr<BaseMapMatrix> map_matrix_ = nullptr;
200  std::shared_ptr<BaseMapMatrixHandler> map_matrix_handler_ = nullptr;
202  bool is_reserved_ = false;
204  bool is_changed_ = false;
205  /* *@brief Indicate map node data is ready*/
206  bool data_is_ready_ = false;
208  mutable size_t file_body_binary_size_ = 0;
209 
210  mutable size_t uncompressed_file_body_size_ = 0;
212  std::shared_ptr<CompressionStrategy> compression_strategy_ = nullptr;
213 };
214 
215 } // namespace pyramid_map
216 } // namespace msf
217 } // namespace localization
218 } // namespace apollo
float GetMapResolution() const
Get the resolution of this map nodex.
Definition: base_map_node.h:132
virtual size_t LoadHeaderBinary(const unsigned char *buf)
Load the map node header from a binary chunk.
virtual bool LoadBinary(FILE *file)
Load the map cell from a binary chunk.
Eigen::Vector2d left_top_corner_
The left top corner of the map node in the global coordinate system.
Definition: base_map_node.h:193
void SetIsReserved(bool is_reserved)
Set if the map node is reserved.
Definition: base_map_node.h:107
bool SaveIntensityImage() const
Save intensity image of node.
bool GetIsReady() const
Get if the map node data is ready.
Definition: base_map_node.h:119
virtual size_t LoadBodyBinary(std::vector< unsigned char > *buf)
Load the map node body from a binary chunk.
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
virtual size_t GetHeaderBinarySize() const
Get the size of the header in bytes.
bool is_reserved_
If the node is reserved in map.
Definition: base_map_node.h:202
Eigen::Vector2d Vector2d
Definition: base_map_fwd.h:36
static Eigen::Vector2d ComputeLeftTopCorner(const BaseMapConfig &config, const MapNodeIndex &index)
virtual size_t GetBodyBinarySize() const
Get the size of the body in bytes.
size_t uncompressed_file_body_size_
Definition: base_map_node.h:210
virtual bool CreateBinary(FILE *file) const
Create the binary. Serialization of the object.
virtual void ResetMapNode()
Reset map cells data.
Eigen::Vector3d Vector3d
Definition: frame_transform.h:27
void SetLeftTopCorner(double x, double y)
Set the left top corner of the map node.
Definition: base_map_node.h:126
bool GetIsReserved() const
Get if the map node is reserved.
Definition: base_map_node.h:110
bool is_changed_
Has the map node been changed.
Definition: base_map_node.h:204
std::shared_ptr< BaseMapMatrix > map_matrix_
The data structure of the map datas, which is a matrix.
Definition: base_map_node.h:198
virtual void Init(const BaseMapConfig *map_config)=0
Initialize the map node. Call this function first before use it!
bool data_is_ready_
Definition: base_map_node.h:206
virtual 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. <return> If global c...
The data structure of the map cells in a map node.
Definition: base_map_matrix.h:30
MapNodeIndex index_
The index of this node.
Definition: base_map_node.h:189
const BaseMapNodeConfig & GetMapNodeConfig() const
Get the map node config.
Definition: base_map_node.h:97
bool SaveAltitudeImage() const
Save altitude image of node.
bool CreateMapDirectoryRecursively(const std::vector< std::string > &paths) const
Try to create the map directory recursively.
std::vector< float > map_resolutions_
The pixel resolutions in the map in meters.
Definition: base_map_config.h:76
std::shared_ptr< CompressionStrategy > compression_strategy_
Definition: base_map_node.h:212
The data structure of a Node in the map.
Definition: base_map_node.h:37
void SetMapNodeIndex(const MapNodeIndex &index)
Set the map node index.
virtual size_t CreateHeaderBinary(unsigned char *buf, size_t buf_size) const
Create the binary header.
BaseMapMatrix & GetMapCellMatrix()
Definition: base_map_node.h:91
virtual size_t GetBinarySize() const
Get the binary size of the object.
const BaseMapMatrix & GetMapCellMatrix() const
Get map cell matrix.
Definition: base_map_node.h:90
const BaseMapConfig & GetMapConfig() const
Get the map settings.
Definition: base_map_node.h:94
virtual void Finalize()
call before deconstruction or reset.
bool GetIsChanged() const
Get if the map data has changed.
Definition: base_map_node.h:113
virtual size_t CreateBodyBinary(std::vector< unsigned char > *buf) const
Create the binary body.
const MapNodeIndex & GetMapNodeIndex() const
Get the map node index.
Definition: base_map_node.h:102
bool Save()
Save the map node to the disk.
The map node config info.
Definition: base_map_node_config.h:31
std::shared_ptr< BaseMapNodeConfig > map_node_config_
The map node config.
Definition: base_map_node.h:196
size_t file_body_binary_size_
The body binary size in file.
Definition: base_map_node.h:208
bool CheckMapDirectoryRecursively(const std::vector< std::string > &paths) const
Try to check the map directory recursively.
The options of the reflectance map.
Definition: base_map_config.h:42
Definition: base_map_node_index.h:33
void SetIsChanged(bool is)
Set if the map node data has changed.
Definition: base_map_node.h:116
bool CreateMapDirectory(const std::string &path) const
Try to create the map directory.
std::shared_ptr< BaseMapMatrixHandler > map_matrix_handler_
The class to load and create map matrix binary.
Definition: base_map_node.h:200
bool Load()
Load the map node from the disk.
virtual void InitMapMatrix(const BaseMapConfig *map_config)
Initialize the map matrix.
const Eigen::Vector2d & GetLeftTopCorner() const
Definition: base_map_node.h:121
const BaseMapConfig * map_config_
The map settings.
Definition: base_map_node.h:186