Public Types | Protected Member Functions | Protected Attributes
jsk_pcl_ros::EdgebasedCubeFinder Class Reference

#include <edgebased_cube_finder.h>

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

List of all members.

Public Types

typedef
jsk_pcl_ros::EdgebasedCubeFinderConfig 
Config
enum  EdgeRelation { NOT_PERPENDICULAR, A_PERPENDICULAR, B_PERPENDICULAR, C_PERPENDICULAR }
typedef pcl::PointXYZRGB PointT
typedef
message_filters::sync_policies::ExactTime
< sensor_msgs::PointCloud2,
jsk_recognition_msgs::ParallelEdgeArray > 
SyncPolicy

Protected Member Functions

virtual std::vector
< CoefficientsPair
combinateCoefficients (const std::vector< pcl::ModelCoefficients::Ptr > &coefficients)
virtual std::vector< IndicesPaircombinateIndices (const std::vector< pcl::PointIndices::Ptr > &indices)
virtual void configCallback (Config &config, uint32_t level)
virtual ConvexPolygon::Ptr convexFromPairs (const pcl::PointCloud< PointT >::Ptr cloud, const CoefficientsPair &coefficients_pair, const IndicesPair &indices_pair)
virtual int countInliers (const pcl::PointCloud< PointT >::Ptr cloud, const ConvexPolygon::Ptr convex)
virtual Cube::Ptr cubeFromIndicesAndCoefficients (const pcl::PointCloud< PointT >::Ptr cloud, const IndicesCoefficientsTriple &indices_coefficients_triple, pcl::PointCloud< EdgebasedCubeFinder::PointT >::Ptr points_on_edge)
virtual void estimate (const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr &input_edges)
virtual void estimate2 (const sensor_msgs::PointCloud2::ConstPtr &input_cloud, const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr &input_edges)
virtual ConvexPolygon::Ptr estimateConvexPolygon (const pcl::PointCloud< PointT >::Ptr cloud, const pcl::PointIndices::Ptr indices, pcl::ModelCoefficients::Ptr coefficients, pcl::PointIndices::Ptr inliers)
virtual void estimateParallelPlane (const ConvexPolygon::Ptr convex, const pcl::PointCloud< PointT >::Ptr filtered_cloud, pcl::PointIndices::Ptr output_inliers, pcl::ModelCoefficients::Ptr output_coefficients)
virtual void estimatePerpendicularPlane (const ConvexPolygon::Ptr convex, const CoefficientsPair &edge_coefficients, const pcl::PointCloud< PointT >::Ptr filtered_cloud, pcl::PointIndices::Ptr output_inliers, pcl::ModelCoefficients::Ptr output_coefficients)
virtual pcl::PointCloud
< PointT >::Ptr 
extractPointCloud (const pcl::PointCloud< PointT >::Ptr cloud, const pcl::PointIndices::Ptr indices)
virtual void filterBasedOnConvex (const pcl::PointCloud< PointT >::Ptr cloud, const std::vector< ConvexPolygon::Ptr > &convexes, std::vector< int > &output_indices)
virtual void filterPairsBasedOnParallelEdgeDistances (const std::vector< IndicesPair > &pairs, const std::vector< CoefficientsPair > &coefficients_pair, std::vector< IndicesPair > &filtered_indices_pairs, std::vector< CoefficientsPair > &filtered_coefficients_pairs)
virtual std::vector
< IndicesCoefficientsTriple
filterPerpendicularEdgeTriples (const std::vector< IndicesCoefficientsTriple > &triples)
virtual bool isPerpendicularVector (const Eigen::Vector3f &a, const Eigen::Vector3f &b)
virtual Line::Ptr midLineFromCoefficientsPair (const CoefficientsPair &pair)
virtual PointPair minMaxPointOnLine (const Line &line, const pcl::PointCloud< PointT >::Ptr cloud)
virtual void onInit ()
virtual EdgeRelation perpendicularEdgeTriple (const Line &edge_a, const Line &edge_b, const Line &edge_c)
virtual pcl::PointIndices::Ptr preparePointCloudForRANSAC (const ConvexPolygon::Ptr convex, const CoefficientsPair &edge_coefficients_pair, const pcl::PointCloud< PointT >::Ptr cloud)
virtual void subscribe ()
virtual std::vector
< IndicesCoefficientsTriple
tripleIndicesAndCoefficients (const std::vector< pcl::PointIndices::Ptr > &indices, const std::vector< pcl::ModelCoefficients::Ptr > &coefficients)
virtual void unsubscribe ()

Protected Attributes

double convex_area_threshold_
double convex_edge_threshold_
double min_inliers_
boost::mutex mutex_
double outlier_threshold_
double parallel_edge_distance_max_threshold_
double parallel_edge_distance_min_threshold_
ros::Publisher pub_
ros::Publisher pub_debug_clusers_
ros::Publisher pub_debug_filtered_cloud_
ros::Publisher pub_debug_marker_
ros::Publisher pub_debug_polygons_
ros::Publisher pub_pose_array_
boost::shared_ptr
< dynamic_reconfigure::Server
< Config > > 
srv_
message_filters::Subscriber
< jsk_recognition_msgs::ParallelEdgeArray > 
sub_edges_
message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
sub_input_
boost::shared_ptr
< message_filters::Synchronizer
< SyncPolicy > > 
sync_

