$search

P Namespace Reference

Classes

class  Array
class  CodebookEntry
class  Config
class  ConfigFile
class  Def
class  DetectGPUSIFT
class  DetectSIFT
class  Except
class  Homography
class  KeyClusterPair
class  Keypoint
class  KeypointDescriptor
class  KeypointPair
class  ModelObject3D
class  Object3D
class  ODetect3D
class  PoseCv
struct  range_bin
class  SDraw
class  SPolygon
class  Vector2
class  Vector3

Typedefs

typedef struct range_bin Bin
typedef float SIFTDescriptor [128]

Functions

double AbsDistPointToLine (const Vector2 &q, const Vector2 &p, const Vector2 &d)
double AngleBetween (const Vector3 &a, const Vector3 &b)
void AngleHalf (const Vector2 &p1, const Vector2 &p2, const Vector2 &p3, Vector2 &p4)
double AngleRAD (const Vector2 &p1, const Vector2 &p2, const Vector2 &p3)
template<class Num >
bool Between (Num x, Num l, Num u)
template<class Num >
bool BetweenEq (Num x, Num l, Num u)
void ChainHull2D (Array< Vector2 > &p, Array< Vector2 > &h)
Vector2 CircleCenter (const Vector2 &pi, const Vector2 &pj, const Vector2 &pk)
bool ClockwiseTo (const Vector2 &a, const Vector2 &b)
void ConvexHull (Array< Vector2 > &p, Array< Vector2 > &h)
void CopyPoseCv (PoseCv &in, PoseCv &out)
void CopyVec (float *svec, float *dvec, unsigned size)
bool CounterClockwiseTo (const Vector2 &a, const Vector2 &b)
Vector3 Cross (const Vector3 &a, const Vector3 &b)
double Cross (const Vector2 &a, const Vector2 &b)
void DeleteCodebook (Array< CodebookEntry * > &codebook)
void DeleteObjects3D (Array< Object3D * > &objects)
void DeletePoseCv (Array< PoseCv * > &ps)
double Det33 (double *m)
double DiffAngle_0_2pi (double b, double a)
 Difference of two angles b - a. The result is scaled to [0..2pi[.
double DiffAngle_mpi_pi (double b, double a)
 Difference of two angles b - a. The result is scaled to [-pi..pi[.
double Distance (const Vector3 &a, const Vector3 &b)
double Distance (const Vector2 &a, const Vector2 &b)
double DistanceSquare (const Vector3 &a, const Vector3 &b)
double DistanceSquare (const Vector2 &a, const Vector2 &b)
double DistPointToLine (const Vector2 &q, const Vector2 &p, const Vector2 &d)
double Dot (const Vector3 &a, const Vector3 &b)
double Dot (const Vector2 &a, const Vector2 &b)
void GetPosScaleAngle (double x, double y, double H[9], double &xr, double &yr, double &scale, double &angle)
bool GetWord (const string &str, string &word, string::size_type &pos)
 Get the next word from a string, starting at pos.
int IMax (int i1, int i2)
int IMin (int i1, int i2)
int IModp (int i, int j)
void InitializePoseCv (PoseCv &pose)
bool Inv33 (double *m, double *r)
void InvPoseCv (PoseCv &in, PoseCv &out)
bool IsEqual (double a, double b)
 Returns true if the values are equal (+/- epsilon).
double IsLeft (Vector2 p0, Vector2 p1, Vector2 p2)
bool IsZero (double d)
 Returns true if the value is near zero (+/- epsilon).
int IWrap (int ival, int ilo, int ihi)
bool LeftOf (const Vector2 &a, const Vector2 &b)
double Length (const Vector3 &v)
double Length (const Vector2 &v)
Vector2 LineIntersection (const Vector2 &p1, const Vector2 &d1, const Vector2 &p2, const Vector2 &d2, double *l1, double *l2) throw (Except)
Vector2 LineIntersection (const Vector2 &p1, const Vector2 &d1, const Vector2 &p2, const Vector2 &d2) throw (Except)
bool LinesIntersecting (const Vector2 &a1, const Vector2 &a2, const Vector2 &b1, const Vector2 &b2, Vector2 &isct)
bool LinesIntersecting (const Vector2 &a1, const Vector2 &a2, const Vector2 &b1, const Vector2 &b2)
void LoadKeypoints (const char *file, P::Array< KeypointDescriptor * > &ks, int format=0)
void LoadLoweKeypoints (const char *file, P::Array< KeypointDescriptor * > &ks, int format=0)
void LoadLoweKeypoints (const char *file, P::Array< Keypoint * > &ks, int format=0)
void MapPoint (double in[2], double H[9], double out[2])
void MapPoint (double xin, double yin, double H[9], double &xout, double &yout)
float MatchKeypoint (KeypointDescriptor *k1, KeypointDescriptor *k2)
template<class Num >
Num Max (Num a, Num b)
Vector3 MidPoint (const Vector3 &a, const Vector3 &b)
Vector2 MidPoint (const Vector2 &a, const Vector2 &b)
template<class Num >
Num Min (Num a, Num b)
void Mul33 (double *m, double s, double *r)
void Mul33 (double *m1, double *m2, double *r)
Vector3 Normalise (const Vector3 &v)
Vector2 Normalise (const Vector2 &v)
bool operator!= (const Vector3 &a, const Vector3 &b)
bool operator!= (const Vector2 &a, const Vector2 &b)
Vector3 operator* (const Vector3 &v, const double s)
Vector3 operator* (const double s, const Vector3 &v)
Vector2 operator* (const Vector2 &v, const double s)
Vector2 operator* (const double s, const Vector2 &v)
Vector3 operator+ (const Vector3 &a, const Vector3 &b)
Vector2 operator+ (const Vector2 &a, const Vector2 &b)
Vector3 operator- (const Vector3 &a, const Vector3 &b)
Vector3 operator- (const Vector3 &v)
Vector2 operator- (const Vector2 &a, const Vector2 &b)
Vector2 operator- (const Vector2 &v)
Vector3 operator/ (const Vector3 &v, const double s) throw (Except)
Vector2 operator/ (const Vector2 &v, const double s) throw (Except)
string & operator<< (string &s, const Vector3 &v)
ostream & operator<< (ostream &os, const Vector3 &v)
string & operator<< (string &s, const Vector2 &v)
ostream & operator<< (ostream &os, const Vector2 &v)
bool operator== (const Vector3 &a, const Vector3 &b)
bool operator== (const Vector2 &a, const Vector2 &b)
const string & operator>> (const string &s, Vector3 &v)
istream & operator>> (istream &is, Vector3 &v) throw (Except)
const string & operator>> (const string &s, Vector2 &v)
istream & operator>> (istream &is, Vector2 &v) throw (Except)
unsigned Other (unsigned i)
unsigned OtherEnd (unsigned end)
unsigned OtherSide (unsigned side)
Vector3 PlaneExp2Normal (const Vector3 &a, const Vector3 &b, const Vector3 &c)
double PolarAngle (const Vector2 &v)
void Quat2Rot (double *q, CvMat *M)
bool RightOf (const Vector2 &a, const Vector2 &b)
void Rot2Quat (CvMat *M, double *q)
void Rot2Vec3 (CvMat *R, double *d)
Vector2 Rotate (const Vector2 &a, double phi)
double ScaleAngle_0_2pi (double a)
 Scale angle to [0..2pi[.
double ScaleAngle_0_pi (double a)
 Scale angle to [0..pi[.
double ScaleAngle_mpi_pi (double a)
 Scale angle to [-pi..pi[.
int ScaleIntAngle_0_8 (int a)
 Scale an integer angle to [0..8[.
template<class Num >
int Sign (Num x)
template<class Num >
Num Sqr (Num x)
 Square of given number.
template<class T >
void Swap (T &a, T &b)
double timespec_diff (struct timespec *x, struct timespec *y)
int timeval_subtract (struct timeval *result, struct timeval *x, struct timeval *y)
void Transpose33 (double *m, double *r)
void Vec32Rot (double *d, CvMat *R)
void WriteKeypoints (P::Array< KeypointDescriptor * > &ks, const char *file, int format=0)

Variables

const unsigned CAM3D = 2
const unsigned END = 1
const unsigned INNER = 0
static const char keyd_type_names [][NAME_LENGTH]
const unsigned LEFT = 0
const unsigned MID = 2
static const int NAME_LENGTH = 40
const unsigned ONE_THIRD = 3
const unsigned OPP = END
const unsigned OUTER = 1
const unsigned RIGHT = 1
const unsigned SAME = START
const unsigned START = 0
const unsigned STOP = 15
const unsigned TWO_THIRD = 4
const unsigned UNDEF_ID = UINT_MAX

Detailed Description

Id
Array.hh 34111 2012-07-03 14:29:54Z student5
Id
CodebookEntry.hh 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
Config.hh 34111 2012-07-03 14:29:54Z student5
Id
ConfigFile.hh 34111 2012-07-03 14:29:54Z student5
Id
DetectGPUSIFT.hh 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
DetectSIFT.hh 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
Geometry.hh 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 30.11.2006

Id
Homography.hh 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-03-30 prankl@acin.tuwien.ac.at

Id
KeyClusterPair.hh 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
Keypoint.hh 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
KeypointPair.hh 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
Math.hh 34111 2012-07-03 14:29:54Z student5

Michael Zillich, 2004-3-04

Id
ModelObject3D.hh 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
Object3D.hh 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
ODetect3D.hh 34111 2012-07-03 14:29:54Z student5

Simple RANSAC based 3d object detector

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
PNamespace.hh 34111 2012-07-03 14:29:54Z student5
Id
PoseCv.hh 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
SDraw.hh 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
SMatrix.hh 34111 2012-07-03 14:29:54Z student5
Id
SPolygon.hh 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
Vector2.hh 34111 2012-07-03 14:29:54Z student5

Michael Zillich, 2004-3-04

Id
Vector3.hh 34111 2012-07-03 14:29:54Z student5
Id
CodebookEntry.cc 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
Config.cc 34111 2012-07-03 14:29:54Z student5
Id
ConfigFile.cc 34111 2012-07-03 14:29:54Z student5
Id
DetectGPUSIFT.cc 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
DetectSIFT.cc 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
Except.cc 34111 2012-07-03 14:29:54Z student5
Id
Geometry.cc 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at TODO:

Id
Keypoint.cc 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
KeypointDescriptor.cc 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
Math.cc 34111 2012-07-03 14:29:54Z student5
Id
ModelObject3D.cc 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
Object3D.cc 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
ODetect3D.cc 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

TODO:

Id
PoseCv.cc 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
SDraw.cc 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
SPolygon.cc 34111 2012-07-03 14:29:54Z student5

Johann Prankl, 2010-01-27 prankl@acin.tuwien.ac.at

Id
Vector2.cc 34111 2012-07-03 14:29:54Z student5

$id$


Typedef Documentation

typedef struct range_bin P::Bin

Definition at line 19 of file Geometry.cc.

typedef float P::SIFTDescriptor

Definition at line 28 of file DetectGPUSIFT.hh.


Function Documentation

double P::AbsDistPointToLine ( const Vector2 &  q,
const Vector2 &  p,
const Vector2 &  d 
)
double P::AngleBetween ( const Vector3 a,
const Vector3 b 
)
void P::AngleHalf ( const Vector2 &  p1,
const Vector2 &  p2,
const Vector2 &  p3,
Vector2 &  p4 
)

AngleHalf finds half an angle. The original angle is defined by the sequence of points P1, P2 and P3. P1 / / P4 / . / . P2--------->P3

Definition at line 234 of file Geometry.cc.

double P::AngleRAD ( const Vector2 &  p1,
const Vector2 &  p2,
const Vector2 &  p3 
)

AngleRAD returns the angle in radians swept out between two rays AngleRAD ( P1, P2, P3 ) + AngleRAD ( P3, P2, P1 ) = 2 * PI

P1 / / / / P2--------->P3

Definition at line 273 of file Geometry.cc.

template<class Num >
bool P::Between ( Num  x,
Num  l,
Num  u 
) [inline]
template<class Num >
bool P::BetweenEq ( Num  x,
Num  l,
Num  u 
) [inline]
void P::ChainHull2D ( Array< Vector2 > &  p,
Array< Vector2 > &  h 
)

Calculate hullpoints

Copyright 2001, softSurfer (www.softsurfer.com) This code may be freely used and modified for any purpose providing that this copyright notice is included with it. SoftSurfer makes no warranty for this code, and cannot be held liable for any real or imagined damage resulting from its use. Users of this code must verify correctness for their application.

nearHull_2D(): the BFP fast approximate 2D convex hull algorithm Input: p[] = an (unsorted) array of 2D points Output: h[] = an array of the convex hull vertices (max is n)

Definition at line 41 of file Geometry.cc.

Vector2 P::CircleCenter ( const Vector2 &  pi,
const Vector2 &  pj,
const Vector2 &  pk 
)
bool P::ClockwiseTo ( const Vector2 &  a,
const Vector2 &  b 
)
void P::ConvexHull ( Array< Vector2 > &  p,
Array< Vector2 > &  h 
)

Definition at line 198 of file Geometry.cc.

void P::CopyPoseCv ( PoseCv &  in,
PoseCv &  out 
) [inline]

Definition at line 52 of file PoseCv.hh.

void P::CopyVec ( float *  svec,
float *  dvec,
unsigned  size 
) [inline]

only copies a vector of floats

Definition at line 350 of file KeypointDescriptor.hh.

bool P::CounterClockwiseTo ( const Vector2 &  a,
const Vector2 &  b 
)
Vector3 P::Cross ( const Vector3 a,
const Vector3 b 
)
double P::Cross ( const Vector2 &  a,
const Vector2 &  b 
)
void P::DeleteCodebook ( Array< CodebookEntry * > &  codebook  )  [inline]
void P::DeleteObjects3D ( Array< Object3D * > &  objects  ) 

Definition at line 36 of file Object3D.cc.

void P::DeletePoseCv ( Array< PoseCv * > &  ps  ) 

Definition at line 75 of file PoseCv.cc.

double P::Det33 ( double *  m  ) 
double P::DiffAngle_0_2pi ( double  b,
double  a 
)

Difference of two angles b - a. The result is scaled to [0..2pi[.

double P::DiffAngle_mpi_pi ( double  b,
double  a 
)

Difference of two angles b - a. The result is scaled to [-pi..pi[.

double P::Distance ( const Vector3 a,
const Vector3 b 
)
double P::Distance ( const Vector2 &  a,
const Vector2 &  b 
)
double P::DistanceSquare ( const Vector3 a,
const Vector3 b 
)
double P::DistanceSquare ( const Vector2 &  a,
const Vector2 &  b 
)
double P::DistPointToLine ( const Vector2 &  q,
const Vector2 &  p,
const Vector2 &  d 
)
double P::Dot ( const Vector3 a,
const Vector3 b 
)
double P::Dot ( const Vector2 &  a,
const Vector2 &  b 
)
void P::GetPosScaleAngle ( double  x,
double  y,
double  H[9],
double &  xr,
double &  yr,
double &  scale,
double &  angle 
) [inline]

returns angle and scale from homography

Definition at line 322 of file Homography.hh.

bool P::GetWord ( const string &  str,
string &  word,
string::size_type &  pos 
)

Get the next word from a string, starting at pos.

Get the next word from a string, starting at pos. Words are separated by whitespaces (as in isspace(3)). The string must contain only a single line. pos contains the position after the word or string::npos if at end of string. Returns true if a word was found, false otherwise.

Definition at line 81 of file ConfigFile.cc.

int P::IMax ( int  i1,
int  i2 
)
int P::IMin ( int  i1,
int  i2 
)
int P::IModp ( int  i,
int  j 
)
void P::InitializePoseCv ( PoseCv &  pose  ) 

Definition at line 58 of file PoseCv.cc.

bool P::Inv33 ( double *  m,
double *  r 
)
void P::InvPoseCv ( PoseCv &  in,
PoseCv &  out 
) [inline]

Definition at line 166 of file PoseCv.hh.

bool P::IsEqual ( double  a,
double  b 
)

Returns true if the values are equal (+/- epsilon).

double P::IsLeft ( Vector2  p0,
Vector2  p1,
Vector2  p2 
)
bool P::IsZero ( double  d  ) 

Returns true if the value is near zero (+/- epsilon).

int P::IWrap ( int  ival,
int  ilo,
int  ihi 
)
bool P::LeftOf ( const Vector2 &  a,
const Vector2 &  b 
)
double P::Length ( const Vector3 v  ) 
double P::Length ( const Vector2 &  v  ) 
Vector2 P::LineIntersection ( const Vector2 &  p1,
const Vector2 &  d1,
const Vector2 &  p2,
const Vector2 &  d2,
double *  l1,
double *  l2 
) throw (Except)

Returns intersection of lines defined by point p and direction d (needs not be a unit vector). l1 and l2 contain the lengths along the lines where the intersection lies, measured in lengths of d1 and d2. So if You want l1 and l2 in pixels, d1 and d2 must be unit vectors.

Definition at line 31 of file Vector2.cc.

Vector2 P::LineIntersection ( const Vector2 &  p1,
const Vector2 &  d1,
const Vector2 &  p2,
const Vector2 &  d2 
) throw (Except)

Returns intersection of lines defined by point p and direction d (needs not be a unit vector).

Definition at line 14 of file Vector2.cc.

bool P::LinesIntersecting ( const Vector2 &  a1,
const Vector2 &  a2,
const Vector2 &  b1,
const Vector2 &  b2,
Vector2 &  isct 
)

Checks wheter lines a and b defined by their end points intersect.

Definition at line 57 of file Vector2.cc.

bool P::LinesIntersecting ( const Vector2 &  a1,
const Vector2 &  a2,
const Vector2 &  b1,
const Vector2 &  b2 
)

Checks wheter lines a and b defined by their end points intersect.

Definition at line 46 of file Vector2.cc.

void P::LoadKeypoints ( const char *  file,
P::Array< KeypointDescriptor * > &  ks,
int  format = 0 
)

Definition at line 499 of file KeypointDescriptor.cc.

void P::LoadLoweKeypoints ( const char *  file,
P::Array< KeypointDescriptor * > &  ks,
int  format = 0 
)

Definition at line 553 of file KeypointDescriptor.cc.

void P::LoadLoweKeypoints ( const char *  file,
P::Array< Keypoint * > &  ks,
int  format = 0 
)

Definition at line 524 of file KeypointDescriptor.cc.

void P::MapPoint ( double  in[2],
double  H[9],
double  out[2] 
) [inline]

Map a point using an (affine) homography

Parameters:
H pointer to a 3x3 homography matrix

Definition at line 310 of file Homography.hh.

void P::MapPoint ( double  xin,
double  yin,
double  H[9],
double &  xout,
double &  yout 
) [inline]

Map a point using an (affine) homography

Parameters:
H pointer to a 3x3 homography matrix

Definition at line 297 of file Homography.hh.

float P::MatchKeypoint ( KeypointDescriptor *  k1,
KeypointDescriptor *  k2 
) [inline]

Definition at line 357 of file KeypointDescriptor.hh.

template<class Num >
Num P::Max ( Num  a,
Num  b 
) [inline]
Vector3 P::MidPoint ( const Vector3 a,
const Vector3 b 
)
Vector2 P::MidPoint ( const Vector2 &  a,
const Vector2 &  b 
)
template<class Num >
Num P::Min ( Num  a,
Num  b 
) [inline]
void P::Mul33 ( double *  m,
double  s,
double *  r 
)
void P::Mul33 ( double *  m1,
double *  m2,
double *  r 
)
Vector3 P::Normalise ( const Vector3 v  ) 
Vector2 P::Normalise ( const Vector2 &  v  ) 
bool P::operator!= ( const Vector3 a,
const Vector3 b 
)
bool P::operator!= ( const Vector2 &  a,
const Vector2 &  b 
)
Vector3 P::operator* ( const Vector3 v,
const double  s 
)
Vector3 P::operator* ( const double  s,
const Vector3 v 
)
Vector2 P::operator* ( const Vector2 &  v,
const double  s 
)
Vector2 P::operator* ( const double  s,
const Vector2 &  v 
)
Vector3 P::operator+ ( const Vector3 a,
const Vector3 b 
)
Vector2 P::operator+ ( const Vector2 &  a,
const Vector2 &  b 
)
Vector3 P::operator- ( const Vector3 a,
const Vector3 b 
)
Vector3 P::operator- ( const Vector3 v  ) 
Vector2 P::operator- ( const Vector2 &  a,
const Vector2 &  b 
)
Vector2 P::operator- ( const Vector2 &  v  ) 
Vector3 P::operator/ ( const Vector3 v,
const double  s 
) throw (Except)
Vector2 P::operator/ ( const Vector2 &  v,
const double  s 
) throw (Except)
string& P::operator<< ( string &  s,
const Vector3 v 
)
ostream& P::operator<< ( ostream &  os,
const Vector3 v 
)
string& P::operator<< ( string &  s,
const Vector2 &  v 
)
ostream& P::operator<< ( ostream &  os,
const Vector2 &  v 
)
bool P::operator== ( const Vector3 a,
const Vector3 b 
)
bool P::operator== ( const Vector2 &  a,
const Vector2 &  b 
)
const string& P::operator>> ( const string &  s,
Vector3 v 
)
istream& P::operator>> ( istream &  is,
Vector3 v 
) throw (Except)
const string& P::operator>> ( const string &  s,
Vector2 &  v 
)
istream& P::operator>> ( istream &  is,
Vector2 &  v 
) throw (Except)
unsigned P::Other ( unsigned  i  )  [inline]

Definition at line 57 of file Math.hh.

unsigned P::OtherEnd ( unsigned  end  )  [inline]

Definition at line 35 of file Math.hh.

unsigned P::OtherSide ( unsigned  side  )  [inline]

Definition at line 52 of file Math.hh.

Vector3 P::PlaneExp2Normal ( const Vector3 a,
const Vector3 b,
const Vector3 c 
)
double P::PolarAngle ( const Vector2 &  v  ) 
void P::Quat2Rot ( double *  q,
CvMat *  M 
) [inline]

Definition at line 130 of file PoseCv.hh.

bool P::RightOf ( const Vector2 &  a,
const Vector2 &  b 
)
void P::Rot2Quat ( CvMat *  M,
double *  q 
) [inline]

Definition at line 59 of file PoseCv.hh.

void P::Rot2Vec3 ( CvMat *  R,
double *  d 
) [inline]

Definition at line 117 of file PoseCv.hh.

Vector2 P::Rotate ( const Vector2 &  a,
double  phi 
)
double P::ScaleAngle_0_2pi ( double  a  ) 

Scale angle to [0..2pi[.

double P::ScaleAngle_0_pi ( double  a  ) 

Scale angle to [0..pi[.

double P::ScaleAngle_mpi_pi ( double  a  ) 

Scale angle to [-pi..pi[.

int P::ScaleIntAngle_0_8 ( int  a  ) 

Scale an integer angle to [0..8[.

template<class Num >
int P::Sign ( Num  x  )  [inline]
template<class Num >
Num P::Sqr ( Num  x  )  [inline]

Square of given number.

template<class T >
void P::Swap ( T &  a,
T &  b 
) [inline]
double P::timespec_diff ( struct timespec *  x,
struct timespec *  y 
)

Returns timespecs x - y as double.

Definition at line 39 of file Math.cc.

int P::timeval_subtract ( struct timeval *  result,
struct timeval *  x,
struct timeval *  y 
)

Subtract the `struct timeval' values x - y. Return 1 if the difference is negative, otherwise 0.

Definition at line 16 of file Math.cc.

void P::Transpose33 ( double *  m,
double *  r 
)
void P::Vec32Rot ( double *  d,
CvMat *  R 
) [inline]

Definition at line 155 of file PoseCv.hh.

void P::WriteKeypoints ( P::Array< KeypointDescriptor * > &  ks,
const char *  file,
int  format = 0 
)

Definition at line 479 of file KeypointDescriptor.cc.


Variable Documentation

const unsigned P::CAM3D = 2

Definition at line 46 of file Math.hh.

const unsigned P::END = 1

Definition at line 29 of file Math.hh.

const unsigned P::INNER = 0

Definition at line 49 of file Math.hh.

const char P::keyd_type_names[][NAME_LENGTH] [static]
Initial value:
 {
  "DOG_SIFT",
  "LOWE_DOG_SIFT",
  "MSER_SIFT",
  "UVMSER_SIFT",
  "HESLAP_SIFT",
  "UNDEF"
  }

Definition at line 25 of file KeypointDescriptor.cc.

const unsigned P::LEFT = 0

Definition at line 44 of file Math.hh.

const unsigned P::MID = 2

Definition at line 30 of file Math.hh.

const int P::NAME_LENGTH = 40 [static]

Definition at line 24 of file KeypointDescriptor.cc.

const unsigned P::ONE_THIRD = 3

Definition at line 31 of file Math.hh.

const unsigned P::OPP = END

Definition at line 42 of file Math.hh.

const unsigned P::OUTER = 1

Definition at line 50 of file Math.hh.

const unsigned P::RIGHT = 1

Definition at line 45 of file Math.hh.

const unsigned P::SAME = START

Definition at line 41 of file Math.hh.

const unsigned P::START = 0

Definition at line 28 of file Math.hh.

const unsigned P::STOP = 15

Definition at line 33 of file Math.hh.

const unsigned P::TWO_THIRD = 4

Definition at line 32 of file Math.hh.

const unsigned P::UNDEF_ID = UINT_MAX

Definition at line 26 of file Math.hh.

 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Properties Friends Defines


blort
Author(s): Michael Zillich, Thomas Mörwald, Johann Prankl, Andreas Richtsfeld, Bence Magyar (ROS version)
autogenerated on Fri Mar 1 16:57:58 2013