Jafar
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
Classes | Public Member Functions | Protected Member Functions | Protected Attributes
jafar::bundler::Adapter< TRACKERS > Class Template Reference

Class Adapter, it acts as an interface between bundler module and detection modules. More...


Detailed Description

template<class TRACKERS>
class jafar::bundler::Adapter< TRACKERS >

Class Adapter, it acts as an interface between bundler module and detection modules.

It gets detection result on a series of views then proceeds with light bundle adjustment.

Definition at line 32 of file adapter.hpp.

#include <adapter.hpp>

List of all members.

Classes

struct  Point3DCompare

Public Member Functions

 Adapter ()
 Default constructor.
 Adapter (const camera::CameraType &camType, const std::string &camCalibFile)
 Constructor.
 Adapter (const camera::CameraType &camType, const std::string &camCalibFile, const TRACKERS &trackers)
 Constructor.
 Adapter (const jafar::camera::CameraType &camType, const std::string &camCalibFile, const std::map< int, geom::T3D * > &toOriginFrames, const TRACKERS &trackers)
 Constructor.
virtual ~Adapter ()
 virtual destructor
void setCamera (const camera::CameraType &camType, const std::string &camCalibFile)
 set camera type
void setTrackers (const TRACKERS &trackers)
 set trackers
void setReferences (const std::map< int, geom::T3D * > &toOriginFrames)
 set references
void insertReference (const int &index, T3D *sensorToOrigin)
 inserts a single reference with key index
void computeMeanReprojectionError ()
 computes mean reprojection error
double meanReprojectionError ()
void removeOutliers (const double &k=1.5)
 removes outliers
std::set< geom::Point3D,
Point3DCompare
trackedObjects ()
 getter for the bundled objects
std::map< int, jblas::vec3trackedPoints ()
 getter for the bundled points
void writeToFile (const string &fullFileName)
 writes output
ViewsManagerviewsManager () const
 getter for the views manager
std::vector
< jafar::bundler::View * > 
viewsList () const
 getter for the views list

Protected Member Functions

virtual void process ()
 main methode processes all the trackers should iteratively call processTracker()
virtual void processTracker ()
 process only one tracker
virtual void loadTrackerViews ()
 loads tracker views for ViewsManager
void addTrackedObject (const geom::Point3D &p)
 adds a 3D point with identifier id to the objects set
void addTrackedObject (const geom::Point3D &p, const double &e)
 adds a 3D point with mean reprojection error e to the objects set
void addTrackedPoint (const int &id, const jblas::vec3 &p)
 adds a 3D point with identifier id to the points map
void addTrackedPoint (const int &id, const jblas::vec3 &p, const double &e)
 adds a 3D point with identifier id mean reprojection error e to the points map

Protected Attributes

ViewsManagervManager
TRACKERS m_trackers
std::set< geom::Point3D,
Point3DCompare
objects
std::map< int, jblas::vec3points
std::map< int, double > errors
double mean_error

Constructor & Destructor Documentation

template<class TRACKERS >
jafar::bundler::Adapter< TRACKERS >::Adapter ( const camera::CameraType &  camType,
const std::string &  camCalibFile 
) [inline]

Constructor.

Parameters:
camType,:IN type of the used camera
camCalibFile,:IN camera calibration file

Definition at line 60 of file adapter.hpp.

template<class TRACKERS >
jafar::bundler::Adapter< TRACKERS >::Adapter ( const camera::CameraType &  camType,
const std::string &  camCalibFile,
const TRACKERS &  trackers 
) [inline]

Constructor.

Parameters:
camType,:IN type of the used camera
camCalibFile,:IN camera calibration file
trackers,:IN 2D detected features lists

Definition at line 72 of file adapter.hpp.

template<class TRACKERS >
jafar::bundler::Adapter< TRACKERS >::Adapter ( const jafar::camera::CameraType &  camType,
const std::string &  camCalibFile,
const std::map< int, geom::T3D * > &  toOriginFrames,
const TRACKERS &  trackers 
) [inline]

Constructor.

Parameters:
camType,:IN type of the used camera
camCalibFile,:IN camera calibration file
toOriginFrames,:IN to origin frame transformations for the whole views
trackers,:IN 2D detected features lists

Definition at line 86 of file adapter.hpp.


Member Function Documentation

template<class TRACKERS >
double jafar::bundler::Adapter< TRACKERS >::meanReprojectionError ( ) [inline]
Returns:
mean repojection error

Definition at line 134 of file adapter.hpp.

template<class TRACKERS >
void jafar::bundler::Adapter< TRACKERS >::removeOutliers ( const double &  k = 1.5) [inline]

removes outliers

Parameters:
k,:IN points which reprojection error > k * mean reprojection error are rejected

Definition at line 143 of file adapter.hpp.

References jafar::bundler::BundlerException::ADAPTER_INVALID_CONSTRAINT, and JFR_PRED_ERROR.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines

Generated on Wed Oct 15 2014 00:37:32 for Jafar by doxygen 1.7.6.1
LAAS-CNRS