shapes.h
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2009-2012, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * $Id$
00037  *
00038  */
00039 #ifndef PCL_PCL_VISUALIZER_SHAPES_H_
00040 #define PCL_PCL_VISUALIZER_SHAPES_H_
00041 
00042 #include <pcl/ModelCoefficients.h>
00043 #include <pcl/point_cloud.h>
00044 #include <pcl/visualization/eigen.h>
00045 #include <pcl/geometry/planar_polygon.h>
00046 
00047 template <typename T> class vtkSmartPointer;
00048 class vtkDataSet;
00049 class vtkUnstructuredGrid;
00050 
00058 namespace pcl
00059 {
00060   namespace visualization
00061   {
00066     template <typename PointT> vtkSmartPointer<vtkDataSet> inline 
00067     createPolygon (const typename pcl::PointCloud<PointT>::ConstPtr &cloud);
00068 
00073     template <typename PointT> vtkSmartPointer<vtkDataSet> inline 
00074     createPolygon (const pcl::PlanarPolygon<PointT> &planar_polygon);
00075 
00081     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00082     createLine (const Eigen::Vector4f &pt1, const Eigen::Vector4f &pt2);
00083 
00090     PCL_EXPORTS vtkSmartPointer<vtkDataSet>
00091     createSphere (const Eigen::Vector4f &center, double radius, int res = 10);
00092 
00119     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00120     createCylinder (const pcl::ModelCoefficients &coefficients, int numsides = 30);
00121 
00144     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00145     createSphere (const pcl::ModelCoefficients &coefficients, int res = 10);
00146 
00169     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00170     createLine (const pcl::ModelCoefficients &coefficients);
00171 
00191     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00192     createPlane (const pcl::ModelCoefficients &coefficients);
00193 
00199     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00200     createPlane (const pcl::ModelCoefficients &coefficients, double x, double y, double z);
00201     
00221     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00222     create2DCircle (const pcl::ModelCoefficients &coefficients, double z = 0.0);
00223 
00228     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00229     createCone (const pcl::ModelCoefficients &coefficients);
00230 
00235     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00236     createCube (const pcl::ModelCoefficients &coefficients);
00237 
00247     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00248     createCube (const Eigen::Vector3f &translation, const Eigen::Quaternionf &rotation,
00249                 double width, double height, double depth);
00250     
00261     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00262     createCube (double x_min, double x_max,
00263                 double y_min, double y_max,
00264                 double z_min, double z_max);
00265     
00269     PCL_EXPORTS void
00270     allocVtkUnstructuredGrid (vtkSmartPointer<vtkUnstructuredGrid> &polydata);
00271   }
00272 }
00275 #include <pcl/visualization/common/impl/shapes.hpp>
00276 
00277 #endif


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:33:37