$search

Tracking::Tracker Class Reference

Main class of Tracker, defining API. More...

#include <Tracker.h>

Inheritance diagram for Tracking::Tracker:
Inheritance graph
[legend]

List of all members.

Classes

struct  Parameter

Public Member Functions

int addModel (TomGine::tgModel &m, TomGine::tgPose &pose, std::string label, bool bfc=true)
 Adds a geometrical model to the tracker.
int addModelFromFile (const char *filename, TomGine::tgPose &pose, std::string label, bool bfc=true)
 Adds a geometrical model from file (ply-fileformat) to the tracker.
void drawCalibrationPattern (float point_size=1.0f)
void drawCoordinates (float linelength=1.0f)
void drawCoordinateSystem (float linelength=0.5f, float linewidth=1.0f, TomGine::tgPose pose=TomGine::tgPose())
void drawImage (unsigned char *image)
void drawModel (const TomGine::tgModel &m, const TomGine::tgPose &p)
void drawModel (TomGine::tgPose p)
void drawModelWireframe (const TomGine::tgModel &m, const TomGine::tgPose &p, float linewidth=1.0f)
void drawPixel (float u, float v, vec3 color=vec3(1.0, 1.0, 1.0), float size=1.0f)
void drawPoint (float x, float y, float z, float size=1.0)
virtual void drawResult (float linewidth=1.0f)=0
 Draw all models.
void drawTest ()
virtual void drawTrackerModel (int id, const TomGine::tgPose &p, float linewidth=1.0f)
virtual void evaluatePDF (int id, float x_min, float y_min, float x_max, float y_max, int res, const char *meshfile, const char *xfile)
float getCamZFar ()
float getCamZNear ()
bool getDrawParticlesFlag ()
bool getEdgesImageFlag ()
cv::Mat getImage ()
 Returns the rendered image.
bool getLockFlag ()
void getModelConfidence (int id, float &c)
 Get mean confidence value of distribution of a model.
void getModelConfidenceColor (int id, float &c)
 Get confidence value of a model at current pose (color based comparison).
void getModelConfidenceEdge (int id, float &c)
 Get confidence value of a model at current pose (edge based comparison).
void getModelConfidenceState (int id, confidence_state &q)
 Get a tracking quality state of a model.
void getModelEdgeMask (int id, Texture &mask)
 Calculates mask produced by the geometry edges of a model.
ModelEntrygetModelEntry (int id)
 Adds a pose hypothesis to model.
void getModelInitialPose (int id, TomGine::tgPose &p)
 Get the initial pose of a model.
void getModelMask (int id, Texture &mask)
 Calculates mask produced by the geometry edges of a model.
bool getModelMaskOwnEdges (int id)
 Gets flag to mask geometry edges of model.
int getModelModeFlag ()
void getModelMovementState (int id, movement_state &m)
 Get movement state of a model.
bool getModelPoint3D (int id, int x_win, int y_win, double &x3, double &y3, double &z3)
 Get 3D point from 2D window coordinates.
void getModelPose (int id, TomGine::tgPose &p)
 Get current pose of a model.
void getModelPoseCamCoords (int id, TomGine::tgPose &p)
 Get current pose of a model in camera coordinates.
void getModelPoseLPF (int id, TomGine::tgPose &p)
 Get low pass filtered pose of a model.
void getModelQualityState (int id, quality_state &q)
 Get a tracking quality state of a model.
void getModelVelocity (int id, float &translational, float &angular)
 Get current velocity of a model ( in m/s and rad/s ).
const Parameter getParams ()
virtual std::vector< float > getPDFxy (Particle pose, float x_min, float y_min, float x_max, float y_max, int res, const char *filename=NULL, const char *filename2=NULL)
unsigned int getSpreadLvl ()
virtual void image_processing (unsigned char *image, int model_id, const TomGine::tgPose &pose, GLenum format=GL_BGR)=0
 Perform image processing with edge detection, painting the model with id as virtual object into image.
virtual void image_processing (unsigned char *image, const TomGine::tgModel &model, const TomGine::tgPose &pose, GLenum format=GL_BGR)=0
 Perform image processing with edge detection, painting a virtual object into the image.
virtual void image_processing (unsigned char *image, GLenum format=GL_BGR)=0
 Perform image processing with edge detection.
bool init (const Parameter &trackParam)
bool init (const char *trackINIFile, const char *camCalFile, const char *poseCalFile)
 Initialize tracker with an INI file and image/window width and height in pixel.
