All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines
Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | Protected Attributes
pcl_cloud_algos::BoxEstimation Class Reference

#include <box_fit_algo.h>

Inheritance diagram for pcl_cloud_algos::BoxEstimation:
Inheritance graph
[legend]

List of all members.

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::stringprovides ()
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::stringrequires ()
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< intcontained_
ros::Publisher contained_pub_
std::string frame_id_
float g_
std::vector< intinliers_
ros::Publisher inliers_pub_
visualization_msgs::Marker marker_
ros::Publisher marker_pub_
boost::shared_ptr< OutputTypemesh_
ros::NodeHandle nh_
std::vector< intoutliers_
ros::Publisher outliers_pub_
std::string output_box_topic_
float r_
double threshold_in_
double threshold_out_

Detailed Description

Definition at line 46 of file box_fit_algo.h.


Member Typedef Documentation

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.


Constructor & Destructor Documentation

Definition at line 52 of file box_fit_algo.h.


Member Function Documentation

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)

Parameters:
cloudinput point cloud message
coeffbox coefficients (see find_model function):

Definition at line 476 of file box_fit_algo.cpp.

Implements pcl_cloud_algos::CloudAlgo.

Reimplemented in pcl_cloud_algos::RobustBoxEstimation.

Definition at line 138 of file box_fit_algo.h.

Reimplemented from pcl_cloud_algos::CloudAlgo.

Definition at line 63 of file box_fit_algo.h.

Reimplemented from pcl_cloud_algos::CloudAlgo.

Definition at line 69 of file box_fit_algo.h.

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

Parameters:
cloudde-noisified input point cloud message
coeffbox 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.

Parameters:
cloudinput point cloud message
coeffbox 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.

Parameters:
cloudinput point cloud message
coeffbox 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.

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)

Parameters:
cloudinput point cloud message
coeffbox 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.

Sets an input cloud if you are using BoxEstimation class outside cloud_algos framework.

Parameters:
cloudinput 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

Parameters:
cloudinput point cloud message
coeffbox coefficients (see find_model function):

Definition at line 389 of file box_fit_algo.cpp.


Member Data Documentation

Definition at line 181 of file box_fit_algo.h.

Definition at line 174 of file box_fit_algo.h.

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.

Definition at line 157 of file box_fit_algo.h.

Definition at line 170 of file box_fit_algo.h.

Definition at line 163 of file box_fit_algo.h.

Definition at line 181 of file box_fit_algo.h.

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.

Definition at line 164 of file box_fit_algo.h.

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.

Definition at line 181 of file box_fit_algo.h.

Definition at line 158 of file box_fit_algo.h.

Definition at line 159 of file box_fit_algo.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


pcl_cloud_algos
Author(s): Nico Blodow, Dejan Pangercic, Zoltan-Csaba Marton
autogenerated on Sun Oct 6 2013 12:05:19