#include <plot.h>
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 ¢er, 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 |
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 |
void Plot::addCloudToViewer | ( | boost::shared_ptr< pcl::visualization::PCLVisualizer > & | viewer, |
const PointCloud::Ptr & | cloud, | ||
const std::string & | name, | ||
int | point_size = 1 |
||
) | [private] |
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.
frame | the frame that the marker's pose is relative to |
center | the position of the marker |
approach | the approach vector |
id | the identifier of the marker |
color | a 3-element array defining the markers color in RGB |
alpha | the transparency level of the marker |
diam | the diameter of the marker |
PointCloud::Ptr Plot::createFingersCloud | ( | const std::vector< GraspHypothesis > & | hand_list, |
double | outer_diameter, | ||
double | hand_depth | ||
) | [private] |
visualization_msgs::Marker Plot::createMarker | ( | const std::string & | frame | ) | [private] |
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::createVisualPublishers | ( | ros::NodeHandle & | node, |
double | marker_lifetime | ||
) |
pcl::PointXYZRGBA Plot::eigenVector3dToPointXYZRGBA | ( | const Eigen::Vector3d & | v | ) | [private] |
void Plot::plotCameraSource | ( | const Eigen::VectorXi & | pts_cam_source_in, |
const PointCloud::Ptr & | cloud | ||
) |
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 |
||
) |
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 |
||
) |
void Plot::plotGraspsRviz | ( | const std::vector< GraspHypothesis > & | hand_list, |
const std::string & | frame, | ||
bool | is_antipodal = false |
||
) |
void Plot::plotHandles | ( | const std::vector< Handle > & | handle_list, |
const PointCloud::Ptr & | cloud, | ||
std::string | str | ||
) |
void Plot::plotHandlesRviz | ( | const std::vector< Handle > & | handle_list, |
const std::string & | frame | ||
) |
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] |
void Plot::setPointColor | ( | const GraspHypothesis & | hand, |
pcl::PointXYZRGBA & | p | ||
) | [private] |
ros::Publisher Plot::antipodal_pub_ [private] |
ros::Publisher Plot::handles_pub_ [private] |
ros::Publisher Plot::hypotheses_pub_ [private] |
double Plot::marker_lifetime_ [private] |