add_gaussian_noise.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2011, 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: add_gaussian_noise.cpp 2417 2011-09-07 07:22:29Z rusu $
00035  *
00036  */
00037 
00038 #include <sensor_msgs/PointCloud2.h>
00039 #include <pcl/point_types.h>
00040 #include <pcl/io/pcd_io.h>
00041 #include <pcl/console/print.h>
00042 #include <pcl/console/parse.h>
00043 #include <pcl/console/time.h>
00044 #include <boost/random.hpp>
00045 #include <boost/random/normal_distribution.hpp>
00046 
00047 using namespace pcl;
00048 using namespace pcl::io;
00049 using namespace pcl::console;
00050 
00051 double default_standard_deviation = 0.01;
00052 
00053 void
00054 printHelp (int, char **argv)
00055 {
00056   print_error ("Syntax is: %s input.pcd output.pcd <options>\n", argv[0]);
00057   print_info ("  where options are:\n");
00058   print_info ("                     -sd X = the standard deviation for the normal distribution (default: ");
00059   print_value ("%f", default_standard_deviation); print_info (")\n");
00060 }
00061 
00062 bool
00063 loadCloud (const std::string &filename, sensor_msgs::PointCloud2 &cloud)
00064 {
00065   TicToc tt;
00066   print_highlight ("Loading "); print_value ("%s ", filename.c_str ());
00067 
00068   tt.tic ();
00069   if (loadPCDFile (filename, cloud) < 0)
00070     return (false);
00071   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms: "); print_value ("%d", cloud.width * cloud.height); print_info (" points]\n");
00072   print_info ("Available dimensions: "); print_value ("%s\n", pcl::getFieldsList (cloud).c_str ());
00073 
00074   return (true);
00075 }
00076 
00077 void
00078 compute (const sensor_msgs::PointCloud2::ConstPtr &input, sensor_msgs::PointCloud2 &output,
00079          double standard_deviation)
00080 {
00081   TicToc tt;
00082   tt.tic ();
00083 
00084   print_highlight ("Adding Gaussian noise with mean 0.0 and standard deviation %f\n", standard_deviation);
00085 
00086   PointCloud<PointXYZ>::Ptr xyz_cloud (new pcl::PointCloud<PointXYZ> ());
00087   fromROSMsg (*input, *xyz_cloud);
00088 
00089   PointCloud<PointXYZ>::Ptr xyz_cloud_filtered (new PointCloud<PointXYZ> ());
00090   xyz_cloud_filtered->points.resize (xyz_cloud->points.size ());
00091   xyz_cloud_filtered->header = xyz_cloud->header;
00092   xyz_cloud_filtered->width = xyz_cloud->width;
00093   xyz_cloud_filtered->height = xyz_cloud->height;
00094 
00095 
00096   boost::mt19937 rng; rng.seed (static_cast<unsigned int> (time (0)));
00097   boost::normal_distribution<> nd (0, standard_deviation);
00098   boost::variate_generator<boost::mt19937&, boost::normal_distribution<> > var_nor (rng, nd);
00099 
00100   for (size_t point_i = 0; point_i < xyz_cloud->points.size (); ++point_i)
00101   {
00102     xyz_cloud_filtered->points[point_i].x = xyz_cloud->points[point_i].x + static_cast<float> (var_nor ());
00103     xyz_cloud_filtered->points[point_i].y = xyz_cloud->points[point_i].y + static_cast<float> (var_nor ());
00104     xyz_cloud_filtered->points[point_i].z = xyz_cloud->points[point_i].z + static_cast<float> (var_nor ());
00105   }
00106 
00107   sensor_msgs::PointCloud2 input_xyz_filtered;
00108   toROSMsg (*xyz_cloud_filtered, input_xyz_filtered);
00109   concatenateFields (*input, input_xyz_filtered, output);
00110 
00111   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms: "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00112 }
00113 
00114 void
00115 saveCloud (const std::string &filename, const sensor_msgs::PointCloud2 &output)
00116 {
00117   TicToc tt;
00118   tt.tic ();
00119 
00120   print_highlight ("Saving "); print_value ("%s ", filename.c_str ());
00121 
00122   pcl::io::savePCDFile (filename, output);
00123 
00124   print_info ("[done, "); print_value ("%g", tt.toc ()); print_info (" ms: "); print_value ("%d", output.width * output.height); print_info (" points]\n");
00125 }
00126 
00127 /* ---[ */
00128 int
00129 main (int argc, char** argv)
00130 {
00131   print_info ("Add Gaussian noise to a point cloud. For more information, use: %s -h\n", argv[0]);
00132 
00133   if (argc < 3)
00134   {
00135     printHelp (argc, argv);
00136     return (-1);
00137   }
00138 
00139   // Parse the command line arguments for .pcd files
00140   std::vector<int> p_file_indices;
00141   p_file_indices = parse_file_extension_argument (argc, argv, ".pcd");
00142   if (p_file_indices.size () != 2)
00143   {
00144     print_error ("Need one input PCD file and one output PCD file to continue.\n");
00145     return (-1);
00146   }
00147 
00148   // Command line parsing
00149   double standard_deviation = default_standard_deviation;
00150   parse_argument (argc, argv, "-sd", standard_deviation);
00151 
00152   // Load the first file
00153   sensor_msgs::PointCloud2::Ptr cloud (new sensor_msgs::PointCloud2);
00154   if (!loadCloud (argv[p_file_indices[0]], *cloud))
00155     return (-1);
00156 
00157   // Add the noise
00158   sensor_msgs::PointCloud2 output;
00159   compute (cloud, output, standard_deviation);
00160 
00161   // Save into the second file
00162   saveCloud (argv[p_file_indices[1]], output);
00163 }
00164 


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:14:38