22 #include "Eigen/Dense" 30 namespace perception {
35 std::shared_ptr<base::AttributePointCloud<base::PointF>>
cloud;
37 std::shared_ptr<base::AttributePointCloud<base::PointD>>
world_cloud;
67 lidar2world_pose = Eigen::Affine3d::Identity();
69 hdmap_struct->road_boundary.clear();
70 hdmap_struct->road_polygons.clear();
71 hdmap_struct->junction_polygons.clear();
72 hdmap_struct->hole_polygons.clear();
74 segmented_objects.clear();
75 tracked_objects.clear();
77 non_ground_indices.
indices.clear();
78 secondary_indices.
indices.clear();
82 const std::vector<uint32_t> &indices) {
83 if (cloud && filtered_cloud) {
std::shared_ptr< base::AttributePointCloud< base::PointF > > cloud
Definition: lidar_frame.h:35
base::PointIndices secondary_indices
Definition: lidar_frame.h:53
std::vector< int > indices
Definition: point.h:76
base::PointIndices non_ground_indices
Definition: lidar_frame.h:51
base::PointIndices roi_indices
Definition: lidar_frame.h:49
Definition: point_cloud.h:33
void CopyPointCloudExclude(const PointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
Definition: point_cloud.h:146
std::vector< std::shared_ptr< base::Object > > segmented_objects
Definition: lidar_frame.h:45
std::string reserve
Definition: lidar_frame.h:57
std::shared_ptr< base::AttributePointCloud< base::PointD > > world_cloud
Definition: lidar_frame.h:37
base::SensorInfo sensor_info
Definition: lidar_frame.h:55
void FilterPointCloud(base::PointCloud< base::PointF > *filtered_cloud, const std::vector< uint32_t > &indices)
Definition: lidar_frame.h:81
Definition: sensor_meta.h:57
std::vector< std::shared_ptr< base::Object > > tracked_objects
Definition: lidar_frame.h:47
Definition: lidar_frame.h:33
std::shared_ptr< base::HdmapStruct > hdmap_struct
Definition: lidar_frame.h:43
Eigen::Affine3d lidar2world_pose
Definition: lidar_frame.h:41
void Reset()
Definition: lidar_frame.h:59
double timestamp
Definition: lidar_frame.h:39