Public Types | Public Member Functions | Protected Attributes | List of all members
ov_core::TrackBase Class Referenceabstract

Visual feature tracking base class. More...

#include <TrackBase.h>

Inheritance diagram for ov_core::TrackBase:
Inheritance graph
[legend]

Public Types

enum  HistogramMethod { NONE, HISTOGRAM, CLAHE }
 Desired pre-processing image method. More...
 

Public Member Functions

void change_feat_id (size_t id_old, size_t id_new)
 Changes the ID of an actively tracked feature to another one. More...
 
virtual void display_active (cv::Mat &img_out, int r1, int g1, int b1, int r2, int g2, int b2, std::string overlay="")
 Shows features extracted in the last image. More...
 
virtual void display_history (cv::Mat &img_out, int r1, int g1, int b1, int r2, int g2, int b2, std::vector< size_t > highlighted={}, std::string overlay="")
 Shows a "trail" for each feature (i.e. its history) More...
 
virtual void feed_new_camera (const CameraData &message)=0
 Process a new image. More...
 
std::shared_ptr< FeatureDatabaseget_feature_database ()
 Get the feature database with all the track information. More...
 
std::unordered_map< size_t, std::vector< size_t > > get_last_ids ()
 Getter method for active features in the last frame (ids per camera) More...
 
std::unordered_map< size_t, std::vector< cv::KeyPoint > > get_last_obs ()
 Getter method for active features in the last frame (observations per camera) More...
 
int get_num_features ()
 Getter method for number of active features. More...
 
void set_num_features (int _num_features)
 Setter method for number of active features. More...
 
 TrackBase (std::unordered_map< size_t, std::shared_ptr< CamBase >> cameras, int numfeats, int numaruco, bool stereo, HistogramMethod histmethod)
 Public constructor with configuration variables. More...
 
virtual ~TrackBase ()
 

Protected Attributes

std::unordered_map< size_t, std::shared_ptr< CamBase > > camera_calib
 Camera object which has all calibration in it. More...
 
std::map< size_t, bool > camera_fisheye
 If we are a fisheye model or not. More...
 
std::atomic< size_t > currid
 Master ID for this tracker (atomic to allow for multi-threading) More...
 
std::shared_ptr< FeatureDatabasedatabase
 Database with all our current features. More...
 
HistogramMethod histogram_method
 What histogram equalization method we should pre-process images with? More...
 
std::unordered_map< size_t, std::vector< size_t > > ids_last
 Set of IDs of each current feature in the database. More...
 
std::map< size_t, cv::Mat > img_last
 Last set of images (use map so all trackers render in the same order) More...
 
std::map< size_t, cv::Mat > img_mask_last
 Last set of images (use map so all trackers render in the same order) More...
 
std::vector< std::mutex > mtx_feeds
 Mutexs for our last set of image storage (img_last, pts_last, and ids_last) More...
 
std::mutex mtx_last_vars
 Mutex for editing the *_last variables. More...
 
int num_features
 Number of features we should try to track frame to frame. More...
 
std::unordered_map< size_t, std::vector< cv::KeyPoint > > pts_last
 Last set of tracked points. More...
 
boost::posix_time::ptime rT1
 
boost::posix_time::ptime rT2
 
boost::posix_time::ptime rT3
 
boost::posix_time::ptime rT4
 
boost::posix_time::ptime rT5
 
boost::posix_time::ptime rT6
 
boost::posix_time::ptime rT7
 
bool use_stereo
 If we should use binocular tracking or stereo tracking for multi-camera. More...
 

Detailed Description

Visual feature tracking base class.

This is the base class for all our visual trackers. The goal here is to provide a common interface so all underlying trackers can simply hide away all the complexities. We have something called the "feature database" which has all the tracking information inside of it. The user can ask this database for features which can then be used in an MSCKF or batch-based setting. The feature tracks store both the raw (distorted) and undistorted/normalized values. Right now we just support two camera models, see: undistort_point_brown() and undistort_point_fisheye().

@m_class{m-note m-warning}

