#include <box_fit2_algo.h>
Public Member Functions | |
ros::Publisher | createPublisher (ros::NodeHandle &nh) |
virtual bool | find_model (boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZINormal > > cloud, std::vector< double > &coeff) |
Function for actual SaC-based model fitting. | |
void | getMinAndMax (Eigen::VectorXf model_coefficients, boost::shared_ptr< pcl::SACModelOrientation< pcl::PointXYZINormal > > model, std::vector< int > &min_max_indices, std::vector< float > &min_max_distances) |
void | pre () |
std::vector< std::string > | requires () |
RobustBoxEstimation () | |
Constructor and destructor. | |
Public Attributes | |
double | eps_angle_ |
Inlier threshold for normals in radians. | |
double | success_probability_ |
If it is not in the (0,1) interval, exhaustive search will be done, otherwise it will be the probability to be set for RANSAC (tradeoff between speed and accuracy). |
Definition at line 40 of file box_fit2_algo.h.
Constructor and destructor.
Definition at line 61 of file box_fit2_algo.h.
ros::Publisher pcl_cloud_algos::RobustBoxEstimation::createPublisher | ( | ros::NodeHandle & | nh | ) | [inline, virtual] |
Reimplemented from pcl_cloud_algos::BoxEstimation.
Definition at line 84 of file box_fit2_algo.h.
bool RobustBoxEstimation::find_model | ( | boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZINormal > > | cloud, |
std::vector< double > & | coeff | ||
) | [virtual] |
Function for actual SaC-based model fitting.
cloud | de-noisified input point cloud message with normals |
coeff | box to-be-filled-in coefficients (15 elements): box center: cx, cy, cz, box dimensions: dx, dy, dz, box robust axes: e1_x, e1y, e1z, e2_x, e2y, e2z, e3_x, e3y, e3z |
actual model fitting happens here
: inliers are actually indexes in the indices_ array, but that is not set (by default it has all the points in the correct order)
: making things transparent for the outside... not really needed
best_model_ contains actually the samples used to find the best model!
: making things transparent for the outside... not really needed
Reimplemented from pcl_cloud_algos::BoxEstimation.
Definition at line 111 of file box_fit2_algo.cpp.
void RobustBoxEstimation::getMinAndMax | ( | Eigen::VectorXf | model_coefficients, |
boost::shared_ptr< pcl::SACModelOrientation< pcl::PointXYZINormal > > | model, | ||
std::vector< int > & | min_max_indices, | ||
std::vector< float > & | min_max_distances | ||
) |
Definition at line 46 of file box_fit2_algo.cpp.
void RobustBoxEstimation::pre | ( | ) | [virtual] |
Reimplemented from pcl_cloud_algos::BoxEstimation.
Definition at line 100 of file box_fit2_algo.cpp.
std::vector< std::string > RobustBoxEstimation::requires | ( | ) | [virtual] |
Reimplemented from pcl_cloud_algos::BoxEstimation.
Definition at line 86 of file box_fit2_algo.cpp.
Inlier threshold for normals in radians.
Definition at line 48 of file box_fit2_algo.h.
If it is not in the (0,1) interval, exhaustive search will be done, otherwise it will be the probability to be set for RANSAC (tradeoff between speed and accuracy).
Definition at line 55 of file box_fit2_algo.h.