#include <primitive_shape_classifier.h>
|
virtual bool | checkFrameId (const sensor_msgs::PointCloud2::ConstPtr &ros_cloud, const sensor_msgs::PointCloud2::ConstPtr &ros_normal, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &ros_indices, const jsk_recognition_msgs::PolygonArray::ConstPtr &ros_polygons) |
|
virtual void | configCallback (Config &config, uint32_t level) |
|
virtual bool | estimate (const pcl::PointCloud< PointT >::Ptr &cloud, const pcl::PointCloud< pcl::Normal >::Ptr &normal, const pcl::ModelCoefficients::Ptr &plane, pcl::PointIndices::Ptr &boundary_indices, pcl::PointCloud< PointT >::Ptr &projected_cloud, float &circle_likelihood, float &box_likelihood) |
|
virtual bool | getSupportPlane (const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< jsk_recognition_utils::Polygon::Ptr > &polygons, pcl::ModelCoefficients::Ptr &coeff) |
|
virtual void | onInit () |
|
virtual void | process (const sensor_msgs::PointCloud2::ConstPtr &ros_cloud, const sensor_msgs::PointCloud2::ConstPtr &ros_normal, const jsk_recognition_msgs::ClusterPointIndices::ConstPtr &ros_indices, const jsk_recognition_msgs::PolygonArray::ConstPtr &ros_polygons) |
|
virtual void | subscribe () |
|
virtual void | unsubscribe () |
|
◆ Config
◆ PointT
◆ SyncPolicy
◆ PrimitiveShapeClassifier()
jsk_pcl_ros::PrimitiveShapeClassifier::PrimitiveShapeClassifier |
( |
| ) |
|
|
inline |
◆ ~PrimitiveShapeClassifier()
jsk_pcl_ros::PrimitiveShapeClassifier::~PrimitiveShapeClassifier |
( |
| ) |
|
|
virtual |
◆ checkFrameId()
bool jsk_pcl_ros::PrimitiveShapeClassifier::checkFrameId |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
ros_cloud, |
|
|
const sensor_msgs::PointCloud2::ConstPtr & |
ros_normal, |
|
|
const jsk_recognition_msgs::ClusterPointIndices::ConstPtr & |
ros_indices, |
|
|
const jsk_recognition_msgs::PolygonArray::ConstPtr & |
ros_polygons |
|
) |
| |
|
protectedvirtual |
◆ configCallback()
void jsk_pcl_ros::PrimitiveShapeClassifier::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ estimate()
bool jsk_pcl_ros::PrimitiveShapeClassifier::estimate |
( |
const pcl::PointCloud< PointT >::Ptr & |
cloud, |
|
|
const pcl::PointCloud< pcl::Normal >::Ptr & |
normal, |
|
|
const pcl::ModelCoefficients::Ptr & |
plane, |
|
|
pcl::PointIndices::Ptr & |
boundary_indices, |
|
|
pcl::PointCloud< PointT >::Ptr & |
projected_cloud, |
|
|
float & |
circle_likelihood, |
|
|
float & |
box_likelihood |
|
) |
| |
|
protectedvirtual |
◆ getSupportPlane()
◆ onInit()
void jsk_pcl_ros::PrimitiveShapeClassifier::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ process()
void jsk_pcl_ros::PrimitiveShapeClassifier::process |
( |
const sensor_msgs::PointCloud2::ConstPtr & |
ros_cloud, |
|
|
const sensor_msgs::PointCloud2::ConstPtr & |
ros_normal, |
|
|
const jsk_recognition_msgs::ClusterPointIndices::ConstPtr & |
ros_indices, |
|
|
const jsk_recognition_msgs::PolygonArray::ConstPtr & |
ros_polygons |
|
) |
| |
|
protectedvirtual |
◆ subscribe()
void jsk_pcl_ros::PrimitiveShapeClassifier::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros::PrimitiveShapeClassifier::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ box_threshold_
double jsk_pcl_ros::PrimitiveShapeClassifier::box_threshold_ |
|
protected |
◆ circle_threshold_
double jsk_pcl_ros::PrimitiveShapeClassifier::circle_threshold_ |
|
protected |
◆ min_points_num_
int jsk_pcl_ros::PrimitiveShapeClassifier::min_points_num_ |
|
protected |
◆ mutex_
◆ pub_boundary_indices_
ros::Publisher jsk_pcl_ros::PrimitiveShapeClassifier::pub_boundary_indices_ |
|
protected |
◆ pub_class_
◆ pub_projected_cloud_
ros::Publisher jsk_pcl_ros::PrimitiveShapeClassifier::pub_projected_cloud_ |
|
protected |
◆ queue_size_
int jsk_pcl_ros::PrimitiveShapeClassifier::queue_size_ |
|
protected |
◆ sac_distance_threshold_
double jsk_pcl_ros::PrimitiveShapeClassifier::sac_distance_threshold_ |
|
protected |
◆ sac_max_iterations_
int jsk_pcl_ros::PrimitiveShapeClassifier::sac_max_iterations_ |
|
protected |
◆ sac_radius_limit_max_
double jsk_pcl_ros::PrimitiveShapeClassifier::sac_radius_limit_max_ |
|
protected |
◆ sac_radius_limit_min_
double jsk_pcl_ros::PrimitiveShapeClassifier::sac_radius_limit_min_ |
|
protected |
◆ srv_
◆ sub_cloud_
◆ sub_indices_
◆ sub_normal_
◆ sub_polygons_
◆ sync_
The documentation for this class was generated from the following files: