Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
ov_core::TrackDescriptor Class Reference

Descriptor-based visual tracking. More...

#include <TrackDescriptor.h>

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

Public Member Functions

void feed_new_camera (const CameraData &message) override
 Process a new image. More...
 
 TrackDescriptor (std::unordered_map< size_t, std::shared_ptr< CamBase >> cameras, int numfeats, int numaruco, bool stereo, HistogramMethod histmethod, int fast_threshold, int gridx, int gridy, int minpxdist, double knnratio)
 Public constructor with configuration variables. More...
 
- Public Member Functions inherited from ov_core::TrackBase
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...
 
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 Member Functions

void feed_monocular (const CameraData &message, size_t msg_id)
 Process a new monocular image. More...
 
void feed_stereo (const CameraData &message, size_t msg_id_left, size_t msg_id_right)
 Process new stereo pair of images. More...
 
void perform_detection_monocular (const cv::Mat &img0, const cv::Mat &mask0, std::vector< cv::KeyPoint > &pts0, cv::Mat &desc0, std::vector< size_t > &ids0)
 Detects new features in the current image. More...
 
void perform_detection_stereo (const cv::Mat &img0, const cv::Mat &img1, const cv::Mat &mask0, const cv::Mat &mask1, std::vector< cv::KeyPoint > &pts0, std::vector< cv::KeyPoint > &pts1, cv::Mat &desc0, cv::Mat &desc1, size_t cam_id0, size_t cam_id1, std::vector< size_t > &ids0, std::vector< size_t > &ids1)
 Detects new features in the current stereo pair. More...
 
void robust_match (const std::vector< cv::KeyPoint > &pts0, const std::vector< cv::KeyPoint > &pts1, const cv::Mat &desc0, const cv::Mat &desc1, size_t id0, size_t id1, std::vector< cv::DMatch > &matches)
 Find matches between two keypoint+descriptor sets. More...
 
void robust_ratio_test (std::vector< std::vector< cv::DMatch >> &matches)
 
void robust_symmetry_test (std::vector< std::vector< cv::DMatch >> &matches1, std::vector< std::vector< cv::DMatch >> &matches2, std::vector< cv::DMatch > &good_matches)
 

Protected Attributes

std::unordered_map< size_t, cv::Mat > desc_last
 
int grid_x
 
int grid_y
 
double knn_ratio
 
cv::Ptr< cv::DescriptorMatcher > matcher = cv::DescriptorMatcher::create("BruteForce-Hamming")
 
int min_px_dist
 
cv::Ptr< cv::ORB > orb0 = cv::ORB::create()
 
cv::Ptr< cv::ORB > orb1 = cv::ORB::create()
 
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
 
int threshold
 
- Protected Attributes inherited from ov_core::TrackBase
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...
 

Additional Inherited Members

- Public Types inherited from ov_core::TrackBase
enum  HistogramMethod { NONE, HISTOGRAM, CLAHE }
 Desired pre-processing image method. More...
 

Detailed Description

Descriptor-based visual tracking.

Here we use descriptor matching to track features from one frame to the next. We track both temporally, and across stereo pairs to get stereo constraints. Right now we use ORB descriptors as we have found it is the fastest when computing descriptors. Tracks are then rejected based on a ratio test and ransac.

Definition at line 37 of file TrackDescriptor.h.

Constructor & Destructor Documentation

◆ TrackDescriptor()

ov_core::TrackDescriptor::TrackDescriptor ( std::unordered_map< size_t, std::shared_ptr< CamBase >>  cameras,
int  numfeats,
int  numaruco,
bool  stereo,
HistogramMethod  histmethod,
int  fast_threshold,
int  gridx,
int  gridy,
int  minpxdist,
double  knnratio 
)
inlineexplicit

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?)
fast_thresholdFAST detection threshold
gridxsize of grid in the x-direction / u-direction
gridysize of grid in the y-direction / v-direction
minpxdistfeatures need to be at least this number pixels away from each other
knnratiomatching ratio needed (smaller value forces top two descriptors during match to be more different)

Definition at line 53 of file TrackDescriptor.h.

Member Function Documentation

◆ feed_monocular()

void TrackDescriptor::feed_monocular ( const CameraData message,
size_t  msg_id 
)
protected

Process a new monocular image.

Parameters
messageContains our timestamp, images, and camera ids
msg_idthe camera index in message data vector

Definition at line 63 of file TrackDescriptor.cpp.

◆ feed_new_camera()

void TrackDescriptor::feed_new_camera ( const CameraData message)
overridevirtual

Process a new image.

Parameters
messageContains our timestamp, images, and camera ids

Implements ov_core::TrackBase.

Definition at line 33 of file TrackDescriptor.cpp.

◆ feed_stereo()

void TrackDescriptor::feed_stereo ( const CameraData message,
size_t  msg_id_left,
size_t  msg_id_right 
)
protected

Process new stereo pair of images.

Parameters
messageContains our timestamp, images, and camera ids
msg_id_leftfirst image index in message data vector
msg_id_rightsecond image index in message data vector

Definition at line 180 of file TrackDescriptor.cpp.

◆ perform_detection_monocular()

void TrackDescriptor::perform_detection_monocular ( const cv::Mat &  img0,
const cv::Mat &  mask0,
std::vector< cv::KeyPoint > &  pts0,
cv::Mat &  desc0,
std::vector< size_t > &  ids0 
)
protected

Detects new features in the current image.

Parameters
img0image we will detect features on
mask0mask which has what ROI we do not want features in
pts0vector of extracted keypoints
desc0vector of the extracted descriptors
ids0vector of all new IDs

Given a set of images, and their currently extracted features, this will try to add new features. We return all extracted descriptors here since we DO NOT need to do stereo tracking left to right. Our vector of IDs will be later overwritten when we match features temporally to the previous frame's features. See robust_match() for the matching.

