RigidJointFilter.h
Go to the documentation of this file.
1 /*
2  * RigidJointFilter.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 RIGIDJOINTFILTER_H_
33 #define RIGIDJOINTFILTER_H_
34 
36 
37 namespace omip
38 {
39 
42 
44 {
45 public:
46 
51 
55  virtual ~RigidJointFilter();
56 
63  RigidJointFilterPtr clone() const
64  {
65  return (RigidJointFilterPtr(doClone()));
66  }
67 
71  RigidJointFilter(const RigidJointFilter &rigid_joint);
72 
77  virtual void predictMeasurement();
78 
84 
89  virtual geometry_msgs::TwistWithCovariance getPredictedSRBPoseWithCovInSensorFrame();
90 
97  virtual geometry_msgs::TwistWithCovariance getPredictedSRBDeltaPoseWithCovInSensorFrame();
98 
105  virtual geometry_msgs::TwistWithCovariance getPredictedSRBVelocityWithCovInSensorFrame();
106 
107 
111  virtual std::vector<visualization_msgs::Marker> getJointMarkersInRRBFrame() const;
112 
116  virtual JointFilterType getJointFilterType() const;
117 
118  virtual void estimateUnnormalizedModelProbability() ;
119 
123  virtual std::string getJointFilterTypeStr() const;
124 
125  virtual void initialize();
126 
127  virtual void setMaxTranslationRigid(double max_trans);
128 
129  virtual void setMaxRotationRigid(double max_rot);
130 
131 protected:
132 
139  virtual RigidJointFilter* doClone() const
140  {
141  return (new RigidJointFilter(*this));
142  }
143 
146 
148 
149 };
150 
151 }
152 
153 #endif /* RIGIDJOINTFILTER_H_ */
virtual void estimateUnnormalizedModelProbability()
virtual void setMaxTranslationRigid(double max_trans)
virtual JointFilterType getJointFilterType() const
virtual geometry_msgs::TwistWithCovariance getPredictedSRBDeltaPoseWithCovInSensorFrame()
Generate a prediction about the change in pose of the second rigid body (SRB) and its covariance usin...
virtual void estimateMeasurementHistoryLikelihood()
JointFilterType
Definition: JointFilter.h:71
virtual void setMaxRotationRigid(double max_rot)
virtual void predictMeasurement()
RigidJointFilterPtr clone() const
virtual geometry_msgs::TwistWithCovariance getPredictedSRBPoseWithCovInSensorFrame()
virtual std::string getJointFilterTypeStr() const
virtual std::vector< visualization_msgs::Marker > getJointMarkersInRRBFrame() const
virtual geometry_msgs::TwistWithCovariance getPredictedSRBVelocityWithCovInSensorFrame()
Generate a prediction about the velocity of the second rigid body (SRB) and its covariance using the ...
boost::shared_ptr< RigidJointFilter > RigidJointFilterPtr
virtual RigidJointFilter * doClone() const


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