28 namespace perception {
31 class BaseCalibrationService;
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
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