Apollo 10.0
自动驾驶开放平台
ndt_map_node.cc
浏览该文件的文档.
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
18
21
22namespace apollo {
23namespace localization {
24namespace msf {
25namespace pyramid_map {
26
29
30void NdtMapNode::Init(const BaseMapConfig* map_config) {
31 map_config_ = map_config;
32
35 map_node_config_->has_map_version_ = false;
36 map_node_config_->has_body_md5_ = false;
37 is_reserved_ = false;
38 data_is_ready_ = false;
39 is_changed_ = false;
42
43 map_matrix_.reset(new NdtMapMatrix());
48}
49void NdtMapNode::Init(const BaseMapConfig* map_config,
50 const MapNodeIndex& index, bool create_map_cells) {
51 map_config_ = map_config;
52
54 map_node_config_->node_index_ = index;
58 map_node_config_->has_map_version_ = false;
59 map_node_config_->has_body_md5_ = false;
60 is_reserved_ = false;
61 data_is_ready_ = false;
62 is_changed_ = false;
65
66 map_matrix_.reset(new NdtMapMatrix());
70 if (create_map_cells) {
72 }
73}
74
75Eigen::Vector3d NdtMapNode::GetCoordinate3D(unsigned int x, unsigned int y,
76 int altitude_index) const {
77 const Eigen::Vector2d& left_top_corner = GetLeftTopCorner();
78 Eigen::Vector2d coord_2d;
79 coord_2d[0] =
80 left_top_corner[0] + (static_cast<double>(x)) * GetMapResolution();
81 coord_2d[1] =
82 left_top_corner[1] + (static_cast<double>(y)) * GetMapResolution();
83
84 double altitude =
86 Eigen::Vector3d coord_3d;
87 coord_3d[0] = coord_2d[0];
88 coord_3d[1] = coord_2d[1];
89 coord_3d[2] = altitude;
90
91 return coord_3d;
92}
93
94Eigen::Vector3d NdtMapNode::GetCoordinateCenter3D(unsigned int x,
95 unsigned int y,
96 int altitude_index) const {
97 const Eigen::Vector2d& left_top_corner = GetLeftTopCorner();
98 Eigen::Vector2d coord_2d;
99 coord_2d[0] =
100 left_top_corner[0] + (static_cast<double>(x) + 0.5) * GetMapResolution();
101 coord_2d[1] =
102 left_top_corner[1] + (static_cast<double>(y) + 0.5) * GetMapResolution();
103
104 double altitude =
106 Eigen::Vector3d coord_3d;
107 coord_3d[0] = coord_2d[0];
108 coord_3d[1] = coord_2d[1];
109 coord_3d[2] = altitude;
110
111 return coord_3d;
112}
113
114void NdtMapNode::Reduce(NdtMapNode* map_node, const NdtMapNode& map_node_new) {
115 assert(map_node->index_.m_ == map_node_new.index_.m_);
116 assert(map_node->index_.n_ == map_node_new.index_.n_);
117 assert(map_node->index_.resolution_id_ == map_node_new.index_.resolution_id_);
118 assert(map_node->index_.zone_id_ == map_node_new.index_.zone_id_);
120 static_cast<NdtMapMatrix*>(map_node->map_matrix_.get()),
121 static_cast<const NdtMapMatrix&>(*map_node_new.map_matrix_));
122}
123
124} // namespace pyramid_map
125} // namespace msf
126} // namespace localization
127} // namespace apollo
std::shared_ptr< CompressionStrategy > compression_strategy_
@bried The compression strategy.
const BaseMapConfig * map_config_
The map settings.
bool is_changed_
Has the map node been changed.
bool is_reserved_
If the node is reserved in map.
MapNodeIndex index_
The index of this node
const Eigen::Vector2d & GetLeftTopCorner() const
static Eigen::Vector2d ComputeLeftTopCorner(const BaseMapConfig &config, const MapNodeIndex &index)
std::shared_ptr< BaseMapMatrixHandler > map_matrix_handler_
The class to load and create map matrix binary.
std::shared_ptr< BaseMapMatrix > map_matrix_
The data structure of the map datas, which is a matrix.
Eigen::Vector2d left_top_corner_
The left top corner of the map node in the global coordinate system.
std::shared_ptr< BaseMapNodeConfig > map_node_config_
The map node config.
float GetMapResolution() const
Get the resolution of this map nodex.
virtual void InitMapMatrix(const BaseMapConfig *map_config)
Initialize the map matrix.
unsigned int m_
The map node ID at the northing direction.
unsigned int resolution_id_
The ID of the resolution.
unsigned int n_
The map node ID at the easting direction.
static float CalAltitude(const float resolution, const int altitude_index)
Calculate altitude from altitude index.
The data structure of ndt Map matrix.
static void Reduce(NdtMapMatrix *cells, const NdtMapMatrix &cells_new)
Combine two NdtMapMatrix instances (Reduce).
void Init(const BaseMapConfig *map_config)
Initialize the map node.
unsigned int num_valid_single_cells_
The number of single cells with elements.
unsigned int num_valid_cells_
The number of cells with elements.
Eigen::Vector3d GetCoordinateCenter3D(unsigned int x, unsigned int y, int altitude_index) const
Given the local x, y, altitude index, return the global coordinate.
static void Reduce(NdtMapNode *map_node, const NdtMapNode &map_node_new)
Combine two map nodes (Reduce operation in mapreduce).
float GetMapResolutionZ() const
Get the resolution of this map nodex.
Eigen::Vector3d GetCoordinate3D(unsigned int x, unsigned int y, int altitude_index) const
Given the local x, y, altitude index, return the global coordinate.
class register implement
Definition arena_queue.h:37