Apollo  6.0
Open source self driving car software
sensor_data_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 
17 #pragma once
18 
19 #include <memory>
20 #include <string>
21 #include <unordered_map>
22 #include <vector>
23 
24 #include "gtest/gtest_prod.h"
25 
26 #include "cyber/common/macros.h"
31 
32 namespace apollo {
33 namespace perception {
34 namespace fusion {
35 
37  public:
38  bool Init();
39 
40  void Reset();
41 
42  void AddSensorMeasurements(const base::FrameConstPtr& frame_ptr);
43 
44  bool IsLidar(const base::FrameConstPtr& frame_ptr);
45  bool IsRadar(const base::FrameConstPtr& frame_ptr);
46  bool IsCamera(const base::FrameConstPtr& frame_ptr);
47 
48  // Getter
49  void GetLatestSensorFrames(double timestamp, const std::string& sensor_id,
50  std::vector<SensorFramePtr>* frames) const;
51 
52  void GetLatestFrames(double timestamp,
53  std::vector<SensorFramePtr>* frames) const;
54 
55  bool GetPose(const std::string& sensor_id, double timestamp,
56  Eigen::Affine3d* pose) const;
57 
59  const std::string& sensor_id) const;
60 
61  private:
62  bool inited_ = false;
63  std::unordered_map<std::string, SensorPtr> sensors_;
64 
65  const common::SensorManager* sensor_manager_ = nullptr;
66 
67  FRIEND_TEST(SensorDataManagerTest, test);
69 };
70 
71 } // namespace fusion
72 } // namespace perception
73 } // namespace apollo
base::BaseCameraModelPtr GetCameraIntrinsic(const std::string &sensor_id) const
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
void GetLatestFrames(double timestamp, std::vector< SensorFramePtr > *frames) const
bool IsLidar(const base::FrameConstPtr &frame_ptr)
Definition: sensor_data_manager.h:36
bool GetPose(const std::string &sensor_id, double timestamp, Eigen::Affine3d *pose) const
#define DECLARE_SINGLETON(classname)
Definition: macros.h:52
std::shared_ptr< const Frame > FrameConstPtr
Definition: frame.h:61
bool IsRadar(const base::FrameConstPtr &frame_ptr)
void GetLatestSensorFrames(double timestamp, const std::string &sensor_id, std::vector< SensorFramePtr > *frames) const
Definition: sensor_manager.h:35
bool IsCamera(const base::FrameConstPtr &frame_ptr)
std::shared_ptr< BaseCameraModel > BaseCameraModelPtr
Definition: camera.h:75
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
void AddSensorMeasurements(const base::FrameConstPtr &frame_ptr)