#include <multi_plane_sac_segmentation.h>
|
virtual void | applyRecursiveRANSAC (const pcl::PointCloud< PointT >::Ptr &input, const pcl::PointCloud< pcl::Normal >::Ptr &normal, const Eigen::Vector3f &imu_vector, std::vector< pcl::PointIndices::Ptr > &output_inliers, std::vector< pcl::ModelCoefficients::Ptr > &output_coefficients, std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &output_polygons) |
|
virtual void | configCallback (Config &config, uint32_t level) |
|
virtual void | onInit () |
|
virtual void | publishResult (const std_msgs::Header &header, const std::vector< pcl::PointIndices::Ptr > &inliers, const std::vector< pcl::ModelCoefficients::Ptr > &coefficients, const std::vector< jsk_recognition_utils::ConvexPolygon::Ptr > &convexes) |
|
virtual void | segment (const sensor_msgs::PointCloud2::ConstPtr &msg) |
|
virtual void | segment (const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::PointCloud2::ConstPtr &msg_nromal) |
|
virtual void | segmentWithClusters (const sensor_msgs::PointCloud2::ConstPtr &msg, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &clusters) |
|
virtual void | segmentWithImu (const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::Imu::ConstPtr &imu) |
|
virtual void | segmentWithImu (const sensor_msgs::PointCloud2::ConstPtr &msg, const sensor_msgs::PointCloud2::ConstPtr &msg_nromal, const sensor_msgs::Imu::ConstPtr &imu) |
|
virtual void | subscribe () |
|
virtual void | unsubscribe () |
|
◆ Config
◆ NormalImuSynchronizer
◆ PointT
◆ SyncClusterPolicy
◆ SyncImuPolicy
◆ SyncNormalImuPolicy
◆ SyncPolicy
◆ ~MultiPlaneSACSegmentation()
jsk_pcl_ros::MultiPlaneSACSegmentation::~MultiPlaneSACSegmentation |
( |
| ) |
|
|
virtual |
◆ applyRecursiveRANSAC()
◆ configCallback()
void jsk_pcl_ros::MultiPlaneSACSegmentation::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ onInit()
void jsk_pcl_ros::MultiPlaneSACSegmentation::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ publishResult()
◆ segment() [1/2]
void jsk_pcl_ros::MultiPlaneSACSegmentation::segment |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg | ) |
|
|
protectedvirtual |
◆ segment() [2/2]
void jsk_pcl_ros::MultiPlaneSACSegmentation::segment |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg, |
|
|
const sensor_msgs::PointCloud2::ConstPtr & |
msg_nromal |
|
) |
| |
|
protectedvirtual |
◆ segmentWithClusters()
void jsk_pcl_ros::MultiPlaneSACSegmentation::segmentWithClusters |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg, |
|
|
const jsk_recognition_msgs::ClusterPointIndices::ConstPtr & |
clusters |
|
) |
| |
|
protectedvirtual |
◆ segmentWithImu() [1/2]
void jsk_pcl_ros::MultiPlaneSACSegmentation::segmentWithImu |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg, |
|
|
const sensor_msgs::Imu::ConstPtr & |
imu |
|
) |
| |
|
protectedvirtual |
◆ segmentWithImu() [2/2]
void jsk_pcl_ros::MultiPlaneSACSegmentation::segmentWithImu |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
msg, |
|
|
const sensor_msgs::PointCloud2::ConstPtr & |
msg_nromal, |
|
|
const sensor_msgs::Imu::ConstPtr & |
imu |
|
) |
| |
|
protectedvirtual |
◆ subscribe()
void jsk_pcl_ros::MultiPlaneSACSegmentation::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros::MultiPlaneSACSegmentation::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ eps_angle_
double jsk_pcl_ros::MultiPlaneSACSegmentation::eps_angle_ |
|
protected |
◆ max_iterations_
int jsk_pcl_ros::MultiPlaneSACSegmentation::max_iterations_ |
|
protected |
◆ min_inliers_
int jsk_pcl_ros::MultiPlaneSACSegmentation::min_inliers_ |
|
protected |
◆ min_points_
int jsk_pcl_ros::MultiPlaneSACSegmentation::min_points_ |
|
protected |
◆ min_trial_
int jsk_pcl_ros::MultiPlaneSACSegmentation::min_trial_ |
|
protected |
◆ mutex_
◆ normal_distance_weight_
double jsk_pcl_ros::MultiPlaneSACSegmentation::normal_distance_weight_ |
|
protected |
◆ outlier_threshold_
double jsk_pcl_ros::MultiPlaneSACSegmentation::outlier_threshold_ |
|
protected |
◆ pub_coefficients_
ros::Publisher jsk_pcl_ros::MultiPlaneSACSegmentation::pub_coefficients_ |
|
protected |
◆ pub_inliers_
◆ pub_polygons_
◆ srv_
◆ sub_
◆ sub_clusters_
◆ sub_imu_
◆ sub_input_
◆ sub_normal_
◆ sync_
◆ sync_cluster_
◆ sync_imu_
◆ sync_normal_imu_
◆ tf_listener_
◆ use_clusters_
bool jsk_pcl_ros::MultiPlaneSACSegmentation::use_clusters_ |
|
protected |
◆ use_imu_parallel_
bool jsk_pcl_ros::MultiPlaneSACSegmentation::use_imu_parallel_ |
|
protected |
◆ use_imu_perpendicular_
bool jsk_pcl_ros::MultiPlaneSACSegmentation::use_imu_perpendicular_ |
|
protected |
◆ use_normal_
bool jsk_pcl_ros::MultiPlaneSACSegmentation::use_normal_ |
|
protected |
The documentation for this class was generated from the following files: