Apollo  6.0
Open source self driving car software
sensor_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 <memory>
19 #include <string>
20 #include <unordered_map>
21 
22 #include "cyber/common/macros.h"
27 
28 namespace apollo {
29 namespace perception {
30 namespace common {
31 
34 
36  public:
37  bool Init();
38 
39  bool IsSensorExist(const std::string& name) const;
40 
41  bool GetSensorInfo(const std::string& name,
42  apollo::perception::base::SensorInfo* sensor_info) const;
43 
44  std::shared_ptr<BaseCameraDistortionModel> GetDistortCameraModel(
45  const std::string& name) const;
46 
47  std::shared_ptr<BaseCameraModel> GetUndistortCameraModel(
48  const std::string& name) const;
49 
50  // sensor type functions
51  bool IsHdLidar(const std::string& name) const;
52  bool IsHdLidar(const apollo::perception::base::SensorType& type) const;
53  bool IsLdLidar(const std::string& name) const;
54  bool IsLdLidar(const apollo::perception::base::SensorType& type) const;
55 
56  bool IsLidar(const std::string& name) const;
57  bool IsLidar(const apollo::perception::base::SensorType& type) const;
58  bool IsRadar(const std::string& name) const;
59  bool IsRadar(const apollo::perception::base::SensorType& type) const;
60  bool IsCamera(const std::string& name) const;
61  bool IsCamera(const apollo::perception::base::SensorType& type) const;
62  bool IsUltrasonic(const std::string& name) const;
63  bool IsUltrasonic(const apollo::perception::base::SensorType& type) const;
64 
65  // sensor frame id function
66  std::string GetFrameId(const std::string& name) const;
67 
68  private:
69  inline std::string IntrinsicPath(const std::string& frame_id) {
70  std::string intrinsics =
71  FLAGS_obs_sensor_intrinsic_path + "/" + frame_id + "_intrinsics.yaml";
72  return intrinsics;
73  }
74 
75  private:
76  std::mutex mutex_;
77  bool inited_ = false;
78 
79  std::unordered_map<std::string, apollo::perception::base::SensorInfo>
80  sensor_info_map_;
81  std::unordered_map<std::string, std::shared_ptr<BaseCameraDistortionModel>>
82  distort_model_map_;
83  std::unordered_map<std::string, std::shared_ptr<BaseCameraModel>>
84  undistort_model_map_;
85 
87 };
88 
89 } // namespace common
90 } // namespace perception
91 } // namespace apollo
bool IsHdLidar(const std::string &name) const
std::shared_ptr< BaseCameraDistortionModel > GetDistortCameraModel(const std::string &name) const
bool IsSensorExist(const std::string &name) const
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
bool GetSensorInfo(const std::string &name, apollo::perception::base::SensorInfo *sensor_info) const
bool IsCamera(const std::string &name) const
std::string GetFrameId(const std::string &name) const
#define DECLARE_SINGLETON(classname)
Definition: macros.h:52
bool IsRadar(const std::string &name) const
std::shared_ptr< BaseCameraModel > GetUndistortCameraModel(const std::string &name) const
Definition: sensor_meta.h:57
Definition: sensor_manager.h:35
bool IsUltrasonic(const std::string &name) const
bool IsLdLidar(const std::string &name) const
SensorType
Sensor types are set in the order of lidar, radar, camera, ultrasonic Please make sure SensorType has...
Definition: sensor_meta.h:29
bool IsLidar(const std::string &name) const