RemoveSensorBias.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 "RemoveSensorBias.h"
00036 
00037 #include "PointMatcherPrivate.h"
00038 
00039 #include <string>
00040 #include <vector>
00041 
00042 #include <boost/format.hpp>
00043 #include <ciso646>
00044 #include <cmath>
00045 
00046 
00047 template<typename T>
00048 RemoveSensorBiasDataPointsFilter<T>::RemoveSensorBiasDataPointsFilter(const Parameters& params):
00049         PointMatcher<T>::DataPointsFilter("RemoveSensorBiasDataPointsFilter", 
00050                 RemoveSensorBiasDataPointsFilter::availableParameters(), params),
00051         sensorType(SensorType(Parametrizable::get<int>("sensorType"))),
00052         angleThreshold(Parametrizable::get<T>("angleThreshold")/180.*M_PI)
00053 {
00054 }
00055 
00056 template<typename T>
00057 typename PointMatcher<T>::DataPoints 
00058 RemoveSensorBiasDataPointsFilter<T>::filter(const DataPoints& input)
00059 {
00060         DataPoints output(input);
00061         inPlaceFilter(output);
00062         return output;
00063 }
00064 
00065 template<typename T>
00066 void RemoveSensorBiasDataPointsFilter<T>::inPlaceFilter(DataPoints& cloud)
00067 {
00068         //Check if there is normals info
00069         if (!cloud.descriptorExists("incidenceAngles"))
00070                 throw InvalidField("RemoveSensorBiasDataPointsFilter: Error, cannot find incidence angles in descriptors.");
00071         //Check if there is normals info
00072         if (!cloud.descriptorExists("observationDirections"))
00073                 throw InvalidField("RemoveSensorBiasDataPointsFilter: Error, cannot find observationDirections in descriptors.");
00074                 
00075         const auto& incidenceAngles = cloud.getDescriptorViewByName("incidenceAngles");
00076         const auto& observationDirections = cloud.getDescriptorViewByName("observationDirections");
00077 
00078         double aperture, k1, k2;
00079 
00080         switch(sensorType)
00081         {
00082                 case LMS_1XX: 
00083                 {
00084                         aperture = SensorParameters::LMS_1XX.aperture;
00085                         k1 = SensorParameters::LMS_1XX.k1;
00086                         k2 = SensorParameters::LMS_1XX.k2;
00087                         break;
00088                 }
00089                 case HDL_32E: 
00090                 {
00091                         aperture = SensorParameters::HDL_32E.aperture;
00092                         k1 = SensorParameters::HDL_32E.k1;
00093                         k2 = SensorParameters::HDL_32E.k2;
00094                         break;
00095                 }
00096                 default:
00097                         throw InvalidParameter(
00098                                 (boost::format("RemoveSensorBiasDataPointsFilter: Error, cannot remove bias for sensorType id %1% .") % sensorType).str());
00099         }
00100 
00101         const std::size_t nbPts = cloud.getNbPoints();
00102         const std::size_t dim = cloud.features.rows();
00103         
00104 
00105         assert(dim == 3 or dim == 4); //check 2D or 3D
00106 
00107         std::size_t j = 0;
00108         for(std::size_t i = 0; i < nbPts; ++i)
00109         {
00110                 const Vector vObs = observationDirections.col(i);
00111 
00112                 const double depth = vObs.norm();
00113                 const T incidence = incidenceAngles(0, i);
00114 
00115                 //check if the incidence angle could be estimated.
00116                 //For angles very close to 90 degrees, a small error of estimation could change drastically the correction, so we skip those points.
00117                 if(not std::isnan(incidence) and incidence >= 0. and incidence < angleThreshold)
00118                 {
00119                         const double correction = k1 * diffDist(depth, incidence, aperture) + k2 * ratioCurvature(depth, incidence, aperture);
00120 
00121                         Vector p = cloud.features.col(i);
00122                         p.head(dim-1) += correction * vObs.normalized(); 
00123                         cloud.features.col(i) = p;
00124                         cloud.setColFrom(j, cloud, i);
00125                         ++j;
00126                 }               
00127         }
00128         cloud.conservativeResize(j);
00129 }
00130 
00131 template<typename T>
00132 std::array<double, 4> RemoveSensorBiasDataPointsFilter<T>::getCoefficients(const double depth, const T theta, const double aperture) const
00133 {
00134         const double sigma = tau / std::sqrt(2. * M_PI);
00135         const double w0 = lambda_light / (M_PI * aperture);
00136 
00137         const double A  = 2. * std::pow(depth * std::tan(theta), 2) / std::pow(sigma * c, 2) + 2. / std::pow(aperture, 2);
00138         const double K1 = std::pow(std::cos(theta), 3);
00139         const double K2 = 3. * std::pow(std::cos(theta), 2) * std::sin(theta);
00140         const double L1 = pulse_intensity * std::pow(w0 / (aperture * depth * std::cos(theta)), 2) *
00141                 std::sqrt(M_PI) * std::erf(aperture * std::sqrt(A)) / (2. * std::pow(A, 3. / 2.));
00142         const double L2 = pulse_intensity * std::pow(w0 / (aperture * depth * std::cos(theta)), 2) * K2 / (2. * A);
00143 
00144         const double a0 = 2. * A * K1 * L1;
00145         const double a1 = -(2. * std::tan(theta) * depth * 
00146                         (L1 * K2 - 2. * L2 * aperture * std::exp(-A * std::pow(aperture, 2)))) / (std::pow(sigma, 2) * c);
00147         const double a2 = -L1 * 2. * A * K1 * (std::pow(sigma * c * std::cos(theta), 2) * A + 2. * std::pow(std::cos(theta) * depth, 2) - 2. * std::pow(depth, 2)) / 
00148                 (2 * std::pow(c * std::cos(theta), 2) * std::pow(sigma, 4) * A);
00149         const double a3 = L1 * K2 * depth * std::tan(theta) * (std::pow(sigma * c, 2) * A - 2. * std::pow(depth * std::tan(theta), 2)) / 
00150                 (std::pow(sigma, 6) * std::pow(c, 3) * A);
00151 
00152         return {a0, a1, a2, a3};
00153 }
00154 
00155 template<typename T>
00156 double RemoveSensorBiasDataPointsFilter<T>::diffDist(const double depth, const T theta, const double aperture) const
00157 {
00158         static constexpr double epsilon = 1e-5;
00159         
00160         const std::array<double, 4> a = getCoefficients(depth, theta, aperture);
00161 
00162         double Tmax;
00163 
00164         if(theta < epsilon) // approx. 0
00165                 Tmax = 0.;
00166         else // theta >0
00167                 Tmax = (-2 * a[2] - std::sqrt(4 * pow(a[2], 2) - 12 * a[1] * a[3])) / (6 * a[3]);
00168         
00169         return Tmax * c / 2.;
00170 }
00171 
00172 template<typename T>
00173 double RemoveSensorBiasDataPointsFilter<T>::ratioCurvature(const double depth, const T theta, const double aperture) const
00174 {
00175         static constexpr double epsilon = 1e-5;
00176         const std::array<double,4> a = getCoefficients(depth, theta, aperture);
00177         const std::array<double,4> b = getCoefficients(depth, 0., aperture);
00178 
00179         double Tmax;
00180 
00181         if(theta < epsilon) // approx. 0
00182                 Tmax = 0.;
00183         else // theta >0
00184                 Tmax = ( -2 * a[2] - std::sqrt(4 * std::pow(a[2], 2) - 12 * a[1] * a[3])) / (6 * a[3]);
00185         
00186         return 1. - 2 * b[2] / (2 * a[2] + 6 * Tmax * a[3]);
00187 }
00188 
00189 template struct RemoveSensorBiasDataPointsFilter<float>;
00190 template struct RemoveSensorBiasDataPointsFilter<double>;


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