Interface to be implemented by feature trackers It derives from the RecursiveEstimator interface. More...
#include <FeatureTracker.h>
Public Member Functions | |
virtual void | correctState ()=0 |
Corrects the predicted state(s). First we track the features using both the prediction with the system model (copy of the previous feature locations) and if there is a prediction from the higher level (RBT) we track features using it too. We then decide which prediction is the "most likely" based on the quality measurement that the feature tracker returns and use the new location to update the belief state. More... | |
FeatureTracker (double loop_period_ns) | |
Default constructor. More... | |
virtual cv_bridge::CvImagePtr | getDepthEdgesImg () |
virtual cv_bridge::CvImagePtr | getDepthImg () |
virtual cv_bridge::CvImagePtr | getDetectingMaskImg () |
virtual cv_bridge::CvImagePtr | getPredictedAndLastFeaturesImg () |
virtual cv_bridge::CvImagePtr | getPredictingMaskImg () |
virtual cv_bridge::CvImagePtr | getRGBImg () |
virtual ft_state_t | getState () const =0 |
virtual cv_bridge::CvImagePtr | getTrackedFeaturesImg () |
virtual cv_bridge::CvImagePtr | getTrackedFeaturesWithPredictionMaskImg () |
virtual cv_bridge::CvImagePtr | getTrackingMaskImg () |
virtual void | predictState (double time_interval_ns)=0 |
First step when updating the filter. The next state is predicted from current state and system model (part of the RecursiveEstimatorInterace) In the FeatureTracker the system model is the most simple one: no change in the state. So the predicted state is just the current state. More... | |
virtual void | setCameraInfoMsg (const sensor_msgs::CameraInfo *camera_info) |
virtual void | setDynamicReconfigureValues (feature_tracker::FeatureTrackerDynReconfConfig &config)=0 |
virtual void | setFullRGBDPC (PointCloudPCL::ConstPtr full_rgb_pc) |
virtual void | setOcclusionMaskImg (cv_bridge::CvImagePtr occ_mask_img) |
virtual | ~FeatureTracker () |
Default destructor (empty) More... | |
Public Member Functions inherited from omip::RecursiveEstimatorFilterInterface< ft_state_t, ft_measurement_t > | |
virtual void | addPredictedState (const StateType &predicted_state, const double &predicted_state_timestamp_ns)=0 |
virtual MeasurementType | getPredictedMeasurement () const |
virtual void | predictMeasurement ()=0 |
RecursiveEstimatorFilterInterface (double loop_period_ns) | |
virtual void | setMeasurement (const MeasurementType &acquired_measurement, const double &measurement_timestamp) |
virtual | ~RecursiveEstimatorFilterInterface () |
Additional Inherited Members | |
Protected Attributes inherited from omip::RecursiveEstimatorFilterInterface< ft_state_t, ft_measurement_t > | |
std::string | _filter_name |
double | _loop_period_ns |
MeasurementType | _measurement |
double | _measurement_timestamp_ns |
StateType | _most_likely_predicted_state |
MeasurementType | _predicted_measurement |
std::vector< StateType > | _predicted_states |
double | _previous_measurement_timestamp_ns |
StateType | _state |
Interface to be implemented by feature trackers It derives from the RecursiveEstimator interface.
Definition at line 54 of file FeatureTracker.h.
|
inline |
Default constructor.
Definition at line 62 of file FeatureTracker.h.
|
inlinevirtual |
Default destructor (empty)
Definition at line 71 of file FeatureTracker.h.
|
pure virtual |
Corrects the predicted state(s). First we track the features using both the prediction with the system model (copy of the previous feature locations) and if there is a prediction from the higher level (RBT) we track features using it too. We then decide which prediction is the "most likely" based on the quality measurement that the feature tracker returns and use the new location to update the belief state.
Implements omip::RecursiveEstimatorFilterInterface< ft_state_t, ft_measurement_t >.
Implemented in omip::PointFeatureTracker.
|
inlinevirtual |
Get the image with the depth edges, used to reject Features that are on edges
Reimplemented in omip::PointFeatureTracker.
Definition at line 157 of file FeatureTracker.h.
|
inlinevirtual |
Reimplemented in omip::PointFeatureTracker.
Definition at line 129 of file FeatureTracker.h.
|
inlinevirtual |
Get the mask used to detect new features. Combines edges, max depth and mask of current features (to not detect them)
Reimplemented in omip::PointFeatureTracker.
Definition at line 184 of file FeatureTracker.h.
|
inlinevirtual |
Get the image with the last feature locations and the predicted feature locations
Reimplemented in omip::PointFeatureTracker.
Definition at line 193 of file FeatureTracker.h.
|
inlinevirtual |
Get the image with the depth edges, used to reject Features that are on edges
Reimplemented in omip::PointFeatureTracker.
Definition at line 166 of file FeatureTracker.h.
|
inlinevirtual |
Reimplemented in omip::PointFeatureTracker.
Definition at line 124 of file FeatureTracker.h.
|
pure virtual |
Get a point cloud with the 3D locations and the unique Feature Id (L value) of the last tracked features
Reimplemented from omip::RecursiveEstimatorFilterInterface< ft_state_t, ft_measurement_t >.
Implemented in omip::PointFeatureTracker.
|
inlinevirtual |
Get the last tracked Features as marks in the RGB image
Reimplemented in omip::PointFeatureTracker.
Definition at line 138 of file FeatureTracker.h.
|
inlinevirtual |
Get a pointer to a RGB image with markers where the Features have been tracked in the last step and only showing the RGB area where the features are searched
Reimplemented in omip::PointFeatureTracker.
Definition at line 148 of file FeatureTracker.h.
|
inlinevirtual |
Get the mask used to track features. Combines edges, predictions mask and max depth
Reimplemented in omip::PointFeatureTracker.
Definition at line 175 of file FeatureTracker.h.
|
pure virtual |
First step when updating the filter. The next state is predicted from current state and system model (part of the RecursiveEstimatorInterace) In the FeatureTracker the system model is the most simple one: no change in the state. So the predicted state is just the current state.
Implements omip::RecursiveEstimatorFilterInterface< ft_state_t, ft_measurement_t >.
Implemented in omip::PointFeatureTracker.
|
inlinevirtual |
Set the parameters of the camera to project the predicted Feature locations to the image plane
camera_info | - Pointer to the CameraInfo message containing the camera parameters |
Reimplemented in omip::PointFeatureTracker.
Definition at line 118 of file FeatureTracker.h.
|
pure virtual |
Implemented in omip::PointFeatureTracker.
|
inlinevirtual |
Set the input RGB-D point cloud
full_rgb_pc | - Shared pointer to the input RGB-D point cloud |
Reimplemented in omip::PointFeatureTracker.
Definition at line 101 of file FeatureTracker.h.
|
inlinevirtual |
Set the input occlusion mask image
rgb_img | - Shared pointer to the input occlusion mask image |
Reimplemented in omip::PointFeatureTracker.
Definition at line 109 of file FeatureTracker.h.