Apollo  v5.5.0
Open source self driving car software
camera_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 <vector>
20 
26 
27 namespace apollo {
28 namespace perception {
29 namespace camera {
30 
31 class BaseCalibrationService;
32 
33 struct CameraFrame {
34  // timestamp
35  double timestamp = 0.0;
36  // frame sequence id
37  int frame_id = 0;
38  // data provider
40  // calibration service
42  // camera intrinsics
43  Eigen::Matrix3f camera_k_matrix = Eigen::Matrix3f::Identity();
44  // narrow to obstacle projected_matrix
45  Eigen::Matrix3d project_matrix = Eigen::Matrix3d::Identity();
46  // camera to world pose
47  Eigen::Affine3d camera2world_pose = Eigen::Affine3d::Identity();
48  // hdmap struct
50  // tracker proposed objects
51  std::vector<base::ObjectPtr> proposed_objects;
52  // segmented objects
53  std::vector<base::ObjectPtr> detected_objects;
54  // tracked objects
55  std::vector<base::ObjectPtr> tracked_objects;
56  // feature of all detected object ( num x dim)
57  // detect lane mark info
58  std::vector<base::LaneLine> lane_objects;
59  std::vector<float> pred_vpt;
60  std::shared_ptr<base::Blob<float>> track_feature_blob = nullptr;
61  std::shared_ptr<base::Blob<float>> lane_detected_blob = nullptr;
62  // detected traffic lights
63  std::vector<base::TrafficLightPtr> traffic_lights;
64 
65  void Reset() {}
66 }; // struct CameraFrame
67 
68 } // namespace camera
69 } // namespace perception
70 } // namespace apollo
int frame_id
Definition: camera_frame.h:37
base::HdmapStructPtr hdmap_struct
Definition: camera_frame.h:49
Definition: data_provider.h:32
Eigen::Matrix3f camera_k_matrix
Definition: camera_frame.h:43
Definition: camera_frame.h:33
DataProvider * data_provider
Definition: camera_frame.h:39
std::vector< base::LaneLine > lane_objects
Definition: camera_frame.h:58
BaseCalibrationService * calibration_service
Definition: camera_frame.h:41
Eigen::Affine3d camera2world_pose
Definition: camera_frame.h:47
std::vector< base::ObjectPtr > proposed_objects
Definition: camera_frame.h:51
Definition: blob.h:72
std::vector< float > pred_vpt
Definition: camera_frame.h:59
std::shared_ptr< base::Blob< float > > track_feature_blob
Definition: camera_frame.h:60
Definition: base_calibration_service.h:40
std::vector< base::TrafficLightPtr > traffic_lights
Definition: camera_frame.h:63
void Reset()
Definition: camera_frame.h:65
double timestamp
Definition: camera_frame.h:35
std::shared_ptr< base::Blob< float > > lane_detected_blob
Definition: camera_frame.h:61
std::vector< base::ObjectPtr > tracked_objects
Definition: camera_frame.h:55
std::shared_ptr< HdmapStruct > HdmapStructPtr
Definition: hdmap_struct.h:44
std::vector< base::ObjectPtr > detected_objects
Definition: camera_frame.h:53
Eigen::Matrix3d project_matrix
Definition: camera_frame.h:45