SLProject  4.2.000
A platform independent 3D computer graphics framework for desktop OS, Android, iOS and online in web browsers
CVTrackedWAI Class Reference

Tracker that uses the ORB-Slam based WAI library (Where Am I) More...

#include <CVTrackedWAI.h>

Inheritance diagram for CVTrackedWAI:
[legend]

Public Member Functions

 CVTrackedWAI (const string &vocabularyFile)
 
 ~CVTrackedWAI () override
 
bool track (CVMat imageGray, CVMat imageBgr, CVCalibration *calib) final
 
- Public Member Functions inherited from CVTracked
 CVTracked ()
 
virtual ~CVTracked ()=default
 
void drawDetection (bool draw)
 
bool isVisible ()
 
bool drawDetection ()
 
CVMatx44f objectViewMat ()
 

Private Attributes

WAISlam_waiSlamer = nullptr
 
ORB_SLAM2::ORBextractor * _trackingExtractor = nullptr
 
ORB_SLAM2::ORBextractor * _initializationExtractor = nullptr
 
WAIOrbVocabulary_voc
 

Additional Inherited Members

- Static Public Member Functions inherited from CVTracked
static cv::Matx44f createGLMatrix (const CVMat &tVec, const CVMat &rVec)
 Create an OpenGL 4x4 matrix from an OpenCV translation & rotation vector. More...
 
static void createRvecTvec (const CVMatx44f &glMat, CVMat &tVec, CVMat &rVec)
 Creates the OpenCV rvec & tvec vectors from an column major OpenGL 4x4 matrix. More...
 
static CVMatx44f calcObjectMatrix (const CVMatx44f &cameraObjectMat, const CVMatx44f &objectViewMat)
 
static CVVec3f averageVector (vector< CVVec3f > vectors, vector< float > weights)
 
static SLQuat4f averageQuaternion (vector< SLQuat4f > quaternions, vector< float > weights)
 
static void resetTimes ()
 Resets all static variables. More...
 
- Static Public Attributes inherited from CVTracked
static AvgFloat trackingTimesMS
 Averaged time for video tracking in ms. More...
 
static AvgFloat detectTimesMS
 Averaged time for video feature detection & description in ms. More...
 
static AvgFloat detect1TimesMS
 Averaged time for video feature detection subpart 1 in ms. More...
 
static AvgFloat detect2TimesMS
 Averaged time for video feature detection subpart 2 in ms. More...
 
static AvgFloat matchTimesMS
 Averaged time for video feature matching in ms. More...
 
static AvgFloat optFlowTimesMS
 Averaged time for video feature optical flow tracking in ms. More...
 
static AvgFloat poseTimesMS
 Averaged time for video feature pose estimation in ms. More...
 
- Protected Attributes inherited from CVTracked
bool _isVisible
 Flag if marker is visible. More...
 
bool _drawDetection
 Flag if detection should be drawn into image. More...
 
CVMatx44f _objectViewMat
 view transformation matrix More...
 
HighResTimer _timer
 High resolution timer. More...
 

Detailed Description

Tracker that uses the ORB-Slam based WAI library (Where Am I)

Definition at line 25 of file CVTrackedWAI.h.

Constructor & Destructor Documentation

◆ CVTrackedWAI()

CVTrackedWAI::CVTrackedWAI ( const string &  vocabularyFile)
explicit

Definition at line 15 of file CVTrackedWAI.cpp.

16 {
17  _voc = new WAIOrbVocabulary();
18  float startMS = _timer.elapsedTimeInMilliSec();
19 
20  try
21  {
22  _voc->loadFromFile(vocabularyFile);
23  }
24  catch (std::exception& e)
25  {
26  Utils::log("SLProject",
27  "Could not open the ORB vocabulary file: %s",
28  e.what());
29  exit(0);
30  }
31  SL_LOG_DEBUG("Loaded voc file : %f ms", _timer.elapsedTimeInMilliSec() - startMS);
32 }
#define SL_LOG_DEBUG(...)
Definition: SL.h:237
HighResTimer _timer
High resolution timer.
Definition: CVTracked.h:94
WAIOrbVocabulary * _voc
Definition: CVTrackedWAI.h:39
float elapsedTimeInMilliSec()
Definition: HighResTimer.h:38
void loadFromFile(std::string strVocFile)
void log(const char *tag, const char *format,...)
logs a formatted string platform independently
Definition: Utils.cpp:1103

◆ ~CVTrackedWAI()

CVTrackedWAI::~CVTrackedWAI ( )
override

Definition at line 34 of file CVTrackedWAI.cpp.

35 {
36  delete _trackingExtractor;
37  delete _waiSlamer;
38 }
ORB_SLAM2::ORBextractor * _trackingExtractor
Definition: CVTrackedWAI.h:37
WAISlam * _waiSlamer
Definition: CVTrackedWAI.h:36

Member Function Documentation

◆ track()

bool CVTrackedWAI::track ( CVMat  imageGray,
CVMat  imageBgr,
CVCalibration calib 
)
finalvirtual

