misc.h
Go to the documentation of this file.
00001 #ifndef RGBD_SLAM_MISC_H_
00002 #define RGBD_SLAM_MISC_H_
00003 /* This file is part of RGBDSLAM.
00004  * 
00005  * RGBDSLAM is free software: you can redistribute it and/or modify
00006  * it under the terms of the GNU General Public License as published by
00007  * the Free Software Foundation, either version 3 of the License, or
00008  * (at your option) any later version.
00009  * 
00010  * RGBDSLAM is distributed in the hope that it will be useful,
00011  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00012  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00013  * GNU General Public License for more details.
00014  * 
00015  * You should have received a copy of the GNU General Public License
00016  * along with RGBDSLAM.  If not, see <http://www.gnu.org/licenses/>.
00017  */
00018 #include <QMatrix4x4>
00019 
00020 void printTransform(const char* name, const tf::Transform t) ;
00022 void logTransform(QTextStream& out, const tf::Transform& t, double timestamp, const char* label = NULL);
00023 void printQMatrix4x4(const char* name, const QMatrix4x4& m);
00024 
00026 QMatrix4x4    g2o2QMatrix(const g2o::SE3Quat se3) ;
00028 tf::Transform g2o2TF(     const g2o::SE3Quat se3) ;
00030 g2o::SE3Quat  eigen2G2O(  const Eigen::Matrix4d& eigen_mat);
00032 g2o::SE3Quat  tf2G2O(     const tf::Transform t);
00033 
00035 void mat2components(const Eigen::Matrix4f& t, double& roll, double& pitch, double& yaw, double& dist);
00037 void mat2RPY(const Eigen::Matrix4f& t, double& roll, double& pitch, double& yaw);
00039 void mat2dist(const Eigen::Matrix4f& t, double &dist);
00040 
00041 
00043 pointcloud_type* createXYZRGBPointCloud (const sensor_msgs::ImageConstPtr& depth_msg, const sensor_msgs::ImageConstPtr& rgb_msg, const sensor_msgs::CameraInfoConstPtr& cam_info); 
00044 
00046 void transformAndAppendPointCloud (const pointcloud_type &cloud_in, pointcloud_type &cloud_to_append_to,
00047                                    const tf::Transform transformation, float Max_Depth);
00048 
00049 
00050 geometry_msgs::Point pointInWorldFrame(const Eigen::Vector4f& point3d, g2o::SE3Quat transf);
00051 // true if translation > 10cm or largest euler-angle>5 deg
00052 // used to decide if the camera has moved far enough to generate a new nodes
00053 bool isBigTrafo(const Eigen::Matrix4f& t);
00054 bool isBigTrafo(const g2o::SE3Quat& t);
00055 
00056 
00057 //bool overlappingViews(LoadedEdge3D edge);
00058 //bool triangleRayIntersection(Eigen::Vector3d triangle1,Eigen::Vector3d triangle2, Eigen::Vector3d ray_origin, Eigen::Vector3d ray);
00059 
00060 
00064 cv::FeatureDetector* createDetector( const std::string& detectorType );
00066 cv::DescriptorExtractor* createDescriptorExtractor( const std::string& descriptorType );
00068 void depthToCV8UC1(const cv::Mat& float_img, cv::Mat& mono8_img);
00069 
00071 std::string openCVCode2String(unsigned int code);
00072 
00074 void printMatrixInfo(cv::Mat& image, std::string name = std::string(""));
00075 
00077 bool asyncFrameDrop(ros::Time depth, ros::Time rgb);
00078 
00079 double errorFunction(const Eigen::Vector4f& x1, const double x1_depth_cov, 
00080                       const Eigen::Vector4f& x2, const double x2_depth_cov, 
00081                       const Eigen::Matrix4f& tf_1_to_2);
00082 
00083 double errorFunction2(const Eigen::Vector4f& x1, 
00084                       const Eigen::Vector4f& x2, 
00085                       const Eigen::Matrix4f& tf_1_to_2);
00086 
00087 float getMinDepthInNeighborhood(const cv::Mat& depth, cv::Point2f center, float diameter);
00088 
00089 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends Defines


rgbdslam
Author(s): Felix Endres, Juergen Hess, Nikolas Engelhard
autogenerated on Wed Dec 26 2012 15:53:08