shapes.cpp
Go to the documentation of this file.
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 5501 2012-04-04 07:08:51Z rusu $
00035  *
00036  */
00037 #include <pcl/visualization/common/shapes.h>
00038 #include <pcl/common/angles.h>
00039 
00041 vtkSmartPointer<vtkDataSet> 
00042 pcl::visualization::createCylinder (const pcl::ModelCoefficients &coefficients, int numsides)
00043 {
00044   vtkSmartPointer<vtkLineSource> line = vtkSmartPointer<vtkLineSource>::New ();
00045   line->SetPoint1 (coefficients.values[0], coefficients.values[1], coefficients.values[2]);
00046   line->SetPoint2 (coefficients.values[3]+coefficients.values[0], coefficients.values[4]+coefficients.values[1], coefficients.values[5]+coefficients.values[2]);
00047 
00048   vtkSmartPointer<vtkTubeFilter> tuber = vtkSmartPointer<vtkTubeFilter>::New ();
00049   tuber->SetInputConnection (line->GetOutputPort ());
00050   tuber->SetRadius (coefficients.values[6]);
00051   tuber->SetNumberOfSides (numsides);
00052 
00053   return (tuber->GetOutput ());
00054 }
00055 
00057 vtkSmartPointer<vtkDataSet> 
00058 pcl::visualization::createSphere (const pcl::ModelCoefficients &coefficients, int res)
00059 {
00060   // Set the sphere origin
00061   vtkSmartPointer<vtkTransform> t = vtkSmartPointer<vtkTransform>::New ();
00062   t->Identity (); t->Translate (coefficients.values[0], coefficients.values[1], coefficients.values[2]);
00063 
00064   vtkSmartPointer<vtkSphereSource> s_sphere = vtkSmartPointer<vtkSphereSource>::New ();
00065   s_sphere->SetRadius (coefficients.values[3]);
00066   s_sphere->SetPhiResolution (res);
00067   s_sphere->SetThetaResolution (res);
00068   s_sphere->LatLongTessellationOff ();
00069   
00070   vtkSmartPointer<vtkTransformPolyDataFilter> tf = vtkSmartPointer<vtkTransformPolyDataFilter>::New ();
00071   tf->SetTransform (t);
00072   tf->SetInputConnection (s_sphere->GetOutputPort ());
00073 
00074   return (tf->GetOutput ());
00075 }
00076 
00078 vtkSmartPointer<vtkDataSet> 
00079 pcl::visualization::createCube (const pcl::ModelCoefficients &coefficients)
00080 {
00081   // coefficients = [Tx, Ty, Tz, Qx, Qy, Qz, Qw, width, height, depth]
00082   vtkSmartPointer<vtkTransform> t = vtkSmartPointer<vtkTransform>::New ();
00083   t->Identity ();
00084   t->Translate (coefficients.values[0], coefficients.values[1], coefficients.values[2]);
00085   
00086   Eigen::AngleAxisf a (Eigen::Quaternionf (coefficients.values[6], coefficients.values[3],
00087                                            coefficients.values[4], coefficients.values[5]));
00088   t->RotateWXYZ (pcl::rad2deg (a.angle ()), a.axis ()[0], a.axis ()[1], a.axis ()[2]);
00089   
00090   vtkSmartPointer<vtkCubeSource> cube = vtkSmartPointer<vtkCubeSource>::New ();
00091   cube->SetXLength (coefficients.values[7]);
00092   cube->SetYLength (coefficients.values[8]);
00093   cube->SetZLength (coefficients.values[9]);
00094   
00095   vtkSmartPointer<vtkTransformPolyDataFilter> tf = vtkSmartPointer<vtkTransformPolyDataFilter>::New ();
00096   tf->SetTransform (t);
00097   tf->SetInputConnection (cube->GetOutputPort ());
00098   
00099   return (tf->GetOutput ());
00100 }
00101 
00103 vtkSmartPointer<vtkDataSet> 
00104 pcl::visualization::createCube (const Eigen::Vector3f &translation, const Eigen::Quaternionf &rotation,
00105                                 double width, double height, double depth)
00106 {
00107   // coefficients = [Tx, Ty, Tz, Qx, Qy, Qz, Qw, width, height, depth]
00108   vtkSmartPointer<vtkTransform> t = vtkSmartPointer<vtkTransform>::New ();
00109   t->Identity ();
00110   t->Translate (translation.x (), translation.y (), translation.z ());
00111   
00112   Eigen::AngleAxisf a (rotation);
00113   t->RotateWXYZ (pcl::rad2deg (a.angle ()), a.axis ()[0], a.axis ()[1], a.axis ()[2]);
00114   
00115   vtkSmartPointer<vtkCubeSource> cube = vtkSmartPointer<vtkCubeSource>::New ();
00116   cube->SetXLength (width);
00117   cube->SetYLength (height);
00118   cube->SetZLength (depth);
00119   
00120   vtkSmartPointer<vtkTransformPolyDataFilter> tf = vtkSmartPointer<vtkTransformPolyDataFilter>::New ();
00121   tf->SetTransform (t);
00122   tf->SetInputConnection (cube->GetOutputPort ());
00123   
00124   return (tf->GetOutput ());
00125 }
00126 
00128 vtkSmartPointer<vtkDataSet> 
00129 pcl::visualization::createCube (double x_min, double x_max,
00130                                 double y_min, double y_max,
00131                                 double z_min, double z_max)
00132 {
00133   vtkSmartPointer<vtkTransform> t = vtkSmartPointer<vtkTransform>::New ();
00134   
00135   vtkSmartPointer<vtkCubeSource> cube = vtkSmartPointer<vtkCubeSource>::New ();
00136   cube->SetBounds (x_min, x_max, y_min, y_max, z_min, z_max);
00137 
00138   return (cube->GetOutput ());
00139 }
00140 
00142 vtkSmartPointer<vtkDataSet> 
00143 pcl::visualization::createLine (const pcl::ModelCoefficients &coefficients)
00144 {
00145   vtkSmartPointer<vtkLineSource> line = vtkSmartPointer<vtkLineSource>::New ();
00146   line->SetPoint1 (coefficients.values[0], coefficients.values[1], coefficients.values[2]);
00147   line->SetPoint2 (coefficients.values[3] + coefficients.values[0], 
00148                    coefficients.values[4] + coefficients.values[1], 
00149                    coefficients.values[5] + coefficients.values[2]);
00150   line->Update ();
00151 
00152   return (line->GetOutput ());
00153 }
00154 
00156 vtkSmartPointer<vtkDataSet> 
00157 pcl::visualization::createPlane (const pcl::ModelCoefficients &coefficients)
00158 {
00159   vtkSmartPointer<vtkPlaneSource> plane = vtkSmartPointer<vtkPlaneSource>::New ();
00160   plane->SetNormal (coefficients.values[0], coefficients.values[1], coefficients.values[2]);
00161 
00162   double norm_sqr = coefficients.values[0] * coefficients.values[0]
00163                   + coefficients.values[1] * coefficients.values[1]
00164                   + coefficients.values[2] * coefficients.values[2];
00165 
00166   plane->Push (-coefficients.values[3] / sqrt(norm_sqr));
00167   return (plane->GetOutput ());
00168 }
00169 
00171 vtkSmartPointer<vtkDataSet> 
00172 pcl::visualization::create2DCircle (const pcl::ModelCoefficients &coefficients, double z)
00173 {
00174   vtkSmartPointer<vtkDiskSource> disk = vtkSmartPointer<vtkDiskSource>::New ();
00175   // Maybe the resolution should be lower e.g. 50 or 25 
00176   disk->SetCircumferentialResolution (100);
00177   disk->SetInnerRadius (coefficients.values[2] - 0.001);
00178   disk->SetOuterRadius (coefficients.values[2] + 0.001);
00179   disk->SetCircumferentialResolution (20);
00180 
00181   // An alternative to <vtkDiskSource> could be <vtkRegularPolygonSource> with <vtkTubeFilter>
00182   /*
00183   vtkSmartPointer<vtkRegularPolygonSource> circle = vtkSmartPointer<vtkRegularPolygonSource>::New();
00184   circle->SetRadius (coefficients.values[2]);
00185   circle->SetNumberOfSides (100);
00186   
00187   vtkSmartPointer<vtkTubeFilter> tube = vtkSmartPointer<vtkTubeFilter>::New();
00188   tube->SetInput (circle->GetOutput());
00189   tube->SetNumberOfSides (25);
00190   tube->SetRadius (0.001);
00191   */ 
00192 
00193   // Set the circle origin
00194   vtkSmartPointer<vtkTransform> t = vtkSmartPointer<vtkTransform>::New ();
00195   t->Identity (); 
00196   t->Translate (coefficients.values[0], coefficients.values[1], z);
00197 
00198   vtkSmartPointer<vtkTransformPolyDataFilter> tf = vtkSmartPointer<vtkTransformPolyDataFilter>::New ();
00199   tf->SetTransform (t);
00200   tf->SetInputConnection (disk->GetOutputPort ());
00201   /*
00202   tf->SetInputConnection (tube->GetOutputPort ());
00203   */
00204 
00205   return (tf->GetOutput ());
00206 }
00207 
00209 vtkSmartPointer<vtkDataSet> 
00210 pcl::visualization::createCone (const pcl::ModelCoefficients &coefficients)
00211 {
00212   vtkSmartPointer<vtkConeSource> cone = vtkSmartPointer<vtkConeSource>::New ();
00213   cone->SetHeight (1.0);
00214   cone->SetCenter (coefficients.values[0] + coefficients.values[3] * 0.5, 
00215                    coefficients.values[1] + coefficients.values[1] * 0.5,
00216                    coefficients.values[2] + coefficients.values[2] * 0.5);
00217   cone->SetDirection (-coefficients.values[3], -coefficients.values[4], -coefficients.values[5]);
00218   cone->SetResolution (100);
00219   cone->SetAngle (coefficients.values[6]);
00220 
00221   return (cone->GetOutput ());
00222 }
00223 
00225 vtkSmartPointer<vtkDataSet> 
00226 pcl::visualization::createSphere (const Eigen::Vector4f &center, double radius, int res)
00227 {
00228   // Set the sphere origin
00229   vtkSmartPointer<vtkTransform> t = vtkSmartPointer<vtkTransform>::New ();
00230   t->Identity (); 
00231   t->Translate (center[0], center[1], center[2]);
00232 
00233   vtkSmartPointer<vtkSphereSource> s_sphere = vtkSmartPointer<vtkSphereSource>::New ();
00234   s_sphere->SetRadius (radius);
00235   s_sphere->SetPhiResolution (res);
00236   s_sphere->SetThetaResolution (res);
00237   s_sphere->LatLongTessellationOff ();
00238   
00239   vtkSmartPointer<vtkTransformPolyDataFilter> tf = vtkSmartPointer<vtkTransformPolyDataFilter>::New ();
00240   tf->SetTransform (t);
00241   tf->SetInputConnection (s_sphere->GetOutputPort ());
00242   tf->Update ();
00243 
00244   return (tf->GetOutput ());
00245 }
00246 
00248 vtkSmartPointer<vtkDataSet>
00249 pcl::visualization::createLine (const Eigen::Vector4f &pt1, const Eigen::Vector4f &pt2)
00250 {
00251   vtkSmartPointer<vtkLineSource> line = vtkSmartPointer<vtkLineSource>::New ();
00252   line->SetPoint1 (pt1.x (), pt1.y (), pt1.z ());
00253   line->SetPoint2 (pt2.x (), pt2.y (), pt2.z ());
00254   line->Update ();
00255 
00256   return (line->GetOutput ());
00257 }
00259 void
00260 pcl::visualization::allocVtkUnstructuredGrid (vtkSmartPointer<vtkUnstructuredGrid> &polydata)
00261 {
00262   polydata = vtkSmartPointer<vtkUnstructuredGrid>::New ();
00263 }
00264 
00265 


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