This function is called every frame in the apps onUpdateVideo function. It uses the on-the-fly built 3D point cloud generated by the ORB-SLAM2 library that is integrated within the lib-WAI. It only works well if the camera is calibrated.

Parameters
imageGrayImage for processing
imageBgrImage for visualizations
calibPointer to a valid camera calibration
Returns
returns true if pose estimation was successful

Implements CVTracked.

Definition at line 49 of file CVTrackedWAI.cpp.

52 {
54 
55  bool result = false;
56 
57  float startMS = _timer.elapsedTimeInMilliSec();
58 
59  if (!_waiSlamer)
60  {
61  if (_voc == nullptr)
62  return false;
63 
64  int nf = 1000; // NO. of features
65  float fScaleFactor = 1.2f; // Scale factor for pyramid construction
66  int nLevels = 8; // NO. of pyramid levels
67  int fIniThFAST = 20; // Init threshold for FAST corner detector
68  int fMinThFAST = 7; // Min. threshold for FAST corner detector
69  _trackingExtractor = new ORB_SLAM2::ORBextractor(nf,
70  fScaleFactor,
71  nLevels,
72  fIniThFAST,
73  fMinThFAST);
74 
75  _initializationExtractor = new ORB_SLAM2::ORBextractor(2 * nf,
76  fScaleFactor,
77  nLevels,
78  fIniThFAST,
79  fMinThFAST);
80 
81  WAISlam::Params params;
82  params.cullRedundantPerc = 0.95f;
83  params.ensureKFIntegration = false;
84  params.fixOldKfs = false;
85  params.onlyTracking = false;
86  params.retainImg = false;
87  params.serial = false;
88  params.trackOptFlow = false;
89 
90  _waiSlamer = new WAISlam(calib->cameraMat(),
91  calib->distortion(),
92  _voc,
96  nullptr, // global map
97  params);
98  }
99 
100  if (_waiSlamer->update(imageGray))
101  {
102  cv::Mat pose = _waiSlamer->getPose();
103 
104  // ORB-SLAM uses a right handed Y-down coordinate system
105  // SLProject uses a right handed Y-Up coordinate system
106  cv::Mat rot = cv::Mat::eye(4, 4, CV_32F);
107  rot.at<float>(1, 1) = -1.0f; // mirror y-axis
108  rot.at<float>(2, 2) = -1.0f; // mirror z-axis
109 
110  pose = rot * pose;
111 
112  pose.copyTo(_objectViewMat);
113 
114  result = true;
115  }
116 
117  if (_drawDetection)
118  {
119  _waiSlamer->drawInfo(imageBgr, 1.0f, true, true, true);
120  }
121 
122  // TODO(dgj1): at the moment we cant differentiate between these two
123  // as they are both done in the same call to WAI
126 
127  return result;
128 }
#define PROFILE_FUNCTION()
Definition: Instrumentor.h:41
const CVMat & cameraMat() const
const CVMat & distortion() const
CVMatx44f _objectViewMat
view transformation matrix
Definition: CVTracked.h:93
static AvgFloat detectTimesMS
Averaged time for video feature detection & description in ms.
Definition: CVTracked.h:83
bool _drawDetection
Flag if detection should be drawn into image.
Definition: CVTracked.h:92
static AvgFloat poseTimesMS
Averaged time for video feature pose estimation in ms.
Definition: CVTracked.h:88
ORB_SLAM2::ORBextractor * _initializationExtractor
Definition: CVTrackedWAI.h:38
void set(T value)
Sets the current value in the value array and builds the average.
Definition: Averaged.h:53
virtual bool update(cv::Mat &imageGray)
Definition: WAISlam.cpp:471
virtual cv::Mat getPose()
Definition: WAISlam.cpp:551
virtual void drawInfo(cv::Mat &imageBGR, float scale, bool showInitLine, bool showKeyPoints, bool showKeyPointsMatched)
Definition: WAISlam.cpp:488
bool ensureKFIntegration
Definition: WAISlam.h:32
bool fixOldKfs
Definition: WAISlam.h:41
bool trackOptFlow
Definition: WAISlam.h:43
bool retainImg
Definition: WAISlam.h:36
float cullRedundantPerc
Definition: WAISlam.h:48
bool onlyTracking
Definition: WAISlam.h:38

Member Data Documentation

◆ _initializationExtractor

ORB_SLAM2::ORBextractor* CVTrackedWAI::_initializationExtractor = nullptr
private

Definition at line 38 of file CVTrackedWAI.h.

◆ _trackingExtractor

ORB_SLAM2::ORBextractor* CVTrackedWAI::_trackingExtractor = nullptr
private

Definition at line 37 of file CVTrackedWAI.h.

◆ _voc

WAIOrbVocabulary* CVTrackedWAI::_voc
private

Definition at line 39 of file CVTrackedWAI.h.

◆ _waiSlamer

WAISlam* CVTrackedWAI::_waiSlamer = nullptr
private

Definition at line 36 of file CVTrackedWAI.h.


The documentation for this class was generated from the following files: