#include <edge_depth_refinement.h>
|
virtual void | configCallback (Config &config, uint32_t level) |
|
virtual boost::tuple< int, int > | findMinMaxIndex (const int width, const int height, const std::vector< int > &indices) |
|
virtual void | integrateDuplicatedIndices (const pcl::PointCloud< PointT >::Ptr &cloud, const std::set< int > &duplicated_set, const std::vector< pcl::PointIndices::Ptr > all_inliers, pcl::PointIndices::Ptr &output_indices) |
|
virtual jsk_recognition_utils::Line::Ptr | lineFromCoefficients (const pcl::ModelCoefficients::Ptr coefficients) |
|
virtual void | onInit () |
|
virtual void | publishIndices (ros::Publisher &pub, ros::Publisher &pub_coefficients, ros::Publisher &pub_edges, const std::vector< pcl::PointIndices::Ptr > inliers, const std::vector< pcl::ModelCoefficients::Ptr > coefficients, const std_msgs::Header &header) |
|
virtual void | refine (const sensor_msgs::PointCloud2ConstPtr &point, const jsk_recognition_msgs::ClusterPointIndicesConstPtr &indices) |
|
virtual void | removeDuplicatedEdges (const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< pcl::PointIndices::Ptr > inliers, const std::vector< pcl::ModelCoefficients::Ptr > coefficients, std::vector< pcl::PointIndices::Ptr > &output_inliers, std::vector< pcl::ModelCoefficients::Ptr > &output_coefficients) |
|
virtual void | removeOutliers (const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< PCLIndicesMsg > &indices, std::vector< pcl::PointIndices::Ptr > &output_inliers, std::vector< pcl::ModelCoefficients::Ptr > &output_coefficients) |
|
virtual void | removeOutliersByLine (const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< int > &indices, pcl::PointIndices &inliers, pcl::ModelCoefficients &coefficients) |
|
virtual jsk_recognition_utils::Segment::Ptr | segmentFromIndices (const pcl::PointCloud< PointT >::Ptr &cloud, const std::vector< int > &indices, const jsk_recognition_utils::Line::Ptr &line) |
|
virtual void | subscribe () |
|
virtual void | unsubscribe () |
|
Definition at line 92 of file edge_depth_refinement.h.
◆ Config
◆ PointT
◆ SyncPolicy
◆ ~EdgeDepthRefinement()
jsk_pcl_ros::EdgeDepthRefinement::~EdgeDepthRefinement |
( |
| ) |
|
|
virtual |
◆ configCallback()
void jsk_pcl_ros::EdgeDepthRefinement::configCallback |
( |
Config & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
protectedvirtual |
◆ findMinMaxIndex()
boost::tuple< int, int > jsk_pcl_ros::EdgeDepthRefinement::findMinMaxIndex |
( |
const int |
width, |
|
|
const int |
height, |
|
|
const std::vector< int > & |
indices |
|
) |
| |
|
protectedvirtual |
◆ integrateDuplicatedIndices()
void jsk_pcl_ros::EdgeDepthRefinement::integrateDuplicatedIndices |
( |
const pcl::PointCloud< PointT >::Ptr & |
cloud, |
|
|
const std::set< int > & |
duplicated_set, |
|
|
const std::vector< pcl::PointIndices::Ptr > |
all_inliers, |
|
|
pcl::PointIndices::Ptr & |
output_indices |
|
) |
| |
|
protectedvirtual |
◆ lineFromCoefficients()
◆ onInit()
void jsk_pcl_ros::EdgeDepthRefinement::onInit |
( |
| ) |
|
|
protectedvirtual |
◆ publishIndices()
◆ refine()
void jsk_pcl_ros::EdgeDepthRefinement::refine |
( |
const sensor_msgs::PointCloud2ConstPtr & |
point, |
|
|
const jsk_recognition_msgs::ClusterPointIndicesConstPtr & |
indices |
|
) |
| |
|
protectedvirtual |
◆ removeDuplicatedEdges()
void jsk_pcl_ros::EdgeDepthRefinement::removeDuplicatedEdges |
( |
const pcl::PointCloud< PointT >::Ptr & |
cloud, |
|
|
const std::vector< pcl::PointIndices::Ptr > |
inliers, |
|
|
const std::vector< pcl::ModelCoefficients::Ptr > |
coefficients, |
|
|
std::vector< pcl::PointIndices::Ptr > & |
output_inliers, |
|
|
std::vector< pcl::ModelCoefficients::Ptr > & |
output_coefficients |
|
) |
| |
|
protectedvirtual |
◆ removeOutliers()
◆ removeOutliersByLine()
void jsk_pcl_ros::EdgeDepthRefinement::removeOutliersByLine |
( |
const pcl::PointCloud< PointT >::Ptr & |
cloud, |
|
|
const std::vector< int > & |
indices, |
|
|
pcl::PointIndices & |
inliers, |
|
|
pcl::ModelCoefficients & |
coefficients |
|
) |
| |
|
protectedvirtual |
◆ segmentFromIndices()
◆ subscribe()
void jsk_pcl_ros::EdgeDepthRefinement::subscribe |
( |
| ) |
|
|
protectedvirtual |
◆ unsubscribe()
void jsk_pcl_ros::EdgeDepthRefinement::unsubscribe |
( |
| ) |
|
|
protectedvirtual |
◆ duplication_angle_threshold_
double jsk_pcl_ros::EdgeDepthRefinement::duplication_angle_threshold_ |
|
protected |
◆ duplication_distance_threshold_
double jsk_pcl_ros::EdgeDepthRefinement::duplication_distance_threshold_ |
|
protected |
◆ min_inliers_
int jsk_pcl_ros::EdgeDepthRefinement::min_inliers_ |
|
protected |
◆ mutex_
◆ outlier_distance_threshold_
double jsk_pcl_ros::EdgeDepthRefinement::outlier_distance_threshold_ |
|
protected |
◆ pub_coefficients_
◆ pub_edges_
◆ pub_indices_
◆ pub_outlier_removed_coefficients_
ros::Publisher jsk_pcl_ros::EdgeDepthRefinement::pub_outlier_removed_coefficients_ |
|
protected |
◆ pub_outlier_removed_edges_
ros::Publisher jsk_pcl_ros::EdgeDepthRefinement::pub_outlier_removed_edges_ |
|
protected |
◆ pub_outlier_removed_indices_
ros::Publisher jsk_pcl_ros::EdgeDepthRefinement::pub_outlier_removed_indices_ |
|
protected |
◆ srv_
◆ sub_indices_
◆ sub_input_
◆ sync_
The documentation for this class was generated from the following files: