PointToPlaneWithCov.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--2012,
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 
00036 #include <iostream>
00037 
00038 #include "Eigen/SVD"
00039 
00040 #include "ErrorMinimizersImpl.h"
00041 #include "PointMatcherPrivate.h"
00042 #include "Functions.h"
00043 
00044 using namespace Eigen;
00045 using namespace std;
00046 
00047 typedef PointMatcherSupport::Parametrizable Parametrizable;
00048 typedef PointMatcherSupport::Parametrizable P;
00049 typedef Parametrizable::Parameters Parameters;
00050 typedef Parametrizable::ParameterDoc ParameterDoc;
00051 typedef Parametrizable::ParametersDoc ParametersDoc;
00052 
00053 template<typename T>
00054 PointToPlaneWithCovErrorMinimizer<T>::PointToPlaneWithCovErrorMinimizer(const Parameters& params):
00055         PointToPlaneErrorMinimizer<T>(PointToPlaneWithCovErrorMinimizer::availableParameters(), params),
00056         sensorStdDev(Parametrizable::get<T>("sensorStdDev"))
00057 {
00058 }
00059 
00060 template<typename T>
00061 typename PointMatcher<T>::TransformationParameters PointToPlaneWithCovErrorMinimizer<T>::compute(const ErrorElements& mPts_const)
00062 {
00063         ErrorElements mPts = mPts_const;
00064     typename PointMatcher<T>::TransformationParameters out = PointToPlaneErrorMinimizer<T>::compute_in_place(mPts);
00065 
00066     this->covMatrix = this->estimateCovariance(mPts, out);
00067 
00068     return out;
00069 }
00070 
00071 template<typename T>
00072 typename PointMatcher<T>::Matrix
00073 PointToPlaneWithCovErrorMinimizer<T>::estimateCovariance(const ErrorElements& mPts, const TransformationParameters& transformation)
00074 {
00075     const int max_nbr_point = mPts.reading.getNbPoints();
00076 
00077     Matrix covariance(Matrix::Zero(6,6));
00078     Matrix J_hessian(Matrix::Zero(6,6));
00079     Matrix d2J_dReadingdX(Matrix::Zero(6, max_nbr_point));
00080     Matrix d2J_dReferencedX(Matrix::Zero(6, max_nbr_point));
00081 
00082     Vector reading_point(Vector::Zero(3));
00083     Vector reference_point(Vector::Zero(3));
00084     Vector normal(3);
00085     Vector reading_direction(Vector::Zero(3));
00086     Vector reference_direction(Vector::Zero(3));
00087 
00088     //TODO: should be constView
00089     Matrix normals = mPts.reference.getDescriptorViewByName("normals");
00090 
00091     if (normals.rows() < 3)    // Make sure there are normals in DataPoints
00092         return std::numeric_limits<T>::max() * Matrix::Identity(6,6);
00093 
00094     T beta = -asin(transformation(2,0));
00095     T alpha = atan2(transformation(2,1), transformation(2,2));
00096     T gamma = atan2(transformation(1,0)/cos(beta), transformation(0,0)/cos(beta));
00097     T t_x = transformation(0,3);
00098     T t_y = transformation(1,3);
00099     T t_z = transformation(2,3);
00100 
00101     Vector tmp_vector_6(Vector::Zero(6));
00102 
00103     int valid_points_count = 0;
00104 
00105     //TODO: add missing const
00106     for(int i = 0; i < max_nbr_point; ++i)
00107     {
00108         //if (outlierWeights(0,i) > 0.0)
00109         {
00110             reading_point = mPts.reading.features.block(0,i,3,1);
00111             //int reference_idx = matches.ids(0,i);
00112             reference_point = mPts.reference.features.block(0,i,3,1);
00113 
00114             normal = normals.block(0,i,3,1);
00115 
00116             T reading_range = reading_point.norm();
00117             reading_direction = reading_point / reading_range;
00118             T reference_range = reference_point.norm();
00119             reference_direction = reference_point / reference_range;
00120 
00121             T n_alpha = normal(2)*reading_direction(1) - normal(1)*reading_direction(2);
00122             T n_beta = normal(0)*reading_direction(2) - normal(2)*reading_direction(0);
00123             T n_gamma = normal(1)*reading_direction(0) - normal(0)*reading_direction(1);
00124 
00125             T E = normal(0)*(reading_point(0) - gamma*reading_point(1) + beta*reading_point(2) + t_x - reference_point(0));
00126             E +=  normal(1)*(gamma*reading_point(0) + reading_point(1) - alpha*reading_point(2) + t_y - reference_point(1));
00127             E +=  normal(2)*(-beta*reading_point(0) + alpha*reading_point(1) + reading_point(2) + t_z - reference_point(2));
00128 
00129             T N_reading = normal(0)*(reading_direction(0) - gamma*reading_direction(1) + beta*reading_direction(2));
00130             N_reading +=  normal(1)*(gamma*reading_direction(0) + reading_direction(1) - alpha*reading_direction(2));
00131             N_reading +=  normal(2)*(-beta*reading_direction(0) + alpha*reading_direction(1) + reading_direction(2));
00132 
00133             T N_reference = -(normal(0)*reference_direction(0) + normal(1)*reference_direction(1) + normal(2)*reference_direction(2));
00134 
00135             // update the hessian and d2J/dzdx
00136             tmp_vector_6 << normal(0), normal(1), normal(2), reading_range * n_alpha, reading_range * n_beta, reading_range * n_gamma;
00137 
00138             J_hessian += tmp_vector_6 * tmp_vector_6.transpose();
00139 
00140             tmp_vector_6 << normal(0) * N_reading, normal(1) * N_reading, normal(2) * N_reading, n_alpha * (E + reading_range * N_reading), n_beta * (E + reading_range * N_reading), n_gamma * (E + reading_range * N_reading);
00141 
00142             d2J_dReadingdX.block(0,valid_points_count,6,1) = tmp_vector_6;
00143 
00144             tmp_vector_6 << normal(0) * N_reference, normal(1) * N_reference, normal(2) * N_reference, reference_range * n_alpha * N_reference, reference_range * n_beta * N_reference, reference_range * n_gamma * N_reference;
00145 
00146             d2J_dReferencedX.block(0,valid_points_count,6,1) = tmp_vector_6;
00147 
00148             valid_points_count++;
00149         } // if (outlierWeights(0,i) > 0.0)
00150     }
00151 
00152     Matrix d2J_dZdX(Matrix::Zero(6, 2 * valid_points_count));
00153     d2J_dZdX.block(0,0,6,valid_points_count) = d2J_dReadingdX.block(0,0,6,valid_points_count);
00154     d2J_dZdX.block(0,valid_points_count,6,valid_points_count) = d2J_dReferencedX.block(0,0,6,valid_points_count);
00155 
00156     Matrix inv_J_hessian = J_hessian.inverse();
00157 
00158     covariance = d2J_dZdX * d2J_dZdX.transpose();
00159     covariance = inv_J_hessian * covariance * inv_J_hessian;
00160 
00161     return (sensorStdDev * sensorStdDev) * covariance;
00162 }
00163 
00164 
00165 template<typename T>
00166 typename PointMatcher<T>::Matrix PointToPlaneWithCovErrorMinimizer<T>::getCovariance() const
00167 {
00168   return covMatrix;
00169 }
00170 
00171 template struct PointToPlaneWithCovErrorMinimizer<float>;
00172 template struct PointToPlaneWithCovErrorMinimizer<double>;


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