FeatureTracker.h
Go to the documentation of this file.
1 /*
2  * FeatureTracker.h
3  *
4  * Author: roberto
5  *
6  * This is a modified implementation of the method for online estimation of kinematic structures described in our paper
7  * "Online Interactive Perception of Articulated Objects with Multi-Level Recursive Estimation Based on Task-Specific Priors"
8  * (Martín-Martín and Brock, 2014).
9  * This implementation can be used to reproduce the results of the paper and to be applied to new research.
10  * The implementation allows also to be extended to perceive different information/models or to use additional sources of information.
11  * A detail explanation of the method and the system can be found in our paper.
12  *
13  * If you are using this implementation in your research, please consider citing our work:
14  *
15 @inproceedings{martinmartin_ip_iros_2014,
16 Title = {Online Interactive Perception of Articulated Objects with Multi-Level Recursive Estimation Based on Task-Specific Priors},
17 Author = {Roberto {Mart\'in-Mart\'in} and Oliver Brock},
18 Booktitle = {Proceedings of the IEEE/RSJ International Conference on Intelligent Robots and Systems},
19 Pages = {2494-2501},
20 Year = {2014},
21 Location = {Chicago, Illinois, USA},
22 Note = {http://www.robotics.tu-berlin.de/fileadmin/fg170/Publikationen_pdf/martinmartin_ip_iros_2014.pdf},
23 Url = {http://www.robotics.tu-berlin.de/fileadmin/fg170/Publikationen_pdf/martinmartin_ip_iros_2014.pdf},
24 Projectname = {Interactive Perception}
25 }
26  * If you have questions or suggestions, contact us:
27  * roberto.martinmartin@tu-berlin.de
28  *
29  * Enjoy!
30  */
31 
32 #ifndef FEATURE_TRACKER_H_
33 #define FEATURE_TRACKER_H_
34 
38 
39 //ROS and OpenCV
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>
44 
45 namespace omip
46 {
47 
54 class FeatureTracker : public RecursiveEstimatorFilterInterface<ft_state_t, ft_measurement_t>
55 {
56 public:
57 
62  FeatureTracker(double loop_period_ns) :
63  RecursiveEstimatorFilterInterface(loop_period_ns)
64  {
65  }
66 
71  virtual ~FeatureTracker()
72  {
73  }
74 
80  virtual void predictState(double time_interval_ns) = 0;
81 
88  virtual void correctState() = 0;
89 
95  virtual ft_state_t getState() const = 0;
96 
101  virtual void setFullRGBDPC(PointCloudPCL::ConstPtr full_rgb_pc)
102  {
103  }
104 
109  virtual void setOcclusionMaskImg(cv_bridge::CvImagePtr occ_mask_img)
110  {
111  }
112 
118  virtual void setCameraInfoMsg(const sensor_msgs::CameraInfo* camera_info)
119  {
120  }
121 
122  virtual void setDynamicReconfigureValues(feature_tracker::FeatureTrackerDynReconfConfig &config) =0;
123 
125  {
127  }
128 
130  {
132  }
133 
139  {
141  }
142 
149  {
151  }
152 
158  {
160  }
161 
167  {
169  }
170 
176  {
178  }
179 
185  {
187  }
188 
194  {
196  }
197 };
198 }
199 
200 #endif /* FEATURE_TRACKER_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 ...


feature_tracker
Author(s): Roberto Martín-Martín
autogenerated on Mon Jun 10 2019 14:06:08