Classes | Functions
RPP Namespace Reference

Classes

class  Quaternion
 
class  Solution
 

Functions

void AbsKernel (cv::Mat P, cv::Mat Q, const std::vector< cv::Mat > &F, const cv::Mat &G, cv::Mat &R, cv::Mat &t, cv::Mat &Qout, double &err2)
 
void AbsKernel (Mat P, Mat Q, const vector< Mat > &F, const Mat &G, Mat &R, Mat &t, Mat &Qout, double &err2)
 
bool DecomposeR (const cv::Mat &R, cv::Mat &Rz2, cv::Mat &ret)
 
bool DecomposeR (const Mat &R, Mat &Rz2, Mat &ret)
 
cv::Mat EstimateT (const cv::Mat &R, const cv::Mat &G, const std::vector< cv::Mat > &F, const cv::Mat &P)
 
Mat EstimateT (const Mat &R, const Mat &G, const vector< Mat > &F, const Mat &P)
 
bool Get2ndPose_Exact (const cv::Mat &v, const cv::Mat &P, const cv::Mat &R, const cv::Mat &t, std::vector< Solution > &ret)
 
bool Get2ndPose_Exact (const Mat &v, const Mat &P, const Mat &R, const Mat &t, vector< Solution > &ret)
 
bool GetRfor2ndPose_V_Exact (const cv::Mat &v, const cv::Mat &P, const cv::Mat &R, const cv::Mat &t, std::vector< Solution > &ret)
 
bool GetRfor2ndPose_V_Exact (const Mat &v, const Mat &P, const Mat &R, const Mat &t, vector< Solution > &ret)
 
cv::Mat GetRotationbyVector (const cv::Vec3d &v1, const cv::Vec3d &v2)
 
Mat GetRotationbyVector (const Vec3d &v1, const Vec3d &v2)
 
void GetRotationY_wrtT (const cv::Mat &v, const cv::Mat &P, const cv::Mat &t, const cv::Mat &Rz, std::vector< double > &al, cv::Mat &tnew, std::vector< double > &at)
 
void GetRotationY_wrtT (const Mat &v, const Mat &p, const Mat &t, const Mat &Rz, vector< double > &al, Mat &tnew, vector< double > &at)
 
cv::Mat Mean (const cv::Mat &m)
 
Mat Mean (const Mat &m)
 
cv::Mat Mul (const cv::Mat &a, const cv::Mat &b)
 
Mat Mul (const Mat &a, const Mat &b)
 
double Norm (const cv::Mat &m)
 
double Norm (const Mat &m)
 
cv::Mat NormRv (const cv::Mat &R)
 
cv::Mat NormRv (const cv::Vec3d &V)
 
Mat NormRv (const Mat &R)
 
Mat NormRv (const Vec3d &V)
 
void ObjPose (const Mat _P, Mat Qp, Mat initR, Mat &R, Mat &t, int &it, double &obj_err, double &img_err)
 
void ObjPose (const cv::Mat P, cv::Mat Qp, cv::Mat initR, cv::Mat &R, cv::Mat &t, int &it, double &obj_err, double &img_err)
 
cv::Mat Point2Mat (const std::vector< cv::Point3d > &pts)
 
cv::Mat Point2Mat (const std::vector< cv::Point2d > &pts)
 
Mat Point2Mat (const vector< Point3d > &pts)
 
Mat Point2Mat (const vector< Point2d > &pts)
 
void Print (const cv::Mat &m)
 
void Print (const Quaternion &q)
 
void Print (const Mat &m)
 
cv::Mat quat2mat (const Quaternion &Q)
 
Quaternion Quaternion_byAngleAndVector (double q_angle, const cv::Vec3d &q_vector)
 
Quaternion Quaternion_byAngleAndVector (double q_angle, const Vec3d &q_vector)
 
Quaternion Quaternion_byVectorAndScalar (const cv::Vec3d &vector, double scalar)
 
Quaternion Quaternion_multiplyByScalar (const Quaternion &q, double scalar)
 
double Quaternion_Norm (const Quaternion &Q)
 
bool Rpp (const Mat &model_3D, const Mat &iprts, Mat &Rlu, Mat &tlu, int &it1, double &obj_err1, double &img_err1, vector< Solution > &sol)
 
bool Rpp (const cv::Mat &model_3D, const cv::Mat &iprts, cv::Mat &Rlu, cv::Mat &tlu, int &it1, double &obj_err1, double &img_err1, std::vector< Solution > &sol)
 
bool RpyAng (const cv::Mat &R, cv::Vec3d &ret)
 
