22 #include "Eigen/Dense" 30 namespace perception {
34 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
37 std::shared_ptr<base::AttributePointCloud<base::PointF>>
cloud;
39 std::shared_ptr<base::AttributePointCloud<base::PointD>>
world_cloud;
71 lidar2world_pose = Eigen::Affine3d::Identity();
72 novatel2world_pose = Eigen::Affine3d::Identity();
74 hdmap_struct->road_boundary.clear();
75 hdmap_struct->road_polygons.clear();
76 hdmap_struct->junction_polygons.clear();
77 hdmap_struct->hole_polygons.clear();
79 segmented_objects.clear();
80 tracked_objects.clear();
82 non_ground_indices.
indices.clear();
83 secondary_indices.
indices.clear();
87 const std::vector<uint32_t> &indices) {
88 if (cloud && filtered_cloud) {
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::shared_ptr< base::AttributePointCloud< base::PointF > > cloud
Definition: lidar_frame.h:37
base::PointIndices secondary_indices
Definition: lidar_frame.h:57
std::vector< int > indices
Definition: point.h:75
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
base::PointIndices non_ground_indices
Definition: lidar_frame.h:55
base::PointIndices roi_indices
Definition: lidar_frame.h:53
Eigen::Affine3d novatel2world_pose
Definition: lidar_frame.h:45
Definition: point_cloud.h:37
void CopyPointCloudExclude(const PointCloud< PointT > &rhs, const std::vector< IndexType > &indices)
Definition: point_cloud.h:153
std::vector< std::shared_ptr< base::Object > > segmented_objects
Definition: lidar_frame.h:49
std::string reserve
Definition: lidar_frame.h:61
std::shared_ptr< base::AttributePointCloud< base::PointD > > world_cloud
Definition: lidar_frame.h:39
base::SensorInfo sensor_info
Definition: lidar_frame.h:59
void FilterPointCloud(base::PointCloud< base::PointF > *filtered_cloud, const std::vector< uint32_t > &indices)
Definition: lidar_frame.h:86
Definition: sensor_meta.h:57
std::vector< std::shared_ptr< base::Object > > tracked_objects
Definition: lidar_frame.h:51
Definition: lidar_frame.h:33
std::shared_ptr< base::HdmapStruct > hdmap_struct
Definition: lidar_frame.h:47
Eigen::Affine3d lidar2world_pose
Definition: lidar_frame.h:43
void Reset()
Definition: lidar_frame.h:63
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
double timestamp
Definition: lidar_frame.h:41