30 #ifndef MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H 31 #define MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H 38 #include <pcl/point_types.h> 72 return map_grid_max_ * 4;
81 const std::string& name);
83 const size_t num_particles,
84 const size_t current_num_particles);
85 pcl::PointCloud<PointType>::Ptr
filter(
86 const pcl::PointCloud<PointType>::ConstPtr& pc)
const;
89 const pcl::PointCloud<PointType>::ConstPtr& pc,
90 const std::vector<Vec3>& origins,
95 #endif // MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H float beam_likelihood_min_
pcl::PointCloud< PointType >::Ptr filter(const pcl::PointCloud< PointType >::ConstPtr &pc) const
std::shared_ptr< ChunkedKdtree > Ptr
LidarMeasurementModelBeam(const float x, const float y, const float z)
LidarMeasurementResult measure(ChunkedKdtree< PointType >::Ptr &kdtree, const pcl::PointCloud< PointType >::ConstPtr &pc, const std::vector< Vec3 > &origins, const State6DOF &s) const
float getSinTotalRef() const
size_t num_points_default_
void setGlobalLocalizationStatus(const size_t num_particles, const size_t current_num_particles)
void loadConfig(const ros::NodeHandle &nh, const std::string &name)
float getMaxSearchRange() const
size_t num_points_global_
PointCloudRandomSampler sampler_