generate.hpp
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) 2010-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 the copyright holder(s) 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 
00040 #ifndef PCL_COMMON_GENERATE_HPP_
00041 #define PCL_COMMON_GENERATE_HPP_
00042 
00043 #include <pcl/console/print.h>
00044 
00046 template <typename PointT, typename GeneratorT>
00047 pcl::common::CloudGenerator<PointT, GeneratorT>::CloudGenerator ()
00048   : x_generator_ ()
00049   , y_generator_ ()
00050   , z_generator_ ()
00051 {}
00052 
00054 template <typename PointT, typename GeneratorT>
00055 pcl::common::CloudGenerator<PointT, GeneratorT>::CloudGenerator (const GeneratorParameters& params)
00056 {
00057   setParameters (params);
00058 }
00059 
00060 
00062 template <typename PointT, typename GeneratorT>
00063 pcl::common::CloudGenerator<PointT, GeneratorT>::CloudGenerator (const GeneratorParameters& x_params,
00064                                                                  const GeneratorParameters& y_params,
00065                                                                  const GeneratorParameters& z_params)
00066   : x_generator_ (x_params)
00067   , y_generator_ (y_params)
00068   , z_generator_ (z_params)
00069 {}
00070 
00072 template <typename PointT, typename GeneratorT> void
00073 pcl::common::CloudGenerator<PointT, GeneratorT>::setParameters (const GeneratorParameters& params)
00074 {
00075   GeneratorParameters y_params = params;
00076   y_params.seed += 1;
00077   GeneratorParameters z_params = y_params;
00078   z_params.seed += 1;
00079   x_generator_.setParameters (params);
00080   y_generator_.setParameters (y_params);
00081   z_generator_.setParameters (z_params);  
00082 }
00083 
00085 template <typename PointT, typename GeneratorT> void
00086 pcl::common::CloudGenerator<PointT, GeneratorT>::setParametersForX (const GeneratorParameters& x_params)
00087 {
00088   x_generator_.setParameters (x_params);
00089 }
00090 
00092 template <typename PointT, typename GeneratorT> void
00093 pcl::common::CloudGenerator<PointT, GeneratorT>::setParametersForY (const GeneratorParameters& y_params)
00094 {
00095   y_generator_.setParameters (y_params);
00096 }
00097 
00099 template <typename PointT, typename GeneratorT> void
00100 pcl::common::CloudGenerator<PointT, GeneratorT>::setParametersForZ (const GeneratorParameters& z_params)
00101 {
00102   z_generator_.setParameters (z_params);
00103 }
00104 
00106 template <typename PointT, typename GeneratorT> const typename pcl::common::CloudGenerator<PointT, GeneratorT>::GeneratorParameters& 
00107 pcl::common::CloudGenerator<PointT, GeneratorT>::getParametersForX () const
00108 {
00109   x_generator_.getParameters ();
00110 }
00111 
00113 template <typename PointT, typename GeneratorT> const typename pcl::common::CloudGenerator<PointT, GeneratorT>::GeneratorParameters& 
00114 pcl::common::CloudGenerator<PointT, GeneratorT>::getParametersForY () const
00115 {
00116   y_generator_.getParameters ();
00117 }
00118 
00120 template <typename PointT, typename GeneratorT> const typename pcl::common::CloudGenerator<PointT, GeneratorT>::GeneratorParameters& 
00121 pcl::common::CloudGenerator<PointT, GeneratorT>::getParametersForZ () const
00122 {
00123   z_generator_.getParameters ();
00124 }
00125 
00127 template <typename PointT, typename GeneratorT> PointT
00128 pcl::common::CloudGenerator<PointT, GeneratorT>::get ()
00129 {
00130   PointT p;
00131   p.x = x_generator_.run ();
00132   p.y = y_generator_.run ();
00133   p.z = z_generator_.run ();
00134   return (p);
00135 }
00136 
00138 template <typename PointT, typename GeneratorT> int
00139 pcl::common::CloudGenerator<PointT, GeneratorT>::fill (pcl::PointCloud<PointT>& cloud)
00140 {
00141   return (fill (cloud.width, cloud.height, cloud));
00142 }
00143 
00145 template <typename PointT, typename GeneratorT> int
00146 pcl::common::CloudGenerator<PointT, GeneratorT>::fill (int width, int height, pcl::PointCloud<PointT>& cloud)
00147 {
00148   if (width < 1)
00149   {
00150     PCL_ERROR ("[pcl::common::CloudGenerator] Cloud width must be >= 1!\n");
00151     return (-1);
00152   }
00153   
00154   if (height < 1)
00155   {
00156     PCL_ERROR ("[pcl::common::CloudGenerator] Cloud height must be >= 1!\n");
00157     return (-1);
00158   }
00159   
00160   if (!cloud.empty ())
00161   {
00162     PCL_WARN ("[pcl::common::CloudGenerator] Cloud data will be erased with new data!\n");
00163   }
00164   
00165   cloud.width = width;
00166   cloud.height = height;
00167   cloud.resize (cloud.width * cloud.height);
00168   cloud.is_dense = true;
00169   for (typename pcl::PointCloud<PointT>::iterator points_it = cloud.begin ();
00170        points_it != cloud.end ();
00171        ++points_it)
00172   {
00173     points_it->x = x_generator_.run ();
00174     points_it->y = y_generator_.run ();
00175     points_it->z = z_generator_.run ();
00176   }
00177   return (0);
00178 }
00179 
00181 template <typename GeneratorT>
00182 pcl::common::CloudGenerator<pcl::PointXY, GeneratorT>::CloudGenerator ()
00183   : x_generator_ ()
00184   , y_generator_ ()
00185 {}
00186 
00188 template <typename GeneratorT>
00189 pcl::common::CloudGenerator<pcl::PointXY, GeneratorT>::CloudGenerator (const GeneratorParameters& x_params,
00190                                                                        const GeneratorParameters& y_params)
00191   : x_generator_ (x_params)
00192   , y_generator_ (y_params)
00193 {}
00194 
00196 template <typename GeneratorT>
00197 pcl::common::CloudGenerator<pcl::PointXY, GeneratorT>::CloudGenerator (const GeneratorParameters& params)
00198 {
00199   setParameters (params);
00200 }
00201 
00203 template <typename GeneratorT> void
00204 pcl::common::CloudGenerator<pcl::PointXY, GeneratorT>::setParameters (const GeneratorParameters& params)
00205 {
00206   x_generator_.setParameters (params);
00207   GeneratorParameters y_params = params;
00208   y_params.seed += 1;
00209   y_generator_.setParameters (y_params);
00210 }
00211 
00213 template <typename GeneratorT> void
00214 pcl::common::CloudGenerator<pcl::PointXY, GeneratorT>::setParametersForX (const GeneratorParameters& x_params)
00215 {
00216   x_generator_.setParameters (x_params);
00217 }
00218 
00220 template <typename GeneratorT> void
00221 pcl::common::CloudGenerator<pcl::PointXY, GeneratorT>::setParametersForY (const GeneratorParameters& y_params)
00222 {
00223   y_generator_.setParameters (y_params);
00224 }
00225 
00227 template <typename GeneratorT> const typename pcl::common::CloudGenerator<pcl::PointXY, GeneratorT>::GeneratorParameters& 
00228 pcl::common::CloudGenerator<pcl::PointXY, GeneratorT>::getParametersForX () const
00229 {
00230   x_generator_.getParameters ();
00231 }
00232 
00234 template <typename GeneratorT> const typename pcl::common::CloudGenerator<pcl::PointXY, GeneratorT>::GeneratorParameters& 
00235 pcl::common::CloudGenerator<pcl::PointXY, GeneratorT>::getParametersForY () const
00236 {
00237   y_generator_.getParameters ();
00238 }
00239 
00241 template <typename GeneratorT> pcl::PointXY
00242 pcl::common::CloudGenerator<pcl::PointXY, GeneratorT>::get ()
00243 {
00244   pcl::PointXY p;
00245   p.x = x_generator_.run ();
00246   p.y = y_generator_.run ();
00247   return (p);
00248 }
00249 
00251 template <typename GeneratorT> int
00252 pcl::common::CloudGenerator<pcl::PointXY, GeneratorT>::fill (pcl::PointCloud<pcl::PointXY>& cloud)
00253 {
00254   return (fill (cloud.width, cloud.height, cloud));
00255 }
00256 
00258 template <typename GeneratorT> int
00259 pcl::common::CloudGenerator<pcl::PointXY, GeneratorT>::fill (int width, int height, pcl::PointCloud<pcl::PointXY>& cloud)
00260 {
00261   if (width < 1)
00262   {
00263     PCL_ERROR ("[pcl::common::CloudGenerator] Cloud width must be >= 1\n!");
00264     return (-1);
00265   }
00266   
00267   if (height < 1)
00268   {
00269     PCL_ERROR ("[pcl::common::CloudGenerator] Cloud height must be >= 1\n!");
00270     return (-1);
00271   }
00272   
00273   if (!cloud.empty ())
00274     PCL_WARN ("[pcl::common::CloudGenerator] Cloud data will be erased with new data\n!");
00275 
00276   cloud.width = width;
00277   cloud.height = height;
00278   cloud.resize (cloud.width * cloud.height);
00279   cloud.is_dense = true;
00280 
00281   for (pcl::PointCloud<pcl::PointXY>::iterator points_it = cloud.begin ();
00282        points_it != cloud.end ();
00283        ++points_it)
00284   {
00285     points_it->x = x_generator_.run ();
00286     points_it->y = y_generator_.run ();
00287   }
00288   return (0);
00289 }
00290 
00291 #endif


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:24:19