A Note on Multi-Threading Support
There is some support for asynchronous multi-threaded feature tracking of independent cameras. The key assumption during implementation is that the user will not try to track on the same camera in parallel, and instead call on different cameras. For example, if I have two cameras, I can either sequentially call the feed function, or I spin each of these into separate threads and wait for their return. The currid is atomic to allow for multiple threads to access it without issue and ensure that all features have unique id values. We also have mutex for access for the calibration and previous images and tracks (used during visualization). It should be noted that if a thread calls visualization, it might hang or the feed thread might, due to acquiring the mutex for that specific camera id / feed.

This base class also handles most of the heavy lifting with the visualization, but the sub-classes can override this and do their own logic if they want (i.e. the TrackAruco has its own logic for visualization). This visualization needs access to the prior images and their tracks, thus must synchronise in the case of multi-threading. This shouldn't impact performance, but high frequency visualization calls can negatively effect the performance.

Definition at line 72 of file TrackBase.h.

Member Enumeration Documentation

◆ HistogramMethod

Desired pre-processing image method.

Enumerator
NONE 
HISTOGRAM 
CLAHE 

Definition at line 78 of file TrackBase.h.

Constructor & Destructor Documentation

◆ TrackBase()

TrackBase::TrackBase ( std::unordered_map< size_t, std::shared_ptr< CamBase >>  cameras,
int  numfeats,
int  numaruco,
bool  stereo,
HistogramMethod  histmethod 
)

Public constructor with configuration variables.

Parameters
camerascamera calibration object which has all camera intrinsics in it
numfeatsnumber of features we want want to track (i.e. track 200 points from frame to frame)
numarucothe max id of the arucotags, so we ensure that we start our non-auroc features above this value
stereoif we should do stereo feature tracking or binocular
histmethodwhat type of histogram pre-processing should be done (histogram eq?)

Definition at line 30 of file TrackBase.cpp.

◆ ~TrackBase()

virtual ov_core::TrackBase::~TrackBase ( )
inlinevirtual

Definition at line 91 of file TrackBase.h.

Member Function Documentation

◆ change_feat_id()

void TrackBase::change_feat_id ( size_t  id_old,
size_t  id_new 
)

Changes the ID of an actively tracked feature to another one.

This function can be helpfull if you detect a loop-closure with an old frame. One could then change the id of an active feature to match the old feature id!

Parameters
id_oldOld id we want to change
id_newId we want to change the old id to

Definition at line 230 of file TrackBase.cpp.

◆ display_active()

void TrackBase::display_active ( cv::Mat &  img_out,
int  r1,
int  g1,
int  b1,
int  r2,
int  g2,
int  b2,
std::string  overlay = "" 
)
virtual

Shows features extracted in the last image.

Parameters
img_outimage to which we will overlayed features on
r1,g1,b1first color to draw in
r2,g2,b2second color to draw in
overlayText overlay to replace to normal "cam0" in the top left of screen

Definition at line 43 of file TrackBase.cpp.

◆ display_history()

void TrackBase::display_history ( cv::Mat &  img_out,
int  r1,
int  g1,
int  b1,
int  r2,
int  g2,
int  b2,
std::vector< size_t >  highlighted = {},
std::string  overlay = "" 
)
virtual

Shows a "trail" for each feature (i.e. its history)

Parameters
img_outimage to which we will overlayed features on
r1,g1,b1first color to draw in
r2,g2,b2second color to draw in
highlightedunique ids which we wish to highlight (e.g. slam feats)
overlayText overlay to replace to normal "cam0" in the top left of screen

Definition at line 119 of file TrackBase.cpp.

◆ feed_new_camera()

virtual void ov_core::TrackBase::feed_new_camera ( const CameraData message)
pure virtual

Process a new image.

Parameters
messageContains our timestamp, images, and camera ids

Implemented in ov_core::TrackAruco, ov_core::TrackKLT, ov_core::TrackDescriptor, and ov_core::TrackSIM.

◆ get_feature_database()

std::shared_ptr<FeatureDatabase> ov_core::TrackBase::get_feature_database ( )
inline

Get the feature database with all the track information.

Returns
FeatureDatabase pointer that one can query for features

Definition at line 123 of file TrackBase.h.

◆ get_last_ids()

std::unordered_map<size_t, std::vector<size_t> > ov_core::TrackBase::get_last_ids ( )
inline

Getter method for active features in the last frame (ids per camera)

Definition at line 143 of file TrackBase.h.

◆ get_last_obs()

