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: shapes.h 5501 2012-04-04 07:08:51Z rusu $
00037  *
00038  */
00039 #ifndef PCL_PCL_VISUALIZER_SHAPES_H_
00040 #define PCL_PCL_VISUALIZER_SHAPES_H_
00041 
00042 #include <Eigen/Geometry>
00043 #include <pcl/ModelCoefficients.h>
00044 #include <pcl/point_cloud.h>
00045 #include <pcl/visualization/vtk.h>
00046 #include <pcl/geometry/planar_polygon.h>
00047 
00055 namespace pcl
00056 {
00057   namespace visualization
00058   {
00063     template <typename PointT> vtkSmartPointer<vtkDataSet> inline 
00064     createPolygon (const typename pcl::PointCloud<PointT>::ConstPtr &cloud);
00065 
00070     template <typename PointT> vtkSmartPointer<vtkDataSet> inline 
00071     createPolygon (const pcl::PlanarPolygon<PointT> &planar_polygon);
00072 
00078     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00079     createLine (const Eigen::Vector4f &pt1, const Eigen::Vector4f &pt2);
00080 
00087     PCL_EXPORTS vtkSmartPointer<vtkDataSet>
00088     createSphere (const Eigen::Vector4f &center, double radius, int res = 10);
00089 
00116     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00117     createCylinder (const pcl::ModelCoefficients &coefficients, int numsides = 30);
00118 
00141     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00142     createSphere (const pcl::ModelCoefficients &coefficients, int res = 10);
00143 
00166     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00167     createLine (const pcl::ModelCoefficients &coefficients);
00168 
00188     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00189     createPlane (const pcl::ModelCoefficients &coefficients);
00190 
00210     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00211     create2DCircle (const pcl::ModelCoefficients &coefficients, double z = 0.0);
00212 
00217     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00218     createCone (const pcl::ModelCoefficients &coefficients);
00219 
00224     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00225     createCube (const pcl::ModelCoefficients &coefficients);
00226 
00236     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00237     createCube (const Eigen::Vector3f &translation, const Eigen::Quaternionf &rotation,
00238                 double width, double height, double depth);
00239     
00250     PCL_EXPORTS vtkSmartPointer<vtkDataSet> 
00251     createCube (double x_min, double x_max,
00252                 double y_min, double y_max,
00253                 double z_min, double z_max);
00254     
00258     PCL_EXPORTS void
00259     allocVtkUnstructuredGrid (vtkSmartPointer<vtkUnstructuredGrid> &polydata);
00260   }
00261 }
00264 #include <pcl/visualization/common/impl/shapes.hpp>
00265 
00266 #endif


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:17:56