svo
Semi-Direct Visual Odometry
include/svo/map.h
Go to the documentation of this file.
00001 // This file is part of SVO - Semi-direct Visual Odometry.
00002 //
00003 // Copyright (C) 2014 Christian Forster <forster at ifi dot uzh dot ch>
00004 // (Robotics and Perception Group, University of Zurich, Switzerland).
00005 //
00006 // SVO is free software: you can redistribute it and/or modify it under the
00007 // terms of the GNU General Public License as published by the Free Software
00008 // Foundation, either version 3 of the License, or any later version.
00009 //
00010 // SVO is distributed in the hope that it will be useful, but WITHOUT ANY
00011 // WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS
00012 // FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
00013 //
00014 // You should have received a copy of the GNU General Public License
00015 // along with this program.  If not, see <http://www.gnu.org/licenses/>.
00016 
00017 #ifndef SVO_MAP_H_
00018 #define SVO_MAP_H_
00019 
00020 #include <queue>
00021 #include <boost/noncopyable.hpp>
00022 #include <boost/thread.hpp>
00023 #include <svo/global.h>
00024 
00025 namespace svo {
00026 
00027 class Point;
00028 class Feature;
00029 class Seed;
00030 
00032 class MapPointCandidates
00033 {
00034 public:
00035   typedef pair<Point*, Feature*> PointCandidate;
00036   typedef list<PointCandidate> PointCandidateList;
00037 
00040   boost::mutex mut_;
00041 
00044   PointCandidateList candidates_;
00045   list< Point* > trash_points_;
00046 
00047   MapPointCandidates();
00048   ~MapPointCandidates();
00049 
00051   void newCandidatePoint(Point* point, double depth_sigma2);
00052 
00054   void addCandidatePointToFrame(FramePtr frame);
00055 
00057   bool deleteCandidatePoint(Point* point);
00058 
00060   void removeFrameCandidates(FramePtr frame);
00061 
00063   void reset();
00064 
00065   void deleteCandidate(PointCandidate& c);
00066 
00067   void emptyTrash();
00068 };
00069 
00071 class Map : boost::noncopyable
00072 {
00073 public:
00074   list< FramePtr > keyframes_;          
00075   list< Point* > trash_points_;         
00076   MapPointCandidates point_candidates_;
00077 
00078   Map();
00079   ~Map();
00080 
00082   void reset();
00083 
00085   void safeDeletePoint(Point* pt);
00086 
00088   void deletePoint(Point* pt);
00089 
00091   bool safeDeleteFrame(FramePtr frame);
00092 
00094   void removePtFrameRef(Frame* frame, Feature* ftr);
00095 
00097   void addKeyframe(FramePtr new_keyframe);
00098 
00100   void getCloseKeyframes(const FramePtr& frame, list< pair<FramePtr,double> >& close_kfs) const;
00101 
00103   FramePtr getClosestKeyframe(const FramePtr& frame) const;
00104 
00106   FramePtr getFurthestKeyframe(const Vector3d& pos) const;
00107 
00108   bool getKeyframeById(const int id, FramePtr& frame) const;
00109 
00111   void transform(const Matrix3d& R, const Vector3d& t, const double& s);
00112 
00116   void emptyTrash();
00117 
00119   inline FramePtr lastKeyframe() { return keyframes_.back(); }
00120 
00122   inline size_t size() const { return keyframes_.size(); }
00123 };
00124 
00126 namespace map_debug {
00127 
00128 void mapStatistics(Map* map);
00129 void mapValidation(Map* map, int id);
00130 void frameValidation(Frame* frame, int id);
00131 void pointValidation(Point* point, int id);
00132 
00133 } // namespace map_debug
00134 } // namespace svo
00135 
00136 #endif // SVO_MAP_H_
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines