32 #ifndef FEATURE_TRACKER_H_ 33 #define FEATURE_TRACKER_H_ 40 #include <opencv2/features2d/features2d.hpp> 41 #include <opencv2/core/core.hpp> 42 #include <camera_info_manager/camera_info_manager.h> 43 #include <feature_tracker/FeatureTrackerDynReconfConfig.h>
virtual ~FeatureTracker()
Default destructor (empty)
virtual void setDynamicReconfigureValues(feature_tracker::FeatureTrackerDynReconfConfig &config)=0
boost::shared_ptr< CvImage > CvImagePtr
FeatureCloudPCLwc::Ptr ft_state_t
virtual cv_bridge::CvImagePtr getTrackingMaskImg()
virtual void correctState()=0
Corrects the predicted state(s). First we track the features using both the prediction with the syste...
virtual cv_bridge::CvImagePtr getPredictedAndLastFeaturesImg()
virtual cv_bridge::CvImagePtr getPredictingMaskImg()
virtual void setFullRGBDPC(PointCloudPCL::ConstPtr full_rgb_pc)
virtual cv_bridge::CvImagePtr getTrackedFeaturesWithPredictionMaskImg()
virtual cv_bridge::CvImagePtr getTrackedFeaturesImg()
virtual cv_bridge::CvImagePtr getDepthImg()
Interface to be implemented by feature trackers It derives from the RecursiveEstimator interface...
virtual void setOcclusionMaskImg(cv_bridge::CvImagePtr occ_mask_img)
virtual cv_bridge::CvImagePtr getDetectingMaskImg()
FeatureTracker(double loop_period_ns)
Default constructor.
virtual void setCameraInfoMsg(const sensor_msgs::CameraInfo *camera_info)
virtual ft_state_t getState() const =0
virtual cv_bridge::CvImagePtr getRGBImg()
virtual cv_bridge::CvImagePtr getDepthEdgesImg()
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 ...