24 namespace perception {
38 const std::shared_ptr<apollo::drivers::PointCloud const>& message,
44 std::string
Name()
const override {
return "PointCloudPreprocessor"; }
51 bool filter_naninf_points_ =
true;
52 bool filter_nearby_box_points_ =
true;
53 float box_forward_x_ = 0.0f;
54 float box_backward_x_ = 0.0f;
55 float box_forward_y_ = 0.0f;
56 float box_backward_y_ = 0.0f;
57 bool filter_high_z_points_ =
true;
58 float z_threshold_ = 5.0f;
59 static const float kPointInfThreshold;
Definition: pointcloud_preprocessor.h:27
PlanningContext is the runtime context in planning. It is persistent across multiple frames...
Definition: atomic_hash_map.h:25
Definition: base_pointcloud_preprocessor.h:34
bool Init(const PointCloudPreprocessorInitOptions &options=PointCloudPreprocessorInitOptions()) override
Definition: base_pointcloud_preprocessor.h:30
bool Preprocess(const PointCloudPreprocessorOptions &options, const std::shared_ptr< apollo::drivers::PointCloud const > &message, LidarFrame *frame) const override
virtual ~PointCloudPreprocessor()=default
Definition: lidar_frame.h:33
std::shared_ptr< PointFCloud > PointFCloudPtr
Definition: point_cloud.h:482
std::string Name() const override
Definition: pointcloud_preprocessor.h:44
PointCloudPreprocessor()
Definition: pointcloud_preprocessor.h:29
Eigen::Affine3d Affine3d
Definition: base_map_fwd.h:34
std::shared_ptr< PointDCloud > PointDCloudPtr
Definition: point_cloud.h:485
Definition: base_pointcloud_preprocessor.h:40