DisconnectedJointFilter.h
Go to the documentation of this file.
1 /*
2  * DisconnectedJointFilter.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 DISCONNECTEDJOINTFILTER_H_
33 #define DISCONNECTEDJOINTFILTER_H_
34 
36 
37 namespace omip
38 {
39 
42 
44 {
45 public:
46 
51 
55  virtual ~DisconnectedJointFilter();
56 
63  DisconnectedJointFilterPtr clone() const
64  {
66  }
67 
72 
77  virtual geometry_msgs::TwistWithCovariance getPredictedSRBPoseWithCovInSensorFrame();
78 
85  virtual geometry_msgs::TwistWithCovariance getPredictedSRBDeltaPoseWithCovInSensorFrame();
86 
93  virtual geometry_msgs::TwistWithCovariance getPredictedSRBVelocityWithCovInSensorFrame();
94 
98  virtual std::vector<visualization_msgs::Marker> getJointMarkersInRRBFrame() const;
99 
103  virtual JointFilterType getJointFilterType() const;
104 
108  virtual std::string getJointFilterTypeStr() const;
109 
116  virtual double getProbabilityOfJointFilter() const;
117 
118  virtual void initialize();
119 
120 protected:
121 
128  // Disconnected Joint is the only model where we ALWAYS know the normalized probability of the model given the data, because
129  // it is a value that we use as quality threshold for all other joints (the normalized probability of any other joint should be higher than this
130  // constant value to be selected as most probable joint)
131  //double _unnormalized_disc_joint_probability;
132 
134  {
135  return (new DisconnectedJointFilter(*this));
136  }
137 
138 };
139 
140 }
141 
142 #endif /* DISCONNECTEDJOINTFILTER_H_ */
DisconnectedJointFilterPtr clone() const
virtual geometry_msgs::TwistWithCovariance getPredictedSRBVelocityWithCovInSensorFrame()
Generate a prediction about the velocity of the second rigid body (SRB) and its covariance using the ...
virtual geometry_msgs::TwistWithCovariance getPredictedSRBDeltaPoseWithCovInSensorFrame()
Generate a prediction about the change in pose of the second rigid body (SRB) and its covariance usin...
JointFilterType
Definition: JointFilter.h:71
boost::shared_ptr< DisconnectedJointFilter > DisconnectedJointFilterPtr
virtual double getProbabilityOfJointFilter() const
Return the normalized joint filter probability of the Disconnected Joint model, which is a constant v...
virtual JointFilterType getJointFilterType() const
virtual std::string getJointFilterTypeStr() const
virtual DisconnectedJointFilter * doClone() const
virtual geometry_msgs::TwistWithCovariance getPredictedSRBPoseWithCovInSensorFrame()
Generate a prediction about the pose-twist of the second rigid body (SRB) and its covariance using th...
virtual std::vector< visualization_msgs::Marker > getJointMarkersInRRBFrame() const


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