Registry.cpp
Go to the documentation of this file.
00001 // vim: ts=4:sw=4:noexpandtab
00002 /*
00003 
00004 Copyright (c) 2010--2012,
00005 François Pomerleau and Stephane Magnenat, ASL, ETHZ, Switzerland
00006 You can contact the authors at <f dot pomerleau at gmail dot com> and
00007 <stephane at magnenat dot net>
00008 
00009 All rights reserved.
00010 
00011 Redistribution and use in source and binary forms, with or without
00012 modification, are permitted provided that the following conditions are met:
00013     * Redistributions of source code must retain the above copyright
00014       notice, this list of conditions and the following disclaimer.
00015     * Redistributions in binary form must reproduce the above copyright
00016       notice, this list of conditions and the following disclaimer in the
00017       documentation and/or other materials provided with the distribution.
00018     * Neither the name of the <organization> nor the
00019       names of its contributors may be used to endorse or promote products
00020       derived from this software without specific prior written permission.
00021 
00022 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00023 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00024 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00025 DISCLAIMED. IN NO EVENT SHALL ETH-ASL BE LIABLE FOR ANY
00026 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00027 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00029 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00030 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00031 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00032 
00033 */
00034 
00035 #include "PointMatcher.h"
00036 #include "PointMatcherPrivate.h"
00037 
00038 #include "LoggerImpl.h"
00039 #include "TransformationsImpl.h"
00040 #include "DataPointsFiltersImpl.h"
00041 #include "MatchersImpl.h"
00042 #include "OutlierFiltersImpl.h"
00043 #include "ErrorMinimizersImpl.h"
00044 #include "TransformationCheckersImpl.h"
00045 #include "InspectorsImpl.h"
00046 
00047 #include <cassert>
00048 #include <iostream>
00049 #include <limits>
00050 
00051 using namespace std;
00052 using namespace PointMatcherSupport;
00053 
00055 InvalidElement::InvalidElement(const std::string& reason):
00056     runtime_error(reason)
00057 {}
00058 
00060 template<typename T>
00061 PointMatcher<T>::PointMatcher()
00062 {
00063     ADD_TO_REGISTRAR_NO_PARAM(Transformation, RigidTransformation, typename TransformationsImpl<T>::RigidTransformation)
00064     
00065     ADD_TO_REGISTRAR_NO_PARAM(DataPointsFilter, IdentityDataPointsFilter, typename DataPointsFiltersImpl<T>::IdentityDataPointsFilter)
00066     ADD_TO_REGISTRAR_NO_PARAM(DataPointsFilter, RemoveNaNDataPointsFilter, typename DataPointsFiltersImpl<T>::RemoveNaNDataPointsFilter)
00067     ADD_TO_REGISTRAR(DataPointsFilter, MaxDistDataPointsFilter, typename DataPointsFiltersImpl<T>::MaxDistDataPointsFilter)
00068     ADD_TO_REGISTRAR(DataPointsFilter, MinDistDataPointsFilter, typename DataPointsFiltersImpl<T>::MinDistDataPointsFilter)
00069     ADD_TO_REGISTRAR(DataPointsFilter, BoundingBoxDataPointsFilter, typename DataPointsFiltersImpl<T>::BoundingBoxDataPointsFilter)
00070     ADD_TO_REGISTRAR(DataPointsFilter, MaxQuantileOnAxisDataPointsFilter, typename DataPointsFiltersImpl<T>::MaxQuantileOnAxisDataPointsFilter)
00071     ADD_TO_REGISTRAR(DataPointsFilter, MaxDensityDataPointsFilter, typename DataPointsFiltersImpl<T>::MaxDensityDataPointsFilter)
00072     ADD_TO_REGISTRAR(DataPointsFilter, SurfaceNormalDataPointsFilter, typename DataPointsFiltersImpl<T>::SurfaceNormalDataPointsFilter)
00073     ADD_TO_REGISTRAR(DataPointsFilter, SamplingSurfaceNormalDataPointsFilter, typename DataPointsFiltersImpl<T>::SamplingSurfaceNormalDataPointsFilter)
00074     ADD_TO_REGISTRAR(DataPointsFilter, OrientNormalsDataPointsFilter, typename DataPointsFiltersImpl<T>::OrientNormalsDataPointsFilter)
00075     ADD_TO_REGISTRAR(DataPointsFilter, RandomSamplingDataPointsFilter, typename DataPointsFiltersImpl<T>::RandomSamplingDataPointsFilter)
00076     ADD_TO_REGISTRAR(DataPointsFilter, MaxPointCountDataPointsFilter, typename DataPointsFiltersImpl<T>::MaxPointCountDataPointsFilter)
00077     ADD_TO_REGISTRAR(DataPointsFilter, FixStepSamplingDataPointsFilter, typename DataPointsFiltersImpl<T>::FixStepSamplingDataPointsFilter)
00078     ADD_TO_REGISTRAR(DataPointsFilter, ShadowDataPointsFilter, typename DataPointsFiltersImpl<T>::ShadowDataPointsFilter)
00079     ADD_TO_REGISTRAR(DataPointsFilter, SimpleSensorNoiseDataPointsFilter, typename DataPointsFiltersImpl<T>::SimpleSensorNoiseDataPointsFilter)
00080     ADD_TO_REGISTRAR(DataPointsFilter, ObservationDirectionDataPointsFilter, typename DataPointsFiltersImpl<T>::ObservationDirectionDataPointsFilter)
00081     
00082     ADD_TO_REGISTRAR_NO_PARAM(Matcher, NullMatcher, typename MatchersImpl<T>::NullMatcher)
00083     ADD_TO_REGISTRAR(Matcher, KDTreeMatcher, typename MatchersImpl<T>::KDTreeMatcher)
00084     ADD_TO_REGISTRAR(Matcher, KDTreeVarDistMatcher, typename MatchersImpl<T>::KDTreeVarDistMatcher)
00085     
00086     ADD_TO_REGISTRAR_NO_PARAM(OutlierFilter, NullOutlierFilter, typename OutlierFiltersImpl<T>::NullOutlierFilter)
00087     ADD_TO_REGISTRAR(OutlierFilter, MaxDistOutlierFilter, typename OutlierFiltersImpl<T>::MaxDistOutlierFilter)
00088     ADD_TO_REGISTRAR(OutlierFilter, MinDistOutlierFilter, typename OutlierFiltersImpl<T>::MinDistOutlierFilter)
00089     ADD_TO_REGISTRAR(OutlierFilter, MedianDistOutlierFilter, typename OutlierFiltersImpl<T>::MedianDistOutlierFilter)
00090     ADD_TO_REGISTRAR(OutlierFilter, TrimmedDistOutlierFilter, typename OutlierFiltersImpl<T>::TrimmedDistOutlierFilter)
00091     ADD_TO_REGISTRAR(OutlierFilter, VarTrimmedDistOutlierFilter, typename OutlierFiltersImpl<T>::VarTrimmedDistOutlierFilter)
00092     ADD_TO_REGISTRAR(OutlierFilter, SurfaceNormalOutlierFilter, typename OutlierFiltersImpl<T>::SurfaceNormalOutlierFilter)
00093     
00094     ADD_TO_REGISTRAR_NO_PARAM(ErrorMinimizer, IdentityErrorMinimizer, typename ErrorMinimizersImpl<T>::IdentityErrorMinimizer)
00095     ADD_TO_REGISTRAR_NO_PARAM(ErrorMinimizer, PointToPointErrorMinimizer, typename ErrorMinimizersImpl<T>::PointToPointErrorMinimizer)
00096     ADD_TO_REGISTRAR(ErrorMinimizer, PointToPlaneErrorMinimizer, typename ErrorMinimizersImpl<T>::PointToPlaneErrorMinimizer)
00097     
00098     ADD_TO_REGISTRAR(TransformationChecker, CounterTransformationChecker, typename TransformationCheckersImpl<T>::CounterTransformationChecker)
00099     ADD_TO_REGISTRAR(TransformationChecker, DifferentialTransformationChecker, typename TransformationCheckersImpl<T>::DifferentialTransformationChecker)
00100     ADD_TO_REGISTRAR(TransformationChecker, BoundTransformationChecker, typename TransformationCheckersImpl<T>::BoundTransformationChecker)
00101     
00102     ADD_TO_REGISTRAR_NO_PARAM(Inspector, NullInspector, typename InspectorsImpl<T>::NullInspector)
00103     ADD_TO_REGISTRAR(Inspector, PerformanceInspector, typename InspectorsImpl<T>::PerformanceInspector)
00104     ADD_TO_REGISTRAR(Inspector, VTKFileInspector, typename InspectorsImpl<T>::VTKFileInspector)
00105     
00106     ADD_TO_REGISTRAR_NO_PARAM(Logger, NullLogger, NullLogger)
00107     ADD_TO_REGISTRAR(Logger, FileLogger, FileLogger)
00108 }
00109 
00110 // static instances plus wrapper function to get them from templatized static method in PointMatcher
00111 
00112 PointMatcher<float> _PointMatcherFloat;
00113 PointMatcher<double> _PointMatcherDouble;
00114 
00115 template<typename T>
00116 const PointMatcher<T>& _getPM();
00117 
00118 template<>
00119 const PointMatcher<float>& _getPM<float>() { return _PointMatcherFloat; }
00120 template<>
00121 const PointMatcher<double>& _getPM<double>() { return _PointMatcherDouble; }
00122 
00124 template<typename T>
00125 const PointMatcher<T>& PointMatcher<T>::get()
00126 {
00127     return _getPM<T>();
00128 }
00129 
00130 template const PointMatcher<float>& PointMatcher<float>::get();
00131 template const PointMatcher<double>& PointMatcher<double>::get();
00132 


libpointmatcher
Author(s): Stéphane Magnenat, François Pomerleau
autogenerated on Thu Jan 2 2014 11:16:06