Skip to content

Commit 5f1ef97

Browse files
authored
Add files via upload
1 parent dfe7753 commit 5f1ef97

File tree

4 files changed

+15
-3
lines changed

4 files changed

+15
-3
lines changed

src/orb_slam/include/KeyFrame.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -74,6 +74,8 @@ class KeyFrameConstInfo{
7474
cv::Mat mK;
7575
std::vector<cv::KeyPoint> mvKeys;
7676
std::vector<cv::KeyPoint> mvKeysUn;
77+
std::vector<float> mvuRight; // negative value for monocular points
78+
std::vector<float> mvDepth; // negative value for monocular points
7779
cv::Mat mDescriptors;
7880
bool mbFirstConnection;
7981

src/orb_slam/include/MapPoint.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,7 @@ class MapPoint
5252
int Observations();
5353

5454
void AddObservation(KeyFrame* pKF,size_t idx);
55+
void AddObservationStatic(KeyFrame* pKF, size_t idx);
5556
void EraseObservation(KeyFrame* pKF);
5657
void AssignReference(KeyFrame* pKF);
5758

src/orb_slam/include/Optimizer.h

Lines changed: 11 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -26,7 +26,15 @@
2626
#include "KeyFrame.h"
2727
#include "LoopClosing.h"
2828
#include "Frame.h"
29+
#include "g2o/core/block_solver.h"
30+
#include "g2o/core/optimization_algorithm_levenberg.h"
31+
#include "g2o/solvers/eigen/linear_solver_eigen.h"
32+
#include "g2o/types/sba/types_six_dof_expmap.h"
33+
#include "g2o/core/robust_kernel_impl.h"
34+
#include "g2o/solvers/dense/linear_solver_dense.h"
2935
#include "g2o/types/sim3/types_seven_dof_expmap.h"
36+
#include "g2o/core/auto_differentiation.h"
37+
#include <g2o/solvers/cholmod/linear_solver_cholmod.h>
3038
#include <Eigen/Dense>
3139
#include <opencv2/core/eigen.hpp>
3240
namespace ORB_SLAM2
@@ -44,7 +52,7 @@ class Optimizer
4452
void static GlobalBundleAdjustemnt(Map* pMap, int nIterations=5, bool *pbStopFlag=NULL,
4553
const unsigned long nLoopKF=0, const bool bRobust = true);
4654
void static LocalBundleAdjustment(KeyFrame* pKF, bool *pbStopFlag, Map *pMap);
47-
int static PoseOptimization(Frame* pFrame);
55+
static int PoseOptimization(Frame* pFrame);
4856

4957
// if bFixScale is true, 6DoF optimization (stereo,rgbd), 7DoF otherwise (mono)
5058
void static OptimizeEssentialGraph(Map* pMap, KeyFrame* pLoopKF, KeyFrame* pCurKF,
@@ -58,8 +66,8 @@ class Optimizer
5866
g2o::Sim3 &g2oS12, const float th2, const bool bFixScale);
5967

6068
//optimize extrinsic
61-
int static OptimizeExtrinsicGlobal(vector<KeyFrame*> &allKF, const vector<Eigen::Isometry3d> &vTwl, Eigen::Isometry3d &Tcl, double &scale, bool verbose=true);
62-
int static OptimizeExtrinsicLocal(vector<KeyFrame*> &allKF, const vector<Eigen::Isometry3d> &vTwl, Eigen::Isometry3d &Tcl, double &scale, bool verbose=true);
69+
static int OptimizeExtrinsicGlobal(vector<KeyFrame*> &allKF, const vector<Eigen::Isometry3d> &vTwl, Eigen::Isometry3d &Tcl, double &scale, bool verbose=true);
70+
static int OptimizeExtrinsicLocal(vector<KeyFrame*> &allKF, const vector<Eigen::Isometry3d> &vTwl, Eigen::Isometry3d &Tcl, double &scale, bool verbose=true);
6371
};
6472

6573
} //namespace ORB_SLAM

src/orb_slam/include/System.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -32,6 +32,7 @@
3232
#include "Map.h"
3333
#include "LocalMapping.h"
3434
#include "LoopClosing.h"
35+
3536
#include "KeyFrameDatabase.h"
3637
#include "ORBVocabulary.h"
3738
#include "Viewer.h"

0 commit comments

Comments
 (0)