载入中...
搜索中...
未找到
backend.h
浏览该文件的文档.
1
12#pragma once
13#include "camera.h"
14#include "common_include.h"
15#include "g2o_types.h"
16#include "map.h"
17#include "viewer.h"
18#include "config.h"
19
21
26class Backend {
27public:
28 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
29 typedef std::shared_ptr<Backend> Ptr;
30
31 static Ptr getInstance() {
32 static Ptr backend(new Backend);
33 return backend;
34 }
35
36 void getPointsAndFrames(std::vector<Frame::Ptr> &frames, std::vector<MapPoint::Ptr> &points);
37
38 void addVertexAndEdge(std::unordered_map<std::size_t, PoseVertex *> &poseVertexes,
39 std::unordered_map<std::size_t, PointVertex *> &pointVertexes,
40 std::unordered_map<Feature::Ptr, PosePointEdge *> &edges,
41 std::vector<Frame::Ptr> &frames, std::vector<MapPoint::Ptr> &points,
42 g2o::SparseOptimizer &graph);
43
44 void run();
45
46 void setMap(const Map::Ptr &map) { m_map = map; }
47
48 void setCamera(const Camera::Ptr &camera) { m_camera = camera; }
49
50 void setViewer(const Viewer::Ptr &viewer) { m_viewer = viewer; }
51
52 void optimize(std::unique_lock<std::mutex> &lck);
53
54 void setOptValue(std::unordered_map<std::size_t, PoseVertex *> poseVertexes,
55 std::unordered_map<std::size_t, PointVertex *> pointVertexes);
56
57 double detectOutlier(g2o::SparseOptimizer &graph,
58 std::unordered_map<Feature::Ptr, PosePointEdge *> &edges);
59
60 Backend(const Backend &other) = delete;
61
62 Backend &operator=(const Backend &other) = delete;
63
64private:
65 Backend() = default;
69 bool m_isStop = false;
70};
71
定义Camera相机类
后端优化类
Definition backend.h:26
Backend(const Backend &other)=delete
static Ptr getInstance()
Definition backend.h:31
void setCamera(const Camera::Ptr &camera)
Definition backend.h:48
Backend & operator=(const Backend &other)=delete
void addVertexAndEdge(std::unordered_map< std::size_t, PoseVertex * > &poseVertexes, std::unordered_map< std::size_t, PointVertex * > &pointVertexes, std::unordered_map< Feature::Ptr, PosePointEdge * > &edges, std::vector< Frame::Ptr > &frames, std::vector< MapPoint::Ptr > &points, g2o::SparseOptimizer &graph)
添加顶点和边信息
Definition backend.cc:72
void optimize(std::unique_lock< std::mutex > &lck)
进行优化,外点剔除,优化结果回带和清理地图信息
Definition backend.cc:10
bool m_isStop
后端停止标识
Definition backend.h:69
void run()
后端启动的线程函数
Definition backend.cc:38
double detectOutlier(g2o::SparseOptimizer &graph, std::unordered_map< Feature::Ptr, PosePointEdge * > &edges)
检测后端优化过程中的外点
Definition backend.cc:128
void getPointsAndFrames(std::vector< Frame::Ptr > &frames, std::vector< MapPoint::Ptr > &points)
从m_map中获取激活关键帧和激活地图点
Definition backend.cc:54
Map::Ptr m_map
地图
Definition backend.h:66
Backend()=default
Viewer::Ptr m_viewer
全局展示对象
Definition backend.h:68
Camera::Ptr m_camera
相机,保存内参
Definition backend.h:67
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef std::shared_ptr< Backend > Ptr
Definition backend.h:29
void setViewer(const Viewer::Ptr &viewer)
Definition backend.h:50
void setOptValue(std::unordered_map< std::size_t, PoseVertex * > poseVertexes, std::unordered_map< std::size_t, PointVertex * > pointVertexes)
保证地图的线程安全条件下,更新地图信息
Definition backend.cc:170
void setMap(const Map::Ptr &map)
Definition backend.h:46
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef std::shared_ptr< Camera > Ptr
Definition camera.h:27
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef std::shared_ptr< Map > Ptr
Definition map.h:125
EIGEN_MAKE_ALIGNED_OPERATOR_NEW typedef std::shared_ptr< Viewer > Ptr
Definition viewer.h:29
引入所有所需头文件,定义所有所需超参数
#define NAMESPACE_END
Definition common_include.h:41
#define NAMESPACE_BEGIN
Definition common_include.h:40
编写slam系统的超参数信息类
定义slam系统的数据结构包括Feature、Frame、MapPoint、Map
展示Frontend的m_currFrame和Map的m_activeFrames和activePoints