Skip to content

Commit

Permalink
add some comments
Browse files Browse the repository at this point in the history
  • Loading branch information
gaoxiang12 committed May 25, 2019
1 parent f30c640 commit 1189474
Show file tree
Hide file tree
Showing 9 changed files with 39 additions and 14 deletions.
2 changes: 0 additions & 2 deletions ch13/config/default.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,8 @@
# data
# the tum dataset directory, change it to yours!
dataset_dir: /media/xiang/Data/Dataset/Kitti/dataset/sequences/00
# dataset_dir: /mnt/1A9286BD92869CBF/Dataset/Kitti/dataset/sequences/02

# camera intrinsics
# fr1
camera.fx: 517.3
camera.fy: 516.5
camera.cx: 325.1
Expand Down
12 changes: 6 additions & 6 deletions ch13/include/myslam/frontend.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,9 +26,10 @@ class Frontend {

Frontend();

/// 外部接口,添加一个帧并计算其定位结果
bool AddFrame(Frame::Ptr frame);

//
/// Set函数
void SetMap(Map::Ptr map) { map_ = map; }

void SetBackend(std::shared_ptr<Backend> backend) { backend_ = backend; }
Expand Down Expand Up @@ -112,11 +113,10 @@ class Frontend {
// data
FrontendStatus status_ = FrontendStatus::INITING;

Frame::Ptr current_frame_ = nullptr;
Frame::Ptr last_frame_ = nullptr;
Frame::Ptr ref_frame_ = nullptr;
Camera::Ptr camera_left_ = nullptr;
Camera::Ptr camera_right_ = nullptr;
Frame::Ptr current_frame_ = nullptr; // 当前帧
Frame::Ptr last_frame_ = nullptr; // 上一帧
Camera::Ptr camera_left_ = nullptr; // 左侧相机
Camera::Ptr camera_right_ = nullptr; // 右侧相机

Map::Ptr map_ = nullptr;
std::shared_ptr<Backend> backend_ = nullptr;
Expand Down
4 changes: 4 additions & 0 deletions ch13/include/myslam/g2o_types.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@

namespace myslam {
/// vertex and edges used in g2o ba
/// 位姿顶点
class VertexPose : public g2o::BaseVertex<6, SE3> {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
Expand All @@ -40,6 +41,7 @@ class VertexPose : public g2o::BaseVertex<6, SE3> {
virtual bool write(std::ostream &out) const override { return true; }
};

/// 路标顶点
class VertexXYZ : public g2o::BaseVertex<3, Vec3> {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
Expand All @@ -56,6 +58,7 @@ class VertexXYZ : public g2o::BaseVertex<3, Vec3> {
virtual bool write(std::ostream &out) const override { return true; }
};

/// 仅估计位姿的一元边
class EdgeProjectionPoseOnly : public g2o::BaseUnaryEdge<2, Vec2, VertexPose> {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
Expand Down Expand Up @@ -97,6 +100,7 @@ class EdgeProjectionPoseOnly : public g2o::BaseUnaryEdge<2, Vec2, VertexPose> {
Mat33 _K;
};

/// 带有地图和位姿的二元边
class EdgeProjection
: public g2o::BaseBinaryEdge<2, Vec2, VertexPose, VertexXYZ> {
public:
Expand Down
9 changes: 7 additions & 2 deletions ch13/include/myslam/map.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
namespace myslam {

/**
* @brief
* @brief 地图
* 和地图的交互:前端调用InsertKeyframe和InsertMapPoint插入新帧和地图点,后端维护地图的结构,判定outlier/剔除等等
*/
class Map {
Expand All @@ -21,24 +21,29 @@ class Map {

Map() {}

/// 增加一个关键帧
void InsertKeyFrame(Frame::Ptr frame);

/// 增加一个地图顶点
void InsertMapPoint(MapPoint::Ptr map_point);

/// 获取所有地图点
LandmarksType GetAllMapPoints() {
std::unique_lock<std::mutex> lck(data_mutex_);
return landmarks_;
}
/// 获取所有关键帧
KeyframesType GetAllKeyFrames() {
std::unique_lock<std::mutex> lck(data_mutex_);
return keyframes_;
}

/// 获取激活地图点
LandmarksType GetActiveMapPoints() {
std::unique_lock<std::mutex> lck(data_mutex_);
return active_landmarks_;
}

/// 获取激活关键帧
KeyframesType GetActiveKeyFrames() {
std::unique_lock<std::mutex> lck(data_mutex_);
return active_keyframes_;
Expand Down
8 changes: 6 additions & 2 deletions ch13/include/myslam/mappoint.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,14 +10,17 @@ struct Frame;

struct Feature;

/**
* 路标点类
* 特征点在三角化之后形成路标点
*/
struct MapPoint {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
typedef std::shared_ptr<MapPoint> Ptr;
unsigned long id_ = 0; // ID
bool is_outlier_ = false;
Vec3 pos_ = Vec3::Zero(); // Position in world

std::mutex data_mutex_;
int observed_times_ = 0; // being observed by feature matching algo.
std::list<std::weak_ptr<Feature>> observations_;
Expand All @@ -42,12 +45,13 @@ struct MapPoint {
observed_times_++;
}

void RemoveObservation(std::shared_ptr<Feature> feat);

std::list<std::weak_ptr<Feature>> GetObs() {
std::unique_lock<std::mutex> lck(data_mutex_);
return observations_;
}

void RemoveObservation(std::shared_ptr<Feature> feat);
// factory function
static MapPoint::Ptr CreateNewMappoint();
};
Expand Down
6 changes: 6 additions & 0 deletions ch13/include/myslam/viewer.h
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,10 @@
#include "myslam/map.h"

namespace myslam {

/**
* 可视化
*/
class Viewer {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
Expand All @@ -24,8 +28,10 @@ class Viewer {

void Close();

// 增加一个当前帧
void AddCurrentFrame(Frame::Ptr current_frame);

// 更新地图
void UpdateMap();

private:
Expand Down
5 changes: 5 additions & 0 deletions ch13/include/myslam/visual_odometry.h
Original file line number Diff line number Diff line change
Expand Up @@ -10,10 +10,14 @@

namespace myslam {

/**
* VO 对外接口
*/
class VisualOdometry {
public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
typedef std::shared_ptr<VisualOdometry> Ptr;

/// constructor with config file
VisualOdometry(std::string &config_path);

Expand All @@ -33,6 +37,7 @@ class VisualOdometry {
*/
bool Step();

/// 获取前端状态
FrontendStatus GetFrontendStatus() const { return frontend_->GetStatus(); }

private:
Expand Down
2 changes: 1 addition & 1 deletion ch13/src/backend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,7 @@ void Backend::Optimize(Map::KeyframesType &keyframes,

// edges
int index = 1;
double chi2_th = 5.991; // robust kernel 阈值
double chi2_th = 5.991; // robust kernel 阈值
std::map<EdgeProjection *, Feature::Ptr> edges_and_features;

for (auto &landmark : landmarks) {
Expand Down
5 changes: 4 additions & 1 deletion ch13/src/frontend.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -382,6 +382,9 @@ bool Frontend::BuildInitMap() {
return true;
}

bool Frontend::Reset() { return true; }
bool Frontend::Reset() {
LOG(INFO) << "Reset is not implemented. ";
return true;
}

} // namespace myslam

0 comments on commit 1189474

Please sign in to comment.