Detailed Description

Definition at line 157 of file edgebased_cube_finder.h.


Member Typedef Documentation

typedef jsk_pcl_ros::EdgebasedCubeFinderConfig jsk_pcl_ros::EdgebasedCubeFinder::Config

Definition at line 164 of file edgebased_cube_finder.h.

typedef pcl::PointXYZRGB jsk_pcl_ros::EdgebasedCubeFinder::PointT

Definition at line 163 of file edgebased_cube_finder.h.

typedef message_filters::sync_policies::ExactTime< sensor_msgs::PointCloud2, jsk_recognition_msgs::ParallelEdgeArray > jsk_pcl_ros::EdgebasedCubeFinder::SyncPolicy

Definition at line 162 of file edgebased_cube_finder.h.


Member Enumeration Documentation

Enumerator:
NOT_PERPENDICULAR 
A_PERPENDICULAR 
B_PERPENDICULAR 
C_PERPENDICULAR 

Definition at line 165 of file edgebased_cube_finder.h.


Member Function Documentation

std::vector< CoefficientsPair > jsk_pcl_ros::EdgebasedCubeFinder::combinateCoefficients ( const std::vector< pcl::ModelCoefficients::Ptr > &  coefficients) [protected, virtual]

Definition at line 1203 of file edgebased_cube_finder_nodelet.cpp.

std::vector< IndicesPair > jsk_pcl_ros::EdgebasedCubeFinder::combinateIndices ( const std::vector< pcl::PointIndices::Ptr > &  indices) [protected, virtual]

Definition at line 1189 of file edgebased_cube_finder_nodelet.cpp.

void jsk_pcl_ros::EdgebasedCubeFinder::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]

Definition at line 366 of file edgebased_cube_finder_nodelet.cpp.

ConvexPolygon::Ptr jsk_pcl_ros::EdgebasedCubeFinder::convexFromPairs ( const pcl::PointCloud< PointT >::Ptr  cloud,
const CoefficientsPair coefficients_pair,
const IndicesPair indices_pair 
) [protected, virtual]

Definition at line 460 of file edgebased_cube_finder_nodelet.cpp.

int jsk_pcl_ros::EdgebasedCubeFinder::countInliers ( const pcl::PointCloud< PointT >::Ptr  cloud,
const ConvexPolygon::Ptr  convex 
) [protected, virtual]

Definition at line 328 of file edgebased_cube_finder_nodelet.cpp.

Cube::Ptr jsk_pcl_ros::EdgebasedCubeFinder::cubeFromIndicesAndCoefficients ( const pcl::PointCloud< PointT >::Ptr  cloud,
const IndicesCoefficientsTriple indices_coefficients_triple,
pcl::PointCloud< EdgebasedCubeFinder::PointT >::Ptr  points_on_edge 
) [protected, virtual]

Definition at line 589 of file edgebased_cube_finder_nodelet.cpp.

void jsk_pcl_ros::EdgebasedCubeFinder::estimate ( const sensor_msgs::PointCloud2::ConstPtr &  input_cloud,
const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr &  input_edges 
) [protected, virtual]

Definition at line 700 of file edgebased_cube_finder_nodelet.cpp.

void jsk_pcl_ros::EdgebasedCubeFinder::estimate2 ( const sensor_msgs::PointCloud2::ConstPtr &  input_cloud,
const jsk_recognition_msgs::ParallelEdgeArray::ConstPtr &  input_edges 
) [protected, virtual]

Definition at line 866 of file edgebased_cube_finder_nodelet.cpp.

ConvexPolygon::Ptr jsk_pcl_ros::EdgebasedCubeFinder::estimateConvexPolygon ( const pcl::PointCloud< PointT >::Ptr  cloud,
const pcl::PointIndices::Ptr  indices,
pcl::ModelCoefficients::Ptr  coefficients,
pcl::PointIndices::Ptr  inliers 
) [protected, virtual]

Definition at line 1160 of file edgebased_cube_finder_nodelet.cpp.

void jsk_pcl_ros::EdgebasedCubeFinder::estimateParallelPlane ( const ConvexPolygon::Ptr  convex,
const pcl::PointCloud< PointT >::Ptr  filtered_cloud,
pcl::PointIndices::Ptr  output_inliers,
pcl::ModelCoefficients::Ptr  output_coefficients 
) [protected, virtual]

Definition at line 546 of file edgebased_cube_finder_nodelet.cpp.

void jsk_pcl_ros::EdgebasedCubeFinder::estimatePerpendicularPlane ( const ConvexPolygon::Ptr  convex,
const CoefficientsPair edge_coefficients,
const pcl::PointCloud< PointT >::Ptr  filtered_cloud,
pcl::PointIndices::Ptr  output_inliers,
pcl::ModelCoefficients::Ptr  output_coefficients 
) [protected, virtual]

