#include <edgebased_cube_finder.h>
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 |
Public Member Functions | |
virtual | ~EdgebasedCubeFinder () |
Protected Member Functions | |
virtual std::vector< CoefficientsPair > | combinateCoefficients (const std::vector< pcl::ModelCoefficients::Ptr > &coefficients) |
virtual std::vector< IndicesPair > | combinateIndices (const std::vector< pcl::PointIndices::Ptr > &indices) |
virtual void | configCallback (Config &config, uint32_t level) |
virtual jsk_recognition_utils::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 jsk_recognition_utils::ConvexPolygon::Ptr convex) |
virtual jsk_recognition_utils::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 jsk_recognition_utils::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 jsk_recognition_utils::ConvexPolygon::Ptr convex, const pcl::PointCloud< PointT >::Ptr filtered_cloud, pcl::PointIndices::Ptr output_inliers, pcl::ModelCoefficients::Ptr output_coefficients) |
virtual void | estimatePerpendicularPlane (const jsk_recognition_utils::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< jsk_recognition_utils::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 jsk_recognition_utils::Line::Ptr | midLineFromCoefficientsPair (const CoefficientsPair &pair) |
virtual jsk_recognition_utils::PointPair | minMaxPointOnLine (const jsk_recognition_utils::Line &line, const pcl::PointCloud< PointT >::Ptr cloud) |
virtual void | onInit () |
virtual EdgeRelation | perpendicularEdgeTriple (const jsk_recognition_utils::Line &edge_a, const jsk_recognition_utils::Line &edge_b, const jsk_recognition_utils::Line &edge_c) |
virtual pcl::PointIndices::Ptr | preparePointCloudForRANSAC (const jsk_recognition_utils::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_ |
Definition at line 189 of file edgebased_cube_finder.h.
typedef jsk_pcl_ros::EdgebasedCubeFinderConfig jsk_pcl_ros::EdgebasedCubeFinder::Config |
Definition at line 196 of file edgebased_cube_finder.h.
typedef pcl::PointXYZRGB jsk_pcl_ros::EdgebasedCubeFinder::PointT |
Definition at line 195 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 194 of file edgebased_cube_finder.h.
Enumerator | |
---|---|
NOT_PERPENDICULAR | |
A_PERPENDICULAR | |
B_PERPENDICULAR | |
C_PERPENDICULAR |
Definition at line 197 of file edgebased_cube_finder.h.
|
virtual |
Definition at line 443 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 1257 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 1243 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 403 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 510 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 365 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 639 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 750 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 920 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 1214 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 596 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 615 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 483 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 382 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 536 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 865 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 812 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 473 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 495 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 414 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 832 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 571 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 454 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 1179 of file edgebased_cube_finder_nodelet.cpp.
|
protectedvirtual |
Definition at line 467 of file edgebased_cube_finder_nodelet.cpp.
|
protected |
Definition at line 331 of file edgebased_cube_finder.h.
|
protected |
Definition at line 332 of file edgebased_cube_finder.h.
|
protected |
Definition at line 330 of file edgebased_cube_finder.h.
|
protected |
Definition at line 325 of file edgebased_cube_finder.h.
|
protected |
Definition at line 329 of file edgebased_cube_finder.h.
|
protected |
Definition at line 333 of file edgebased_cube_finder.h.
|
protected |
Definition at line 333 of file edgebased_cube_finder.h.
|
protected |
Definition at line 321 of file edgebased_cube_finder.h.
|
protected |
Definition at line 324 of file edgebased_cube_finder.h.
|
protected |
Definition at line 323 of file edgebased_cube_finder.h.
|
protected |
Definition at line 323 of file edgebased_cube_finder.h.
|
protected |
Definition at line 324 of file edgebased_cube_finder.h.
|
protected |
Definition at line 322 of file edgebased_cube_finder.h.
|
protected |
Definition at line 317 of file edgebased_cube_finder.h.
|
protected |
Definition at line 320 of file edgebased_cube_finder.h.
|
protected |
Definition at line 319 of file edgebased_cube_finder.h.
|
protected |
Definition at line 318 of file edgebased_cube_finder.h.