20#include <unordered_map>
53 const std::shared_ptr<apollo::drivers::OculiiPointCloud const>& message,
62 std::string
Name()
const override {
return "RadarPreprocessor"; }
66 const Eigen::Affine3d& pose,
69 float CalCompensatedVelocity(
73 float rcs_offset_ = 0.0f;
74 bool filter_naninf_points_ =
true;
75 bool filter_high_z_points_ =
true;
76 float z_threshold_ = 5.0f;
77 static const float kPointInfThreshold;
79 static int current_idx_;
80 static std::unordered_map<int, int> local2global_;
bool Init(const PreprocessorInitOptions &options) override
Init RadarPreprocessor config
bool Preprocess(const std::shared_ptr< apollo::drivers::OculiiPointCloud const > &message, const PreprocessorOptions &options, RadarFrame *frame) override
Process radar point cloud.
virtual ~RadarPreprocessor()
std::string Name() const override
The name of the RadarPreprocessor
#define DISALLOW_COPY_AND_ASSIGN(classname)
std::shared_ptr< RadarPointFCloud > RadarPointFCloudPtr
std::shared_ptr< RadarPointDCloud > RadarPointDCloudPtr