void loadCalibrationPattern (const char *mdl_file)
void loadImage (unsigned char *image, GLenum format=GL_BGR)
 Perform image processing with edge detection.
void printStatistics ()
void removeModel (int id)
 Remove model from tracker by id.
void reset (int id)
 Resets the pose of a model to the initial pose.
void reset ()
 Resets the pose of all models to the initial pose.
void resetUnlockLock ()
 Uses the reset function but also locks, calls track() and unlocks the tracker so every confidence will get updated.
void saveModel (int id, const char *pathname)
 Save model to file.
void saveModels (const char *pathname)
 Save all models to file.
virtual void savePDF (std::vector< float > vPDFMap, float x_min, float y_min, float x_max, float y_max, int res, const char *meshfile, const char *xfile)
void saveScreenshot (const char *filename)
 Takes screenshot and saves it to file.
bool setCameraParameters (TomGine::tgCamera::Parameter cam_par)
virtual void setColorShader ()
void setDrawParticlesFlag (bool val)
virtual void setEdgeShader ()
void setEdgesImageFlag (bool val)
void setFrameTime (double dTime)
virtual void setKernelSize (int val)
void setLockFlag (bool val)
void setModelInitialPose (int id, TomGine::tgPose &p)
 Set the initial pose of a model.
void setModelLock (int id, bool lock)
 Locks the model with id.
void setModelMask (int id, Texture *mask=0)
 Sets mask for a model to define edges which are not considered for the model.
void setModelMaskOwnEdges (int id, bool masked)
 Sets flag to mask geometry edges of model.
void setModelModeFlag (int val)
void setModelPredictor (int id, Predictor *predictor)
 Set a model predictor.
void setModelPredictorNoConvergence (int id, float no_conv)
 Set the number of particles (in percent) which are voting for no convergence (for capturing fast movement).
void setModelRecursionsParticle (int id, int num_recursions, int num_particles)
 Sets the number of recursions and particles used for tracking.
void setSpreadLvl (unsigned int val)
virtual void textureFromImage (int id, const TomGine::tgPose &pose, bool use_num_pixels=true)
virtual void textureFromImage (bool force=false)
 Captures image and attaches it to model as texture.
virtual bool track (int id)=0
 Tracks model by id by matching their edges against edges of images.
virtual bool track ()=0
 Tracks all models by matching their edges against edges of images.
 Tracker ()
virtual void untextureModels ()
 Remove textures from model.
 ~Tracker ()

Protected Member Functions

void computeModelEdgeMask (ModelEntry *modelEntry, Texture &mask)
void getGlError ()
bool init ()
bool initGL ()
virtual bool initInternal ()=0
bool loadCamParsFromINI (const char *camCalFile, const char *poseCalFile)
bool loadTrackParsFromINI (const char *inifile)
 Load parameter of tracker with an INI file.

Protected Attributes

std::vector< vec3m_calib_points
TomGine::tgCamera m_cam_default
TomGine::tgCamera m_cam_perspective
bool m_draw_edges
bool m_drawimage
float m_ftime
ModelEntryList m_hypotheses
ImageProcessorm_ip
TomGine::tgLighting m_lighting
bool m_lock
ModelEntryList m_modellist
int m_showmodel
bool m_showparticles
Texturem_tex_frame
std::vector< Texture * > m_tex_frame_ip
Timer m_timer
bool m_tracker_initialized
Parameter params

Detailed Description

Main class of Tracker, defining API.

Definition at line 31 of file Tracker.h.


Constructor & Destructor Documentation

Tracking::Tracker::Tracker (  ) 
Tracking::Tracker::~Tracker (  ) 

Member Function Documentation

int Tracking::Tracker::addModel ( TomGine::tgModel m,
TomGine::tgPose pose,
std::string  label,
bool  bfc = true 
)

Adds a geometrical model to the tracker.

Returns:
id of the added model (-1 if not successfull)
int Tracking::Tracker::addModelFromFile ( const char *  filename,
TomGine::tgPose pose,
std::string  label,
bool  bfc = true 
)

Adds a geometrical model from file (ply-fileformat) to the tracker.

