#include <edge_depth_refinement.h>
Public Types | |
typedef jsk_pcl_ros::EdgeDepthRefinementConfig | Config |
typedef pcl::PointXYZRGB | PointT |
typedef message_filters::sync_policies::ExactTime < sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > | SyncPolicy |
Protected Member Functions | |
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 () |
Protected Attributes | |
double | duplication_angle_threshold_ |
double | duplication_distance_threshold_ |
int | min_inliers_ |
boost::mutex | mutex_ |
double | outlier_distance_threshold_ |
ros::Publisher | pub_coefficients_ |
ros::Publisher | pub_edges_ |
ros::Publisher | pub_indices_ |
ros::Publisher | pub_outlier_removed_coefficients_ |
ros::Publisher | pub_outlier_removed_edges_ |
ros::Publisher | pub_outlier_removed_indices_ |
boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ |
message_filters::Subscriber < jsk_recognition_msgs::ClusterPointIndices > | sub_indices_ |
message_filters::Subscriber < sensor_msgs::PointCloud2 > | sub_input_ |
boost::shared_ptr < message_filters::Synchronizer < SyncPolicy > > | sync_ |
Definition at line 60 of file edge_depth_refinement.h.
typedef jsk_pcl_ros::EdgeDepthRefinementConfig jsk_pcl_ros::EdgeDepthRefinement::Config |
Definition at line 67 of file edge_depth_refinement.h.
typedef pcl::PointXYZRGB jsk_pcl_ros::EdgeDepthRefinement::PointT |
Definition at line 66 of file edge_depth_refinement.h.
typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ClusterPointIndices > jsk_pcl_ros::EdgeDepthRefinement::SyncPolicy |
Definition at line 65 of file edge_depth_refinement.h.
void jsk_pcl_ros::EdgeDepthRefinement::configCallback | ( | Config & | config, |
uint32_t | level | ||
) | [protected, virtual] |
Definition at line 394 of file edge_depth_refinement_nodelet.cpp.
boost::tuple< int, int > jsk_pcl_ros::EdgeDepthRefinement::findMinMaxIndex | ( | const int | width, |
const int | height, | ||
const std::vector< int > & | indices | ||
) | [protected, virtual] |
Definition at line 117 of file edge_depth_refinement_nodelet.cpp.
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 | ||
) | [protected, virtual] |
Definition at line 179 of file edge_depth_refinement_nodelet.cpp.
jsk_recognition_utils::Line::Ptr jsk_pcl_ros::EdgeDepthRefinement::lineFromCoefficients | ( | const pcl::ModelCoefficients::Ptr | coefficients | ) | [protected, virtual] |
Definition at line 104 of file edge_depth_refinement_nodelet.cpp.
void jsk_pcl_ros::EdgeDepthRefinement::onInit | ( | void | ) | [protected, virtual] |
Definition at line 46 of file edge_depth_refinement_nodelet.cpp.
void jsk_pcl_ros::EdgeDepthRefinement::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 | ||
) | [protected, virtual] |
Definition at line 355 of file edge_depth_refinement_nodelet.cpp.
void jsk_pcl_ros::EdgeDepthRefinement::refine | ( | const sensor_msgs::PointCloud2ConstPtr & | point, |
const jsk_recognition_msgs::ClusterPointIndicesConstPtr & | indices | ||
) | [protected, virtual] |
Definition at line 403 of file edge_depth_refinement_nodelet.cpp.
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 | ||
) | [protected, virtual] |
Definition at line 195 of file edge_depth_refinement_nodelet.cpp.
void jsk_pcl_ros::EdgeDepthRefinement::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 | ||
) | [protected, virtual] |
Definition at line 315 of file edge_depth_refinement_nodelet.cpp.
void jsk_pcl_ros::EdgeDepthRefinement::removeOutliersByLine | ( | const pcl::PointCloud< PointT >::Ptr & | cloud, |
const std::vector< int > & | indices, | ||
pcl::PointIndices & | inliers, | ||
pcl::ModelCoefficients & | coefficients | ||
) | [protected, virtual] |
Definition at line 335 of file edge_depth_refinement_nodelet.cpp.
jsk_recognition_utils::Segment::Ptr jsk_pcl_ros::EdgeDepthRefinement::segmentFromIndices | ( | const pcl::PointCloud< PointT >::Ptr & | cloud, |
const std::vector< int > & | indices, | ||
const jsk_recognition_utils::Line::Ptr & | line | ||
) | [protected, virtual] |
Definition at line 161 of file edge_depth_refinement_nodelet.cpp.
void jsk_pcl_ros::EdgeDepthRefinement::subscribe | ( | ) | [protected, virtual] |
Definition at line 76 of file edge_depth_refinement_nodelet.cpp.
void jsk_pcl_ros::EdgeDepthRefinement::unsubscribe | ( | ) | [protected, virtual] |
Definition at line 89 of file edge_depth_refinement_nodelet.cpp.
double jsk_pcl_ros::EdgeDepthRefinement::duplication_angle_threshold_ [protected] |
Definition at line 147 of file edge_depth_refinement.h.
double jsk_pcl_ros::EdgeDepthRefinement::duplication_distance_threshold_ [protected] |
Definition at line 148 of file edge_depth_refinement.h.
int jsk_pcl_ros::EdgeDepthRefinement::min_inliers_ [protected] |
Definition at line 143 of file edge_depth_refinement.h.
boost::mutex jsk_pcl_ros::EdgeDepthRefinement::mutex_ [protected] |
Definition at line 138 of file edge_depth_refinement.h.
double jsk_pcl_ros::EdgeDepthRefinement::outlier_distance_threshold_ [protected] |
Definition at line 142 of file edge_depth_refinement.h.
Definition at line 136 of file edge_depth_refinement.h.
Definition at line 137 of file edge_depth_refinement.h.
Definition at line 135 of file edge_depth_refinement.h.
Definition at line 136 of file edge_depth_refinement.h.
Definition at line 137 of file edge_depth_refinement.h.
Definition at line 135 of file edge_depth_refinement.h.
boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::EdgeDepthRefinement::srv_ [protected] |
Definition at line 131 of file edge_depth_refinement.h.
message_filters::Subscriber<jsk_recognition_msgs::ClusterPointIndices> jsk_pcl_ros::EdgeDepthRefinement::sub_indices_ [protected] |
Definition at line 133 of file edge_depth_refinement.h.
message_filters::Subscriber<sensor_msgs::PointCloud2> jsk_pcl_ros::EdgeDepthRefinement::sub_input_ [protected] |
Definition at line 132 of file edge_depth_refinement.h.
boost::shared_ptr<message_filters::Synchronizer<SyncPolicy> > jsk_pcl_ros::EdgeDepthRefinement::sync_ [protected] |
Definition at line 134 of file edge_depth_refinement.h.