std::unordered_map<size_t, std::vector<cv::KeyPoint> > ov_core::TrackBase::get_last_obs ( )
inline

Getter method for active features in the last frame (observations per camera)

Definition at line 137 of file TrackBase.h.

◆ get_num_features()

int ov_core::TrackBase::get_num_features ( )
inline

Getter method for number of active features.

Definition at line 149 of file TrackBase.h.

◆ set_num_features()

void ov_core::TrackBase::set_num_features ( int  _num_features)
inline

Setter method for number of active features.

Definition at line 152 of file TrackBase.h.

Member Data Documentation

◆ camera_calib

std::unordered_map<size_t, std::shared_ptr<CamBase> > ov_core::TrackBase::camera_calib
protected

Camera object which has all calibration in it.

Definition at line 156 of file TrackBase.h.

◆ camera_fisheye

std::map<size_t, bool> ov_core::TrackBase::camera_fisheye
protected

If we are a fisheye model or not.

Definition at line 162 of file TrackBase.h.

◆ currid

std::atomic<size_t> ov_core::TrackBase::currid
protected

Master ID for this tracker (atomic to allow for multi-threading)

Definition at line 192 of file TrackBase.h.

◆ database

std::shared_ptr<FeatureDatabase> ov_core::TrackBase::database
protected

Database with all our current features.

Definition at line 159 of file TrackBase.h.

◆ histogram_method

HistogramMethod ov_core::TrackBase::histogram_method
protected

What histogram equalization method we should pre-process images with?

Definition at line 171 of file TrackBase.h.

◆ ids_last

std::unordered_map<size_t, std::vector<size_t> > ov_core::TrackBase::ids_last
protected

Set of IDs of each current feature in the database.

Definition at line 189 of file TrackBase.h.

◆ img_last

std::map<size_t, cv::Mat> ov_core::TrackBase::img_last
protected

Last set of images (use map so all trackers render in the same order)

Definition at line 180 of file TrackBase.h.

◆ img_mask_last

std::map<size_t, cv::Mat> ov_core::TrackBase::img_mask_last
protected

Last set of images (use map so all trackers render in the same order)

Definition at line 183 of file TrackBase.h.

◆ mtx_feeds

std::vector<std::mutex> ov_core::TrackBase::mtx_feeds
protected

Mutexs for our last set of image storage (img_last, pts_last, and ids_last)

Definition at line 174 of file TrackBase.h.

◆ mtx_last_vars

std::mutex ov_core::TrackBase::mtx_last_vars
protected

Mutex for editing the *_last variables.

Definition at line 177 of file TrackBase.h.

◆ num_features

int ov_core::TrackBase::num_features
protected

Number of features we should try to track frame to frame.

Definition at line 165 of file TrackBase.h.

◆ pts_last

std::unordered_map<size_t, std::vector<cv::KeyPoint> > ov_core::TrackBase::pts_last
protected

Last set of tracked points.

Definition at line 186 of file TrackBase.h.

◆ rT1

boost::posix_time::ptime ov_core::TrackBase::rT1
protected

Definition at line 195 of file TrackBase.h.

◆ rT2

boost::posix_time::ptime ov_core::TrackBase::rT2
protected

Definition at line 195 of file TrackBase.h.

◆ rT3

boost::posix_time::ptime ov_core::TrackBase::rT3
protected

Definition at line 195 of file TrackBase.h.

◆ rT4

boost::posix_time::ptime ov_core::TrackBase::rT4
protected

Definition at line 195 of file TrackBase.h.

◆ rT5

boost::posix_time::ptime ov_core::TrackBase::rT5
protected

Definition at line 195 of file TrackBase.h.

◆ rT6

boost::posix_time::ptime ov_core::TrackBase::rT6
protected

Definition at line 195 of file TrackBase.h.

◆ rT7

boost::posix_time::ptime ov_core::TrackBase::rT7
protected

Definition at line 195 of file TrackBase.h.

◆ use_stereo

bool ov_core::TrackBase::use_stereo
protected

If we should use binocular tracking or stereo tracking for multi-camera.

Definition at line 168 of file TrackBase.h.


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


ov_core
Author(s): Patrick Geneva , Kevin Eckenhoff , Guoquan Huang
autogenerated on Mon Jan 22 2024 03:08:17