Public Member Functions
omip::FeatureTracker Class Reference

Interface to be implemented by feature trackers It derives from the RecursiveEstimator interface. More...

#include <FeatureTracker.h>

Inheritance diagram for omip::FeatureTracker:
Inheritance graph
[legend]

List of all members.

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.
 FeatureTracker (double loop_period_ns)
 Default constructor.
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.
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)

Detailed Description

Interface to be implemented by feature trackers It derives from the RecursiveEstimator interface.

Definition at line 54 of file FeatureTracker.h.


Constructor & Destructor Documentation

omip::FeatureTracker::FeatureTracker ( double  loop_period_ns) [inline]

Default constructor.

Definition at line 62 of file FeatureTracker.h.

virtual omip::FeatureTracker::~FeatureTracker ( ) [inline, virtual]

Default destructor (empty)

Definition at line 71 of file FeatureTracker.h.


Member Function Documentation

virtual void omip::FeatureTracker::correctState ( ) [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.

Get the image with the depth edges, used to reject Features that are on edges

Returns:
- Shared pointer to the image of depth edges

Reimplemented in omip::PointFeatureTracker.

Definition at line 157 of file FeatureTracker.h.

Reimplemented in omip::PointFeatureTracker.

Definition at line 129 of file FeatureTracker.h.

Get the mask used to detect new features. Combines edges, max depth and mask of current features (to not detect them)

Returns:
- Shared pointer to the image of detecting mask

Reimplemented in omip::PointFeatureTracker.

Definition at line 184 of file FeatureTracker.h.

Get the image with the last feature locations and the predicted feature locations

Returns:
- Shared pointer to the image of the predicted and last features

Reimplemented in omip::PointFeatureTracker.

Definition at line 193 of file FeatureTracker.h.

Get the image with the depth edges, used to reject Features that are on edges

Returns:
- Shared pointer to the image of depth edges

Reimplemented in omip::PointFeatureTracker.

Definition at line 166 of file FeatureTracker.h.

Reimplemented in omip::PointFeatureTracker.

Definition at line 124 of file FeatureTracker.h.

virtual ft_state_t omip::FeatureTracker::getState ( ) const [pure virtual]

Get a point cloud with the 3D locations and the unique Feature Id (L value) of the last tracked features

Returns:
- Shared pointer to the 3D XYZL point cloud of tracked Features

Reimplemented from omip::RecursiveEstimatorFilterInterface< ft_state_t, ft_measurement_t >.

Implemented in omip::PointFeatureTracker.

Get the last tracked Features as marks in the RGB image

Returns:
- Shared pointer to the image with the 2D tracked Feature locations marked

Reimplemented in omip::PointFeatureTracker.

Definition at line 138 of file FeatureTracker.h.

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

Returns:
- Shared pointer to the RGB image with markers and searching areas

Reimplemented in omip::PointFeatureTracker.

Definition at line 148 of file FeatureTracker.h.

Get the mask used to track features. Combines edges, predictions mask and max depth

Returns:
- Shared pointer to the image of tracking mask

Reimplemented in omip::PointFeatureTracker.

Definition at line 175 of file FeatureTracker.h.

virtual void omip::FeatureTracker::predictState ( double  time_interval_ns) [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.

virtual void omip::FeatureTracker::setCameraInfoMsg ( const sensor_msgs::CameraInfo *  camera_info) [inline, virtual]

Set the parameters of the camera to project the predicted Feature locations to the image plane

Parameters:
camera_info- Pointer to the CameraInfo message containing the camera parameters

Reimplemented in omip::PointFeatureTracker.

Definition at line 118 of file FeatureTracker.h.

virtual void omip::FeatureTracker::setDynamicReconfigureValues ( feature_tracker::FeatureTrackerDynReconfConfig &  config) [pure virtual]

Implemented in omip::PointFeatureTracker.

virtual void omip::FeatureTracker::setFullRGBDPC ( PointCloudPCL::ConstPtr  full_rgb_pc) [inline, virtual]

Set the input RGB-D point cloud

Parameters:
full_rgb_pc- Shared pointer to the input RGB-D point cloud

Reimplemented in omip::PointFeatureTracker.

Definition at line 101 of file FeatureTracker.h.

virtual void omip::FeatureTracker::setOcclusionMaskImg ( cv_bridge::CvImagePtr  occ_mask_img) [inline, virtual]

Set the input occlusion mask image

Parameters:
rgb_img- Shared pointer to the input occlusion mask image

Reimplemented in omip::PointFeatureTracker.

Definition at line 109 of file FeatureTracker.h.


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


feature_tracker
Author(s): Roberto Martín-Martín
autogenerated on Sat Jun 8 2019 18:26:39