30 #ifndef MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H 31 #define MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H 39 #include <pcl/point_types.h> 54 std::shared_ptr<Raycast<LidarMeasurementModelBase::PointType>>
raycaster_;
98 const std::string& name);
100 const size_t num_particles,
101 const size_t current_num_particles);
102 pcl::PointCloud<PointType>::Ptr
filter(
103 const pcl::PointCloud<PointType>::ConstPtr& pc)
const;
106 const pcl::PointCloud<PointType>::ConstPtr& pc,
107 const std::vector<Vec3>& origins,
111 const Vec3& beam_begin,
const Vec3& beam_end,
116 #endif // MCL_3DL_LIDAR_MEASUREMENT_MODELS_LIDAR_MEASUREMENT_MODEL_BEAM_H float beam_likelihood_min_
bool add_penalty_short_only_mode_
uint32_t filter_label_max_
pcl::PointCloud< PointType >::Ptr filter(const pcl::PointCloud< PointType >::ConstPtr &pc) const
float additional_search_range_
std::shared_ptr< ChunkedKdtree > Ptr
uint32_t getFilterLabelMax() const
std::shared_ptr< Raycast< LidarMeasurementModelBase::PointType > > raycaster_
LidarMeasurementResult measure(ChunkedKdtree< PointType >::Ptr &kdtree, const pcl::PointCloud< PointType >::ConstPtr &pc, const std::vector< Vec3 > &origins, const State6DOF &s) const
BeamStatus getBeamStatus(ChunkedKdtree< PointType >::Ptr &kdtree, const Vec3 &beam_begin, const Vec3 &beam_end, typename mcl_3dl::Raycast< PointType >::CastResult &result) 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)
LidarMeasurementModelBeam(const float grid_size_x, const float grid_size_y, const float grid_size_z)
float getMaxSearchRange() const
size_t num_points_global_