NormalSpace.cpp
Go to the documentation of this file.
00001 // kate: replace-tabs off; indent-width 4; indent-mode normal
00002 // vim: ts=4:sw=4:noexpandtab
00003 /*
00004 
00005 Copyright (c) 2010--2018,
00006 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
00007 You can contact the authors at <f dot pomerleau at gmail dot com> and
00008 <stephane at magnenat dot net>
00009 
00010 All rights reserved.
00011 
00012 Redistribution and use in source and binary forms, with or without
00013 modification, are permitted provided that the following conditions are met:
00014     * Redistributions of source code must retain the above copyright
00015       notice, this list of conditions and the following disclaimer.
00016     * Redistributions in binary form must reproduce the above copyright
00017       notice, this list of conditions and the following disclaimer in the
00018       documentation and/or other materials provided with the distribution.
00019     * Neither the name of the <organization> nor the
00020       names of its contributors may be used to endorse or promote products
00021       derived from this software without specific prior written permission.
00022 
00023 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00024 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00025 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00026 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
00027 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00028 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00030 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00031 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00032 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00033 
00034 */
00035 #include "NormalSpace.h"
00036 
00037 #include <algorithm>
00038 #include <vector>
00039 #include <unordered_map>
00040 #include <random>
00041 #include <ciso646>
00042 #include <cmath>
00043 #include <numeric>
00044 
00045 // NormalSpaceDataPointsFilter
00046 template <typename T>
00047 NormalSpaceDataPointsFilter<T>::NormalSpaceDataPointsFilter(const Parameters& params) :
00048         PointMatcher<T>::DataPointsFilter("NormalSpaceDataPointsFilter", 
00049                 NormalSpaceDataPointsFilter::availableParameters(), params),
00050         nbSample{Parametrizable::get<std::size_t>("nbSample")},
00051         seed{Parametrizable::get<std::size_t>("seed")},
00052         epsilon{Parametrizable::get<T>("epsilon")},
00053         nbBucket{std::size_t(ceil(2.0 * M_PI / epsilon) * ceil(M_PI / epsilon))}
00054 {
00055 }
00056 
00057 template <typename T>
00058 typename PointMatcher<T>::DataPoints
00059 NormalSpaceDataPointsFilter<T>::filter(const DataPoints& input)
00060 {
00061         DataPoints output(input);
00062         inPlaceFilter(output);
00063         return output;
00064 }
00065 
00066 //TODO: Add support for 2D by building histogram of polar coordinate with uniform sampling
00067 
00068 template <typename T>
00069 void NormalSpaceDataPointsFilter<T>::inPlaceFilter(DataPoints& cloud)
00070 {
00071         //check dimension
00072         const std::size_t featDim = cloud.features.rows();
00073         if(featDim < 4) //3D case support only
00074         {
00075                 std::cerr << "ERROR: NormalSpaceDataPointsFilter does not support 2D point cloud yet (does nothing)" << std::endl;
00076                 return;
00077         }
00078                 
00079         //Check number of points
00080         const int nbPoints = cloud.getNbPoints();               
00081         if(nbSample >= std::size_t(nbPoints))
00082                 return;
00083 
00084         //Check if there is normals info
00085         if (!cloud.descriptorExists("normals"))
00086                 throw InvalidField("OrientNormalsDataPointsFilter: Error, cannot find normals in descriptors.");
00087 
00088         const auto& normals = cloud.getDescriptorViewByName("normals");
00089         
00090         std::mt19937 gen(seed); //Standard mersenne_twister_engine seeded with seed
00091 
00092         //bucketed normal space
00093         std::vector<std::vector<int> > idBuckets;
00094         idBuckets.resize(nbBucket);
00095         
00096         std::vector<std::size_t> keepIndexes;
00097         keepIndexes.reserve(nbSample);
00098 
00099         // Generate a random sequence of indices so that elements are placed in buckets in random order
00100         std::vector<std::size_t> randIdcs(nbPoints);
00101         std::iota(randIdcs.begin(), randIdcs.end(), 0);
00102         std::random_shuffle(randIdcs.begin(), randIdcs.end());
00103 
00105         for (auto randIdx : randIdcs)
00106         {
00107                 // Allow for slight approximiation errors
00108                 assert(normals.col(randIdx).head(3).norm() >= 1.0-0.00001);
00109                 assert(normals.col(randIdx).head(3).norm() <= 1.0+0.00001);
00110                 // Catch errors where theta will be NaN
00111                 assert((normals(2,randIdx) <= 1.0) && (normals(2,randIdx) >= -1.0));
00112 
00113                 //Theta = polar angle in [0 ; pi]
00114                 const T theta = std::acos(normals(2, randIdx));
00115                 //Phi = azimuthal angle in [0 ; 2pi]
00116                 const T phi = std::fmod(std::atan2(normals(1, randIdx), normals(0, randIdx)) + 2. * M_PI, 2. * M_PI);
00117 
00118                 // Catch normal space hashing errors
00119                 assert(bucketIdx(theta, phi) < nbBucket);
00120                 idBuckets[bucketIdx(theta, phi)].push_back(randIdx);
00121         }
00122 
00123         // Remove empty buckets
00124         idBuckets.erase(std::remove_if(idBuckets.begin(), idBuckets.end(),
00125                                 [](const std::vector<int>& bucket) { return bucket.empty(); }),
00126                                 idBuckets.end());
00127 
00129         for (std::size_t i=0; i<nbSample; i++)
00130         {
00131                 // Get a random bucket
00132                 std::uniform_int_distribution<std::size_t> uniBucket(0,idBuckets.size()-1);
00133                 std::size_t curBucketIdx = uniBucket(gen);
00134                 std::vector<int>& curBucket = idBuckets[curBucketIdx];
00135 
00137                 int idToKeep = curBucket[curBucket.size()-1];
00138                 curBucket.pop_back();
00139                 keepIndexes.push_back(static_cast<std::size_t>(idToKeep));
00140 
00141                 // Remove the bucket if it is empty
00142                 if (curBucket.empty()) {
00143                         idBuckets.erase(idBuckets.begin()+curBucketIdx);
00144                 }
00145         }
00146 
00147         //TODO: evaluate performances between this solution and sorting the indexes
00148         // We build map of (old index to new index), in case we sample pts at the begining of the pointcloud
00149         std::unordered_map<std::size_t, std::size_t> mapidx;
00150         std::size_t idx = 0;
00151         
00153         for(std::size_t id : keepIndexes)
00154         {
00155                 //retrieve index from lookup table if sampling in already switched element
00156                 if(id<idx)
00157                         id = mapidx[id];
00158                 //Switch columns id and idx
00159                 cloud.swapCols(idx, id);        
00160                 //Maintain new index position   
00161                 mapidx[idx] = id;
00162                 //Update index
00163                 ++idx;
00164         }
00165         cloud.conservativeResize(nbSample);
00166 }
00167 
00168 template <typename T>
00169 std::size_t NormalSpaceDataPointsFilter<T>::bucketIdx(T theta, T phi) const
00170 {
00171         //Theta = polar angle in [0 ; pi] and Phi = azimuthal angle in [0 ; 2pi]
00172         assert( (theta >= 0.0) && (theta <= static_cast<T>(M_PI)) && "Theta not in [0, Pi]");
00173         assert( (phi >= 0) && (phi <= 2*static_cast<T>(M_PI)) && "Phi not in [0, 2Pi]");
00174 
00175         // Wrap Theta at Pi
00176         if (theta == static_cast<T>(M_PI)) { theta = 0.0; };
00177         // Wrap Phi at 2Pi
00178         if (phi == 2*static_cast<T>(M_PI)) { phi = 0.0; };
00179         //                               block number           block size               element number
00180         return static_cast<std::size_t>( floor(theta/epsilon) * ceil(2.0*M_PI/epsilon) + floor(phi/epsilon) );
00181 }
00182 
00183 template struct NormalSpaceDataPointsFilter<float>;
00184 template struct NormalSpaceDataPointsFilter<double>;


libpointmatcher
Author(s):
autogenerated on Thu Jun 20 2019 19:51:31