Definition at line 565 of file edgebased_cube_finder_nodelet.cpp.

pcl::PointCloud< EdgebasedCubeFinder::PointT >::Ptr jsk_pcl_ros::EdgebasedCubeFinder::extractPointCloud ( const pcl::PointCloud< PointT >::Ptr  cloud,
const pcl::PointIndices::Ptr  indices 
) [protected, virtual]

Definition at line 433 of file edgebased_cube_finder_nodelet.cpp.

void jsk_pcl_ros::EdgebasedCubeFinder::filterBasedOnConvex ( const pcl::PointCloud< PointT >::Ptr  cloud,
const std::vector< ConvexPolygon::Ptr > &  convexes,
std::vector< int > &  output_indices 
) [protected, virtual]

Definition at line 345 of file edgebased_cube_finder_nodelet.cpp.

void jsk_pcl_ros::EdgebasedCubeFinder::filterPairsBasedOnParallelEdgeDistances ( const std::vector< IndicesPair > &  pairs,
const std::vector< CoefficientsPair > &  coefficients_pair,
std::vector< IndicesPair > &  filtered_indices_pairs,
std::vector< CoefficientsPair > &  filtered_coefficients_pairs 
) [protected, virtual]

Definition at line 486 of file edgebased_cube_finder_nodelet.cpp.

Definition at line 811 of file edgebased_cube_finder_nodelet.cpp.

bool jsk_pcl_ros::EdgebasedCubeFinder::isPerpendicularVector ( const Eigen::Vector3f &  a,
const Eigen::Vector3f &  b 
) [protected, virtual]

Definition at line 758 of file edgebased_cube_finder_nodelet.cpp.

Definition at line 423 of file edgebased_cube_finder_nodelet.cpp.

PointPair jsk_pcl_ros::EdgebasedCubeFinder::minMaxPointOnLine ( const Line line,
const pcl::PointCloud< PointT >::Ptr  cloud 
) [protected, virtual]

Definition at line 445 of file edgebased_cube_finder_nodelet.cpp.

void jsk_pcl_ros::EdgebasedCubeFinder::onInit ( void  ) [protected, virtual]

Reimplemented from jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 377 of file edgebased_cube_finder_nodelet.cpp.

EdgebasedCubeFinder::EdgeRelation jsk_pcl_ros::EdgebasedCubeFinder::perpendicularEdgeTriple ( const Line edge_a,
const Line edge_b,
const Line edge_c 
) [protected, virtual]

Definition at line 778 of file edgebased_cube_finder_nodelet.cpp.

pcl::PointIndices::Ptr jsk_pcl_ros::EdgebasedCubeFinder::preparePointCloudForRANSAC ( const ConvexPolygon::Ptr  convex,
const CoefficientsPair edge_coefficients_pair,
const pcl::PointCloud< PointT >::Ptr  cloud 
) [protected, virtual]

Definition at line 521 of file edgebased_cube_finder_nodelet.cpp.

void jsk_pcl_ros::EdgebasedCubeFinder::subscribe ( ) [protected, virtual]
std::vector< IndicesCoefficientsTriple > jsk_pcl_ros::EdgebasedCubeFinder::tripleIndicesAndCoefficients ( const std::vector< pcl::PointIndices::Ptr > &  indices,
const std::vector< pcl::ModelCoefficients::Ptr > &  coefficients 
) [protected, virtual]

Definition at line 1125 of file edgebased_cube_finder_nodelet.cpp.

void jsk_pcl_ros::EdgebasedCubeFinder::unsubscribe ( ) [protected, virtual]

Member Data Documentation

Definition at line 299 of file edgebased_cube_finder.h.

Definition at line 300 of file edgebased_cube_finder.h.

Definition at line 298 of file edgebased_cube_finder.h.

Definition at line 293 of file edgebased_cube_finder.h.

Definition at line 297 of file edgebased_cube_finder.h.

Definition at line 301 of file edgebased_cube_finder.h.

Definition at line 301 of file edgebased_cube_finder.h.

Definition at line 289 of file edgebased_cube_finder.h.

Definition at line 291 of file edgebased_cube_finder.h.

Definition at line 291 of file edgebased_cube_finder.h.

Definition at line 291 of file edgebased_cube_finder.h.

Definition at line 291 of file edgebased_cube_finder.h.

Definition at line 290 of file edgebased_cube_finder.h.

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_pcl_ros::EdgebasedCubeFinder::srv_ [protected]

Definition at line 285 of file edgebased_cube_finder.h.

message_filters::Subscriber<jsk_recognition_msgs::ParallelEdgeArray> jsk_pcl_ros::EdgebasedCubeFinder::sub_edges_ [protected]

Definition at line 288 of file edgebased_cube_finder.h.

Definition at line 287 of file edgebased_cube_finder.h.

Definition at line 286 of file edgebased_cube_finder.h.


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


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:49