#include <normal_estimation_omp.h>

Public Types | |
| typedef pcl_ros::FeatureConfig | Config |
| typedef boost::shared_ptr< NormalEstimationOMP > | Ptr |
Public Member Functions | |
| NormalEstimationOMP () | |
Protected Member Functions | |
| virtual void | configCallback (Config &config, uint32_t level) |
| virtual void | estimate (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg) |
| virtual void | onInit () |
| virtual void | subscribe () |
| virtual void | unsubscribe () |
Protected Attributes | |
| int | k_ |
| boost::mutex | mutex_ |
| int | num_of_threads_ |
| ros::Publisher | pub_ |
| ros::Publisher | pub_average_time_ |
| ros::Publisher | pub_latest_time_ |
| ros::Publisher | pub_with_xyz_ |
| double | search_radius_ |
| std::string | sensor_frame_ |
| boost::shared_ptr< dynamic_reconfigure::Server< Config > > | srv_ |
| ros::Subscriber | sub_ |
| jsk_recognition_utils::WallDurationTimer | timer_ |
Definition at line 82 of file normal_estimation_omp.h.
| typedef pcl_ros::FeatureConfig jsk_pcl_ros::NormalEstimationOMP::Config |
Definition at line 118 of file normal_estimation_omp.h.
| typedef boost::shared_ptr<NormalEstimationOMP> jsk_pcl_ros::NormalEstimationOMP::Ptr |
Definition at line 117 of file normal_estimation_omp.h.
|
inline |
Definition at line 119 of file normal_estimation_omp.h.
|
protectedvirtual |
Definition at line 72 of file normal_estimation_omp_nodelet.cpp.
|
protectedvirtual |
Definition at line 80 of file normal_estimation_omp_nodelet.cpp.
|
protectedvirtual |
Definition at line 43 of file normal_estimation_omp_nodelet.cpp.
|
protectedvirtual |
Definition at line 62 of file normal_estimation_omp_nodelet.cpp.
|
protectedvirtual |
Definition at line 67 of file normal_estimation_omp_nodelet.cpp.
|
protected |
Definition at line 140 of file normal_estimation_omp.h.
|
protected |
Definition at line 131 of file normal_estimation_omp.h.
|
protected |
Definition at line 142 of file normal_estimation_omp.h.
|
protected |
Definition at line 132 of file normal_estimation_omp.h.
|
protected |
Definition at line 135 of file normal_estimation_omp.h.
|
protected |
Definition at line 134 of file normal_estimation_omp.h.
|
protected |
Definition at line 133 of file normal_estimation_omp.h.
|
protected |
Definition at line 141 of file normal_estimation_omp.h.
|
protected |
Definition at line 138 of file normal_estimation_omp.h.
|
protected |
Definition at line 139 of file normal_estimation_omp.h.
|
protected |
Definition at line 137 of file normal_estimation_omp.h.
|
protected |
Definition at line 136 of file normal_estimation_omp.h.