21#include "modules/common_msgs/sensor_msgs/oculii_radar.pb.h"
73 const std::shared_ptr<apollo::drivers::OculiiPointCloud const>& message,
82 virtual std::string
Name()
const = 0;
89#define PERCEPTION_REGISTER_PREPROCESSOR(name) \
90 PERCEPTION_REGISTER_CLASS(BasePreprocessor, name)
virtual bool Preprocess(const std::shared_ptr< apollo::drivers::OculiiPointCloud const > &message, const PreprocessorOptions &options, RadarFrame *frame)=0
Process radar point cloud.
virtual ~BasePreprocessor()=default
BasePreprocessor()=default
Construct a new Base Preprocessor object
virtual bool Init(const PreprocessorInitOptions &options)=0
Init base preprocessor config
virtual std::string Name() const =0
The name of the radar base Preprocessor
#define DISALLOW_COPY_AND_ASSIGN(classname)
#define PERCEPTION_REGISTER_REGISTERER(base_class)
Eigen::Vector3f car_angular_speed
Eigen::Vector3f car_linear_speed
Eigen::Matrix4d * radar2novatel_trans
Eigen::Matrix4d * radar2world_pose