Public Member Functions | Private Member Functions | Private Attributes
Plot Class Reference

#include <plot.h>

List of all members.

Public Member Functions

void createVisualPublishers (ros::NodeHandle &node, double marker_lifetime)
 Create publishers for handles and grasp hypotheses to visualize them in Rviz.
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 plotFingers (const std::vector< Handle > &handle_list, const PointCloud::Ptr &cloud, std::string str, double outer_diameter=0.09, double hand_depth=0.09)
 Plot a list of handles.
void plotFingers (const std::vector< GraspHypothesis > &hand_list, const PointCloud::Ptr &cloud, std::string str, double outer_diameter=0.09, double hand_depth=0.09)
 Plot a list of grasps.
void plotGraspsRviz (const std::vector< GraspHypothesis > &hand_list, const std::string &frame, bool is_antipodal=false)
 Plot the grasp hypotheseses in Rviz.
void plotHandles (const std::vector< Handle > &handle_list, const PointCloud::Ptr &cloud, std::string str)
 Plot the handles.
void plotHandlesRviz (const std::vector< Handle > &handle_list, const std::string &frame)
 Plot the handles in Rviz.
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.
void addCloudToViewer (boost::shared_ptr< pcl::visualization::PCLVisualizer > &viewer, const PointCloud::Ptr &cloud, const std::string &name, int point_size=1)
 Add a point cloud to a PCL visualizer.
visualization_msgs::Marker createApproachMarker (const std::string &frame, const geometry_msgs::Point &center, const Eigen::Vector3d &approach, int id, const double *color, double alpha, double diam)
 Create a visual marker for an approach vector in Rviz.
PointCloud::Ptr createFingersCloud (const std::vector< GraspHypothesis > &hand_list, double outer_diameter, double hand_depth)
 Create a point cloud that stores the visual representations of the grasps.
visualization_msgs::Marker createMarker (const std::string &frame)
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.
pcl::PointXYZRGBA eigenVector3dToPointXYZRGBA (const Eigen::Vector3d &v)
 Convert an Eigen vector to a PCL point.
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.
void setPointColor (const GraspHypothesis &hand, pcl::PointXYZRGBA &p)
 Set the color of a point.

Private Attributes

ros::Publisher antipodal_pub_
 ROS publisher for antipodal grasps (Rviz)
ros::Publisher handles_pub_
 ROS publisher for handles (Rviz)
ros::Publisher hypotheses_pub_
 ROS publisher for grasp hypotheses (Rviz)
double marker_lifetime_
 max time that markers are visualized in Rviz

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 56 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 235 of file plot.cpp.

void Plot::addCloudToViewer ( boost::shared_ptr< pcl::visualization::PCLVisualizer > &  viewer,
const PointCloud::Ptr &  cloud,
const std::string &  name,
int  point_size = 1 
) [private]

Add a point cloud to a PCL visualizer.

Parameters:
viewerthe PCL visualizer that the cloud is added to
cloudthe cloud to be added

Definition at line 226 of file plot.cpp.

visualization_msgs::Marker Plot::createApproachMarker ( const std::string &  frame,
const geometry_msgs::Point &  center,
const Eigen::Vector3d &  approach,
int  id,
const double *  color,
double  alpha,
double  diam 
) [private]

Create a visual marker for an approach vector in Rviz.

Parameters:
framethe frame that the marker's pose is relative to
centerthe position of the marker
approachthe approach vector
idthe identifier of the marker
colora 3-element array defining the markers color in RGB
alphathe transparency level of the marker
diamthe diameter of the marker

Definition at line 477 of file plot.cpp.

PointCloud::Ptr Plot::createFingersCloud ( const std::vector< GraspHypothesis > &  hand_list,
double  outer_diameter,
double  hand_depth 
) [private]

Create a point cloud that stores the visual representations of the grasps.

Parameters:
hand_listthe list of grasps to be be stored in the point cloud
outer_diameterthe outer diameter of the visual grasp representation

Definition at line 59 of file plot.cpp.

visualization_msgs::Marker Plot::createMarker ( const std::string &  frame) [private]

Create a visual marker.

Parameters:
framethe frame that the marker's pose is relative to

Definition at line 503 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 189 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 303 of file plot.cpp.

void Plot::createVisualPublishers ( ros::NodeHandle node,
double  marker_lifetime 
)

Create publishers for handles and grasp hypotheses to visualize them in Rviz.

Parameters:
nodethe ROS node for which the publishers are advertised
marker_lifetimethe lifetime of each visual marker

Definition at line 311 of file plot.cpp.

pcl::PointXYZRGBA Plot::eigenVector3dToPointXYZRGBA ( const Eigen::Vector3d &  v) [private]

Convert an Eigen vector to a PCL point.

Parameters:
vthe Eigen vector to be converted

Definition at line 533 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 169 of file plot.cpp.

void Plot::plotFingers ( const std::vector< Handle > &  handle_list,
const PointCloud::Ptr &  cloud,
std::string  str,
double  outer_diameter = 0.09,
double  hand_depth = 0.09 
)

Plot a list of handles.

Parameters:
hand_listthe list of grasps
cloudthe point cloud to be plotted
strthe title of the plot window
outer_diameterthe width of the drawn grasps

Definition at line 4 of file plot.cpp.

void Plot::plotFingers ( const std::vector< GraspHypothesis > &  hand_list,
const PointCloud::Ptr &  cloud,
std::string  str,
double  outer_diameter = 0.09,
double  hand_depth = 0.09 
)

Plot a list of grasps.

Parameters:
hand_listthe list of grasps
cloudthe point cloud to be plotted
strthe title of the plot window
outer_diameterthe width of the drawn grasps

Definition at line 42 of file plot.cpp.

void Plot::plotGraspsRviz ( const std::vector< GraspHypothesis > &  hand_list,
const std::string &  frame,
bool  is_antipodal = false 
)

Plot the grasp hypotheseses in Rviz.

Parameters:
hand_listthe list of grasp hypotheses
framethe frame that the poses of the grasp hypotheses are relative to

Definition at line 319 of file plot.cpp.

void Plot::plotHandles ( const std::vector< Handle > &  handle_list,
const PointCloud::Ptr &  cloud,
std::string  str 
)

Plot the handles.

Parameters:
handle_listthe list of handles
framethe frame that the poses of the handle grasps are relative to
strthe title of the PCL visualization window

Definition at line 384 of file plot.cpp.

void Plot::plotHandlesRviz ( const std::vector< Handle > &  handle_list,
const std::string &  frame 
)

Plot the handles in Rviz.

Parameters:
handle_listthe list of handles
framethe frame that the poses of the handle grasps are relative to

Definition at line 360 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 133 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 122 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 250 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 157 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 142 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 277 of file plot.cpp.

void Plot::setPointColor ( const GraspHypothesis hand,
pcl::PointXYZRGBA &  p 
) [private]

Set the color of a point.

Parameters:
handthe grasp that the point belongs to
pthe point for which the color is set

Definition at line 514 of file plot.cpp.


Member Data Documentation

ROS publisher for antipodal grasps (Rviz)

Definition at line 254 of file plot.h.

ROS publisher for handles (Rviz)

Definition at line 255 of file plot.h.

ROS publisher for grasp hypotheses (Rviz)

Definition at line 253 of file plot.h.

double Plot::marker_lifetime_ [private]

max time that markers are visualized in Rviz

Definition at line 256 of file plot.h.


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


agile_grasp
Author(s): Andreas ten Pas
autogenerated on Sat Jun 8 2019 20:08:27