Public Member Functions | Private Member Functions
Plot Class Reference

#include <plot.h>

List of all members.

Public Member Functions

void plotCameraSource (const Eigen::VectorXi &pts_cam_source_in, const PointCloud::Ptr &cloud)
 Plot the camera source for each point in the point cloud.
void plotHands (const std::vector< GraspHypothesis > &hand_list, const PointCloud::Ptr &cloud, std::string str, bool use_grasp_bottom=false)
 Plot a set of grasp hypotheses.
void plotHands (const std::vector< GraspHypothesis > &hand_list, const std::vector< GraspHypothesis > &antipodal_hand_list, const PointCloud::Ptr &cloud, std::string str, bool use_grasp_bottom=false)
 Plot a set of grasp hypotheses and a set of antipodal grasps.
void plotLocalAxes (const std::vector< Quadric > &quadric_list, const PointCloud::Ptr &cloud)
 Plot a set of quadrics by plotting their local axes.
void plotSamples (const std::vector< int > &index_list, const PointCloud::Ptr &cloud)
 Plot a set of samples.

Private Member Functions

void addCloudNormalsToViewer (boost::shared_ptr< pcl::visualization::PCLVisualizer > &viewer, const PointCloudNormal::Ptr &cloud, double line_width, double *color_cloud, double *color_normals, const std::string &cloud_name, const std::string &normals_name)
 Add a point cloud with normals to a PCL visualizer.
PointCloudNormal::Ptr createNormalsCloud (const std::vector< GraspHypothesis > &hand_list, bool plots_only_antipodal, bool plots_grasp_bottom)
 Create a point cloud with normals that represent the approach vectors for a set of grasp hypotheses.
boost::shared_ptr
< pcl::visualization::PCLVisualizer > 
createViewer (std::string title)
 Create a PCL visualizer.
void plotHandsHelper (const PointCloudNormal::Ptr &hands_cloud, const PointCloudNormal::Ptr &antipodal_hands_cloud, const PointCloud::Ptr &cloud, std::string str, bool use_grasp_bottom)
 Plot two point clouds representing grasp hypotheses and antipodal grasps, respectively.
void runViewer (boost::shared_ptr< pcl::visualization::PCLVisualizer > &viewer)
 Run/show a PCL visualizer until an escape key is hit.

Detailed Description

Plot class

This class provides a set of visualization methods that visualize the output of the algorithm and some intermediate steps. The visualization is done using PCL Visualizer.

Definition at line 50 of file plot.h.


Member Function Documentation

void Plot::addCloudNormalsToViewer ( boost::shared_ptr< pcl::visualization::PCLVisualizer > &  viewer,
const PointCloudNormal::Ptr &  cloud,
double  line_width,
double *  color_cloud,
double *  color_normals,
const std::string &  cloud_name,
const std::string &  normals_name 
) [private]

Add a point cloud with normals to a PCL visualizer.

Parameters:
viewerthe PCL visualizer that the cloud is added to
cloudthe cloud to be added
line_widththe line width for drawing normals
color_cloudthe color that is used to draw the cloud
color_normalsthe color that is used to draw the normals
cloud_namean identifier string for the cloud
normals_namean identifier string for the normals

Definition at line 122 of file plot.cpp.

PointCloudNormal::Ptr Plot::createNormalsCloud ( const std::vector< GraspHypothesis > &  hand_list,
bool  plots_only_antipodal,
bool  plots_grasp_bottom 
) [private]

Create a point cloud with normals that represent the approach vectors for a set of grasp hypotheses.

Parameters:
hand_listthe set of grasp hypotheses
plots_only_antipodalwhether only the approach vectors of antipodal grasps are considered
plots_grasp_bottomwhether the approach vectors plotted originate from the grasp bottom point

Definition at line 85 of file plot.cpp.

boost::shared_ptr< pcl::visualization::PCLVisualizer > Plot::createViewer ( std::string  title) [private]

Create a PCL visualizer.

Parameters:
titlethe title of the visualization window

Definition at line 194 of file plot.cpp.

void Plot::plotCameraSource ( const Eigen::VectorXi &  pts_cam_source_in,
const PointCloud::Ptr &  cloud 
)

Plot the camera source for each point in the point cloud.

Parameters:
pts_cam_source_inthe camera source for each point in the point cloud
cloudthe point cloud to be plotted

Definition at line 57 of file plot.cpp.

void Plot::plotHands ( const std::vector< GraspHypothesis > &  hand_list,
const PointCloud::Ptr &  cloud,
std::string  str,
bool  use_grasp_bottom = false 
)

Plot a set of grasp hypotheses.

Parameters:
hand_listthe set of grasp hypotheses to be plotted
cloudthe point cloud to be plotted
strthe title of the visualization window
use_grasp_bottomwhether the grasps plotted originate from the grasp bottom point

Definition at line 15 of file plot.cpp.

void Plot::plotHands ( const std::vector< GraspHypothesis > &  hand_list,
const std::vector< GraspHypothesis > &  antipodal_hand_list,
const PointCloud::Ptr &  cloud,
std::string  str,
bool  use_grasp_bottom = false 
)

Plot a set of grasp hypotheses and a set of antipodal grasps.

Parameters:
hand_listthe set of grasp hypotheses to be plotted
antipodal_hand_listthe set of antipodal grasps to be plotted
cloudthe point cloud to be plotted
strthe title of the visualization window
use_grasp_bottomwhether the grasps plotted originate from the grasp bottom point

Definition at line 4 of file plot.cpp.

void Plot::plotHandsHelper ( const PointCloudNormal::Ptr &  hands_cloud,
const PointCloudNormal::Ptr &  antipodal_hands_cloud,
const PointCloud::Ptr &  cloud,
std::string  str,
bool  use_grasp_bottom 
) [private]

Plot two point clouds representing grasp hypotheses and antipodal grasps, respectively.

Parameters:
hands_cloudthe cloud that represents the grasp hypotheses
antipodal_hands_cloudthe cloud that represents the antipodal grasps
cloudthe point cloud to be plotted
strthe title of the visualization window
use_grasp_bottomwhether the grasps plotted originate from the grasp bottom point

Definition at line 137 of file plot.cpp.

void Plot::plotLocalAxes ( const std::vector< Quadric > &  quadric_list,
const PointCloud::Ptr &  cloud 
)

Plot a set of quadrics by plotting their local axes.

Parameters:
quadric_listthe list of quadrics to be plotted
cloudthe point cloud to be plotted

Definition at line 43 of file plot.cpp.

void Plot::plotSamples ( const std::vector< int > &  index_list,
const PointCloud::Ptr &  cloud 
)

Plot a set of samples.

Parameters:
index_listthe list of samples (indices into the point cloud)
cloudthe point cloud to be plotted

Definition at line 24 of file plot.cpp.

void Plot::runViewer ( boost::shared_ptr< pcl::visualization::PCLVisualizer > &  viewer) [private]

Run/show a PCL visualizer until an escape key is hit.

Parameters:
viewerthe PCL visualizer to be shown

Definition at line 168 of file plot.cpp.


The documentation for this class was generated from the following files:


agile_grasp
Author(s):
autogenerated on Thu Aug 27 2015 12:01:28