Simulated tracker for when we already have uv measurements! More...
#include <TrackSIM.h>
Public Member Functions | |
void | feed_measurement_simulation (double timestamp, const std::vector< int > &camids, const std::vector< std::vector< std::pair< size_t, Eigen::VectorXf >>> &feats) |
Feed function for a synchronized simulated cameras. More... | |
void | feed_new_camera (const CameraData &message) override |
Process a new image. More... | |
TrackSIM (std::unordered_map< size_t, std::shared_ptr< CamBase >> cameras, int numaruco) | |
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< FeatureDatabase > | get_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 () |
Additional Inherited Members | |
Public Types inherited from ov_core::TrackBase | |
enum | HistogramMethod { NONE, HISTOGRAM, CLAHE } |
Desired pre-processing image method. More... | |
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< FeatureDatabase > | database |
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... | |
Simulated tracker for when we already have uv measurements!
This class should be used when we are using the ov_msckf::Simulator class to generate measurements. It simply takes the resulting simulation data and appends it to the internal feature database.
Definition at line 35 of file TrackSIM.h.
|
inline |
Public constructor with configuration variables.
cameras | camera calibration object which has all camera intrinsics in it |
numaruco | the max id of the arucotags, so we ensure that we start our non-auroc features above this value |
Definition at line 43 of file TrackSIM.h.
void TrackSIM::feed_measurement_simulation | ( | double | timestamp, |
const std::vector< int > & | camids, | ||
const std::vector< std::vector< std::pair< size_t, Eigen::VectorXf >>> & | feats | ||
) |
Feed function for a synchronized simulated cameras.
timestamp | Time that this image was collected |
camids | Camera ids that we have simulated measurements for |
feats | Raw uv simulated measurements |
Definition at line 30 of file TrackSIM.cpp.
|
inlineoverridevirtual |
Process a new image.
message | Contains our timestamp, images, and camera ids |
Implements ov_core::TrackBase.
Definition at line 51 of file TrackSIM.h.