solvepnp.h
Go to the documentation of this file.
00001 /*M///////////////////////////////////////////////////////////////////////////////////////
00002 //
00003 //  IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
00004 //
00005 //  By downloading, copying, installing or using the software you agree to this license.
00006 //  If you do not agree to this license, do not download, install,
00007 //  copy or use the software.
00008 //
00009 //
00010 //                          License Agreement
00011 //                For Open Source Computer Vision Library
00012 //
00013 // Copyright (C) 2000-2008, Intel Corporation, all rights reserved.
00014 // Copyright (C) 2009, Willow Garage Inc., all rights reserved.
00015 // Copyright (C) 2013, OpenCV Foundation, all rights reserved.
00016 // Third party copyrights are property of their respective owners.
00017 //
00018 // Redistribution and use in source and binary forms, with or without modification,
00019 // are permitted provided that the following conditions are met:
00020 //
00021 //   * Redistribution's of source code must retain the above copyright notice,
00022 //     this list of conditions and the following disclaimer.
00023 //
00024 //   * Redistribution's in binary form must reproduce the above copyright notice,
00025 //     this list of conditions and the following disclaimer in the documentation
00026 //     and/or other materials provided with the distribution.
00027 //
00028 //   * The name of the copyright holders may not be used to endorse or promote products
00029 //     derived from this software without specific prior written permission.
00030 //
00031 // This software is provided by the copyright holders and contributors "as is" and
00032 // any express or implied warranties, including, but not limited to, the implied
00033 // warranties of merchantability and fitness for a particular purpose are disclaimed.
00034 // In no event shall the Intel Corporation or contributors be liable for any direct,
00035 // indirect, incidental, special, exemplary, or consequential damages
00036 // (including, but not limited to, procurement of substitute goods or services;
00037 // loss of use, data, or profits; or business interruption) however caused
00038 // and on any theory of liability, whether in contract, strict liability,
00039 // or tort (including negligence or otherwise) arising in any way out of
00040 // the use of this software, even if advised of the possibility of such damage.
00041 //
00042 //M*/
00043 
00044 #ifndef RTABMAP_CORELIB_SRC_OPENCV_SOLVEPNP_H_
00045 #define RTABMAP_CORELIB_SRC_OPENCV_SOLVEPNP_H_
00046 
00047 #include <opencv2/core/core.hpp>
00048 #include <opencv2/calib3d/calib3d.hpp>
00049 
00050 namespace cv3 {
00051 
00052 
00053 
00054 
00090 bool solvePnPRansac( cv::InputArray objectPoints, cv::InputArray imagePoints,
00091                                         cv::InputArray cameraMatrix, cv::InputArray distCoeffs,
00092                                         cv::OutputArray rvec, cv::OutputArray tvec,
00093                                         bool useExtrinsicGuess = false, int iterationsCount = 100,
00094                                         float reprojectionError = 8.0, double confidence = 0.99,
00095                                         cv::OutputArray inliers = cv::noArray(), int flags = CV_ITERATIVE );
00096 
00097 int RANSACUpdateNumIters( double p, double ep, int modelPoints, int maxIters );
00098 
00099 class LMSolver : public cv::Algorithm
00100 {
00101 public:
00102     class Callback
00103     {
00104     public:
00105         virtual ~Callback() {}
00106         virtual bool compute(cv::InputArray param, cv::OutputArray err, cv::OutputArray J) const = 0;
00107     };
00108 
00109     virtual void setCallback(const cv::Ptr<LMSolver::Callback>& cb) = 0;
00110     virtual int run(cv::InputOutputArray _param0) const = 0;
00111 };
00112 
00113 cv::Ptr<LMSolver> createLMSolver(const cv::Ptr<LMSolver::Callback>& cb, int maxIters);
00114 
00115 class PointSetRegistrator : public cv::Algorithm
00116 {
00117 public:
00118     class Callback
00119     {
00120     public:
00121         virtual ~Callback() {}
00122         virtual int runKernel(cv::InputArray m1, cv::InputArray m2, cv::OutputArray model) const = 0;
00123         virtual void computeError(cv::InputArray m1, cv::InputArray m2, cv::InputArray model, cv::OutputArray err) const = 0;
00124         virtual bool checkSubset(cv::InputArray, cv::InputArray, int) const { return true; }
00125     };
00126 
00127     virtual void setCallback(const cv::Ptr<PointSetRegistrator::Callback>& cb) = 0;
00128     virtual bool run(cv::InputArray m1, cv::InputArray m2, cv::OutputArray model, cv::OutputArray mask) const = 0;
00129 };
00130 
00131 cv::Ptr<PointSetRegistrator> createRANSACPointSetRegistrator(const cv::Ptr<PointSetRegistrator::Callback>& cb,
00132                                                                     int modelPoints, double threshold,
00133                                                                     double confidence=0.99, int maxIters=1000 );
00134 
00135 cv::Ptr<PointSetRegistrator> createLMeDSPointSetRegistrator(const cv::Ptr<PointSetRegistrator::Callback>& cb,
00136                                                                    int modelPoints, double confidence=0.99, int maxIters=1000 );
00137 
00138 template<typename T> inline int compressElems( T* ptr, const uchar* mask, int mstep, int count )
00139 {
00140     int i, j;
00141     for( i = j = 0; i < count; i++ )
00142         if( mask[i*mstep] )
00143         {
00144             if( i > j )
00145                 ptr[j] = ptr[i];
00146             j++;
00147         }
00148     return j;
00149 }
00150 
00151 }
00152 
00153 #endif /* RTABMAP_CORELIB_SRC_OPENCV_SOLVEPNP_H_ */


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