21 #include "modules/drivers/proto/pointcloud.pb.h" 25 namespace perception {
52 const std::shared_ptr<apollo::drivers::PointCloud const>& message,
61 std::string
Name()
const {
return "PointCloudPreprocessor"; }
65 const Eigen::Affine3d& pose,
68 bool filter_naninf_points_ =
true;
69 bool filter_nearby_box_points_ =
true;
70 float box_forward_x_ = 0.0f;
71 float box_backward_x_ = 0.0f;
72 float box_forward_y_ = 0.0f;
73 float box_backward_y_ = 0.0f;
74 bool filter_high_z_points_ =
true;
75 float z_threshold_ = 5.0f;
76 static const float kPointInfThreshold;
Definition: pointcloud_preprocessor.h:36
Definition: pointcloud_preprocessor.h:32
Definition: pointcloud_preprocessor.h:28
Eigen::Affine3d sensor2novatel_extrinsics
Definition: pointcloud_preprocessor.h:33
std::string sensor_name
Definition: pointcloud_preprocessor.h:29
Definition: lidar_frame.h:33
std::shared_ptr< PointFCloud > PointFCloudPtr
Definition: point_cloud.h:472
std::string Name() const
Definition: pointcloud_preprocessor.h:61
std::shared_ptr< PointDCloud > PointDCloudPtr
Definition: point_cloud.h:475