Apollo 10.0
自动驾驶开放平台
|
#include <camera_frame.h>
Public 属性 | |
std::uint64_t | frame_id |
double | timestamp = 0.0 |
std::vector< std::shared_ptr< DataProvider > > | data_provider |
std::vector< base::ObjectPtr > | detected_objects |
std::vector< float > | k_lidar2img |
std::shared_ptr< base::AttributePointCloud< base::PointF > > | cloud |
int | frame_id = 0 |
DataProvider * | data_provider = nullptr |
BaseCalibrationService * | calibration_service = nullptr |
base::HdmapStructPtr | hdmap_struct = nullptr |
std::vector< base::ObjectPtr > | proposed_objects |
std::vector< base::ObjectPtr > | tracked_objects |
std::vector< base::LaneLine > | lane_objects |
std::vector< float > | pred_vpt |
std::shared_ptr< base::Blob< float > > | track_feature_blob = nullptr |
std::shared_ptr< base::Blob< float > > | lane_detected_blob = nullptr |
std::vector< base::TrafficLightPtr > | traffic_lights |
Eigen::Matrix3f | camera_k_matrix = Eigen::Matrix3f::Identity() |
Eigen::Matrix4d | camera_extrinsic = Eigen::Matrix4d::Identity() |
Eigen::Matrix3d | project_matrix = Eigen::Matrix3d::Identity() |
Eigen::Affine3d | camera2world_pose = Eigen::Affine3d::Identity() |
TrackState | track_state = TrackState::Predict |
在文件 camera_frame.h 第 31 行定义.
BaseCalibrationService* apollo::perception::camera::CameraFrame::calibration_service = nullptr |
在文件 camera_frame.h 第 44 行定义.
Eigen::Affine3d apollo::perception::camera::CameraFrame::camera2world_pose = Eigen::Affine3d::Identity() |
在文件 camera_frame.h 第 68 行定义.
Eigen::Matrix4d apollo::perception::camera::CameraFrame::camera_extrinsic = Eigen::Matrix4d::Identity() |
在文件 camera_frame.h 第 64 行定义.
Eigen::Matrix3f apollo::perception::camera::CameraFrame::camera_k_matrix = Eigen::Matrix3f::Identity() |
在文件 camera_frame.h 第 62 行定义.
std::shared_ptr<base::AttributePointCloud<base::PointF> > apollo::perception::camera::CameraFrame::cloud |
在文件 camera_frame.h 第 41 行定义.
std::vector< std::shared_ptr< DataProvider > > apollo::perception::camera::CameraFrame::data_provider |
在文件 camera_frame.h 第 36 行定义.
DataProvider* apollo::perception::camera::CameraFrame::data_provider = nullptr |
在文件 camera_frame.h 第 42 行定义.
std::vector< base::ObjectPtr > apollo::perception::camera::CameraFrame::detected_objects |
在文件 camera_frame.h 第 37 行定义.
std::uint64_t apollo::perception::camera::CameraFrame::frame_id |
在文件 camera_frame.h 第 33 行定义.
int apollo::perception::camera::CameraFrame::frame_id = 0 |
在文件 camera_frame.h 第 40 行定义.
base::HdmapStructPtr apollo::perception::camera::CameraFrame::hdmap_struct = nullptr |
在文件 camera_frame.h 第 46 行定义.
std::vector<float> apollo::perception::camera::CameraFrame::k_lidar2img |
在文件 camera_frame.h 第 39 行定义.
std::shared_ptr<base::Blob<float> > apollo::perception::camera::CameraFrame::lane_detected_blob = nullptr |
在文件 camera_frame.h 第 58 行定义.
std::vector<base::LaneLine> apollo::perception::camera::CameraFrame::lane_objects |
在文件 camera_frame.h 第 55 行定义.
std::vector<float> apollo::perception::camera::CameraFrame::pred_vpt |
在文件 camera_frame.h 第 56 行定义.
Eigen::Matrix3d apollo::perception::camera::CameraFrame::project_matrix = Eigen::Matrix3d::Identity() |
在文件 camera_frame.h 第 66 行定义.
std::vector<base::ObjectPtr> apollo::perception::camera::CameraFrame::proposed_objects |
在文件 camera_frame.h 第 48 行定义.
double apollo::perception::camera::CameraFrame::timestamp = 0.0 |
在文件 camera_frame.h 第 35 行定义.
std::shared_ptr<base::Blob<float> > apollo::perception::camera::CameraFrame::track_feature_blob = nullptr |
在文件 camera_frame.h 第 57 行定义.
TrackState apollo::perception::camera::CameraFrame::track_state = TrackState::Predict |
在文件 camera_frame.h 第 73 行定义.
std::vector<base::ObjectPtr> apollo::perception::camera::CameraFrame::tracked_objects |
在文件 camera_frame.h 第 52 行定义.
std::vector<base::TrafficLightPtr> apollo::perception::camera::CameraFrame::traffic_lights |
在文件 camera_frame.h 第 60 行定义.