TransformationChecker.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 "PointMatcher.h"
00037 #include "PointMatcherPrivate.h"
00038 
00040 template<typename T>
00041 PointMatcher<T>::TransformationChecker::TransformationChecker()
00042 {} 
00043 
00045 template<typename T>
00046 PointMatcher<T>::TransformationChecker::TransformationChecker(const std::string& className, const ParametersDoc paramsDoc, const Parameters& params):
00047         Parametrizable(className,paramsDoc,params)
00048 {}
00049 
00051 template<typename T>
00052 PointMatcher<T>::TransformationChecker::~TransformationChecker()
00053 {} 
00054 
00056 template<typename T>
00057 const typename PointMatcher<T>::Vector& PointMatcher<T>::TransformationChecker::getLimits() const
00058 {
00059         return limits;
00060 }
00061 
00063 template<typename T>
00064 const typename PointMatcher<T>::Vector& PointMatcher<T>::TransformationChecker::getConditionVariables() const
00065 {
00066         return conditionVariables;
00067 }
00068 
00070 template<typename T>
00071 const typename PointMatcher<T>::TransformationChecker::StringVector& PointMatcher<T>::TransformationChecker::getLimitNames() const
00072 {
00073         return limitNames;
00074 }
00075 
00077 template<typename T>
00078 const typename PointMatcher<T>::TransformationChecker::StringVector& PointMatcher<T>::TransformationChecker::getConditionVariableNames() const
00079 {
00080         return conditionVariableNames;
00081 }
00082 
00084 template<typename T>
00085 typename PointMatcher<T>::Vector PointMatcher<T>::TransformationChecker::matrixToAngles(const TransformationParameters& parameters)
00086 {
00087         Vector angles;
00088         if(parameters.rows() == 4)
00089         {
00090                 angles = Vector::Zero(3);
00091 
00092                 angles(0) = atan2(parameters(2,0), parameters(2,1));
00093                 angles(1) = acos(parameters(2,2));
00094                 angles(2) = -atan2(parameters(0,2), parameters(1,2));
00095         }
00096         else
00097         {
00098                 angles = Vector::Zero(1);
00099 
00100                 angles(0) = acos(parameters(0,0));
00101         }
00102 
00103         return angles;
00104 }
00105 
00106 template struct PointMatcher<float>::TransformationChecker;
00107 template struct PointMatcher<double>::TransformationChecker;
00108 
00109 
00111 template<typename T>
00112 void PointMatcher<T>::TransformationCheckers::init(const TransformationParameters& parameters, bool& iterate)
00113 {
00114         for (TransformationCheckersIt it = this->begin(); it != this->end(); ++it)
00115                 (*it)->init(parameters, iterate);
00116 }
00117 
00119 template<typename T>
00120 void PointMatcher<T>::TransformationCheckers::check(const TransformationParameters& parameters, bool& iterate)
00121 {
00122         for (TransformationCheckersIt it = this->begin(); it != this->end(); ++it)
00123                 (*it)->check(parameters, iterate);
00124 }
00125 
00126 template struct PointMatcher<float>::TransformationCheckers;
00127 template struct PointMatcher<double>::TransformationCheckers;


libpointmatcher
Author(s):
autogenerated on Mon Sep 14 2015 02:59:06