#include <hinted_plane_detector.h>
|
virtual void | configCallback (Config &config, uint32_t level) |
|
virtual void | densityFilter (const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const pcl::PointIndices::Ptr indices, pcl::PointIndices &output) |
|
virtual void | detect (const sensor_msgs::PointCloud2::ConstPtr &cloud_msg, const sensor_msgs::PointCloud2::ConstPtr &hint_cloud_msg) |
|
virtual bool | detectHintPlane (pcl::PointCloud< pcl::PointXYZ >::Ptr hint_cloud, jsk_recognition_utils::ConvexPolygon::Ptr &convex) |
|
virtual bool | detectLargerPlane (pcl::PointCloud< pcl::PointNormal >::Ptr input_cloud, jsk_recognition_utils::ConvexPolygon::Ptr hint_convex) |
|
virtual void | euclideanFilter (const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const pcl::PointIndices::Ptr indices, const jsk_recognition_utils::ConvexPolygon::Ptr hint_convex, pcl::PointIndices &output) |
|
virtual pcl::PointIndices::Ptr | getBestCluster (pcl::PointCloud< pcl::PointNormal >::Ptr input_cloud, const std::vector< pcl::PointIndices > &cluster_indices, const jsk_recognition_utils::ConvexPolygon::Ptr hint_convex) |
|
virtual void | hintFilter (const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const jsk_recognition_utils::ConvexPolygon::Ptr hint_convex, pcl::PointIndices &output) |
|
virtual void | onInit () |
|
virtual void | planeFilter (const pcl::PointCloud< pcl::PointNormal >::Ptr cloud, const pcl::PointIndices::Ptr indices, const Eigen::Vector3f &normal, pcl::PointIndices &output, pcl::ModelCoefficients &coefficients) |
|
virtual void | publishPolygon (const jsk_recognition_utils::ConvexPolygon::Ptr convex, ros::Publisher &pub_polygon, ros::Publisher &pub_polygon_array, const pcl::PCLHeader &header) |
|
virtual void | setHintCloud (const sensor_msgs::PointCloud2::ConstPtr &msg) |
|
virtual void | subscribe () |
|
virtual void | unsubscribe () |
|
Definition at line 88 of file hinted_plane_detector.h.
◆ Config
◆ SyncPolicy
◆ HintedPlaneDetector()
jsk_pcl_ros::HintedPlaneDetector::HintedPlaneDetector |
( |
| ) |
|
|
inline |
◆ ~HintedPlaneDetector()
jsk_pcl_ros::HintedPlaneDetector::~HintedPlaneDetector |
( |
| ) |
|
|
virtual |
◆ configCallback()
void jsk_pcl_ros::HintedPlaneDetector::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ densityFilter()
void jsk_pcl_ros::HintedPlaneDetector::densityFilter |
( |
const pcl::PointCloud< pcl::PointNormal >::Ptr |
cloud, |
|
|
const pcl::PointIndices::Ptr |
indices, |
|
|
pcl::PointIndices & |
output |
|
) |
| |
|
protectedvirtual |
◆ detect()
void jsk_pcl_ros::HintedPlaneDetector::detect |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
cloud_msg, |
|
|
const sensor_msgs::PointCloud2::ConstPtr & |
hint_cloud_msg |
|
) |
| |
|
protectedvirtual |
◆ detectHintPlane()
◆ detectLargerPlane()
◆ euclideanFilter()
◆ getBestCluster()
◆ hintFilter()
◆ onInit()
void jsk_pcl_ros::HintedPlaneDetector::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ planeFilter()
void jsk_pcl_ros::HintedPlaneDetector::planeFilter |
( |
const pcl::PointCloud< pcl::PointNormal >::Ptr |
cloud, |
|
|
const pcl::PointIndices::Ptr |
indices, |
|
|
const Eigen::Vector3f & |
normal, |
|
|
pcl::PointIndices & |
output, |
|
|
pcl::ModelCoefficients & |
coefficients |
|
) |
| |
|
protectedvirtual |
◆ publishPolygon()
◆ setHintCloud()
void jsk_pcl_ros::HintedPlaneDetector::setHintCloud |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg | ) |
|
|
protectedvirtual |
◆ subscribe()
void jsk_pcl_ros::HintedPlaneDetector::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros::HintedPlaneDetector::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ density_num_
int jsk_pcl_ros::HintedPlaneDetector::density_num_ |
|
protected |
◆ density_radius_
double jsk_pcl_ros::HintedPlaneDetector::density_radius_ |
|
protected |
◆ enable_density_filtering_
bool jsk_pcl_ros::HintedPlaneDetector::enable_density_filtering_ |
|
protected |
◆ enable_distance_filtering_
bool jsk_pcl_ros::HintedPlaneDetector::enable_distance_filtering_ |
|
protected |
◆ enable_euclidean_filtering_
bool jsk_pcl_ros::HintedPlaneDetector::enable_euclidean_filtering_ |
|
protected |
◆ enable_normal_filtering_
bool jsk_pcl_ros::HintedPlaneDetector::enable_normal_filtering_ |
|
protected |
◆ eps_angle_
double jsk_pcl_ros::HintedPlaneDetector::eps_angle_ |
|
protected |
◆ euclidean_clustering_filter_min_size_
int jsk_pcl_ros::HintedPlaneDetector::euclidean_clustering_filter_min_size_ |
|
protected |
◆ euclidean_clustering_filter_tolerance_
double jsk_pcl_ros::HintedPlaneDetector::euclidean_clustering_filter_tolerance_ |
|
protected |
◆ hint_cloud_
sensor_msgs::PointCloud2::ConstPtr jsk_pcl_ros::HintedPlaneDetector::hint_cloud_ |
|
protected |
◆ hint_max_iteration_
int jsk_pcl_ros::HintedPlaneDetector::hint_max_iteration_ |
|
protected |
◆ hint_min_size_
int jsk_pcl_ros::HintedPlaneDetector::hint_min_size_ |
|
protected |
◆ hint_outlier_threashold_
double jsk_pcl_ros::HintedPlaneDetector::hint_outlier_threashold_ |
|
protected |
◆ max_iteration_
int jsk_pcl_ros::HintedPlaneDetector::max_iteration_ |
|
protected |
◆ min_size_
int jsk_pcl_ros::HintedPlaneDetector::min_size_ |
|
protected |
◆ mutex_
◆ normal_filter_eps_angle_
double jsk_pcl_ros::HintedPlaneDetector::normal_filter_eps_angle_ |
|
protected |
◆ outlier_threashold_
double jsk_pcl_ros::HintedPlaneDetector::outlier_threashold_ |
|
protected |
◆ pub_coefficients_
◆ pub_density_filtered_indices_
ros::Publisher jsk_pcl_ros::HintedPlaneDetector::pub_density_filtered_indices_ |
|
protected |
◆ pub_euclidean_filtered_indices_
ros::Publisher jsk_pcl_ros::HintedPlaneDetector::pub_euclidean_filtered_indices_ |
|
protected |
◆ pub_hint_coefficients_
ros::Publisher jsk_pcl_ros::HintedPlaneDetector::pub_hint_coefficients_ |
|
protected |
◆ pub_hint_filtered_indices_
ros::Publisher jsk_pcl_ros::HintedPlaneDetector::pub_hint_filtered_indices_ |
|
protected |
◆ pub_hint_inliers_
◆ pub_hint_polygon_
◆ pub_hint_polygon_array_
ros::Publisher jsk_pcl_ros::HintedPlaneDetector::pub_hint_polygon_array_ |
|
protected |
◆ pub_inliers_
◆ pub_plane_filtered_indices_
ros::Publisher jsk_pcl_ros::HintedPlaneDetector::pub_plane_filtered_indices_ |
|
protected |
◆ pub_polygon_
◆ pub_polygon_array_
◆ srv_
◆ sub_cloud_
◆ sub_cloud_single_
◆ sub_hint_cloud_
◆ sub_hint_cloud_single_
◆ sync_
◆ synchronize_
bool jsk_pcl_ros::HintedPlaneDetector::synchronize_ |
|
protected |
The documentation for this class was generated from the following files: