Public Member Functions | Private Types | Private Attributes | List of all members
mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE > Class Template Reference

#include <point_cloud_sampler_with_normal.h>

Inheritance diagram for mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >:
Inheritance graph
[legend]

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_
 

Detailed Description

template<class POINT_TYPE>
class mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >

Definition at line 53 of file point_cloud_sampler_with_normal.h.

Member Typedef Documentation

template<class POINT_TYPE>
using mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >::Matrix = Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic>
private

Definition at line 56 of file point_cloud_sampler_with_normal.h.

template<class POINT_TYPE>
using mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >::Vector = Eigen::Matrix<double, Eigen::Dynamic, 1>
private

Definition at line 57 of file point_cloud_sampler_with_normal.h.

Constructor & Destructor Documentation

template<class POINT_TYPE>
mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >::PointCloudSamplerWithNormal ( const unsigned int  random_seed = std::random_device()())
inlineexplicit

Definition at line 69 of file point_cloud_sampler_with_normal.h.

Member Function Documentation

template<class POINT_TYPE>
void mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >::loadConfig ( const ros::NodeHandle nh)
inline

Definition at line 78 of file point_cloud_sampler_with_normal.h.

template<class POINT_TYPE>
pcl::PointCloud<POINT_TYPE>::Ptr mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >::sample ( const typename pcl::PointCloud< POINT_TYPE >::ConstPtr &  pc,
const size_t  num 
) const
inlinefinalvirtual
template<class POINT_TYPE>
void mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >::setParameters ( const double  perform_weighting_ratio,
const double  max_weight_ratio,
const double  max_weight,
const double  normal_search_range 
)
inline

Definition at line 87 of file point_cloud_sampler_with_normal.h.

template<class POINT_TYPE>
void mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >::setParticleStatistics ( const State6DOF mean,
const std::vector< State6DOF > &  covariances 
)
inline

Definition at line 96 of file point_cloud_sampler_with_normal.h.

Member Data Documentation

template<class POINT_TYPE>
Vector mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >::eigen_values_
private

Definition at line 62 of file point_cloud_sampler_with_normal.h.

template<class POINT_TYPE>
Matrix mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >::eigen_vectors_
private

Definition at line 61 of file point_cloud_sampler_with_normal.h.

template<class POINT_TYPE>
std::shared_ptr<std::default_random_engine> mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >::engine_
private

Definition at line 59 of file point_cloud_sampler_with_normal.h.

template<class POINT_TYPE>
double mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >::max_weight_
private

Definition at line 65 of file point_cloud_sampler_with_normal.h.

template<class POINT_TYPE>
double mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >::max_weight_ratio_
private

Definition at line 64 of file point_cloud_sampler_with_normal.h.

template<class POINT_TYPE>
State6DOF mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >::mean_
private

Definition at line 60 of file point_cloud_sampler_with_normal.h.

template<class POINT_TYPE>
double mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >::normal_search_range_
private

Definition at line 66 of file point_cloud_sampler_with_normal.h.

template<class POINT_TYPE>
double mcl_3dl::PointCloudSamplerWithNormal< POINT_TYPE >::perform_weighting_ratio_
private

Definition at line 63 of file point_cloud_sampler_with_normal.h.


The documentation for this class was generated from the following file:


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:16:29