solvepnp.h
Go to the documentation of this file.
1 /*M///////////////////////////////////////////////////////////////////////////////////////
2 //
3 // IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
4 //
5 // By downloading, copying, installing or using the software you agree to this license.
6 // If you do not agree to this license, do not download, install,
7 // copy or use the software.
8 //
9 //
10 // License Agreement
11 // For Open Source Computer Vision Library
12 //
13 // Copyright (C) 2000-2008, Intel Corporation, all rights reserved.
14 // Copyright (C) 2009, Willow Garage Inc., all rights reserved.
15 // Copyright (C) 2013, OpenCV Foundation, all rights reserved.
16 // Third party copyrights are property of their respective owners.
17 //
18 // Redistribution and use in source and binary forms, with or without modification,
19 // are permitted provided that the following conditions are met:
20 //
21 // * Redistribution's of source code must retain the above copyright notice,
22 // this list of conditions and the following disclaimer.
23 //
24 // * Redistribution's in binary form must reproduce the above copyright notice,
25 // this list of conditions and the following disclaimer in the documentation
26 // and/or other materials provided with the distribution.
27 //
28 // * The name of the copyright holders may not be used to endorse or promote products
29 // derived from this software without specific prior written permission.
30 //
31 // This software is provided by the copyright holders and contributors "as is" and
32 // any express or implied warranties, including, but not limited to, the implied
33 // warranties of merchantability and fitness for a particular purpose are disclaimed.
34 // In no event shall the Intel Corporation or contributors be liable for any direct,
35 // indirect, incidental, special, exemplary, or consequential damages
36 // (including, but not limited to, procurement of substitute goods or services;
37 // loss of use, data, or profits; or business interruption) however caused
38 // and on any theory of liability, whether in contract, strict liability,
39 // or tort (including negligence or otherwise) arising in any way out of
40 // the use of this software, even if advised of the possibility of such damage.
41 //
42 //M*/
43 
44 #ifndef RTABMAP_CORELIB_SRC_OPENCV_SOLVEPNP_H_
45 #define RTABMAP_CORELIB_SRC_OPENCV_SOLVEPNP_H_
46 
47 #include <opencv2/core/core.hpp>
48 #include <opencv2/calib3d/calib3d.hpp>
49 #if CV_MAJOR_VERSION >= 3
50 #include <opencv2/calib3d/calib3d_c.h>
51 #endif
52 
53 namespace cv3 {
54 
55 
56 
57 
93 bool solvePnPRansac( cv::InputArray objectPoints, cv::InputArray imagePoints,
94  cv::InputArray cameraMatrix, cv::InputArray distCoeffs,
95  cv::OutputArray rvec, cv::OutputArray tvec,
96  bool useExtrinsicGuess = false, int iterationsCount = 100,
97  float reprojectionError = 8.0, double confidence = 0.99,
98  cv::OutputArray inliers = cv::noArray(), int flags = CV_ITERATIVE );
99 
100 int RANSACUpdateNumIters( double p, double ep, int modelPoints, int maxIters );
101 
102 class LMSolver : public cv::Algorithm
103 {
104 public:
105  class Callback
106  {
107  public:
108  virtual ~Callback() {}
109  virtual bool compute(cv::InputArray param, cv::OutputArray err, cv::OutputArray J) const = 0;
110  };
111 
112  virtual void setCallback(const cv::Ptr<LMSolver::Callback>& cb) = 0;
113  virtual int run(cv::InputOutputArray _param0) const = 0;
114 };
115 
116 cv::Ptr<LMSolver> createLMSolver(const cv::Ptr<LMSolver::Callback>& cb, int maxIters);
117 
118 class PointSetRegistrator : public cv::Algorithm
119 {
120 public:
121  class Callback
122  {
123  public:
124  virtual ~Callback() {}
125  virtual int runKernel(cv::InputArray m1, cv::InputArray m2, cv::OutputArray model) const = 0;
126  virtual void computeError(cv::InputArray m1, cv::InputArray m2, cv::InputArray model, cv::OutputArray err) const = 0;
127  virtual bool checkSubset(cv::InputArray, cv::InputArray, int) const { return true; }
128  };
129 
130  virtual void setCallback(const cv::Ptr<PointSetRegistrator::Callback>& cb) = 0;
131  virtual bool run(cv::InputArray m1, cv::InputArray m2, cv::OutputArray model, cv::OutputArray mask) const = 0;
132 };
133 
134 cv::Ptr<PointSetRegistrator> createRANSACPointSetRegistrator(const cv::Ptr<PointSetRegistrator::Callback>& cb,
135  int modelPoints, double threshold,
136  double confidence=0.99, int maxIters=1000 );
137 
138 cv::Ptr<PointSetRegistrator> createLMeDSPointSetRegistrator(const cv::Ptr<PointSetRegistrator::Callback>& cb,
139  int modelPoints, double confidence=0.99, int maxIters=1000 );
140 
141 template<typename T> inline int compressElems( T* ptr, const uchar* mask, int mstep, int count )
142 {
143  int i, j;
144  for( i = j = 0; i < count; i++ )
145  if( mask[i*mstep] )
146  {
147  if( i > j )
148  ptr[j] = ptr[i];
149  j++;
150  }
151  return j;
152 }
153 
154 }
155 
156 #endif /* RTABMAP_CORELIB_SRC_OPENCV_SOLVEPNP_H_ */
GLM_FUNC_DECL genIType mask(genIType const &count)
int RANSACUpdateNumIters(double p, double ep, int modelPoints, int maxIters)
Definition: solvepnp.cpp:216
Ptr< PointSetRegistrator > createRANSACPointSetRegistrator(const Ptr< PointSetRegistrator::Callback > &_cb, int _modelPoints, double _threshold, double _confidence, int _maxIters)
Definition: solvepnp.cpp:546
unsigned char uchar
Definition: matrix.h:41
bool solvePnPRansac(InputArray _opoints, InputArray _ipoints, InputArray _cameraMatrix, InputArray _distCoeffs, OutputArray _rvec, OutputArray _tvec, bool useExtrinsicGuess, int iterationsCount, float reprojectionError, double confidence, OutputArray _inliers, int flags)
Definition: solvepnp.cpp:112
cv::Ptr< LMSolver > createLMSolver(const cv::Ptr< LMSolver::Callback > &cb, int maxIters)
virtual bool compute(cv::InputArray param, cv::OutputArray err, cv::OutputArray J) const =0
virtual void setCallback(const cv::Ptr< LMSolver::Callback > &cb)=0
Definition: solvepnp.cpp:48
int compressElems(T *ptr, const uchar *mask, int mstep, int count)
Definition: solvepnp.h:141
virtual bool checkSubset(cv::InputArray, cv::InputArray, int) const
Definition: solvepnp.h:127
virtual int run(cv::InputOutputArray _param0) const =0
Ptr< PointSetRegistrator > createLMeDSPointSetRegistrator(const Ptr< PointSetRegistrator::Callback > &_cb, int _modelPoints, double _confidence, int _maxIters)
Definition: solvepnp.cpp:555


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:32