GLIM
Loading...
Searching...
No Matches
cloud_preprocessor.hpp
1#pragma once
2
3#include <random>
4#include <vector>
5#include <Eigen/Core>
6#include <Eigen/Geometry>
7
8#include <glim/preprocess/preprocessed_frame.hpp>
9
10namespace glim {
11
40
46public:
47 using Points = std::vector<Eigen::Vector4d>;
48 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
49
54 virtual ~CloudPreprocessor();
55
62 virtual PreprocessedFrame::Ptr preprocess(const RawPoints::ConstPtr& raw_points);
63
64private:
65 PreprocessedFrame::Ptr preprocess_impl(const RawPoints::ConstPtr& raw_points);
66 std::vector<int> find_neighbors(const Eigen::Vector4d* points, const int num_points, const int k) const;
67
68private:
70 Params params;
71
72 mutable std::mt19937 mt;
73
74 std::shared_ptr<void> tbb_task_arena;
75};
76
77} // namespace glim
Point cloud preprocessor.
Definition cloud_preprocessor.hpp:45
EIGEN_MAKE_ALIGNED_OPERATOR_NEW CloudPreprocessor(const CloudPreprocessorParams &params=CloudPreprocessorParams())
Constructor.
virtual PreprocessedFrame::Ptr preprocess(const RawPoints::ConstPtr &raw_points)
Preprocess a raw point cloud.
Point cloud preprocessing parameters.
Definition cloud_preprocessor.hpp:15
Eigen::Vector3d crop_bbox_max
Bounding box max point.
Definition cloud_preprocessor.hpp:34
int num_threads
Number of threads.
Definition cloud_preprocessor.hpp:38
Eigen::Isometry3d T_imu_lidar
LiDAR-IMU transformation when cropbox is defined in IMU frame.
Definition cloud_preprocessor.hpp:35
bool use_random_grid_downsampling
If true, use random grid downsampling, otherwise, use the conventional voxel grid.
Definition cloud_preprocessor.hpp:24
std::string crop_bbox_frame
Bounding box reference frame.
Definition cloud_preprocessor.hpp:32
double distance_far_thresh
Maximum distance threshold.
Definition cloud_preprocessor.hpp:22
int downsample_target
Target number of points for downsampling.
Definition cloud_preprocessor.hpp:26
double downsample_rate
Downsamping rate (used for random grid downsampling)
Definition cloud_preprocessor.hpp:27
int k_correspondences
Number of neighboring points.
Definition cloud_preprocessor.hpp:36
int outlier_removal_k
Number of neighbors used for outlier removal.
Definition cloud_preprocessor.hpp:29
bool enable_cropbox_filter
If true, filter points out points within box.
Definition cloud_preprocessor.hpp:31
bool global_shutter
Assume all points in a scan are takes at the same moment and replace per-point timestamps with zero (...
Definition cloud_preprocessor.hpp:23
double outlier_std_mul_factor
Statistical outlier removal std dev threshold multiplication factor.
Definition cloud_preprocessor.hpp:30
bool enable_outlier_removal
If true, apply statistical outlier removal.
Definition cloud_preprocessor.hpp:28
Eigen::Vector3d crop_bbox_min
Bounding box min point.
Definition cloud_preprocessor.hpp:33
double downsample_resolution
Downsampling resolution.
Definition cloud_preprocessor.hpp:25
double distance_near_thresh
Minimum distance threshold.
Definition cloud_preprocessor.hpp:21