Parameters:
filename absolute filename of the model (or relative to the execution path)
pose place where the model is initially put to
label label of the model
bfc enable/disable backfaceculling (look up OpenGL Backface Culling)
Returns:
id of the added model (-1 if not successfull)
void Tracking::Tracker::computeModelEdgeMask ( ModelEntry modelEntry,
Texture mask 
) [protected]
void Tracking::Tracker::drawCalibrationPattern ( float  point_size = 1.0f  ) 
void Tracking::Tracker::drawCoordinates ( float  linelength = 1.0f  ) 
void Tracking::Tracker::drawCoordinateSystem ( float  linelength = 0.5f,
float  linewidth = 1.0f,
TomGine::tgPose  pose = TomGine::tgPose() 
)
void Tracking::Tracker::drawImage ( unsigned char *  image  ) 
void Tracking::Tracker::drawModel ( const TomGine::tgModel m,
const TomGine::tgPose p 
)
void Tracking::Tracker::drawModel ( TomGine::tgPose  p  ) 
void Tracking::Tracker::drawModelWireframe ( const TomGine::tgModel m,
const TomGine::tgPose p,
float  linewidth = 1.0f 
)
void Tracking::Tracker::drawPixel ( float  u,
float  v,
vec3  color = vec3(1.0, 1.0, 1.0),
float  size = 1.0f 
)
void Tracking::Tracker::drawPoint ( float  x,
float  y,
float  z,
float  size = 1.0 
)
virtual void Tracking::Tracker::drawResult ( float  linewidth = 1.0f  )  [pure virtual]

Draw all models.

Implemented in Tracking::EdgeTracker, and Tracking::TextureTracker.

void Tracking::Tracker::drawTest (  ) 
virtual void Tracking::Tracker::drawTrackerModel ( int  id,
const TomGine::tgPose p,
float  linewidth = 1.0f 
) [inline, virtual]

Reimplemented in Tracking::TextureTracker.

Definition at line 220 of file Tracker.h.

virtual void Tracking::Tracker::evaluatePDF ( int  id,
float  x_min,
float  y_min,
float  x_max,
float  y_max,
int  res,
const char *  meshfile,
const char *  xfile 
) [inline, virtual]

Reimplemented in Tracking::TextureTracker.

Definition at line 260 of file Tracker.h.

float Tracking::Tracker::getCamZFar (  )  [inline]

Definition at line 244 of file Tracker.h.

float Tracking::Tracker::getCamZNear (  )  [inline]

Definition at line 243 of file Tracker.h.

bool Tracking::Tracker::getDrawParticlesFlag (  )  [inline]

Definition at line 250 of file Tracker.h.

bool Tracking::Tracker::getEdgesImageFlag (  )  [inline]

Definition at line 249 of file Tracker.h.

void Tracking::Tracker::getGlError (  )  [protected]
cv::Mat Tracking::Tracker::getImage (  ) 

Returns the rendered image.

bool Tracking::Tracker::getLockFlag (  )  [inline]

Definition at line 248 of file Tracker.h.

void Tracking::Tracker::getModelConfidence ( int  id,
float &  c 
)

Get mean confidence value of distribution of a model.

void Tracking::Tracker::getModelConfidenceColor ( int  id,
float &  c 
)

Get confidence value of a model at current pose (color based comparison).

void Tracking::Tracker::getModelConfidenceEdge ( int  id,
float &  c 
)

Get confidence value of a model at current pose (edge based comparison).

void Tracking::Tracker::getModelConfidenceState ( int  id,
confidence_state q 
)

Get a tracking quality state of a model.

void Tracking::Tracker::getModelEdgeMask ( int  id,
Texture mask 
)

Calculates mask produced by the geometry edges of a model.

ModelEntry* Tracking::Tracker::getModelEntry ( int  id  ) 

Adds a pose hypothesis to model.

DO NOT USE THIS FUNCTION!

void Tracking::Tracker::getModelInitialPose ( int  id,
TomGine::tgPose p 
)

Get the initial pose of a model.

void Tracking::Tracker::getModelMask ( int  id,
Texture mask 
)

Calculates mask produced by the geometry edges of a model.

bool Tracking::Tracker::getModelMaskOwnEdges ( int  id  ) 

Gets flag to mask geometry edges of model.

int Tracking::Tracker::getModelModeFlag (  )  [inline]

Definition at line 251 of file Tracker.h.

void Tracking::Tracker::getModelMovementState ( int  id,
movement_state m 
)

Get movement state of a model.

bool Tracking::Tracker::getModelPoint3D ( int  id,
int  x_win,
int  y_win,
double &  x3,
double &  y3,
double &  z3 
)

Get 3D point from 2D window coordinates.

void Tracking::Tracker::getModelPose ( int  id,
TomGine::tgPose p 
)

Get current pose of a model.

void Tracking::Tracker::getModelPoseCamCoords ( int  id,
TomGine::tgPose p 
)

