Apollo 10.0
自动驾驶开放平台
camera_frame.h
浏览该文件的文档.
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
27namespace apollo {
28namespace perception {
29namespace camera {
30
31class BaseCalibrationService;
32
33
35
36struct CameraFrame {
37 // timestamp
38 double timestamp = 0.0;
39 // frame sequence id
40 int frame_id = 0;
41 // data provider
43 // calibration service
45 // hdmap struct
47 // tracker proposed objects
48 std::vector<base::ObjectPtr> proposed_objects;
49 // segmented objects
50 std::vector<base::ObjectPtr> detected_objects;
51 // tracked objects
52 std::vector<base::ObjectPtr> tracked_objects;
53 // feature of all detected object ( num x dim)
54 // detect lane mark info
55 std::vector<base::LaneLine> lane_objects;
56 std::vector<float> pred_vpt;
57 std::shared_ptr<base::Blob<float>> track_feature_blob = nullptr;
58 std::shared_ptr<base::Blob<float>> lane_detected_blob = nullptr;
59 // detected traffic lights
60 std::vector<base::TrafficLightPtr> traffic_lights;
61 // camera intrinsics
62 Eigen::Matrix3f camera_k_matrix = Eigen::Matrix3f::Identity();
63 // camera extrinsics
64 Eigen::Matrix4d camera_extrinsic = Eigen::Matrix4d::Identity();
65 // narrow to obstacle projected_matrix
66 Eigen::Matrix3d project_matrix = Eigen::Matrix3d::Identity();
67 // camera to world pose
68 Eigen::Affine3d camera2world_pose = Eigen::Affine3d::Identity();
69
70 // todo(zero): Add stage status to distinguish different stages
71 // stage status
72 // StageStatus stage_status;
74
75 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
76} EIGEN_ALIGN16; // struct CameraFrame
77
78
79
80} // namespace camera
81} // namespace perception
82} // namespace apollo
std::shared_ptr< HdmapStruct > HdmapStructPtr
struct apollo::perception::camera::CameraFrame EIGEN_ALIGN16
class register implement
Definition arena_queue.h:37
std::vector< base::TrafficLightPtr > traffic_lights
std::vector< base::ObjectPtr > proposed_objects
BaseCalibrationService * calibration_service
std::vector< base::LaneLine > lane_objects
std::shared_ptr< base::Blob< float > > lane_detected_blob
std::vector< base::ObjectPtr > tracked_objects
std::shared_ptr< base::Blob< float > > track_feature_blob
std::vector< std::shared_ptr< DataProvider > > data_provider
std::vector< base::ObjectPtr > detected_objects