bool RpyAng (const Mat &R, Vec3d &ret)
 
bool RpyAng_X (const cv::Mat &R, cv::Vec3d &ret)
 
bool RpyAng_X (const Mat &R, Vec3d &ret)
 
cv::Mat RpyMat (const cv::Vec3d &angs)
 
Mat RpyMat (const Vec3d &angs)
 
int sign (double x)
 
cv::Mat Sq (const cv::Mat &m)
 
Mat Sq (const Mat &m)
 
cv::Mat Sum (const cv::Mat &m, int dim=1)
 
Mat Sum (const Mat &m, int dim)
 
cv::Mat Vec2Mat (const cv::Vec3d &v)
 
Mat Vec2Mat (const Vec3d &v)
 
cv::Mat Xform (const cv::Mat &P, const cv::Mat &R, const cv::Mat &t)
 
Mat Xform (const Mat &P, const Mat &R, const Mat &t)
 

Function Documentation

void RPP::AbsKernel ( cv::Mat  P,
cv::Mat  Q,
const std::vector< cv::Mat > &  F,
const cv::Mat &  G,
cv::Mat &  R,
cv::Mat &  t,
cv::Mat &  Qout,
double &  err2 
)
void RPP::AbsKernel ( Mat  P,
Mat  Q,
const vector< Mat > &  F,
const Mat &  G,
Mat &  R,
Mat &  t,
Mat &  Qout,
double &  err2 
)

Definition at line 229 of file RPP.cpp.

bool RPP::DecomposeR ( const cv::Mat &  R,
cv::Mat &  Rz2,
cv::Mat &  ret 
)
bool RPP::DecomposeR ( const Mat &  R,
Mat &  Rz2,
Mat &  ret 
)

Definition at line 755 of file RPP.cpp.

cv::Mat RPP::EstimateT ( const cv::Mat &  R,
const cv::Mat &  G,
const std::vector< cv::Mat > &  F,
const cv::Mat &  P 
)
Mat RPP::EstimateT ( const Mat &  R,
const Mat &  G,
const vector< Mat > &  F,
const Mat &  P 
)

Definition at line 210 of file RPP.cpp.

bool RPP::Get2ndPose_Exact ( const cv::Mat &  v,
const cv::Mat &  P,
const cv::Mat &  R,
const cv::Mat &  t,
std::vector< Solution > &  ret 
)
bool RPP::Get2ndPose_Exact ( const Mat &  v,
const Mat &  P,
const Mat &  R,
const Mat &  t,
vector< Solution > &  ret 
)

Definition at line 693 of file RPP.cpp.

bool RPP::GetRfor2ndPose_V_Exact ( const cv::Mat &  v,
const cv::Mat &  P,
const cv::Mat &  R,
const cv::Mat &  t,
std::vector< Solution > &  ret 
)
bool RPP::GetRfor2ndPose_V_Exact ( const Mat &  v,
const Mat &  P,
const Mat &  R,
const Mat &  t,
vector< Solution > &  ret 
)

Definition at line 847 of file RPP.cpp.

cv::Mat RPP::GetRotationbyVector ( const cv::Vec3d &  v1,
const cv::Vec3d &  v2 
)
Mat RPP::GetRotationbyVector ( const Vec3d &  v1,
const Vec3d &  v2 
)

Definition at line 425 of file RPP.cpp.

void RPP::GetRotationY_wrtT ( const cv::Mat &  v,
const cv::Mat &  P,
const cv::Mat &  t,
const cv::Mat &  Rz,
std::vector< double > &  al,
cv::Mat &  tnew,
std::vector< double > &  at 
)
void RPP::GetRotationY_wrtT ( const Mat &  v,
const Mat &  p,
const Mat &  t,
const Mat &  Rz,
vector< double > &  al,
Mat &  tnew,
vector< double > &  at 
)

Definition at line 947 of file RPP.cpp.

cv::Mat RPP::Mean ( const cv::Mat &  m)
Mat RPP::Mean ( const Mat &  m)

Definition at line 508 of file RPP.cpp.

cv::Mat RPP::Mul ( const cv::Mat &  a,
const cv::Mat &  b 
)
Mat RPP::Mul ( const Mat &  a,
const Mat &  b 
)

Definition at line 493 of file RPP.cpp.

double RPP::Norm ( const cv::Mat &  m)
double RPP::Norm ( const Mat &  m)

Definition at line 840 of file RPP.cpp.

cv::Mat RPP::NormRv ( const cv::Mat &  R)
cv::Mat RPP::NormRv ( const cv::Vec3d &  V)
Mat RPP::NormRv ( const Mat &  R)