Get current pose of a model in camera coordinates.

void Tracking::Tracker::getModelPoseLPF ( int  id,
TomGine::tgPose p 
)

Get low pass filtered pose of a model.

void Tracking::Tracker::getModelQualityState ( int  id,
quality_state q 
)

Get a tracking quality state of a model.

void Tracking::Tracker::getModelVelocity ( int  id,
float &  translational,
float &  angular 
)

Get current velocity of a model ( in m/s and rad/s ).

const Parameter Tracking::Tracker::getParams (  )  [inline]

Definition at line 278 of file Tracker.h.

virtual std::vector<float> Tracking::Tracker::getPDFxy ( Particle  pose,
float  x_min,
float  y_min,
float  x_max,
float  y_max,
int  res,
const char *  filename = NULL,
const char *  filename2 = NULL 
) [inline, virtual]

Definition at line 266 of file Tracker.h.

unsigned int Tracking::Tracker::getSpreadLvl (  )  [inline]

Definition at line 245 of file Tracker.h.

virtual void Tracking::Tracker::image_processing ( unsigned char *  image,
int  model_id,
const TomGine::tgPose pose,
GLenum  format = GL_BGR 
) [pure virtual]

Perform image processing with edge detection, painting the model with id as virtual object into image.

Parameters:
image image data
model_id id of the model
pose position and orientation of the virtual object in world space
format data format

Implemented in Tracking::EdgeTracker, and Tracking::TextureTracker.

virtual void Tracking::Tracker::image_processing ( unsigned char *  image,
const TomGine::tgModel model,
const TomGine::tgPose pose,
GLenum  format = GL_BGR 
) [pure virtual]

Perform image processing with edge detection, painting a virtual object into the image.

Parameters:
image image data
model geometry of virtual object
pose position and orientation of the virtual object in world space
format data format

Implemented in Tracking::EdgeTracker, and Tracking::TextureTracker.

virtual void Tracking::Tracker::image_processing ( unsigned char *  image,
GLenum  format = GL_BGR 
) [pure virtual]

Perform image processing with edge detection.

Parameters:
image image data
format data format

Implemented in Tracking::EdgeTracker, and Tracking::TextureTracker.

bool Tracking::Tracker::init (  )  [protected]
bool Tracking::Tracker::init ( const Parameter trackParam  ) 
bool Tracking::Tracker::init ( const char *  trackINIFile,
const char *  camCalFile,
const char *  poseCalFile 
)

Initialize tracker with an INI file and image/window width and height in pixel.

bool Tracking::Tracker::initGL (  )  [protected]
virtual bool Tracking::Tracker::initInternal (  )  [protected, pure virtual]
void Tracking::Tracker::loadCalibrationPattern ( const char *  mdl_file  ) 
bool Tracking::Tracker::loadCamParsFromINI ( const char *  camCalFile,
const char *  poseCalFile 
) [protected]
void Tracking::Tracker::loadImage ( unsigned char *  image,
GLenum  format = GL_BGR 
)

Perform image processing with edge detection.

bool Tracking::Tracker::loadTrackParsFromINI ( const char *  inifile  )  [protected]

Load parameter of tracker with an INI file.

void Tracking::Tracker::printStatistics (  ) 
void Tracking::Tracker::removeModel ( int  id  ) 

Remove model from tracker by id.

void Tracking::Tracker::reset ( int  id  ) 

Resets the pose of a model to the initial pose.

Parameters:
id the id of the model given by addModel() or addModelFromFile()
void Tracking::Tracker::reset (  ) 

Resets the pose of all models to the initial pose.

void Tracking::Tracker::resetUnlockLock (  ) 

Uses the reset function but also locks, calls track() and unlocks the tracker so every confidence will get updated.

void Tracking::Tracker::saveModel ( int  id,
const char *  pathname 
)

Save model to file.

void Tracking::Tracker::saveModels ( const char *  pathname  ) 

Save all models to file.

virtual void Tracking::Tracker::savePDF ( std::vector< float >  vPDFMap,
float  x_min,
float  y_min,
float  x_max,
float  y_max,
int  res,
const char *  meshfile,
const char *  xfile 
) [inline, virtual]

Definition at line 272 of file Tracker.h.

void Tracking::Tracker::saveScreenshot ( const char *  filename  ) 

Takes screenshot and saves it to file.

bool Tracking::Tracker::setCameraParameters ( TomGine::tgCamera::Parameter  cam_par  ) 
virtual void Tracking::Tracker::setColorShader (  )  [inline, virtual]

