00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #ifndef PLOT_H
00033 #define PLOT_H
00034
00035 #include <pcl/visualization/pcl_visualizer.h>
00036 #include <pcl/visualization/point_cloud_color_handlers.h>
00037
00038 #include <geometry_msgs/Point.h>
00039 #include <ros/ros.h>
00040 #include <visualization_msgs/MarkerArray.h>
00041
00042 #include <agile_grasp/grasp_hypothesis.h>
00043 #include <agile_grasp/handle.h>
00044 #include <agile_grasp/quadric.h>
00045
00046
00047 typedef pcl::PointCloud<pcl::PointNormal> PointCloudNormal;
00048 typedef pcl::PointCloud<pcl::PointXYZRGBA> PointCloud;
00049
00056 class Plot
00057 {
00058 public:
00059
00067 void plotFingers(const std::vector<Handle>& handle_list, const PointCloud::Ptr& cloud, std::string str,
00068 double outer_diameter = 0.09, double hand_depth = 0.09);
00069
00077 void plotFingers(const std::vector<GraspHypothesis>& hand_list, const PointCloud::Ptr& cloud, std::string str,
00078 double outer_diameter = 0.09, double hand_depth = 0.09);
00079
00087 void plotHands(const std::vector<GraspHypothesis>& hand_list, const PointCloud::Ptr& cloud, std::string str,
00088 bool use_grasp_bottom = false);
00089
00098 void plotHands(const std::vector<GraspHypothesis>& hand_list,
00099 const std::vector<GraspHypothesis>& antipodal_hand_list, const PointCloud::Ptr& cloud, std::string str,
00100 bool use_grasp_bottom = false);
00101
00107 void plotSamples(const std::vector<int>& index_list, const PointCloud::Ptr& cloud);
00108
00114 void plotLocalAxes(const std::vector<Quadric>& quadric_list, const PointCloud::Ptr& cloud);
00115
00121 void plotCameraSource(const Eigen::VectorXi& pts_cam_source_in, const PointCloud::Ptr& cloud);
00122
00128 void createVisualPublishers(ros::NodeHandle& node, double marker_lifetime);
00129
00135 void plotGraspsRviz(const std::vector<GraspHypothesis>& hand_list, const std::string& frame,
00136 bool is_antipodal = false);
00137
00143 void plotHandlesRviz(const std::vector<Handle>& handle_list, const std::string& frame);
00144
00151 void plotHandles(const std::vector<Handle>& handle_list, const PointCloud::Ptr& cloud, std::string str);
00152
00153 private:
00154
00160 PointCloud::Ptr createFingersCloud(const std::vector<GraspHypothesis>& hand_list, double outer_diameter,
00161 double hand_depth);
00162
00172 PointCloudNormal::Ptr createNormalsCloud(const std::vector<GraspHypothesis>& hand_list,
00173 bool plots_only_antipodal, bool plots_grasp_bottom);
00174
00180 void addCloudToViewer(boost::shared_ptr<pcl::visualization::PCLVisualizer>& viewer,
00181 const PointCloud::Ptr& cloud, const std::string& name, int point_size = 1);
00182
00193 void addCloudNormalsToViewer(boost::shared_ptr<pcl::visualization::PCLVisualizer>& viewer,
00194 const PointCloudNormal::Ptr& cloud, double line_width, double* color_cloud, double* color_normals,
00195 const std::string& cloud_name, const std::string& normals_name);
00196
00206 void plotHandsHelper(const PointCloudNormal::Ptr& hands_cloud, const PointCloudNormal::Ptr& antipodal_hands_cloud,
00207 const PointCloud::Ptr& cloud, std::string str, bool use_grasp_bottom);
00208
00213 void runViewer(boost::shared_ptr<pcl::visualization::PCLVisualizer>& viewer);
00214
00219 boost::shared_ptr<pcl::visualization::PCLVisualizer> createViewer(std::string title);
00220
00231 visualization_msgs::Marker createApproachMarker(const std::string& frame, const geometry_msgs::Point& center,
00232 const Eigen::Vector3d& approach, int id, const double* color, double alpha, double diam);
00233
00238 visualization_msgs::Marker createMarker(const std::string& frame);
00239
00245 void setPointColor(const GraspHypothesis& hand, pcl::PointXYZRGBA& p);
00246
00251 pcl::PointXYZRGBA eigenVector3dToPointXYZRGBA(const Eigen::Vector3d& v);
00252
00253 ros::Publisher hypotheses_pub_;
00254 ros::Publisher antipodal_pub_;
00255 ros::Publisher handles_pub_;
00256 double marker_lifetime_;
00257 };
00258
00259 #endif