#include <box_fit_algo.h>
Public Types | |
typedef sensor_msgs::PointCloud2 | InputType |
typedef triangle_mesh_msgs::TriangleMesh | OutputType |
Public Member Functions | |
BoxEstimation () | |
virtual void | computeInAndOutliers (boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZINormal > > cloud, std::vector< double > coeff, double threshold_in, double threshold_out) |
void | computeMarker (boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZINormal > > cloud, std::vector< double > coeff) |
Sets the internal box as marker for rvis visualisation. | |
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 model fitting | |
std::vector< double > | getCoeff () |
Returns the computed model coefficients. | |
virtual boost::shared_ptr < sensor_msgs::PointCloud2 > | getContained () |
virtual boost::shared_ptr < sensor_msgs::PointCloud2 > | getInliers () |
visualization_msgs::Marker | getMarker () |
Returns the internal box as marker for rvis visualisation. | |
virtual boost::shared_ptr < sensor_msgs::PointCloud2 > | getOutliers () |
virtual boost::shared_ptr < pcl::PointCloud < pcl::PointXYZINormal > > | getThresholdedInliers (double eps_angle) |
void | init (ros::NodeHandle &) |
boost::shared_ptr< const OutputType > | output () |
void | post () |
void | pre () |
std::string | process (const boost::shared_ptr< const InputType >) |
std::vector< std::string > | provides () |
void | publish_marker (boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZINormal > > cloud, std::vector< double > &coeff) |
publish box as marker for rvis visualisation | |
std::vector< std::string > | requires () |
void | setInputCloud (boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZINormal > > cloud) |
Sets an input cloud if you are using BoxEstimation class outside cloud_algos framework. | |
void | triangulate_box (boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZINormal > > cloud, std::vector< double > &coeff) |
makes triangular mesh out of box coefficients | |
Static Public Member Functions | |
static std::string | default_input_topic () |
static std::string | default_node_name () |
static std::string | default_output_topic () |
Public Attributes | |
bool | publish_marker_ |
Protected Attributes | |
float | b_ |
pcl::PointXYZINormal | box_centroid_ |
boost::shared_ptr < pcl::PointCloud < pcl::PointXYZINormal > > | cloud_ |
std::vector< double > | coeff_ |
std::vector< int > | contained_ |
ros::Publisher | contained_pub_ |
std::string | frame_id_ |
float | g_ |
std::vector< int > | inliers_ |
ros::Publisher | inliers_pub_ |
visualization_msgs::Marker | marker_ |
ros::Publisher | marker_pub_ |
boost::shared_ptr< OutputType > | mesh_ |
ros::NodeHandle | nh_ |
std::vector< int > | outliers_ |
ros::Publisher | outliers_pub_ |
std::string | output_box_topic_ |
float | r_ |
double | threshold_in_ |
double | threshold_out_ |
Definition at line 46 of file box_fit_algo.h.
typedef sensor_msgs::PointCloud2 pcl_cloud_algos::BoxEstimation::InputType |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 61 of file box_fit_algo.h.
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 58 of file box_fit_algo.h.
pcl_cloud_algos::BoxEstimation::BoxEstimation | ( | ) | [inline] |
Definition at line 52 of file box_fit_algo.h.
void BoxEstimation::computeInAndOutliers | ( | boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZINormal > > | cloud, |
std::vector< double > | coeff, | ||
double | threshold_in, | ||
double | threshold_out | ||
) | [virtual] |
Definition at line 259 of file box_fit_algo.cpp.
void BoxEstimation::computeMarker | ( | boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZINormal > > | cloud, |
std::vector< double > | coeff | ||
) |
Sets the internal box as marker for rvis visualisation.
computes model marker (to rviz)
cloud | input point cloud message |
coeff | box coefficients (see find_model function): |
Definition at line 476 of file box_fit_algo.cpp.
ros::Publisher pcl_cloud_algos::BoxEstimation::createPublisher | ( | ros::NodeHandle & | nh | ) | [inline, virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Reimplemented in pcl_cloud_algos::RobustBoxEstimation.
Definition at line 138 of file box_fit_algo.h.
static std::string pcl_cloud_algos::BoxEstimation::default_input_topic | ( | ) | [inline, static] |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 63 of file box_fit_algo.h.
static std::string pcl_cloud_algos::BoxEstimation::default_node_name | ( | ) | [inline, static] |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 69 of file box_fit_algo.h.
static std::string pcl_cloud_algos::BoxEstimation::default_output_topic | ( | ) | [inline, static] |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 66 of file box_fit_algo.h.
bool BoxEstimation::find_model | ( | boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZINormal > > | cloud, |
std::vector< double > & | coeff | ||
) | [virtual] |
function for actual model fitting
cloud | de-noisified input point cloud message |
coeff | box to-be-filled-in coefficients(15 elements): box center: cx, cy, cz, box dimensions: dx, dy, dz, box eigen axes: e1_x, e1y, e1z, e2_x, e2y, e2z, e3_x, e3y, e3z |
actual model fitting happens here
Reimplemented in pcl_cloud_algos::RobustBoxEstimation.
Definition at line 305 of file box_fit_algo.cpp.
std::vector<double> pcl_cloud_algos::BoxEstimation::getCoeff | ( | ) | [inline] |
Returns the computed model coefficients.
cloud | input point cloud message |
coeff | box coefficients (see find_model function): |
Definition at line 136 of file box_fit_algo.h.
boost::shared_ptr< sensor_msgs::PointCloud2 > BoxEstimation::getContained | ( | ) | [virtual] |
Definition at line 209 of file box_fit_algo.cpp.
boost::shared_ptr< sensor_msgs::PointCloud2 > BoxEstimation::getInliers | ( | ) | [virtual] |
Definition at line 194 of file box_fit_algo.cpp.
visualization_msgs::Marker pcl_cloud_algos::BoxEstimation::getMarker | ( | ) | [inline] |
Returns the internal box as marker for rvis visualisation.
cloud | input point cloud message |
coeff | box coefficients (see find_model function): |
Definition at line 128 of file box_fit_algo.h.
boost::shared_ptr< sensor_msgs::PointCloud2 > BoxEstimation::getOutliers | ( | ) | [virtual] |
Definition at line 155 of file box_fit_algo.cpp.
boost::shared_ptr< pcl::PointCloud< pcl::PointXYZINormal > > BoxEstimation::getThresholdedInliers | ( | double | eps_angle | ) | [virtual] |
Definition at line 224 of file box_fit_algo.cpp.
void BoxEstimation::init | ( | ros::NodeHandle & | nh | ) | [virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Definition at line 70 of file box_fit_algo.cpp.
boost::shared_ptr< const BoxEstimation::OutputType > BoxEstimation::output | ( | ) |
Reimplemented from pcl_cloud_algos::CloudAlgo.
Definition at line 150 of file box_fit_algo.cpp.
void BoxEstimation::post | ( | ) | [virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Definition at line 93 of file box_fit_algo.cpp.
void BoxEstimation::pre | ( | ) | [virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Reimplemented in pcl_cloud_algos::RobustBoxEstimation.
Definition at line 84 of file box_fit_algo.cpp.
std::string BoxEstimation::process | ( | const boost::shared_ptr< const InputType > | input | ) |
Definition at line 109 of file box_fit_algo.cpp.
std::vector< std::string > BoxEstimation::provides | ( | ) | [virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Definition at line 104 of file box_fit_algo.cpp.
void BoxEstimation::publish_marker | ( | boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZINormal > > | cloud, |
std::vector< double > & | coeff | ||
) |
publish box as marker for rvis visualisation
publishes model marker (to rviz)
cloud | input point cloud message |
coeff | box coefficients (see find_model function): |
Definition at line 466 of file box_fit_algo.cpp.
std::vector< std::string > BoxEstimation::requires | ( | ) | [virtual] |
Implements pcl_cloud_algos::CloudAlgo.
Reimplemented in pcl_cloud_algos::RobustBoxEstimation.
Definition at line 97 of file box_fit_algo.cpp.
void pcl_cloud_algos::BoxEstimation::setInputCloud | ( | boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZINormal > > | cloud | ) | [inline] |
Sets an input cloud if you are using BoxEstimation class outside cloud_algos framework.
cloud | input point cloud |
Definition at line 148 of file box_fit_algo.h.
void BoxEstimation::triangulate_box | ( | boost::shared_ptr< const pcl::PointCloud< pcl::PointXYZINormal > > | cloud, |
std::vector< double > & | coeff | ||
) |
makes triangular mesh out of box coefficients
triangulates box
cloud | input point cloud message |
coeff | box coefficients (see find_model function): |
Definition at line 389 of file box_fit_algo.cpp.
float pcl_cloud_algos::BoxEstimation::b_ [protected] |
Definition at line 181 of file box_fit_algo.h.
Definition at line 174 of file box_fit_algo.h.
boost::shared_ptr<pcl::PointCloud <pcl::PointXYZINormal> > pcl_cloud_algos::BoxEstimation::cloud_ [protected] |
Definition at line 161 of file box_fit_algo.h.
std::vector<double> pcl_cloud_algos::BoxEstimation::coeff_ [protected] |
Definition at line 173 of file box_fit_algo.h.
std::vector<int> pcl_cloud_algos::BoxEstimation::contained_ [protected] |
Definition at line 157 of file box_fit_algo.h.
Definition at line 170 of file box_fit_algo.h.
std::string pcl_cloud_algos::BoxEstimation::frame_id_ [protected] |
Definition at line 163 of file box_fit_algo.h.
float pcl_cloud_algos::BoxEstimation::g_ [protected] |
Definition at line 181 of file box_fit_algo.h.
std::vector<int> pcl_cloud_algos::BoxEstimation::inliers_ [protected] |
Definition at line 155 of file box_fit_algo.h.
Definition at line 168 of file box_fit_algo.h.
visualization_msgs::Marker pcl_cloud_algos::BoxEstimation::marker_ [protected] |
Definition at line 175 of file box_fit_algo.h.
Definition at line 167 of file box_fit_algo.h.
boost::shared_ptr<OutputType> pcl_cloud_algos::BoxEstimation::mesh_ [protected] |
Definition at line 154 of file box_fit_algo.h.
ros::NodeHandle pcl_cloud_algos::BoxEstimation::nh_ [protected] |
Definition at line 164 of file box_fit_algo.h.
std::vector<int> pcl_cloud_algos::BoxEstimation::outliers_ [protected] |
Definition at line 156 of file box_fit_algo.h.
Definition at line 169 of file box_fit_algo.h.
Definition at line 178 of file box_fit_algo.h.
Definition at line 50 of file box_fit_algo.h.
float pcl_cloud_algos::BoxEstimation::r_ [protected] |
Definition at line 181 of file box_fit_algo.h.
double pcl_cloud_algos::BoxEstimation::threshold_in_ [protected] |
Definition at line 158 of file box_fit_algo.h.
double pcl_cloud_algos::BoxEstimation::threshold_out_ [protected] |
Definition at line 159 of file box_fit_algo.h.