#include <point_cloud_sampler_with_normal.h>
Public Member Functions | |
void | loadConfig (const ros::NodeHandle &nh) |
PointCloudSamplerWithNormal (const unsigned int random_seed=std::random_device()()) | |
pcl::PointCloud< POINT_TYPE >::Ptr | sample (const typename pcl::PointCloud< POINT_TYPE >::ConstPtr &pc, const size_t num) const final |
void | setParameters (const double perform_weighting_ratio, const double max_weight_ratio, const double max_weight, const double normal_search_range) |
void | setParticleStatistics (const State6DOF &mean, const std::vector< State6DOF > &covariances) |
Private Types | |
using | Matrix = Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic > |
using | Vector = Eigen::Matrix< double, Eigen::Dynamic, 1 > |
Private Attributes | |
Vector | eigen_values_ |
Matrix | eigen_vectors_ |
std::shared_ptr< std::default_random_engine > | engine_ |
double | max_weight_ |
double | max_weight_ratio_ |
State6DOF | mean_ |
double | normal_search_range_ |
double | perform_weighting_ratio_ |
Definition at line 53 of file point_cloud_sampler_with_normal.h.
|
private |
Definition at line 56 of file point_cloud_sampler_with_normal.h.
|
private |
Definition at line 57 of file point_cloud_sampler_with_normal.h.
|
inlineexplicit |
Definition at line 69 of file point_cloud_sampler_with_normal.h.
|
inline |
Definition at line 78 of file point_cloud_sampler_with_normal.h.
|
inlinefinalvirtual |
Implements mcl_3dl::PointCloudRandomSampler< POINT_TYPE >.
Definition at line 112 of file point_cloud_sampler_with_normal.h.
|
inline |
Definition at line 87 of file point_cloud_sampler_with_normal.h.
|
inline |
Definition at line 96 of file point_cloud_sampler_with_normal.h.
|
private |
Definition at line 62 of file point_cloud_sampler_with_normal.h.
|
private |
Definition at line 61 of file point_cloud_sampler_with_normal.h.
|
private |
Definition at line 59 of file point_cloud_sampler_with_normal.h.
|
private |
Definition at line 65 of file point_cloud_sampler_with_normal.h.
|
private |
Definition at line 64 of file point_cloud_sampler_with_normal.h.
|
private |
Definition at line 60 of file point_cloud_sampler_with_normal.h.
|
private |
Definition at line 66 of file point_cloud_sampler_with_normal.h.
|
private |
Definition at line 63 of file point_cloud_sampler_with_normal.h.