OMIPUtils.h
Go to the documentation of this file.
1 /*
2  * OMIPUtils.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 OMIP_UTILS_H_
33 #define OMIP_UTILS_H_
34 
35 #include <pcl/point_types.h>
36 #include <Eigen/Geometry>
37 #include <lgsm/Lgsm>
38 #include <boost/shared_ptr.hpp>
39 
40 #include "omip_common/Feature.h"
41 
42 #include <ros/ros.h>
44 
45 #include "wrappers/matrix/matrix_wrapper.h"
46 
48 
49 namespace omip
50 {
51 
62 void EigenAffine2TranslationAndEulerAngles(const Eigen::Affine3d& t, double& x,
63  double& y, double& z, double& roll,
64  double& pitch, double& yaw);
65 
76 void TranslationAndEulerAngles2EigenAffine(const double& x, const double& y, const double& z, const double& roll, const double& pitch,
77  const double& yaw,
78  Eigen::Transform<double, 3, Eigen::Affine> &t);
79 
86 double sampleNormal(double mean, double std_dev);
87 
94 std::ostream& operator <<(std::ostream& os,
95  std::vector<Feature::Id> vector_ids);
96 
103 std::ostream& operator <<(std::ostream& os, Feature::Location location);
104 
105 
106 std::ostream& operator <<(std::ostream& os, Eigen::Twistd twistd);
107 
115 double L2Distance(const Feature::Location& first, const Feature::Location& second);
116 
126 void TransformMatrix2Twist(const Eigen::Matrix4d& transformation_matrix, Eigen::Twistd& twist);
127 
133 void TransformMatrix2TwistUnwrapped(const Eigen::Matrix4d& transformation_matrix, Eigen::Twistd& twist, const Eigen::Twistd& twist_previous);
134 
140 void Twist2TransformMatrix( const Eigen::Twistd& transformation_twist, Eigen::Matrix4d& matrix);
141 
148 void TransformLocation(const Feature::Location& origin, const Eigen::Matrix4d& transformation, Feature::Location& new_location);
149 
156 void TransformLocation(const Feature::Location& origin, const Eigen::Twistd& twist, Feature::Location &new_location, int feat_id=0);
157 
164 void TransformLocation(const Feature::Location& origin, const geometry_msgs::Twist& twist,Feature::Location& new_location);
165 
171 void LocationOfFeature2ColumnVector(const Feature::Location& lof, MatrixWrapper::ColumnVector& col_vec);
172 
178 void LocationOfFeature2ColumnVectorHomogeneous(const Feature::Location &lof, MatrixWrapper::ColumnVector &col_vec);
179 
180 void LocationOfFeature2EigenVectorHomogeneous(const Feature::Location& lof, Eigen::Vector4d& eig_vec);
181 
190  const Feature::Location& location2);
191 
193  const Feature::Location& location2);
199 void GeometryMsgsTwist2EigenTwist(const geometry_msgs::Twist& gm_twist, Eigen::Twistd& eigen_twist);
200 
206 void EigenTwist2GeometryMsgsTwist(Eigen::Twistd& eigen_twist, geometry_msgs::Twist& gm_twist);
207 
213 bool isFinite(const Eigen::Matrix4d& transformation);
214 
215 void Location2PointPCL(const Feature::Location &point_location, pcl::PointXYZ& point_pcl);
216 
217 void LocationAndId2FeaturePCL(const Feature::Location &feature_location, const Feature::Id &feature_id, pcl::PointXYZL& feature_pcl);
218 
219 void LocationAndId2FeaturePCLwc(const Feature::Location &feature_location, const Feature::Id &feature_id, omip::FeaturePCLwc& feature_pcl);
220 
221 void ROSTwist2EigenTwist(const geometry_msgs::Twist& ros_twist, Eigen::Twistd &eigen_twist);
222 
223 Eigen::Twistd unwrapTwist(Eigen::Twistd& current_twist, Eigen::Displacementd& current_displacement, Eigen::Twistd& previous_twist, bool &changed);
224 
225 Eigen::Twistd invertTwist(Eigen::Twistd& current_twist, Eigen::Twistd& previous_twist, bool& inverted);
226 
227 void invert3x3Matrix(const MatrixWrapper::Matrix& to_inv, MatrixWrapper::Matrix& inverse);
228 
229 void invert3x3MatrixEigen(const Eigen::Map<Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> >& to_inv,
230  Eigen::Map<Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> >& inverse);
231 
232 void invert3x3MatrixEigen2(const Eigen::Matrix3d& to_inv, Eigen::Matrix3d& inverse);
233 
234 }
235 
236 #endif /* OMIP_UTILS_H_ */
boost::tuple< double, double, double > Location
Definition: Feature.h:59
Feature::Location operator-(const Feature::Location &location1, const Feature::Location &location2)
Definition: OMIPUtils.cpp:188
void EigenAffine2TranslationAndEulerAngles(const Eigen::Affine3d &t, double &x, double &y, double &z, double &roll, double &pitch, double &yaw)
Definition: OMIPUtils.cpp:14
double L2Distance(const Feature::Location &first, const Feature::Location &second)
Definition: OMIPUtils.cpp:95
void TransformMatrix2Twist(const Eigen::Matrix4d &transformation_matrix, Eigen::Twistd &twist)
Definition: OMIPUtils.cpp:103
bool isFinite(const Eigen::Matrix4d &transformation)
Definition: OMIPUtils.cpp:222
Feature::Location operator+(const Feature::Location &location1, const Feature::Location &location2)
Definition: OMIPUtils.cpp:197
void Twist2TransformMatrix(const Eigen::Twistd &transformation_twist, Eigen::Matrix4d &matrix)
Definition: OMIPUtils.cpp:117
void TranslationAndEulerAngles2EigenAffine(const double &x, const double &y, const double &z, const double &roll, const double &pitch, const double &yaw, Eigen::Transform< double, 3, Eigen::Affine > &t)
Definition: OMIPUtils.cpp:27
void ROSTwist2EigenTwist(const geometry_msgs::Twist &ros_twist, Eigen::Twistd &eigen_twist)
Definition: OMIPUtils.cpp:262
void LocationOfFeature2ColumnVectorHomogeneous(const Feature::Location &lof, MatrixWrapper::ColumnVector &col_vec)
Definition: OMIPUtils.cpp:172
void invert3x3MatrixEigen2(const Eigen::Matrix3d &to_inv, Eigen::Matrix3d &inverse)
Definition: OMIPUtils.cpp:413
double sampleNormal(double mean, double std_dev)
Definition: OMIPUtils.cpp:51
Eigen::Twistd unwrapTwist(Eigen::Twistd &current_twist, Eigen::Displacementd &current_displacement, Eigen::Twistd &previous_twist, bool &changed)
Definition: OMIPUtils.cpp:291
void TransformMatrix2TwistUnwrapped(const Eigen::Matrix4d &transformation_matrix, Eigen::Twistd &twist, const Eigen::Twistd &twist_previous)
Definition: OMIPUtils.cpp:111
void invert3x3Matrix(const MatrixWrapper::Matrix &to_inv, MatrixWrapper::Matrix &inverse)
Definition: OMIPUtils.cpp:378
void LocationOfFeature2ColumnVector(const Feature::Location &lof, MatrixWrapper::ColumnVector &col_vec)
Definition: OMIPUtils.cpp:165
void LocationOfFeature2EigenVectorHomogeneous(const Feature::Location &lof, Eigen::Vector4d &eig_vec)
Definition: OMIPUtils.cpp:180
void LocationAndId2FeaturePCL(const Feature::Location &feature_location, const Feature::Id &feature_id, pcl::PointXYZL &feature_pcl)
Definition: OMIPUtils.cpp:246
Definition: Feature.h:40
void GeometryMsgsTwist2EigenTwist(const geometry_msgs::Twist &gm_twist, Eigen::Twistd &eigen_twist)
Definition: OMIPUtils.cpp:206
void TransformLocation(const Feature::Location &origin, const Eigen::Matrix4d &transformation, Feature::Location &new_location)
Definition: OMIPUtils.cpp:123
void LocationAndId2FeaturePCLwc(const Feature::Location &feature_location, const Feature::Id &feature_id, omip::FeaturePCLwc &feature_pcl)
Definition: OMIPUtils.cpp:254
std::ostream & operator<<(std::ostream &os, std::vector< Feature::Id > vector_ids)
Definition: OMIPUtils.cpp:64
void invert3x3MatrixEigen(const Eigen::Map< Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > > &to_inv, Eigen::Map< Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > > &inverse)
Definition: OMIPUtils.cpp:395
void Location2PointPCL(const Feature::Location &point_location, pcl::PointXYZ &point_pcl)
Definition: OMIPUtils.cpp:239
Eigen::Twistd invertTwist(Eigen::Twistd &current_twist, Eigen::Twistd &previous_twist, bool &inverted)
Definition: OMIPUtils.cpp:358
void EigenTwist2GeometryMsgsTwist(Eigen::Twistd &eigen_twist, geometry_msgs::Twist &gm_twist)
Definition: OMIPUtils.cpp:212


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