#include <organized_pass_through.h>
|
typedef jsk_pcl_ros::OrganizedPassThroughConfig | Config |
|
typedef pcl::PointXYZRGB | PointT |
|
Definition at line 80 of file organized_pass_through.h.
◆ Config
◆ PointT
◆ FilterField
◆ OrganizedPassThrough()
jsk_pcl_ros::OrganizedPassThrough::OrganizedPassThrough |
( |
| ) |
|
◆ configCallback()
void jsk_pcl_ros::OrganizedPassThrough::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ filter()
void jsk_pcl_ros::OrganizedPassThrough::filter |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg | ) |
|
|
protectedvirtual |
◆ filterIndices()
pcl::PointIndices::Ptr jsk_pcl_ros::OrganizedPassThrough::filterIndices |
( |
const pcl::PointCloud< PointT >::Ptr & |
pc | ) |
|
|
protectedvirtual |
◆ isPointNaN()
bool jsk_pcl_ros::OrganizedPassThrough::isPointNaN |
( |
const PointT & |
p | ) |
|
|
inlineprotected |
◆ onInit()
void jsk_pcl_ros::OrganizedPassThrough::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ subscribe()
void jsk_pcl_ros::OrganizedPassThrough::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros::OrganizedPassThrough::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ updateDiagnostic()
◆ filter_field_
FilterField jsk_pcl_ros::OrganizedPassThrough::filter_field_ |
|
protected |
◆ filter_limit_negative_
bool jsk_pcl_ros::OrganizedPassThrough::filter_limit_negative_ |
|
protected |
◆ filtered_points_counter_
jsk_topic_tools::Counter jsk_pcl_ros::OrganizedPassThrough::filtered_points_counter_ |
|
protected |
◆ keep_organized_
bool jsk_pcl_ros::OrganizedPassThrough::keep_organized_ |
|
protected |
◆ max_index_
int jsk_pcl_ros::OrganizedPassThrough::max_index_ |
|
protected |
◆ min_index_
int jsk_pcl_ros::OrganizedPassThrough::min_index_ |
|
protected |
◆ mutex_
◆ pub_
◆ remove_nan_
bool jsk_pcl_ros::OrganizedPassThrough::remove_nan_ |
|
protected |
◆ srv_
◆ sub_
The documentation for this class was generated from the following files: