#include <plot.h>
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. |
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.
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.
viewer | the PCL visualizer that the cloud is added to |
cloud | the cloud to be added |
line_width | the line width for drawing normals |
color_cloud | the color that is used to draw the cloud |
color_normals | the color that is used to draw the normals |
cloud_name | an identifier string for the cloud |
normals_name | an identifier string for the normals |
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.
hand_list | the set of grasp hypotheses |
plots_only_antipodal | whether only the approach vectors of antipodal grasps are considered |
plots_grasp_bottom | whether the approach vectors plotted originate from the grasp bottom point |
boost::shared_ptr< pcl::visualization::PCLVisualizer > Plot::createViewer | ( | std::string | title | ) | [private] |
void Plot::plotCameraSource | ( | const Eigen::VectorXi & | pts_cam_source_in, |
const PointCloud::Ptr & | cloud | ||
) |
void Plot::plotHands | ( | const std::vector< GraspHypothesis > & | hand_list, |
const PointCloud::Ptr & | cloud, | ||
std::string | str, | ||
bool | use_grasp_bottom = false |
||
) |
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.
hand_list | the set of grasp hypotheses to be plotted |
antipodal_hand_list | the set of antipodal grasps to be plotted |
cloud | the point cloud to be plotted |
str | the title of the visualization window |
use_grasp_bottom | whether the grasps plotted originate from the grasp bottom point |
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.
hands_cloud | the cloud that represents the grasp hypotheses |
antipodal_hands_cloud | the cloud that represents the antipodal grasps |
cloud | the point cloud to be plotted |
str | the title of the visualization window |
use_grasp_bottom | whether the grasps plotted originate from the grasp bottom point |
void Plot::plotLocalAxes | ( | const std::vector< Quadric > & | quadric_list, |
const PointCloud::Ptr & | cloud | ||
) |
void Plot::plotSamples | ( | const std::vector< int > & | index_list, |
const PointCloud::Ptr & | cloud | ||
) |
void Plot::runViewer | ( | boost::shared_ptr< pcl::visualization::PCLVisualizer > & | viewer | ) | [private] |