matching_result.h
Go to the documentation of this file.
00001 /* This file is part of RGBDSLAM.
00002  * 
00003  * RGBDSLAM is free software: you can redistribute it and/or modify
00004  * it under the terms of the GNU General Public License as published by
00005  * the Free Software Foundation, either version 3 of the License, or
00006  * (at your option) any later version.
00007  * 
00008  * RGBDSLAM is distributed in the hope that it will be useful,
00009  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00010  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00011  * GNU General Public License for more details.
00012  * 
00013  * You should have received a copy of the GNU General Public License
00014  * along with RGBDSLAM.  If not, see <http://www.gnu.org/licenses/>.
00015  */
00016 
00017 
00018 #ifndef MATCHING_RESULT_H
00019 #define MATCHING_RESULT_H
00020 #include <opencv2/features2d/features2d.hpp>
00021 #include <Eigen/Core>
00022 #include "edge.h"
00023 
00024 class MatchingResult {
00025     public:
00026         MatchingResult() : 
00027           rmse(0.0), 
00028           ransac_trafo(Eigen::Matrix4f::Identity()), 
00029           final_trafo(Eigen::Matrix4f::Identity()), 
00030           icp_trafo(Eigen::Matrix4f::Identity())
00031         {
00032             edge.id1 = edge.id2 = -1;
00033         }
00034         std::vector<cv::DMatch> inlier_matches;
00035         std::vector<cv::DMatch> all_matches;
00036         LoadedEdge3D edge;
00037         float rmse;
00038         Eigen::Matrix4f ransac_trafo;
00039         Eigen::Matrix4f final_trafo;
00040         Eigen::Matrix4f icp_trafo;
00041     public:
00042       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00043 };
00044         
00045 #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