Definition at line 334 of file RPP.cpp.

Mat RPP::NormRv ( const Vec3d &  V)

Definition at line 354 of file RPP.cpp.

void RPP::ObjPose ( const Mat  _P,
Mat  Qp,
Mat  initR,
Mat &  R,
Mat &  t,
int &  it,
double &  obj_err,
double &  img_err 
)

Definition at line 66 of file RPP.cpp.

void RPP::ObjPose ( const cv::Mat  P,
cv::Mat  Qp,
cv::Mat  initR,
cv::Mat &  R,
cv::Mat &  t,
int &  it,
double &  obj_err,
double &  img_err 
)
cv::Mat RPP::Point2Mat ( const std::vector< cv::Point3d > &  pts)
cv::Mat RPP::Point2Mat ( const std::vector< cv::Point2d > &  pts)
Mat RPP::Point2Mat ( const vector< Point3d > &  pts)

Definition at line 525 of file RPP.cpp.

Mat RPP::Point2Mat ( const vector< Point2d > &  pts)

Definition at line 538 of file RPP.cpp.

void RPP::Print ( const cv::Mat &  m)
void RPP::Print ( const Quaternion q)

Definition at line 1236 of file RPP.cpp.

void RPP::Print ( const Mat &  m)

Definition at line 1224 of file RPP.cpp.

Mat RPP::quat2mat ( const Quaternion Q)

Definition at line 401 of file RPP.cpp.

Quaternion RPP::Quaternion_byAngleAndVector ( double  q_angle,
const cv::Vec3d &  q_vector 
)
Quaternion RPP::Quaternion_byAngleAndVector ( double  q_angle,
const Vec3d &  q_vector 
)

Definition at line 367 of file RPP.cpp.

Quaternion RPP::Quaternion_byVectorAndScalar ( const cv::Vec3d &  vector,
double  scalar 
)
inline

Definition at line 139 of file RPP.h.

Quaternion RPP::Quaternion_multiplyByScalar ( const Quaternion q,
double  scalar 
)
inline

Definition at line 144 of file RPP.h.

double RPP::Quaternion_Norm ( const Quaternion Q)
inline

Definition at line 157 of file RPP.h.

bool RPP::Rpp ( const Mat &  model_3D,
const Mat &  iprts,
Mat &  Rlu,
Mat &  tlu,
int &  it1,
double &  obj_err1,
double &  img_err1,
vector< Solution > &  sol 
)

Definition at line 13 of file RPP.cpp.

bool RPP::Rpp ( const cv::Mat &  model_3D,
const cv::Mat &  iprts,
cv::Mat &  Rlu,
cv::Mat &  tlu,
int &  it1,
double &  obj_err1,
double &  img_err1,
std::vector< Solution > &  sol 
)
bool RPP::RpyAng ( const cv::Mat &  R,
cv::Vec3d &  ret 
)
bool RPP::RpyAng ( const Mat &  R,
Vec3d &  ret 
)

Definition at line 592 of file RPP.cpp.

bool RPP::RpyAng_X ( const cv::Mat &  R,
cv::Vec3d &  ret 
)
bool RPP::RpyAng_X ( const Mat &  R,
Vec3d &  ret 
)

Definition at line 659 of file RPP.cpp.

cv::Mat RPP::RpyMat ( const cv::Vec3d &  angs)
Mat RPP::RpyMat ( const Vec3d &  angs)

Definition at line 563 of file RPP.cpp.

int RPP::sign ( double  x)
inline

Definition at line 162 of file RPP.h.

cv::Mat RPP::Sq ( const cv::Mat &  m)
Mat RPP::Sq ( const Mat &  m)

Definition at line 810 of file RPP.cpp.

cv::Mat RPP::Sum ( const cv::Mat &  m,
int  dim = 1 
)
Mat RPP::Sum ( const Mat &  m,
int  dim 
)

Definition at line 458 of file RPP.cpp.

cv::Mat RPP::Vec2Mat ( const cv::Vec3d &  v)
Mat RPP::Vec2Mat ( const Vec3d &  v)

Definition at line 551 of file RPP.cpp.

cv::Mat RPP::Xform ( const cv::Mat &  P,
const cv::Mat &  R,
const cv::Mat &  t 
)
Mat RPP::Xform ( const Mat &  P,
const Mat &  R,
const Mat &  t 
)

Definition at line 823 of file RPP.cpp.



fiducial_pose
Author(s): Jim Vaughan
autogenerated on Thu Dec 28 2017 04:06:58