Registration.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef REGISTRATION_H_
00029 #define REGISTRATION_H_
00030 
00031 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
00032 
00033 #include <rtabmap/core/Parameters.h>
00034 #include <rtabmap/core/Signature.h>
00035 #include <rtabmap/core/RegistrationInfo.h>
00036 
00037 namespace rtabmap {
00038 
00039 class RTABMAP_EXP Registration
00040 {
00041 public:
00042         enum Type {
00043                 kTypeUndef = -1,
00044                 kTypeVis = 0,
00045                 kTypeIcp = 1,
00046                 kTypeVisIcp = 2
00047         };
00048 
00049 public:
00050         static Registration * create(const ParametersMap & parameters);
00051         static Registration * create(Type & type, const ParametersMap & parameters = ParametersMap());
00052 
00053 public:
00054         virtual ~Registration();
00055         virtual void parseParameters(const ParametersMap & parameters);
00056 
00057         bool isImageRequired() const;
00058         bool isScanRequired() const;
00059         bool isUserDataRequired() const;
00060 
00061         int getMinVisualCorrespondences() const;
00062         float getMinGeometryCorrespondencesRatio() const;
00063 
00064         bool varianceFromInliersCount() const {return varianceFromInliersCount_;}
00065         bool force3DoF() const {return force3DoF_;}
00066 
00067         // take ownership!
00068         void setChildRegistration(Registration * child);
00069 
00070         Transform computeTransformation(
00071                         const Signature & from,
00072                         const Signature & to,
00073                         Transform guess = Transform::getIdentity(),
00074                         RegistrationInfo * info = 0) const;
00075         Transform computeTransformation(
00076                         const SensorData & from,
00077                         const SensorData & to,
00078                         Transform SensorData = Transform::getIdentity(),
00079                         RegistrationInfo * info = 0) const;
00080 
00081         Transform computeTransformationMod(
00082                         Signature & from,
00083                         Signature & to,
00084                         Transform guess = Transform::getIdentity(),
00085                         RegistrationInfo * info = 0) const;
00086 
00087 protected:
00088         // take ownership of child
00089         Registration(const ParametersMap & parameters = ParametersMap(), Registration * child = 0);
00090 
00091         // It is safe to modify the signatures in the implementation, if so, the
00092         // child registration will use these modifications.
00093         virtual Transform computeTransformationImpl(
00094                         Signature & from,
00095                         Signature & to,
00096                         Transform guess,
00097                         RegistrationInfo & info) const = 0;
00098 
00099         virtual bool isImageRequiredImpl() const {return false;}
00100         virtual bool isScanRequiredImpl() const {return false;}
00101         virtual bool isUserDataRequiredImpl() const {return false;}
00102         virtual int getMinVisualCorrespondencesImpl() const {return 0;}
00103         virtual float getMinGeometryCorrespondencesRatioImpl() const {return 0.0f;}
00104 
00105 private:
00106         bool varianceFromInliersCount_;
00107         bool force3DoF_;
00108         Registration * child_;
00109 
00110 };
00111 
00112 }
00113 
00114 #endif /* REGISTRATION_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:17