NifTK  16.4.1 - 0798f20
CMIC's Translational Medical Imaging Platform
mitkOpenCVMaths.h
Go to the documentation of this file.
1 /*=============================================================================
2 
3  NifTK: A software platform for medical image computing.
4 
5  Copyright (c) University College London (UCL). All rights reserved.
6 
7  This software is distributed WITHOUT ANY WARRANTY; without even
8  the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR
9  PURPOSE.
10 
11  See LICENSE.txt in the top level directory for details.
12 
13 =============================================================================*/
14 
15 #ifndef mitkOpenCVMaths_h
16 #define mitkOpenCVMaths_h
17 
18 #include "niftkOpenCVUtilsExports.h"
19 #include "mitkOpenCVPointTypes.h"
20 #include <cv.h>
21 #include <mitkPointSet.h>
22 #include <vtkMatrix4x4.h>
23 
28 namespace mitk {
29 
33 extern "C++" NIFTKOPENCVUTILS_EXPORT std::vector<cv::Point3d> SubtractPointFromPoints(const std::vector<cv::Point3d> listOfPoints, const cv::Point3d& point);
34 
35 
39 extern "C++" NIFTKOPENCVUTILS_EXPORT std::vector<cv::Point3d> PointSetToVector(const mitk::PointSet::Pointer& pointSet);
40 
41 
45 extern "C++" NIFTKOPENCVUTILS_EXPORT void MakeIdentity(cv::Matx44d& outputMatrix);
46 
47 
52 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Matx33d CalculateCrossCovarianceH(const std::vector<cv::Point3d>& q, const std::vector<cv::Point3d>& qPrime);
53 
54 
58 extern "C++" NIFTKOPENCVUTILS_EXPORT bool DoSVDPointBasedRegistration(const std::vector<cv::Point3d>& fixedPoints,
59  const std::vector<cv::Point3d>& movingPoints,
60  cv::Matx33d& H,
61  cv::Point3d &p,
62  cv::Point3d& pPrime,
63  cv::Matx44d& outputMatrix,
64  double &fiducialRegistrationError
65  );
66 
67 
71 extern "C++" NIFTKOPENCVUTILS_EXPORT double CalculateFiducialRegistrationError(const std::vector<cv::Point3d>& fixedPoints,
72  const std::vector<cv::Point3d>& movingPoints,
73  const cv::Matx44d& matrix
74  );
75 
76 
80 extern "C++" NIFTKOPENCVUTILS_EXPORT double CalculateFiducialRegistrationError(const mitk::PointSet::Pointer& fixedPointSet,
81  const mitk::PointSet::Pointer& movingPointSet,
82  vtkMatrix4x4& vtkMatrix
83  );
84 
85 
89 extern "C++" NIFTKOPENCVUTILS_EXPORT void ConstructAffineMatrix(const cv::Matx31d& translation, const cv::Matx33d& rotation, cv::Matx44d& matrix);
90 
91 
95 extern "C++" NIFTKOPENCVUTILS_EXPORT void CopyToVTK4x4Matrix(const cv::Matx44d& matrix, vtkMatrix4x4& vtkMatrix);
96 
97 
101 extern "C++" NIFTKOPENCVUTILS_EXPORT void CopyToOpenCVMatrix(const vtkMatrix4x4& matrix, cv::Matx44d& openCVMatrix);
102 
103 
107 extern "C++" NIFTKOPENCVUTILS_EXPORT void CopyToVTK4x4Matrix(const cv::Mat& input, vtkMatrix4x4& output);
108 
109 
113 extern "C++" NIFTKOPENCVUTILS_EXPORT void CopyToOpenCVMatrix(const vtkMatrix4x4& input, cv::Mat& output);
114 
115 
119 extern "C++" NIFTKOPENCVUTILS_EXPORT void CopyToOpenCVMatrix(const cv::Matx44d& matrix, cv::Mat& output);
120 
126 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Matx33d ConstructEulerRxMatrix(const double& rx);
127 
128 
134 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Matx33d ConstructEulerRyMatrix(const double& ry);
135 
136 
142 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Matx33d ConstructEulerRzMatrix(const double& rz);
143 
144 
152 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Matx33d ConstructEulerRotationMatrix(const double& rx, const double& ry, const double& rz);
153 
154 
162 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Matx13d ConvertEulerToRodrigues(
163  const double& rx,
164  const double& ry,
165  const double& rz
166  );
167 
168 
172 extern "C++" NIFTKOPENCVUTILS_EXPORT std::vector <cv::Point3d> operator*(const cv::Mat& M, const std::vector<cv::Point3d>& p);
173 
177 extern "C++" NIFTKOPENCVUTILS_EXPORT std::vector<cv::Point3d> operator*(const cv::Matx44d& M, const std::vector<cv::Point3d>& p);
178 
179 
183 extern "C++" NIFTKOPENCVUTILS_EXPORT std::vector < mitk::WorldPoint > operator*(const cv::Mat& M,
184  const std::vector< mitk::WorldPoint >& p);
185 
189 extern "C++" NIFTKOPENCVUTILS_EXPORT std::vector<mitk::WorldPoint> operator*(const cv::Matx44d& M, const std::vector<mitk::WorldPoint>& p);
190 
191 
195 extern "C++" NIFTKOPENCVUTILS_EXPORT mitk::WorldPoint operator*(const cv::Mat& M,
196  const mitk::WorldPoint & p);
197 
201 extern "C++" NIFTKOPENCVUTILS_EXPORT mitk::WorldPoint operator*(const cv::Matx44d& M, const mitk::WorldPoint& p);
202 
206 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Point3d operator*(const cv::Mat& M, const cv::Point3d& p);
207 
211 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Point3d operator*(const cv::Matx44d& M, const cv::Point3d& p);
212 
216 extern "C++" NIFTKOPENCVUTILS_EXPORT std::pair < cv::Point3d, cv::Point3d > TransformPointPair (const cv::Matx44d& M,
217  const std::pair < cv::Point3d, cv::Point3d>& p);
218 
222 extern "C++" NIFTKOPENCVUTILS_EXPORT bool NearlyEqual(const cv::Point2d& p1, const cv::Point2d& p2, const double& tolerance );
223 
227 extern "C++" NIFTKOPENCVUTILS_EXPORT bool NearlyEqual(const cv::Point3d& p1, const cv::Point3d& p2, const double& tolerance );
228 
232 extern "C++" NIFTKOPENCVUTILS_EXPORT bool ImageHeadersEqual(const cv::Mat& m1, const cv::Mat& m2);
233 
237 extern "C++" NIFTKOPENCVUTILS_EXPORT bool ImageDataEqual(const cv::Mat& m1, const cv::Mat& m2, const double& tolerance );
238 
239 
243 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Point2d operator/(const cv::Point2d& p, const int& n);
244 
245 
249 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Point2d operator*(const cv::Point2d& p1, const cv::Point2d& p2);
250 
251 
257 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Point2d FindIntersect(const cv::Vec4i& line1 , const cv::Vec4i& line2);
258 
265 extern "C++" NIFTKOPENCVUTILS_EXPORT std::vector <cv::Point2d> FindIntersects (const std::vector <cv::Vec4i>&,
266  const bool& RejectIfNotOnBothLines = false , const bool& RejectIfNotPerpendicular = false,
267  const double& angleTolerance = 45.0);
268 
273 extern "C++" NIFTKOPENCVUTILS_EXPORT bool PointInInterval (const cv::Point2d& point , const cv::Vec4i& interval);
274 
278 extern "C++" NIFTKOPENCVUTILS_EXPORT double AngleBetweenLines(cv::Vec4i , cv::Vec4i);
279 
283 extern "C++" NIFTKOPENCVUTILS_EXPORT bool CheckIfLinesArePerpendicular(cv::Vec4i , cv::Vec4i, double toleranceInDegrees);
284 
288 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Point2d GetCentroid(const std::vector<cv::Point2d>& points, bool RefineForOutliers = false, cv::Point2d* StandardDeviation = NULL);
289 
290 
294 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Point3d GetCentroid(const std::vector<cv::Point3d>& points, bool RefineForOutliers = false, cv::Point3d* StandardDeviation = NULL);
295 
296 
307 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Matx44d ConstructRigidTransformationMatrix(
308  const double& rx,
309  const double& ry,
310  const double& rz,
311  const double& tx,
312  const double& ty,
313  const double& tz
314  );
315 
316 
327 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Matx44d ConstructRodriguesTransformationMatrix(
328  const double& r1,
329  const double& r2,
330  const double& r3,
331  const double& tx,
332  const double& ty,
333  const double& tz
334  );
335 
336 
344 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Matx44d ConstructScalingTransformation(const double& sx, const double& sy, const double& sz = 1);
345 
346 
360 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Matx44d ConstructSimilarityTransformationMatrix(
361  const double& rx,
362  const double& ry,
363  const double& rz,
364  const double& tx,
365  const double& ty,
366  const double& tz,
367  const double& sx,
368  const double& sy,
369  const double& sz
370  );
371 
372 
377 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Point3d FindMinimumValues ( std::vector < cv::Point3d > inputValues, cv::Point3i * indexes = NULL );
378 
379 
391 extern "C++" NIFTKOPENCVUTILS_EXPORT mitk::ProjectedPointPair MeanError (
392  std::vector < mitk::ProjectedPointPairsWithTimingError > measured ,
393  std::vector < mitk::ProjectedPointPairsWithTimingError > actual,
394  mitk::ProjectedPointPair * StandardDeviations = NULL , int index = -1,
395  long long allowableTimingError = 30e6, bool duplicateLines = true );
396 
397 
409 extern "C++" NIFTKOPENCVUTILS_EXPORT std::pair <double,double> RMSError
410  (std::vector < mitk::ProjectedPointPairsWithTimingError > measured ,
411  std::vector < mitk::ProjectedPointPairsWithTimingError > actual, int index = -1 ,
412  cv::Point2d outlierSD = cv::Point2d (2.0,2.0) , long long allowableTimingError = 30e6,
413  bool duplicateLines = true);
414 
415 
420 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Mat PerturbTransform (
421  const cv::Mat transformIn,
422  const double tx, const double ty, const double tz,
423  const double rx, const double ry, const double rz );
424 
429 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Point2d FindNearestPoint ( const cv::Point2d& point,
430  const std::vector < cv::Point2d >& matchingPonints ,
431  double* minRatio = NULL , unsigned int * index = NULL );
432 
437 extern "C++" NIFTKOPENCVUTILS_EXPORT mitk::PickedObject FindNearestPickedObject ( const mitk::PickedObject& point,
438  const std::vector < mitk::PickedObject >& matchingPoints ,
439  double* minRatio = NULL );
440 
444 extern "C++" NIFTKOPENCVUTILS_EXPORT bool DistanceCompare ( const cv::Point2d& p1,
445  const cv::Point2d& p2 );
446 
451 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Mat Tracker2ToTracker1Rotation (
452  const std::vector<cv::Mat>& Tracker1ToWorld1, const std::vector<cv::Mat>& World2ToTracker2,
453  double& Residual);
454 
455 
460 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Mat Tracker2ToTracker1Translation (
461  const std::vector<cv::Mat>& Tracker1ToWorld1, const std::vector<cv::Mat>& World2ToTracker2,
462  double& Residual, const cv::Mat & rcg);
463 
464 
469 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Mat Tracker2ToTracker1RotationAndTranslation (
470  const std::vector<cv::Mat>& Tracker1ToWorld1, const std::vector<cv::Mat>& World2ToTracker2,
471  std::vector<double>& Residuals, cv::Mat* World2ToWorld1 = NULL );
472 
473 
478 extern "C++" NIFTKOPENCVUTILS_EXPORT std::vector<cv::Mat> FlipMatrices (const std::vector<cv::Mat> matrices);
479 
480 
484 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Mat AverageMatrices(const std::vector<cv::Mat>& matrices);
485 
486 
490 extern "C++" NIFTKOPENCVUTILS_EXPORT std::vector<int> SortMatricesByDistance (const std::vector<cv::Mat> matrices);
491 
492 
496 extern "C++" NIFTKOPENCVUTILS_EXPORT std::vector<int> SortMatricesByAngle (const std::vector<cv::Mat> matrices);
497 
498 
502 extern "C++" NIFTKOPENCVUTILS_EXPORT double AngleBetweenMatrices(cv::Mat Mat1 , cv::Mat Mat2);
503 
504 
508 extern "C++" NIFTKOPENCVUTILS_EXPORT double DistanceBetweenMatrices(cv::Mat Mat1 , cv::Mat Mat2);
509 
510 
514 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Mat DirectionCosineToQuaternion(cv::Mat dc_Matrix);
515 
516 
521 extern "C++" NIFTKOPENCVUTILS_EXPORT void InvertRigid4x4Matrix(const CvMat& input, CvMat& output);
522 
523 
527 extern "C++" NIFTKOPENCVUTILS_EXPORT void InvertRigid4x4Matrix(const cv::Matx44d& input, cv::Matx44d& output);
528 
529 
533 extern "C++" NIFTKOPENCVUTILS_EXPORT void InvertRigid4x4Matrix(const cv::Mat& input, cv::Mat& output);
534 
535 
541 extern "C++" NIFTKOPENCVUTILS_EXPORT void InterpolateTransformationMatrix(const cv::Mat& before, const cv::Mat& after, const double& proportion, cv::Mat& output);
542 
543 
547 extern "C++" NIFTKOPENCVUTILS_EXPORT void InterpolateTransformationMatrix(const cv::Matx44d& before, const cv::Matx44d& after, const double& proportion, cv::Matx44d& output);
548 
552 extern "C++" NIFTKOPENCVUTILS_EXPORT std::string MatrixType(const cv::Mat& matrix);
553 
557 extern "C++" NIFTKOPENCVUTILS_EXPORT bool IsNaN(const cv::Point2d&);
558 
562 extern "C++" NIFTKOPENCVUTILS_EXPORT bool IsNaN(const cv::Point3d&);
563 
567 extern "C++" NIFTKOPENCVUTILS_EXPORT bool IsNotNaNorInf(const cv::Point2d&);
568 
572 extern "C++" NIFTKOPENCVUTILS_EXPORT bool IsNotNaNorInf(const cv::Point3d&);
573 
579 extern "C++" NIFTKOPENCVUTILS_EXPORT double DistanceToLine ( const std::pair<cv::Point3d, cv::Point3d>& line, const cv::Point3d& point);
580 
587 extern "C++" NIFTKOPENCVUTILS_EXPORT double DistanceBetweenTwoPoints ( const cv::Point3d& p1 , const cv::Point3d& p2, cv::Point3d* delta = NULL );
588 
596 extern "C++" NIFTKOPENCVUTILS_EXPORT double DistanceBetweenTwoSplines ( const std::vector <cv::Point3d>& s0,
597  const std::vector <cv::Point3d>& s1, unsigned int splineOrder , cv::Point3d* delta = NULL );
598 
605 extern "C++" NIFTKOPENCVUTILS_EXPORT double DistanceToLineSegment ( const std::pair<cv::Point3d, cv::Point3d>& line, const cv::Point3d& point, cv::Point3d* delta = NULL);
606 
614 extern "C++" NIFTKOPENCVUTILS_EXPORT double DistanceBetweenLines ( const cv::Point3d& P0, const cv::Point3d& u,
615  const cv::Point3d& Q0, const cv::Point3d& v , cv::Point3d& midpoint );
616 
624 extern "C++" NIFTKOPENCVUTILS_EXPORT double DistanceBetweenLineAndSegment ( const cv::Point3d& P0, const cv::Point3d& u,
625  const cv::Point3d& x0, const cv::Point3d& x1 , cv::Point3d& closestPointOnSecondLine );
626 
627 
633 extern "C++" NIFTKOPENCVUTILS_EXPORT std::pair < cv::Point3d , cv::Point3d > TwoPointsToPLambda ( const std::pair < cv::Point3d , cv::Point3d >& twoPointLine );
634 
639 extern "C++" NIFTKOPENCVUTILS_EXPORT cv::Point3d CrossProduct ( const cv::Point3d& p1, const cv::Point3d& p2);
640 
645 extern "C++" NIFTKOPENCVUTILS_EXPORT double DotProduct ( const cv::Point3d& p1, const cv::Point3d& p2);
646 
651 extern "C++" NIFTKOPENCVUTILS_EXPORT double Norm ( const cv::Point3d& p1);
652 
656 extern "C++" NIFTKOPENCVUTILS_EXPORT unsigned int RemoveOutliers ( std::vector <cv::Point3d>& points,
657  const double& xLow, const double& xHigh,
658  const double& yLow, const double& yHigh,
659  const double& zLow, const double& zHigh);
660 
664 extern "C++" NIFTKOPENCVUTILS_EXPORT unsigned int RemoveOutliers ( std::vector <std::pair < cv::Point3d, double > >& points,
665  const double& xLow, const double& xHigh,
666  const double& yLow, const double& yHigh,
667  const double& zLow, const double& zHigh);
668 
672 extern "C++" NIFTKOPENCVUTILS_EXPORT void ExtractRigidBodyParameters(const vtkMatrix4x4& matrix, mitk::Point3D& outputRodriguesRotationParameters, mitk::Point3D& outputTranslationParameters);
673 
674 } // end namespace
675 
676 #endif
677 
678 
679 
double AngleBetweenLines(cv::Vec4i line1, cv::Vec4i line2)
Definition: mitkOpenCVMaths.cxx:686
bool IsNaN(const cv::Point2d &point)
check if point has a NaN value
Definition: mitkOpenCVMaths.cxx:2270
double Norm(const cv::Point3d &p1)
Calculates the norm product of a vectors (cv::Point3D)
Definition: mitkOpenCVMaths.cxx:2621
bool PointInInterval(const cv::Point2d &point, const cv::Vec4i &interval)
Definition: mitkOpenCVMaths.cxx:658
std::vector< mitk::WorldPoint > operator*(const cv::Mat &M, const std::vector< mitk::WorldPoint > &p)
multiplies a set of points and corresponding scalar values by a 4x4 transformation matrix ...
Definition: mitkOpenCVMaths.cxx:354
cv::Matx13d ConvertEulerToRodrigues(const double &rx, const double &ry, const double &rz)
Converts Euler angles in radians to the Rodrigues rotation vector (axis-angle convention) mentioned i...
Definition: mitkOpenCVMaths.cxx:1003
bool ImageDataEqual(const cv::Mat &m1, const cv::Mat &m2, const double &tolerance)
Tests whether two cv::Mat have the same data.
Definition: mitkOpenCVMaths.cxx:522
bool DistanceCompare(const cv::Point2d &p1, const cv::Point2d &p2)
Compare two cv point based on their distance from 0,0.
Definition: mitkOpenCVMaths.cxx:1486
bool ImageHeadersEqual(const cv::Mat &m1, const cv::Mat &m2)
Tests whether two cv::Mat have the same header info (dimension and data type),.
Definition: mitkOpenCVMaths.cxx:506
Definition: mitkOpenCVPointTypes.h:110
cv::Mat Tracker2ToTracker1RotationAndTranslation(const std::vector< cv::Mat > &Tracker1ToWorld1, const std::vector< cv::Mat > &World2ToTracker2, std::vector< double > &Residuals, cv::Mat *World2ToWorld1)
works out the rigid rotation and translation correspondence between two sets of corresponding rigid b...
Definition: mitkOpenCVMaths.cxx:1660
cv::Matx33d ConstructEulerRxMatrix(const double &rx)
Generates a rotation about X-axis, given a Euler angle in radians.
Definition: mitkOpenCVMaths.cxx:932
cv::Point2d GetCentroid(const std::vector< cv::Point2d > &points, bool RefineForOutliers, cv::Point2d *StandardDeviation)
Calculates the centroid of a vector of points.
Definition: mitkOpenCVMaths.cxx:732
void InterpolateTransformationMatrix(const cv::Mat &before, const cv::Mat &after, const double &proportion, cv::Mat &output)
Interpolates between two matrices.
Definition: mitkOpenCVMaths.cxx:2148
cv::Mat Tracker2ToTracker1Rotation(const std::vector< cv::Mat > &Tracker1ToWorld1, const std::vector< cv::Mat > &World2ToTracker2, double &Residual)
works out the rigid rotation correspondence between two sets of corresponding rigid body transforms ...
Definition: mitkOpenCVMaths.cxx:1494
std::vector< cv::Point3d > PointSetToVector(const mitk::PointSet::Pointer &pointSet)
Converts mitk::PointSet to vector of cv::Point3d, but you lose the point ID contained within the mitk...
Definition: mitkOpenCVMaths.cxx:47
double DistanceBetweenMatrices(cv::Mat Mat1, cv::Mat Mat2)
Returns the distance between two 4x4 matrices.
Definition: mitkOpenCVMaths.cxx:2020
cv::Mat AverageMatrices(const std::vector< cv::Mat > &Matrices)
find the average of a vector of 4x4 matrices
Definition: mitkOpenCVMaths.cxx:1735
bool NearlyEqual(const cv::Point2d &p1, const cv::Point2d &p2, const double &tolerance)
Tests equality of 2 2d points. The openCV == operator struggles on floating points,.
Definition: mitkOpenCVMaths.cxx:480
GLenum GLenum GLenum input
Definition: glew.h:12016
bool IsNotNaNorInf(const cv::Point2d &point)
check if 2D point has a NaN or inf value
Definition: mitkOpenCVMaths.cxx:2297
cv::Matx44d ConstructScalingTransformation(const double &sx, const double &sy, const double &sz)
Constructs a scaling matrix from sx, sy, sz where the scale factors simply appear on the diagonal...
Definition: mitkOpenCVMaths.cxx:1085
cv::Matx44d ConstructSimilarityTransformationMatrix(const double &rx, const double &ry, const double &rz, const double &tx, const double &ty, const double &tz, const double &sx, const double &sy, const double &sz)
Constructs an affine transformation, without skew using the specified parameters, where rotations are...
Definition: mitkOpenCVMaths.cxx:1099
cv::Point3d FindMinimumValues(std::vector< cv::Point3d > inputValues, cv::Point3i *indexes)
Takes a point vector and finds the minimum value in each dimension. Returns the minimum values...
Definition: mitkOpenCVMaths.cxx:1124
cv::Mat DirectionCosineToQuaternion(cv::Mat dc_Matrix)
Converts a 3x3 rotation matrix to a quaternion.
Definition: mitkOpenCVMaths.cxx:2039
Definition: ReceptorMemberCommandTest.cxx:25
cv::Matx33d CalculateCrossCovarianceH(const std::vector< cv::Point3d > &q, const std::vector< cv::Point3d > &qPrime)
Calculates 1/N Sum (q_i * qPrime_i^t) where q_i and qPrime_i are column vectors, so the product is a ...
Definition: mitkOpenCVMaths.cxx:84
void ConstructAffineMatrix(const cv::Matx31d &translation, const cv::Matx33d &rotation, cv::Matx44d &matrix)
Simply copies the translation vector and rotation matrix into the 4x4 matrix.
Definition: mitkOpenCVMaths.cxx:244
cv::Matx33d ConstructEulerRzMatrix(const double &rz)
Generates a rotation about Z-axis, given a Euler angle in radians.
Definition: mitkOpenCVMaths.cxx:970
void MakeIdentity(cv::Matx44d &outputMatrix)
Haven't found a direct method to do this yet.
Definition: mitkOpenCVMaths.cxx:72
std::vector< cv::Point2d > FindIntersects(const std::vector< cv::Vec4i > &lines, const bool &rejectIfPointNotOnBothLines, const bool &rejectIfNotPerpendicular, const double &angleTolerance)
Definition: mitkOpenCVMaths.cxx:700
std::vector< cv::Mat > FlipMatrices(const std::vector< cv::Mat > Matrices)
Flips the matrices in the vector from left handed coordinate system to right handed and vice versa...
Definition: mitkOpenCVMaths.cxx:1815
double DistanceBetweenLineAndSegment(const cv::Point3d &P0, const cv::Point3d &u, const cv::Point3d &x0, const cv::Point3d &x1, cv::Point3d &closestPointOnSecondLine)
calculates the shortest distance between a line and a segment the point must lie on the segment ...
Definition: mitkOpenCVMaths.cxx:2503
bool DoSVDPointBasedRegistration(const std::vector< cv::Point3d > &fixedPoints, const std::vector< cv::Point3d > &movingPoints, cv::Matx33d &H, cv::Point3d &p, cv::Point3d &pPrime, cv::Matx44d &outputMatrix, double &fiducialRegistrationError)
Helper method to do the main SVD bit of the point based registration, and handle the degenerate condi...
Definition: mitkOpenCVMaths.cxx:106
double DistanceToLineSegment(const std::pair< cv::Point3d, cv::Point3d > &line, const cv::Point3d &x0, cv::Point3d *delta)
calculates the distance between a line segment and a point
Definition: mitkOpenCVMaths.cxx:2409
std::vector< int > SortMatricesByAngle(const std::vector< cv::Mat > Matrices)
Sorts the matrices based on the rotations, and returns the order.
Definition: mitkOpenCVMaths.cxx:1931
void ExtractRigidBodyParameters(const vtkMatrix4x4 &matrix, mitk::Point3D &outputRodriguesRotationParameters, mitk::Point3D &outputTranslationParameters)
Decomposes a rigid body matrix into Rodrigues Rotations and Translations.
Definition: mitkOpenCVMaths.cxx:2687
GLdouble GLdouble GLdouble GLdouble q
Definition: glew.h:1398
cv::Mat PerturbTransform(const cv::Mat transformIn, const double tx, const double ty, const double tz, const double rx, const double ry, const double rz)
perturbs a 4x4 matrix with a 6 dof rigid transform. The transform is defined by three translations an...
Definition: mitkOpenCVMaths.cxx:1382
Definition: mitkOpenCVPointTypes.h:172
double AngleBetweenMatrices(cv::Mat Mat1, cv::Mat Mat2)
Returns the angular distance between two rotation matrices.
Definition: mitkOpenCVMaths.cxx:2006
void CopyToVTK4x4Matrix(const cv::Matx44d &matrix, vtkMatrix4x4 &vtkMatrix)
Copies matrix to vtkMatrix.
Definition: mitkOpenCVMaths.cxx:262
const GLdouble * v
Definition: glew.h:1375
cv::Point2d FindIntersect(const cv::Vec4i &line1, const cv::Vec4i &line2)
Definition: mitkOpenCVMaths.cxx:607
cv::Matx33d ConstructEulerRotationMatrix(const double &rx, const double &ry, const double &rz)
Generates a rotation matrix, given Euler angles in radians.
Definition: mitkOpenCVMaths.cxx:989
double DotProduct(const cv::Point3d &p1, const cv::Point3d &p2)
Calculates the dot product of two vectors (cv::Point3D)
Definition: mitkOpenCVMaths.cxx:2615
GLfloat GLfloat p
Definition: glew.h:14169
double CalculateFiducialRegistrationError(const std::vector< cv::Point3d > &fixedPoints, const std::vector< cv::Point3d > &movingPoints, const cv::Matx44d &matrix)
Calculates Fiducial Registration Error by multiplying the movingPoints by the matrix, and comparing with fixedPoints.
Definition: mitkOpenCVMaths.cxx:191
Derived point types to contain data for projection and analysis.
double DistanceBetweenTwoPoints(const cv::Point3d &p1, const cv::Point3d &p2, cv::Point3d *delta)
calculates the distance between two points
Definition: mitkOpenCVMaths.cxx:2343
std::pair< cv::Point3d, cv::Point3d > TransformPointPair(const cv::Matx44d &M, const std::pair< cv::Point3d, cv::Point3d > &p)
multiplies a point pair by a 4x4 transformation matrix
Definition: mitkOpenCVMaths.cxx:473
cv::Point3d CrossProduct(const cv::Point3d &p1, const cv::Point3d &p2)
Calculates the cross product of two vectors (cv::Point3D)
Definition: mitkOpenCVMaths.cxx:2605
cv::Mat Tracker2ToTracker1Translation(const std::vector< cv::Mat > &Tracker1ToWorld1, const std::vector< cv::Mat > &World2ToTracker2, double &Residual, const cv::Mat &rcg)
works out the rigid translation correspondence between two sets of corresponding rigid body transform...
Definition: mitkOpenCVMaths.cxx:1604
GLuint GLenum matrix
Definition: glew.h:12775
GLuint GLdouble GLdouble GLint GLint const GLdouble * points
Definition: glew.h:3085
GLuint index
Definition: glew.h:1798
cv::Matx33d ConstructEulerRyMatrix(const double &ry)
Generates a rotation about Y-axis, given a Euler angle in radians.
Definition: mitkOpenCVMaths.cxx:951
cv::Matx44d ConstructRigidTransformationMatrix(const double &rx, const double &ry, const double &rz, const double &tx, const double &ty, const double &tz)
From rotations in radians and translations in millimetres, constructs a 4x4 transformation matrix...
Definition: mitkOpenCVMaths.cxx:1019
double DistanceToLine(const std::pair< cv::Point3d, cv::Point3d > &line, const cv::Point3d &x0)
calculates the distance between a line and a point
Definition: mitkOpenCVMaths.cxx:2327
unsigned int RemoveOutliers(std::vector< cv::Point3d > &points, const double &xLow, const double &xHigh, const double &yLow, const double &yHigh, const double &zLow, const double &zHigh)
Removes points outside the passed limits.
Definition: mitkOpenCVMaths.cxx:2663
mitk::PickedObject FindNearestPickedObject(const mitk::PickedObject &point, const std::vector< mitk::PickedObject > &matchingPoints, double *minRatio)
Searches through vector of 3D points and lines to find the one closest (by distance) to the passed po...
Definition: mitkOpenCVMaths.cxx:1453
GLclampd n
Definition: glew.h:6789
std::pair< double, double > RMSError(std::vector< mitk::ProjectedPointPairsWithTimingError > measured, std::vector< mitk::ProjectedPointPairsWithTimingError > actual, int indexToUse, cv::Point2d outlierSD, long long allowableTimingError, bool duplicateLines)
Returns the RMS error between two projected point vectors.
Definition: mitkOpenCVMaths.cxx:1174
void InvertRigid4x4Matrix(const CvMat &input, CvMat &output)
Specific method that inverts a matrix without SVD or decomposition, because the input is known to be ...
Definition: mitkOpenCVMaths.cxx:2062
double DistanceBetweenTwoSplines(const std::vector< cv::Point3d > &s1, const std::vector< cv::Point3d > &s2, unsigned int splineOrder, cv::Point3d *delta)
calculates the average shortest distance between two splines.
Definition: mitkOpenCVMaths.cxx:2353
double DistanceBetweenLines(const cv::Point3d &P0, const cv::Point3d &u, const cv::Point3d &Q0, const cv::Point3d &v, cv::Point3d &midpoint)
calculates the shortest distance between two lines
Definition: mitkOpenCVMaths.cxx:2449
std::vector< cv::Point3d > SubtractPointFromPoints(const std::vector< cv::Point3d > listOfPoints, const cv::Point3d &centroid)
Subtracts a point (e.g. the centroid) from a list of points.
Definition: mitkOpenCVMaths.cxx:27
bool CheckIfLinesArePerpendicular(cv::Vec4i line1, cv::Vec4i line2, double tolerance)
Definition: mitkOpenCVMaths.cxx:673
cv::Matx44d ConstructRodriguesTransformationMatrix(const double &r1, const double &r2, const double &r3, const double &tx, const double &ty, const double &tz)
From Rodrigues rotation parameters and translations in millimetres, constructs a 4x4 transformation m...
Definition: mitkOpenCVMaths.cxx:1049
std::string MatrixType(const cv::Mat &matrix)
returns the matrix type as a string
Definition: mitkOpenCVMaths.cxx:2179
mitk::ProjectedPointPair MeanError(std::vector< mitk::ProjectedPointPairsWithTimingError > measured, std::vector< mitk::ProjectedPointPairsWithTimingError > actual, mitk::ProjectedPointPair *StandardDeviations, int indexToUse, long long allowableTimingError, bool duplicateLines)
Returns the mean pixel errors for the right and left sets of projected points.
Definition: mitkOpenCVMaths.cxx:1266
GLsizei const GLcharARB ** string
Definition: glew.h:5194
cv::Point2d operator/(const cv::Point2d &p1, const int &n)
Divides a 2d point by an integer (x=x1/n, y=y1/2)
Definition: mitkOpenCVMaths.cxx:595
void CopyToOpenCVMatrix(const vtkMatrix4x4 &matrix, cv::Matx44d &openCVMatrix)
Copies matrix to openCVMatrix.
Definition: mitkOpenCVMaths.cxx:275
cv::Point2d FindNearestPoint(const cv::Point2d &point, const std::vector< cv::Point2d > &matchingPoints, double *minRatio, unsigned int *Index)
Searches through vector of 2D points to find the one closest (by distance) to the passed point...
Definition: mitkOpenCVMaths.cxx:1415
std::pair< cv::Point3d, cv::Point3d > TwoPointsToPLambda(const std::pair< cv::Point3d, cv::Point3d > &twoPointLine)
converts a line defined by two points on the line to the same line defined by a single point and it's...
Definition: mitkOpenCVMaths.cxx:2594
std::vector< int > SortMatricesByDistance(const std::vector< cv::Mat > Matrices)
Sorts the matrices based on the translations , and returns the order.
Definition: mitkOpenCVMaths.cxx:1875
Definition: mitkOpenCVPointTypes.h:76