Definition at line 355 of file TrackDescriptor.cpp.

◆ perform_detection_stereo()

void TrackDescriptor::perform_detection_stereo ( const cv::Mat &  img0,
const cv::Mat &  img1,
const cv::Mat &  mask0,
const cv::Mat &  mask1,
std::vector< cv::KeyPoint > &  pts0,
std::vector< cv::KeyPoint > &  pts1,
cv::Mat &  desc0,
cv::Mat &  desc1,
size_t  cam_id0,
size_t  cam_id1,
std::vector< size_t > &  ids0,
std::vector< size_t > &  ids1 
)
protected

Detects new features in the current stereo pair.

Parameters
img0left image we will detect features on
img1right image we will detect features on
mask0mask which has what ROI we do not want features in
mask1mask which has what ROI we do not want features in
pts0left vector of new keypoints
pts1right vector of new keypoints
desc0left vector of extracted descriptors
desc1left vector of extracted descriptors
cam_id0id of the first camera
cam_id1id of the second camera
ids0left vector of all new IDs
ids1right vector of all new IDs

This does the same logic as the perform_detection_monocular() function, but we also enforce stereo contraints. We also do STEREO matching from the left to right, and only return good matches that are found in both the left and right. Our vector of IDs will be later overwritten when we match features temporally to the previous frame's features. See robust_match() for the matching.

Definition at line 403 of file TrackDescriptor.cpp.

◆ robust_match()

void TrackDescriptor::robust_match ( const std::vector< cv::KeyPoint > &  pts0,
const std::vector< cv::KeyPoint > &  pts1,
const cv::Mat &  desc0,
const cv::Mat &  desc1,
size_t  id0,
size_t  id1,
std::vector< cv::DMatch > &  matches 
)
protected

Find matches between two keypoint+descriptor sets.

Parameters
pts0first vector of keypoints
pts1second vector of keypoints
desc0first vector of descriptors
desc1second vector of decriptors
id0id of the first camera
id1id of the second camera
matchesvector of matches that we have found

This will perform a "robust match" between the two sets of points (slow but has great results). First we do a simple KNN match from 1to2 and 2to1, which is followed by a ratio check and symmetry check. Original code is from the "RobustMatcher" in the opencv examples, and seems to give very good results in the matches. https://github.com/opencv/opencv/blob/master/samples/cpp/tutorial_code/calib3d/real_time_pose_estimation/src/RobustMatcher.cpp

Definition at line 480 of file TrackDescriptor.cpp.

◆ robust_ratio_test()

void TrackDescriptor::robust_ratio_test ( std::vector< std::vector< cv::DMatch >> &  matches)
protected

Definition at line 538 of file TrackDescriptor.cpp.

◆ robust_symmetry_test()

void TrackDescriptor::robust_symmetry_test ( std::vector< std::vector< cv::DMatch >> &  matches1,
std::vector< std::vector< cv::DMatch >> &  matches2,
std::vector< cv::DMatch > &  good_matches 
)
protected

Definition at line 554 of file TrackDescriptor.cpp.

Member Data Documentation

◆ desc_last

std::unordered_map<size_t, cv::Mat> ov_core::TrackDescriptor::desc_last
protected

Definition at line 168 of file TrackDescriptor.h.

◆ grid_x

int ov_core::TrackDescriptor::grid_x
protected

Definition at line 157 of file TrackDescriptor.h.

◆ grid_y

int ov_core::TrackDescriptor::grid_y
protected

Definition at line 158 of file TrackDescriptor.h.

◆ knn_ratio

double ov_core::TrackDescriptor::knn_ratio
protected

Definition at line 165 of file TrackDescriptor.h.

◆ matcher

cv::Ptr<cv::DescriptorMatcher> ov_core::TrackDescriptor::matcher = cv::DescriptorMatcher::create("BruteForce-Hamming")
protected

Definition at line 153 of file TrackDescriptor.h.

◆ min_px_dist

int ov_core::TrackDescriptor::min_px_dist
protected

Definition at line 161 of file TrackDescriptor.h.

◆ orb0

cv::Ptr<cv::ORB> ov_core::TrackDescriptor::orb0 = cv::ORB::create()
protected

Definition at line 149 of file TrackDescriptor.h.

◆ orb1

cv::Ptr<cv::ORB> ov_core::TrackDescriptor::orb1 = cv::ORB::create()
protected

Definition at line 150 of file TrackDescriptor.h.

◆ rT1

boost::posix_time::ptime ov_core::TrackDescriptor::rT1
protected

Definition at line 146 of file TrackDescriptor.h.

◆ rT2

boost::posix_time::ptime ov_core::TrackDescriptor::rT2
protected

Definition at line 146 of file TrackDescriptor.h.

◆ rT3

boost::posix_time::ptime ov_core::TrackDescriptor::rT3
protected

Definition at line 146 of file TrackDescriptor.h.

◆ rT4

boost::posix_time::ptime ov_core::TrackDescriptor::rT4
protected

Definition at line 146 of file TrackDescriptor.h.

◆ rT5

boost::posix_time::ptime ov_core::TrackDescriptor::rT5
protected

Definition at line 146 of file TrackDescriptor.h.

◆ rT6

boost::posix_time::ptime ov_core::TrackDescriptor::rT6
protected

Definition at line 146 of file TrackDescriptor.h.

◆ rT7

boost::posix_time::ptime ov_core::TrackDescriptor::rT7
protected

Definition at line 146 of file TrackDescriptor.h.

◆ threshold

int ov_core::TrackDescriptor::threshold
protected

Definition at line 156 of file TrackDescriptor.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 Dec 16 2024 03:06:46