Apollo  6.0
Open source self driving car software
sensor_frame.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 <vector>
21 
22 #include "Eigen/Core"
23 
27 
28 namespace apollo {
29 namespace perception {
30 namespace fusion {
31 
34  double timestamp = 0.0;
36 
37  SensorFrameHeader() = default;
38  SensorFrameHeader(const base::SensorInfo& info, double ts,
39  const Eigen::Affine3d& pose)
40  : sensor_info(info), timestamp(ts), sensor2world_pose(pose) {}
41 
42  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
44 
45 class SensorFrame {
46  public:
47  SensorFrame();
48 
49  explicit SensorFrame(const base::FrameConstPtr& base_frame_ptr);
50 
51  void Initialize(const base::FrameConstPtr& base_frame_ptr);
52 
53  void Initialize(const base::FrameConstPtr& base_frame_ptr,
54  const SensorPtr& sensor);
55 
56  // Getter
57  inline double GetTimestamp() const { return header_->timestamp; }
58 
59  inline bool GetPose(Eigen::Affine3d* pose) const {
60  if (pose == nullptr) {
61  AERROR << "pose is not available";
62  return false;
63  }
64  *pose = header_->sensor2world_pose;
65  return true;
66  }
67 
68  inline std::vector<SensorObjectPtr>& GetForegroundObjects() {
69  return foreground_objects_;
70  }
71 
72  inline const std::vector<SensorObjectPtr>& GetForegroundObjects() const {
73  return foreground_objects_;
74  }
75 
76  inline std::vector<SensorObjectPtr>& GetBackgroundObjects() {
77  return background_objects_;
78  }
79 
80  inline const std::vector<SensorObjectPtr>& GetBackgroundObjects() const {
81  return background_objects_;
82  }
83 
84  std::string GetSensorId() const;
85 
86  base::SensorType GetSensorType() const;
87 
88  SensorFrameHeaderConstPtr GetHeader() const { return header_; }
89 
90  private:
91  std::vector<SensorObjectPtr> foreground_objects_;
92  std::vector<SensorObjectPtr> background_objects_;
93 
94  // sensor-specific frame supplements
95  base::LidarFrameSupplement lidar_frame_supplement_;
96  base::RadarFrameSupplement radar_frame_supplement_;
97  base::CameraFrameSupplement camera_frame_supplement_;
98 
99  SensorFrameHeaderPtr header_ = nullptr;
100 };
101 
102 } // namespace fusion
103 } // namespace perception
104 } // namespace apollo
std::vector< SensorObjectPtr > & GetBackgroundObjects()
Definition: sensor_frame.h:76
SensorFrameHeaderConstPtr GetHeader() const
Definition: sensor_frame.h:88
std::shared_ptr< SensorFrameHeader > SensorFrameHeaderPtr
Definition: base_forward_declaration.h:24
bool GetPose(Eigen::Affine3d *pose) const
Definition: sensor_frame.h:59
double GetTimestamp() const
Definition: sensor_frame.h:57
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Eigen::Affine3d sensor2world_pose
Definition: sensor_frame.h:35
base::SensorInfo sensor_info
Definition: sensor_frame.h:33
Definition: frame_supplement.h:29
std::shared_ptr< Sensor > SensorPtr
Definition: base_forward_declaration.h:32
std::vector< SensorObjectPtr > & GetForegroundObjects()
Definition: sensor_frame.h:68
const std::vector< SensorObjectPtr > & GetBackgroundObjects() const
Definition: sensor_frame.h:80
double timestamp
Definition: sensor_frame.h:34
std::shared_ptr< const Frame > FrameConstPtr
Definition: frame.h:61
const std::vector< SensorObjectPtr > & GetForegroundObjects() const
Definition: sensor_frame.h:72
Definition: frame_supplement.h:46
Definition: sensor_meta.h:57
std::shared_ptr< const SensorFrameHeader > SensorFrameHeaderConstPtr
Definition: base_forward_declaration.h:26
#define AERROR
Definition: log.h:44
SensorType
Sensor types are set in the order of lidar, radar, camera, ultrasonic Please make sure SensorType has...
Definition: sensor_meta.h:29
Definition: sensor_frame.h:45
SensorFrameHeader(const base::SensorInfo &info, double ts, const Eigen::Affine3d &pose)
Definition: sensor_frame.h:38
Definition: frame_supplement.h:55
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
struct apollo::perception::fusion::SensorFrameHeader EIGEN_ALIGN16