Apollo  6.0
Open source self driving car software
map_manager.h
Go to the documentation of this file.
1 /******************************************************************************
2  * Copyright 2018 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 <string>
19 
20 #include "gtest/gtest_prod.h"
21 
25 
26 namespace apollo {
27 namespace perception {
28 namespace lidar {
29 
31 
33 
34 class MapManager {
35  public:
36  MapManager() = default;
37 
38  ~MapManager() = default;
39 
40  bool Init(const MapManagerInitOptions& options = MapManagerInitOptions());
41 
42  // @brief: update map structure and lidar2world pose
43  // @param [in]: options
44  // @param [in/out]: frame
45  // hdmap_struct should be filled, required,
46  // lidar2world_pose can be updated, optional,
47  bool Update(const MapManagerOptions& options, LidarFrame* frame);
48 
49  bool QueryPose(Eigen::Affine3d* sensor2world_pose) const;
50 
51  std::string Name() const { return "MapManager"; }
52 
53  private:
54  LidarFrame* cached_frame_ = nullptr;
55  map::HDMapInput* hdmap_input_ = nullptr;
56  // params
57  bool update_pose_ = false;
58  double roi_search_distance_ = 80.0;
59 
60  FRIEND_TEST(LidarLibMapManagerTest, lidar_map_manager_test);
61 }; // class MapManager
62 
63 } // namespace lidar
64 } // namespace perception
65 } // namespace apollo
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: hdmap_input.h:34
bool Init(const char *binary_name)
Definition: lidar_frame.h:33
Definition: map_manager.h:34
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
std::string Name() const
Definition: map_manager.h:51