$search
00001 /* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2010, Willow Garage, Inc. 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 * * Neither the name of Willow Garage, Inc. nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 * 00034 * $Id: shapes.cpp 36093 2011-02-19 21:54:55Z rusu $ 00035 * 00036 */ 00037 #include <pcl_visualization/common/shapes.h> 00038 00040 00044 vtkSmartPointer<vtkDataSet> 00045 pcl_visualization::createCylinder (const pcl::ModelCoefficients &coefficients, int numsides) 00046 { 00047 vtkSmartPointer<vtkLineSource> line = vtkSmartPointer<vtkLineSource>::New (); 00048 line->SetPoint1 (coefficients.values[0], coefficients.values[1], coefficients.values[2]); 00049 line->SetPoint2 (coefficients.values[3]+coefficients.values[0], coefficients.values[4]+coefficients.values[1], coefficients.values[5]+coefficients.values[2]); 00050 00051 vtkSmartPointer<vtkTubeFilter> tuber = vtkSmartPointer<vtkTubeFilter>::New (); 00052 tuber->SetInputConnection (line->GetOutputPort ()); 00053 tuber->SetRadius (coefficients.values[6]); 00054 tuber->SetNumberOfSides (numsides); 00055 00056 return (tuber->GetOutput ()); 00057 } 00058 00063 vtkSmartPointer<vtkDataSet> 00064 pcl_visualization::createSphere (const pcl::ModelCoefficients &coefficients, int res) 00065 { 00066 // Set the sphere origin 00067 vtkSmartPointer<vtkTransform> t = vtkSmartPointer<vtkTransform>::New (); 00068 t->Identity (); t->Translate (coefficients.values[0], coefficients.values[1], coefficients.values[2]); 00069 00070 vtkSmartPointer<vtkSphereSource> s_sphere = vtkSmartPointer<vtkSphereSource>::New (); 00071 s_sphere->SetRadius (coefficients.values[3]); 00072 s_sphere->SetPhiResolution (res); 00073 s_sphere->SetThetaResolution (res); 00074 s_sphere->LatLongTessellationOff (); 00075 00076 vtkSmartPointer<vtkTransformPolyDataFilter> tf = vtkSmartPointer<vtkTransformPolyDataFilter>::New (); 00077 tf->SetTransform (t); 00078 tf->SetInputConnection (s_sphere->GetOutputPort ()); 00079 00080 return (tf->GetOutput ()); 00081 } 00082 00086 vtkSmartPointer<vtkDataSet> 00087 pcl_visualization::createLine (const pcl::ModelCoefficients &coefficients) 00088 { 00089 vtkSmartPointer<vtkLineSource> line = vtkSmartPointer<vtkLineSource>::New (); 00090 line->SetPoint1 (coefficients.values[0], coefficients.values[1], coefficients.values[2]); 00091 line->SetPoint2 (coefficients.values[3] + coefficients.values[0], 00092 coefficients.values[4] + coefficients.values[1], 00093 coefficients.values[5] + coefficients.values[2]); 00094 line->Update (); 00095 00096 return (line->GetOutput ()); 00097 } 00098 00102 vtkSmartPointer<vtkDataSet> 00103 pcl_visualization::createPlane (const pcl::ModelCoefficients &coefficients) 00104 { 00105 vtkSmartPointer<vtkPlaneSource> plane = vtkSmartPointer<vtkPlaneSource>::New (); 00106 plane->SetNormal (coefficients.values[0], coefficients.values[1], coefficients.values[2]); 00107 plane->Push (coefficients.values[3]); 00108 return (plane->GetOutput ()); 00109 } 00110 00115 vtkSmartPointer<vtkDataSet> 00116 pcl_visualization::create2DCircle (const pcl::ModelCoefficients &coefficients, double z) 00117 { 00118 vtkSmartPointer<vtkDiskSource> disk = vtkSmartPointer<vtkDiskSource>::New (); 00119 // Maybe the resolution should be lower e.g. 50 or 25 00120 disk->SetCircumferentialResolution (100); 00121 disk->SetInnerRadius (coefficients.values[2] - 0.001); 00122 disk->SetOuterRadius (coefficients.values[2] + 0.001); 00123 disk->SetCircumferentialResolution (20); 00124 00125 // An alternative to <vtkDiskSource> could be <vtkRegularPolygonSource> with <vtkTubeFilter> 00126 /* 00127 vtkSmartPointer<vtkRegularPolygonSource> circle = vtkSmartPointer<vtkRegularPolygonSource>::New(); 00128 circle->SetRadius (coefficients.values[2]); 00129 circle->SetNumberOfSides (100); 00130 00131 vtkSmartPointer<vtkTubeFilter> tube = vtkSmartPointer<vtkTubeFilter>::New(); 00132 tube->SetInput (circle->GetOutput()); 00133 tube->SetNumberOfSides (25); 00134 tube->SetRadius (0.001); 00135 */ 00136 00137 // Set the circle origin 00138 vtkSmartPointer<vtkTransform> t = vtkSmartPointer<vtkTransform>::New (); 00139 t->Identity (); 00140 t->Translate (coefficients.values[0], coefficients.values[1], z); 00141 00142 vtkSmartPointer<vtkTransformPolyDataFilter> tf = vtkSmartPointer<vtkTransformPolyDataFilter>::New (); 00143 tf->SetTransform (t); 00144 tf->SetInputConnection (disk->GetOutputPort ()); 00145 /* 00146 tf->SetInputConnection (tube->GetOutputPort ()); 00147 */ 00148 00149 return (tf->GetOutput ()); 00150 } 00151 00155 vtkSmartPointer<vtkDataSet> 00156 pcl_visualization::createCone (const pcl::ModelCoefficients &coefficients) 00157 { 00158 vtkSmartPointer<vtkConeSource> cone = vtkSmartPointer<vtkConeSource>::New (); 00159 cone->SetHeight (1.0); 00160 cone->SetCenter (coefficients.values[0] + coefficients.values[3] * 0.5, 00161 coefficients.values[1] + coefficients.values[1] * 0.5, 00162 coefficients.values[2] + coefficients.values[2] * 0.5); 00163 cone->SetDirection (-coefficients.values[3], -coefficients.values[4], -coefficients.values[5]); 00164 cone->SetResolution (100); 00165 cone->SetAngle (coefficients.values[6]); 00166 00167 return (cone->GetOutput ()); 00168 } 00169