Reimplemented in Tracking::TextureTracker.

Definition at line 235 of file Tracker.h.

void Tracking::Tracker::setDrawParticlesFlag ( bool  val  )  [inline]

Definition at line 256 of file Tracker.h.

virtual void Tracking::Tracker::setEdgeShader (  )  [inline, virtual]

Reimplemented in Tracking::TextureTracker.

Definition at line 234 of file Tracker.h.

void Tracking::Tracker::setEdgesImageFlag ( bool  val  )  [inline]

Definition at line 255 of file Tracker.h.

void Tracking::Tracker::setFrameTime ( double  dTime  ) 
virtual void Tracking::Tracker::setKernelSize ( int  val  )  [inline, virtual]

Reimplemented in Tracking::TextureTracker.

Definition at line 233 of file Tracker.h.

void Tracking::Tracker::setLockFlag ( bool  val  ) 
void Tracking::Tracker::setModelInitialPose ( int  id,
TomGine::tgPose p 
)

Set the initial pose of a model.

void Tracking::Tracker::setModelLock ( int  id,
bool  lock 
)

Locks the model with id.

void Tracking::Tracker::setModelMask ( int  id,
Texture mask = 0 
)

Sets mask for a model to define edges which are not considered for the model.

void Tracking::Tracker::setModelMaskOwnEdges ( int  id,
bool  masked 
)

Sets flag to mask geometry edges of model.

void Tracking::Tracker::setModelModeFlag ( int  val  )  [inline]

Definition at line 257 of file Tracker.h.

void Tracking::Tracker::setModelPredictor ( int  id,
Predictor predictor 
)

Set a model predictor.

void Tracking::Tracker::setModelPredictorNoConvergence ( int  id,
float  no_conv 
)

Set the number of particles (in percent) which are voting for no convergence (for capturing fast movement).

void Tracking::Tracker::setModelRecursionsParticle ( int  id,
int  num_recursions,
int  num_particles 
)

Sets the number of recursions and particles used for tracking.

void Tracking::Tracker::setSpreadLvl ( unsigned int  val  )  [inline]

Definition at line 240 of file Tracker.h.

virtual void Tracking::Tracker::textureFromImage ( int  id,
const TomGine::tgPose pose,
bool  use_num_pixels = true 
) [inline, virtual]

Reimplemented in Tracking::TextureTracker.

Definition at line 210 of file Tracker.h.

virtual void Tracking::Tracker::textureFromImage ( bool  force = false  )  [inline, virtual]

Captures image and attaches it to model as texture.

Reimplemented in Tracking::TextureTracker.

Definition at line 209 of file Tracker.h.

virtual bool Tracking::Tracker::track ( int  id  )  [pure virtual]

Tracks model by id by matching their edges against edges of images.

Parameters:
id the id of the model given by addModel() or addModelFromFile()

Implemented in Tracking::EdgeTracker, and Tracking::TextureTracker.

virtual bool Tracking::Tracker::track (  )  [pure virtual]

Tracks all models by matching their edges against edges of images.

Implemented in Tracking::EdgeTracker, and Tracking::TextureTracker.

virtual void Tracking::Tracker::untextureModels (  )  [inline, virtual]

Remove textures from model.

Reimplemented in Tracking::TextureTracker.

Definition at line 213 of file Tracker.h.


Member Data Documentation

std::vector<vec3> Tracking::Tracker::m_calib_points [protected]

Definition at line 287 of file Tracker.h.

Definition at line 300 of file Tracker.h.

Definition at line 299 of file Tracker.h.

Definition at line 306 of file Tracker.h.

Definition at line 308 of file Tracker.h.

float Tracking::Tracker::m_ftime [protected]

Definition at line 292 of file Tracker.h.

Definition at line 297 of file Tracker.h.

Definition at line 290 of file Tracker.h.

Definition at line 289 of file Tracker.h.

bool Tracking::Tracker::m_lock [protected]

Definition at line 303 of file Tracker.h.

Definition at line 296 of file Tracker.h.

Definition at line 305 of file Tracker.h.

Definition at line 304 of file Tracker.h.

Definition at line 284 of file Tracker.h.

std::vector<Texture*> Tracking::Tracker::m_tex_frame_ip [protected]

Definition at line 285 of file Tracker.h.

Definition at line 293 of file Tracker.h.

Definition at line 307 of file Tracker.h.

Definition at line 281 of file Tracker.h.


The documentation for this class was generated from the following file:
 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:59 2013