SamplingVisualizer visualizes individual steps of importance sampling. This can be used to illustrate the different sampling methods. More...
#include <sampling_visualizer.h>
Public Member Functions | |
void | addCylinders (const std::vector< CylindricalShell > &shells, void *viewer_void, std::string handle_index="", double r=0.0, double g=1.0, double b=1.0) |
pcl::ModelCoefficients | createCylinder (Eigen::Vector3d pt_on_axis, Eigen::Vector3d axis_direction, double radius, double extent) |
void | createViewer (PointCloud::ConstPtr cloud, std::vector< CylindricalShell > shells, Eigen::MatrixXd samples, double target_radius) |
boost::shared_ptr < pcl::visualization::PCLVisualizer > | getViewer () |
Private Attributes | |
boost::shared_ptr < pcl::visualization::PCLVisualizer > | viewer |
SamplingVisualizer visualizes individual steps of importance sampling. This can be used to illustrate the different sampling methods.
Definition at line 46 of file sampling_visualizer.h.
void SamplingVisualizer::addCylinders | ( | const std::vector< CylindricalShell > & | shells, |
void * | viewer_void, | ||
std::string | handle_index = "" , |
||
double | r = 0.0 , |
||
double | g = 1.0 , |
||
double | b = 1.0 |
||
) |
Add a set of cylindrical shells to a given pcl-viewer. The color for all shells is defined by the three optional parameters.
shells | the set of cylindrical shells to be added |
viewer_void | the pcl-viewer |
Definition at line 18 of file sampling_visualizer.cpp.
pcl::ModelCoefficients SamplingVisualizer::createCylinder | ( | Eigen::Vector3d | pt_on_axis, |
Eigen::Vector3d | axis_direction, | ||
double | radius, | ||
double | extent | ||
) |
Create a visual cylinder from a point on its axis, its axis, its radius, and its extent.
pt_on_axis | a point on the cylinder's axis |
axis_direction | the vector that represents the cylinder's axis |
radius | the radius of the cylinder |
extent | the extent of the cylinder |
Definition at line 3 of file sampling_visualizer.cpp.
void SamplingVisualizer::createViewer | ( | PointCloud::ConstPtr | cloud, |
std::vector< CylindricalShell > | shells, | ||
Eigen::MatrixXd | samples, | ||
double | target_radius | ||
) |
Create a pcl-viewer that shows a point cloud, a set of cylindrical shells, and a set of samples.
cloud | the cloud to be shown |
shells | the set of cylindrical shells to be shown |
samples | the set of samples to be shown |
target_radius | the target radius |
Definition at line 38 of file sampling_visualizer.cpp.
boost::shared_ptr<pcl::visualization::PCLVisualizer> SamplingVisualizer::getViewer | ( | ) | [inline] |
Returns the pcl-viewer.
Definition at line 84 of file sampling_visualizer.h.
boost::shared_ptr<pcl::visualization::PCLVisualizer> SamplingVisualizer::viewer [private] |
Definition at line 88 of file sampling_visualizer.h.