00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2014, Andreas ten Pas 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * 00018 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00019 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00020 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00021 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00022 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00023 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00024 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00025 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00026 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00027 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00028 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00029 * POSSIBILITY OF SUCH DAMAGE. 00030 */ 00031 00032 #ifndef SAMPLING_H 00033 #define SAMPLING_H 00034 00035 #include "handle_detector/cylindrical_shell.h" 00036 #include <pcl/point_types.h> 00037 #include <pcl/visualization/pcl_visualizer.h> 00038 #include <vector> 00039 00040 typedef pcl::PointCloud<pcl::PointXYZRGBA> PointCloud; 00041 00046 class SamplingVisualizer 00047 { 00048 public: 00056 pcl::ModelCoefficients 00057 createCylinder(Eigen::Vector3d pt_on_axis, Eigen::Vector3d axis_direction, double radius, double extent); 00058 00065 void 00066 addCylinders(const std::vector<CylindricalShell> &shells, void* viewer_void, std::string handle_index = "", double r = 00067 0.0, 00068 double g = 1.0, double b = 1.0); 00069 00077 void 00078 createViewer(PointCloud::ConstPtr cloud, std::vector<CylindricalShell> shells, Eigen::MatrixXd samples, 00079 double target_radius); 00080 00084 inline boost::shared_ptr<pcl::visualization::PCLVisualizer> getViewer() 00085 { 00086 return this->viewer; 00087 } 00088 ; 00089 00090 private: 00091 boost::shared_ptr<pcl::visualization::PCLVisualizer> viewer; 00092 }; 00093 00094 #endif