30 #ifndef MCL_3DL_LIDAR_MEASUREMENT_MODEL_BASE_H 31 #define MCL_3DL_LIDAR_MEASUREMENT_MODEL_BASE_H 40 #include <pcl/point_types.h> 58 : likelihood(likelihood_value)
59 , quality(quality_value)
67 using Ptr = std::shared_ptr<LidarMeasurementModelBase>;
76 virtual void loadConfig(
78 const std::string& name) = 0;
79 virtual void setGlobalLocalizationStatus(
80 const size_t,
const size_t) = 0;
81 virtual float getMaxSearchRange()
const = 0;
83 virtual pcl::PointCloud<PointType>::Ptr filter(
84 const pcl::PointCloud<PointType>::ConstPtr&)
const = 0;
88 const pcl::PointCloud<PointType>::ConstPtr&,
89 const std::vector<Vec3>&,
106 #endif // MCL_3DL_LIDAR_MEASUREMENT_MODEL_BASE_H LidarMeasurementModelBase()
std::shared_ptr< ChunkedKdtree > Ptr
void setRandomSampler(const std::shared_ptr< SamplerType > &sampler)
std::shared_ptr< SamplerType > sampler_
std::shared_ptr< LidarMeasurementModelBase > Ptr
LidarMeasurementResult(const float likelihood_value, const float quality_value)
std::shared_ptr< SamplerType > getRandomSampler()