Go to the documentation of this file.
30 #ifndef MCL_3DL_LIDAR_MEASUREMENT_MODEL_BASE_H
31 #define MCL_3DL_LIDAR_MEASUREMENT_MODEL_BASE_H
40 #include <pcl/point_types.h>
67 using Ptr = std::shared_ptr<LidarMeasurementModelBase>;
78 const std::string& name) = 0;
80 const size_t,
const size_t) = 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
virtual pcl::PointCloud< PointType >::Ptr filter(const pcl::PointCloud< PointType >::ConstPtr &) const =0
virtual float getMaxSearchRange() const =0
std::shared_ptr< ChunkedKdtree > Ptr
std::shared_ptr< SamplerType > getRandomSampler()
LidarMeasurementModelBase()
virtual void setGlobalLocalizationStatus(const size_t, const size_t)=0
virtual void loadConfig(const ros::NodeHandle &nh, const std::string &name)=0
void setRandomSampler(const std::shared_ptr< SamplerType > &sampler)
virtual LidarMeasurementResult measure(ChunkedKdtree< PointType >::Ptr &, const pcl::PointCloud< PointType >::ConstPtr &, const std::vector< Vec3 > &, const State6DOF &) const =0
LidarMeasurementResult(const float likelihood_value, const float quality_value)
std::shared_ptr< SamplerType > sampler_
std::shared_ptr< LidarMeasurementModelBase > Ptr
mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Thu Oct 17 2024 02:18:04