pointcloud_model_generator.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #include "jsk_footstep_planner/pointcloud_model_generator.h"
00037 #include <boost/random.hpp>
00038 
00039 namespace jsk_footstep_planner
00040 {
00041   void PointCloudModelGenerator::generate(
00042     const std::string& model_name,
00043     pcl::PointCloud<PointT>& output,
00044     double hole_rate)
00045   {
00046     output.points.clear();
00047     if (model_name == "flat") {
00048       flat(output, hole_rate);
00049     }
00050     else if (model_name == "stairs") {
00051       stairs(output, hole_rate);
00052     }
00053     else if (model_name == "hills") {
00054       hills(output, hole_rate);
00055     }
00056     else if (model_name == "gaussian") {
00057       gaussian(output, hole_rate);
00058     }
00059   }
00060 
00061   void PointCloudModelGenerator::flat(pcl::PointCloud<PointT>& output, double hole_rate)
00062   {
00063     boost::mt19937 gen( static_cast<unsigned long>(time(0)) );
00064     boost::uniform_real<> dst( 0, 100 );
00065     boost::variate_generator<
00066       boost::mt19937&, boost::uniform_real<>
00067       > rand( gen, dst );
00068 
00069     for (double y = -4; y < 4; y = y + 0.01) {
00070       for (double x = -4; x < 4; x = x + 0.01) {
00071         if (rand() >= hole_rate) {
00072           pcl::PointNormal p;
00073           p.x = x;
00074           p.y = y;
00075           output.points.push_back(p);
00076         }
00077       }
00078     }
00079   }
00080 
00081   void PointCloudModelGenerator::hills(pcl::PointCloud<PointT>& output, double hole_rate)
00082   {
00083     boost::mt19937 gen( static_cast<unsigned long>(time(0)) );
00084     boost::uniform_real<> dst( 0, 100 );
00085     boost::variate_generator<
00086       boost::mt19937&, boost::uniform_real<>
00087       > rand( gen, dst );
00088 
00089     const double height = 0.1;
00090     for (double y = -4; y < 4; y = y + 0.01) {
00091       for (double x = -4; x < 4; x = x + 0.01) {
00092         if (rand() >= hole_rate) {
00093           pcl::PointNormal p;
00094           p.x = x;
00095           p.y = y;
00096           p.z = height * sin(x * 2) * sin(y * 2);
00097           output.points.push_back(p);
00098         }
00099       }
00100     }
00101   }
00102 
00103   void PointCloudModelGenerator::gaussian(pcl::PointCloud<PointT>& output, double hole_rate)
00104   {
00105     boost::mt19937 gen( static_cast<unsigned long>(time(0)) );
00106     boost::uniform_real<> dst( 0, 100 );
00107     boost::variate_generator<
00108       boost::mt19937&, boost::uniform_real<>
00109       > rand( gen, dst );
00110     const double height = 1.0;
00111     const double sigma = 0.3;
00112     for (double y = -4; y < 4; y = y + 0.01) {
00113       for (double x = -4; x < 4; x = x + 0.01) {
00114         if (rand() >= hole_rate) {
00115           pcl::PointNormal p;
00116           p.x = x;
00117           p.y = y;
00118           //p.z = height * sin(x * 2) * sin(y * 2);
00119           p.z = height * exp(-x*x / (2 * sigma * 2)) * exp(-y*y / (2 * sigma * 2));
00120           output.points.push_back(p);
00121         }
00122       }
00123     }
00124   }
00125 
00126   void PointCloudModelGenerator::stairs(pcl::PointCloud<PointT>& output, double hole_rate)
00127   {
00128     boost::mt19937 gen( static_cast<unsigned long>(time(0)) );
00129     boost::uniform_real<> dst( 0, 100 );
00130     boost::variate_generator<
00131       boost::mt19937&, boost::uniform_real<>
00132       > rand( gen, dst );
00133 
00134     for (double y = -4; y < 4; y = y + 0.01) {
00135       // for (double x = -4; x < 0; x = x + 0.01) {
00136       //   if (rand() >= hole_rate) {
00137       //     pcl::PointNormal p;
00138       //     p.x = x;
00139       //     p.y = y;
00140       //     p.z = 0;
00141       //     output.points.push_back(p);
00142       //   }
00143       // }
00144       for (double x = -4; x < 5; x = x + 0.01) {
00145         if (rand() >= hole_rate) {
00146           pcl::PointNormal p;
00147           p.x = x;
00148           p.y = y;
00149           if (x > 0) {
00150             p.z = floor(x * 3) * 0.1;
00151           }
00152           else {
00153             p.z = ceil(x * 3) * 0.1;
00154           }
00155           output.points.push_back(p);
00156         }
00157       }
00158     }
00159   }
00160   
00161 }


jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:37:57