Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
jsk_pcl_ros::PrimitiveShapeClassifier Class Reference

#include <primitive_shape_classifier.h>

Inheritance diagram for jsk_pcl_ros::PrimitiveShapeClassifier:
Inheritance graph
[legend]

Public Types

typedef PrimitiveShapeClassifierConfig Config
 
typedef pcl::PointXYZRGBA PointT
 
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray > SyncPolicy
 

Public Member Functions

 PrimitiveShapeClassifier ()
 
virtual ~PrimitiveShapeClassifier ()
 

Protected Member Functions

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 ()
 

Protected Attributes

double box_threshold_
 
double circle_threshold_
 
int min_points_num_
 
boost::mutex mutex_
 
ros::Publisher pub_boundary_indices_
 
ros::Publisher pub_class_
 
ros::Publisher pub_projected_cloud_
 
int queue_size_
 
double sac_distance_threshold_
 
int sac_max_iterations_
 
double sac_radius_limit_max_
 
double sac_radius_limit_min_
 
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_cloud_
 
message_filters::Subscriber< jsk_recognition_msgs::ClusterPointIndices > sub_indices_
 
message_filters::Subscriber< sensor_msgs::PointCloud2 > sub_normal_
 
message_filters::Subscriber< jsk_recognition_msgs::PolygonArray > sub_polygons_
 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
 

Detailed Description

Definition at line 94 of file primitive_shape_classifier.h.

Member Typedef Documentation

◆ Config

typedef PrimitiveShapeClassifierConfig jsk_pcl_ros::PrimitiveShapeClassifier::Config

Definition at line 133 of file primitive_shape_classifier.h.

◆ PointT

Definition at line 134 of file primitive_shape_classifier.h.

◆ SyncPolicy

typedef message_filters::sync_policies::ExactTime<sensor_msgs::PointCloud2, sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices, jsk_recognition_msgs::PolygonArray> jsk_pcl_ros::PrimitiveShapeClassifier::SyncPolicy

Definition at line 132 of file primitive_shape_classifier.h.

Constructor & Destructor Documentation

◆ PrimitiveShapeClassifier()

jsk_pcl_ros::PrimitiveShapeClassifier::PrimitiveShapeClassifier ( )
inline

Definition at line 136 of file primitive_shape_classifier.h.

◆ ~PrimitiveShapeClassifier()

jsk_pcl_ros::PrimitiveShapeClassifier::~PrimitiveShapeClassifier ( )
virtual

Definition at line 104 of file primitive_shape_classifier_nodelet.cpp.

Member Function Documentation

◆ 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

Definition at line 163 of file primitive_shape_classifier_nodelet.cpp.

◆ configCallback()

void jsk_pcl_ros::PrimitiveShapeClassifier::configCallback ( Config config,
uint32_t  level 
)
protectedvirtual

Definition at line 135 of file primitive_shape_classifier_nodelet.cpp.

◆ 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

Definition at line 295 of file primitive_shape_classifier_nodelet.cpp.

◆ getSupportPlane()

bool jsk_pcl_ros::PrimitiveShapeClassifier::getSupportPlane ( const pcl::PointCloud< PointT >::Ptr &  cloud,
const std::vector< jsk_recognition_utils::Polygon::Ptr > &  polygons,
pcl::ModelCoefficients::Ptr &  coeff 
)
protectedvirtual

Definition at line 376 of file primitive_shape_classifier_nodelet.cpp.

◆ onInit()

void jsk_pcl_ros::PrimitiveShapeClassifier::onInit ( )
protectedvirtual

Definition at line 86 of file primitive_shape_classifier_nodelet.cpp.

◆ 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

Definition at line 189 of file primitive_shape_classifier_nodelet.cpp.

◆ subscribe()

void jsk_pcl_ros::PrimitiveShapeClassifier::subscribe ( )
protectedvirtual

Definition at line 115 of file primitive_shape_classifier_nodelet.cpp.

◆ unsubscribe()

void jsk_pcl_ros::PrimitiveShapeClassifier::unsubscribe ( )
protectedvirtual

Definition at line 127 of file primitive_shape_classifier_nodelet.cpp.

Member Data Documentation

◆ box_threshold_

double jsk_pcl_ros::PrimitiveShapeClassifier::box_threshold_
protected

Definition at line 188 of file primitive_shape_classifier.h.

◆ circle_threshold_

double jsk_pcl_ros::PrimitiveShapeClassifier::circle_threshold_
protected

Definition at line 188 of file primitive_shape_classifier.h.

◆ min_points_num_

int jsk_pcl_ros::PrimitiveShapeClassifier::min_points_num_
protected

Definition at line 184 of file primitive_shape_classifier.h.

◆ mutex_

boost::mutex jsk_pcl_ros::PrimitiveShapeClassifier::mutex_
protected

Definition at line 171 of file primitive_shape_classifier.h.

◆ pub_boundary_indices_

ros::Publisher jsk_pcl_ros::PrimitiveShapeClassifier::pub_boundary_indices_
protected

Definition at line 179 of file primitive_shape_classifier.h.

◆ pub_class_

ros::Publisher jsk_pcl_ros::PrimitiveShapeClassifier::pub_class_
protected

Definition at line 178 of file primitive_shape_classifier.h.

◆ pub_projected_cloud_

ros::Publisher jsk_pcl_ros::PrimitiveShapeClassifier::pub_projected_cloud_
protected

Definition at line 180 of file primitive_shape_classifier.h.

◆ queue_size_

int jsk_pcl_ros::PrimitiveShapeClassifier::queue_size_
protected

Definition at line 183 of file primitive_shape_classifier.h.

◆ sac_distance_threshold_

double jsk_pcl_ros::PrimitiveShapeClassifier::sac_distance_threshold_
protected

Definition at line 186 of file primitive_shape_classifier.h.

◆ sac_max_iterations_

int jsk_pcl_ros::PrimitiveShapeClassifier::sac_max_iterations_
protected

Definition at line 185 of file primitive_shape_classifier.h.

◆ sac_radius_limit_max_

double jsk_pcl_ros::PrimitiveShapeClassifier::sac_radius_limit_max_
protected

Definition at line 187 of file primitive_shape_classifier.h.

◆ sac_radius_limit_min_

double jsk_pcl_ros::PrimitiveShapeClassifier::sac_radius_limit_min_
protected

Definition at line 187 of file primitive_shape_classifier.h.

◆ srv_

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::PrimitiveShapeClassifier::srv_
protected

Definition at line 172 of file primitive_shape_classifier.h.

◆ sub_cloud_

message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::PrimitiveShapeClassifier::sub_cloud_
protected

Definition at line 173 of file primitive_shape_classifier.h.

◆ sub_indices_

message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> jsk_pcl_ros::PrimitiveShapeClassifier::sub_indices_
protected

Definition at line 175 of file primitive_shape_classifier.h.

◆ sub_normal_

message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::PrimitiveShapeClassifier::sub_normal_
protected

Definition at line 174 of file primitive_shape_classifier.h.

◆ sub_polygons_

message_filters::Subscriber<jsk_recognition_msgs::PolygonArray> jsk_pcl_ros::PrimitiveShapeClassifier::sub_polygons_
protected

Definition at line 176 of file primitive_shape_classifier.h.

◆ sync_

boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::PrimitiveShapeClassifier::sync_
protected

Definition at line 177 of file primitive_shape_classifier.h.


The documentation for this class was generated from the following files:


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:46