31 #include<Eigen/StdVector> 50 int nIterations,
bool* pbStopFlag,
const unsigned long nLoopKF,
const bool bRobust)
52 vector<bool> vbNotIncludedMP;
53 vbNotIncludedMP.resize(vpMP.size());
68 long unsigned int maxKFid = 0;
71 for(
size_t i=0; i<vpKFs.size(); i++)
85 const float thHuber2D = sqrt(5.99);
86 const float thHuber3D = sqrt(7.815);
89 for(
size_t i=0; i<vpMP.size(); i++)
96 const int id = pMP->
mnId+maxKFid+1;
105 for(map<KeyFrame*,size_t>::const_iterator mit=observations.begin(); mit!=observations.end(); mit++)
114 const cv::KeyPoint &kpUn = pKF->
mvKeysUn[mit->second];
118 Eigen::Matrix<double,2,1> obs;
119 obs << kpUn.pt.x, kpUn.pt.y;
123 e->
setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(
id)));
124 e->
setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(pKF->
mnId)));
145 Eigen::Matrix<double,3,1> obs;
146 const float kp_ur = pKF->
mvuRight[mit->second];
147 obs << kpUn.pt.x, kpUn.pt.y, kp_ur;
151 e->
setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(
id)));
152 e->
setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(pKF->
mnId)));
155 Eigen::Matrix3d
Info = Eigen::Matrix3d::Identity()*invSigma2;
178 vbNotIncludedMP[i]=
true;
182 vbNotIncludedMP[i]=
false;
193 for(
size_t i=0; i<vpKFs.size(); i++)
206 pKF->
mTcwGBA.create(4,4,CV_32F);
213 for(
size_t i=0; i<vpMP.size(); i++)
215 if(vbNotIncludedMP[i])
231 pMP->
mPosGBA.create(3,1,CV_32F);
251 int nInitialCorrespondences=0;
261 const int N = pFrame->
N;
263 vector<g2o::EdgeSE3ProjectXYZOnlyPose*> vpEdgesMono;
264 vector<size_t> vnIndexEdgeMono;
265 vpEdgesMono.reserve(N);
266 vnIndexEdgeMono.reserve(N);
268 vector<g2o::EdgeStereoSE3ProjectXYZOnlyPose*> vpEdgesStereo;
269 vector<size_t> vnIndexEdgeStereo;
270 vpEdgesStereo.reserve(N);
271 vnIndexEdgeStereo.reserve(N);
273 const float deltaMono = sqrt(5.991);
274 const float deltaStereo = sqrt(7.815);
280 for(
int i=0; i<N; i++)
288 nInitialCorrespondences++;
291 Eigen::Matrix<double,2,1> obs;
292 const cv::KeyPoint &kpUn = pFrame->
mvKeysUn[i];
293 obs << kpUn.pt.x, kpUn.pt.y;
297 e->
setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(0)));
311 e->
Xw[0] = Xw.at<
float>(0);
312 e->
Xw[1] = Xw.at<
float>(1);
313 e->
Xw[2] = Xw.at<
float>(2);
317 vpEdgesMono.push_back(e);
318 vnIndexEdgeMono.push_back(i);
322 nInitialCorrespondences++;
326 Eigen::Matrix<double,3,1> obs;
327 const cv::KeyPoint &kpUn = pFrame->
mvKeysUn[i];
328 const float &kp_ur = pFrame->
mvuRight[i];
329 obs << kpUn.pt.x, kpUn.pt.y, kp_ur;
333 e->
setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(0)));
336 Eigen::Matrix3d
Info = Eigen::Matrix3d::Identity()*invSigma2;
349 e->
Xw[0] = Xw.at<
float>(0);
350 e->
Xw[1] = Xw.at<
float>(1);
351 e->
Xw[2] = Xw.at<
float>(2);
355 vpEdgesStereo.push_back(e);
356 vnIndexEdgeStereo.push_back(i);
364 if(nInitialCorrespondences<3)
369 const float chi2Mono[4]={5.991,5.991,5.991,5.991};
370 const float chi2Stereo[4]={7.815,7.815,7.815, 7.815};
371 const int its[4]={10,10,10,10};
374 for(
size_t it=0; it<4; it++)
382 for(
size_t i=0, iend=vpEdgesMono.size(); i<iend; i++)
386 const size_t idx = vnIndexEdgeMono[i];
393 const float chi2 = e->
chi2();
395 if(chi2>chi2Mono[it])
411 for(
size_t i=0, iend=vpEdgesStereo.size(); i<iend; i++)
415 const size_t idx = vnIndexEdgeStereo[i];
422 const float chi2 = e->
chi2();
424 if(chi2>chi2Stereo[it])
440 if(optimizer.
edges().size()<10)
450 return nInitialCorrespondences-nBad;
456 list<KeyFrame*> lLocalKeyFrames;
458 lLocalKeyFrames.push_back(pKF);
462 for(
int i=0, iend=vNeighKFs.size(); i<iend; i++)
467 lLocalKeyFrames.push_back(pKFi);
471 list<MapPoint*> lLocalMapPoints;
472 for(list<KeyFrame*>::iterator lit=lLocalKeyFrames.begin() , lend=lLocalKeyFrames.end(); lit!=lend; lit++)
474 vector<MapPoint*> vpMPs = (*lit)->GetMapPointMatches();
475 for(vector<MapPoint*>::iterator vit=vpMPs.begin(), vend=vpMPs.end(); vit!=vend; vit++)
482 lLocalMapPoints.push_back(pMP);
489 list<KeyFrame*> lFixedCameras;
490 for(list<MapPoint*>::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++)
492 map<KeyFrame*,size_t> observations = (*lit)->GetObservations();
493 for(map<KeyFrame*,size_t>::iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
501 lFixedCameras.push_back(pKFi);
520 unsigned long maxKFid = 0;
523 for(list<KeyFrame*>::iterator lit=lLocalKeyFrames.begin(), lend=lLocalKeyFrames.end(); lit!=lend; lit++)
531 if(pKFi->
mnId>maxKFid)
536 for(list<KeyFrame*>::iterator lit=lFixedCameras.begin(), lend=lFixedCameras.end(); lit!=lend; lit++)
544 if(pKFi->
mnId>maxKFid)
549 const int nExpectedSize = (lLocalKeyFrames.size()+lFixedCameras.size())*lLocalMapPoints.size();
551 vector<g2o::EdgeSE3ProjectXYZ*> vpEdgesMono;
552 vpEdgesMono.reserve(nExpectedSize);
554 vector<KeyFrame*> vpEdgeKFMono;
555 vpEdgeKFMono.reserve(nExpectedSize);
557 vector<MapPoint*> vpMapPointEdgeMono;
558 vpMapPointEdgeMono.reserve(nExpectedSize);
560 vector<g2o::EdgeStereoSE3ProjectXYZ*> vpEdgesStereo;
561 vpEdgesStereo.reserve(nExpectedSize);
563 vector<KeyFrame*> vpEdgeKFStereo;
564 vpEdgeKFStereo.reserve(nExpectedSize);
566 vector<MapPoint*> vpMapPointEdgeStereo;
567 vpMapPointEdgeStereo.reserve(nExpectedSize);
569 const float thHuberMono = sqrt(5.991);
570 const float thHuberStereo = sqrt(7.815);
572 for(list<MapPoint*>::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++)
577 int id = pMP->
mnId+maxKFid+1;
585 for(map<KeyFrame*,size_t>::const_iterator mit=observations.begin(), mend=observations.end(); mit!=mend; mit++)
591 const cv::KeyPoint &kpUn = pKFi->
mvKeysUn[mit->second];
596 Eigen::Matrix<double,2,1> obs;
597 obs << kpUn.pt.x, kpUn.pt.y;
601 e->
setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(
id)));
602 e->
setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(pKFi->
mnId)));
617 vpEdgesMono.push_back(e);
618 vpEdgeKFMono.push_back(pKFi);
619 vpMapPointEdgeMono.push_back(pMP);
623 Eigen::Matrix<double,3,1> obs;
624 const float kp_ur = pKFi->
mvuRight[mit->second];
625 obs << kpUn.pt.x, kpUn.pt.y, kp_ur;
629 e->
setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(
id)));
630 e->
setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(pKFi->
mnId)));
633 Eigen::Matrix3d
Info = Eigen::Matrix3d::Identity()*invSigma2;
647 vpEdgesStereo.push_back(e);
648 vpEdgeKFStereo.push_back(pKFi);
649 vpMapPointEdgeStereo.push_back(pMP);
672 for(
size_t i=0, iend=vpEdgesMono.size(); i<iend;i++)
675 MapPoint* pMP = vpMapPointEdgeMono[i];
688 for(
size_t i=0, iend=vpEdgesStereo.size(); i<iend;i++)
691 MapPoint* pMP = vpMapPointEdgeStereo[i];
711 vector<pair<KeyFrame*,MapPoint*> > vToErase;
712 vToErase.reserve(vpEdgesMono.size()+vpEdgesStereo.size());
715 for(
size_t i=0, iend=vpEdgesMono.size(); i<iend;i++)
718 MapPoint* pMP = vpMapPointEdgeMono[i];
726 vToErase.push_back(make_pair(pKFi,pMP));
730 for(
size_t i=0, iend=vpEdgesStereo.size(); i<iend;i++)
733 MapPoint* pMP = vpMapPointEdgeStereo[i];
741 vToErase.push_back(make_pair(pKFi,pMP));
748 if(!vToErase.empty())
750 for(
size_t i=0;i<vToErase.size();i++)
753 MapPoint* pMPi = vToErase[i].second;
762 for(list<KeyFrame*>::iterator lit=lLocalKeyFrames.begin(), lend=lLocalKeyFrames.end(); lit!=lend; lit++)
771 for(list<MapPoint*>::iterator lit=lLocalMapPoints.begin(), lend=lLocalMapPoints.end(); lit!=lend; lit++)
784 const map<
KeyFrame *, set<KeyFrame *> > &LoopConnections,
const bool &bFixScale)
800 const unsigned int nMaxKFid = pMap->
GetMaxKFid();
802 vector<g2o::Sim3,Eigen::aligned_allocator<g2o::Sim3> > vScw(nMaxKFid+1);
803 vector<g2o::Sim3,Eigen::aligned_allocator<g2o::Sim3> > vCorrectedSwc(nMaxKFid+1);
804 vector<g2o::VertexSim3Expmap*> vpVertices(nMaxKFid+1);
806 const int minFeat = 100;
809 for(
size_t i=0, iend=vpKFs.size(); i<iend;i++)
816 const int nIDi = pKF->
mnId;
818 LoopClosing::KeyFrameAndPose::const_iterator it = CorrectedSim3.find(pKF);
820 if(it!=CorrectedSim3.end())
822 vScw[nIDi] = it->second;
843 vpVertices[nIDi]=VSim3;
847 set<pair<long unsigned int,long unsigned int> > sInsertedEdges;
849 const Eigen::Matrix<double,7,7> matLambda = Eigen::Matrix<double,7,7>::Identity();
852 for(map<
KeyFrame *, set<KeyFrame *> >::const_iterator mit = LoopConnections.begin(), mend=LoopConnections.end(); mit!=mend; mit++)
855 const long unsigned int nIDi = pKF->
mnId;
856 const set<KeyFrame*> &spConnections = mit->second;
860 for(set<KeyFrame*>::const_iterator sit=spConnections.begin(), send=spConnections.end(); sit!=send; sit++)
862 const long unsigned int nIDj = (*sit)->mnId;
870 e->
setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(nIDj)));
871 e->
setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(nIDi)));
878 sInsertedEdges.insert(make_pair(
min(nIDi,nIDj),max(nIDi,nIDj)));
883 for(
size_t i=0, iend=vpKFs.size(); i<iend; i++)
887 const int nIDi = pKF->
mnId;
891 LoopClosing::KeyFrameAndPose::const_iterator iti = NonCorrectedSim3.find(pKF);
893 if(iti!=NonCorrectedSim3.end())
903 int nIDj = pParentKF->
mnId;
907 LoopClosing::KeyFrameAndPose::const_iterator itj = NonCorrectedSim3.find(pParentKF);
909 if(itj!=NonCorrectedSim3.end())
917 e->
setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(nIDj)));
918 e->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(nIDi)));
919 e->setMeasurement(Sji);
921 e->information() = matLambda;
927 for(set<KeyFrame*>::const_iterator sit=sLoopEdges.begin(), send=sLoopEdges.end(); sit!=send; sit++)
934 LoopClosing::KeyFrameAndPose::const_iterator itl = NonCorrectedSim3.find(pLKF);
936 if(itl!=NonCorrectedSim3.end())
939 Slw = vScw[pLKF->
mnId];
943 el->
setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(pLKF->
mnId)));
944 el->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(nIDi)));
945 el->setMeasurement(Sli);
946 el->information() = matLambda;
953 for(vector<KeyFrame*>::const_iterator vit=vpConnectedKFs.begin(); vit!=vpConnectedKFs.end(); vit++)
956 if(pKFn && pKFn!=pParentKF && !pKF->
hasChild(pKFn) && !sLoopEdges.count(pKFn))
965 LoopClosing::KeyFrameAndPose::const_iterator itn = NonCorrectedSim3.find(pKFn);
967 if(itn!=NonCorrectedSim3.end())
970 Snw = vScw[pKFn->
mnId];
975 en->
setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(pKFn->
mnId)));
976 en->setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(nIDi)));
977 en->setMeasurement(Sni);
978 en->information() = matLambda;
992 for(
size_t i=0;i<vpKFs.size();i++)
996 const int nIDi = pKFi->
mnId;
1000 vCorrectedSwc[nIDi]=CorrectedSiw.
inverse();
1001 Eigen::Matrix3d eigR = CorrectedSiw.
rotation().toRotationMatrix();
1002 Eigen::Vector3d eigt = CorrectedSiw.
translation();
1003 double s = CorrectedSiw.
scale();
1013 for(
size_t i=0, iend=vpMPs.size(); i<iend; i++)
1028 nIDr = pRefKF->
mnId;
1033 g2o::Sim3 correctedSwr = vCorrectedSwc[nIDr];
1037 Eigen::Matrix<double,3,1> eigCorrectedP3Dw = correctedSwr.
map(Srw.
map(eigP3Dw));
1059 const cv::Mat &K1 = pKF1->
mK;
1060 const cv::Mat &K2 = pKF2->
mK;
1085 const int N = vpMatches1.size();
1087 vector<g2o::EdgeSim3ProjectXYZ*> vpEdges12;
1088 vector<g2o::EdgeInverseSim3ProjectXYZ*> vpEdges21;
1089 vector<size_t> vnIndexEdge;
1091 vnIndexEdge.reserve(2*N);
1092 vpEdges12.reserve(2*N);
1093 vpEdges21.reserve(2*N);
1095 const float deltaHuber = sqrt(th2);
1097 int nCorrespondences = 0;
1099 for(
int i=0; i<N; i++)
1107 const int id1 = 2*i+1;
1108 const int id2 = 2*(i+1);
1114 if(!pMP1->
isBad() && !pMP2->
isBad() && i2>=0)
1118 cv::Mat P3D1c = R1w*P3D1w + t1w;
1120 vPoint1->
setId(id1);
1126 cv::Mat P3D2c = R2w*P3D2w + t2w;
1128 vPoint2->
setId(id2);
1141 Eigen::Matrix<double,2,1> obs1;
1142 const cv::KeyPoint &kpUn1 = pKF1->
mvKeysUn[i];
1143 obs1 << kpUn1.pt.x, kpUn1.pt.y;
1146 e12->
setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(id2)));
1147 e12->
setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(0)));
1150 e12->
setInformation(Eigen::Matrix2d::Identity()*invSigmaSquare1);
1158 Eigen::Matrix<double,2,1> obs2;
1159 const cv::KeyPoint &kpUn2 = pKF2->
mvKeysUn[i2];
1160 obs2 << kpUn2.pt.x, kpUn2.pt.y;
1164 e21->
setVertex(0, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(id1)));
1165 e21->
setVertex(1, dynamic_cast<g2o::OptimizableGraph::Vertex*>(optimizer.
vertex(0)));
1168 e21->
setInformation(Eigen::Matrix2d::Identity()*invSigmaSquare2);
1175 vpEdges12.push_back(e12);
1176 vpEdges21.push_back(e21);
1177 vnIndexEdge.push_back(i);
1186 for(
size_t i=0; i<vpEdges12.size();i++)
1193 if(e12->
chi2()>th2 || e21->
chi2()>th2)
1195 size_t idx = vnIndexEdge[i];
1196 vpMatches1[idx]=
static_cast<MapPoint*
>(NULL);
1205 int nMoreIterations;
1211 if(nCorrespondences-nBad<10)
1217 optimizer.
optimize(nMoreIterations);
1220 for(
size_t i=0; i<vpEdges12.size();i++)
1227 if(e12->
chi2()>th2 || e21->
chi2()>th2)
1229 size_t idx = vnIndexEdge[i];
1230 vpMatches1[idx]=
static_cast<MapPoint*
>(NULL);
void EraseMapPointMatch(const size_t &idx)
static Eigen::Matrix< double, 3, 3 > toMatrix3d(const cv::Mat &cvMat3)
long unsigned int mnBALocalForKF
static int OptimizeSim3(KeyFrame *pKF1, KeyFrame *pKF2, std::vector< MapPoint * > &vpMatches1, g2o::Sim3 &g2oS12, const float th2, const bool bFixScale)
std::vector< MapPoint * > mvpMapPoints
map< KeyFrame *, g2o::Sim3, std::less< KeyFrame * >, Eigen::aligned_allocator< std::pair< KeyFrame *const, g2o::Sim3 > > > KeyFrameAndPose
long unsigned int GetMaxKFid()
BlockSolver< BlockSolverTraits< 6, 3 > > BlockSolver_6_3
const std::vector< cv::KeyPoint > mvKeysUn
long unsigned int mnBAGlobalForKF
std::vector< KeyFrame * > GetAllKeyFrames()
long unsigned int mnCorrectedByKF
static cv::Mat toCvSE3(const Eigen::Matrix< double, 3, 3 > &R, const Eigen::Matrix< double, 3, 1 > &t)
virtual double chi2() const
computes the chi2 based on the cached error value, only valid after computeError has been called...
std::mutex mMutexMapUpdate
Implementation of the Levenberg Algorithm.
int optimize(int iterations, bool online=false)
std::vector< KeyFrame * > GetCovisiblesByWeight(const int &w)
std::set< KeyFrame * > GetLoopEdges()
long unsigned int mnBAGlobalForKF
std::vector< MapPoint * > GetMapPointMatches()
std::vector< bool > mvbOutlier
const InformationType & information() const
information matrix of the constraint
virtual void setMeasurement(const Measurement &m)
void setRobustKernel(RobustKernel *ptr)
linear solver using dense cholesky decomposition
static cv::Mat toCvMat(const g2o::SE3Quat &SE3)
const Vector3d & translation() const
void setVertex(size_t i, Vertex *v)
void UpdateNormalAndDepth()
virtual void setDelta(double delta)
std::vector< cv::KeyPoint > mvKeysUn
std::vector< MapPoint * > GetAllMapPoints()
Vertex * vertex(int id)
returns the vertex number id appropriately casted
SE3 Vertex parameterized internally with a transformation matrix and externally with its exponential ...
Traits::LinearSolverType LinearSolverType
virtual void setId(int id)
sets the id of the node in the graph be sure that the graph keeps consistent after changing the id ...
static std::mutex mGlobalMutex
static void GlobalBundleAdjustemnt(Map *pMap, int nIterations=5, bool *pbStopFlag=NULL, const unsigned long nLoopKF=0, const bool bRobust=true)
const std::vector< float > mvInvLevelSigma2
virtual bool removeVertex(HyperGraph::Vertex *v)
std::map< KeyFrame *, size_t > GetObservations()
static void OptimizeEssentialGraph(Map *pMap, KeyFrame *pLoopKF, KeyFrame *pCurKF, const LoopClosing::KeyFrameAndPose &NonCorrectedSim3, const LoopClosing::KeyFrameAndPose &CorrectedSim3, const map< KeyFrame *, set< KeyFrame * > > &LoopConnections, const bool &bFixScale)
std::vector< float > mvuRight
long unsigned int mnBAFixedForKF
void setVerbose(bool verbose)
const EdgeSet & edges() const
KeyFrame * GetReferenceKeyFrame()
void setForceStopFlag(bool *flag)
void setAlgorithm(OptimizationAlgorithm *algorithm)
static Eigen::Matrix< double, 3, 1 > toVector3d(const cv::Mat &cvVector)
linear solver which uses the sparse Cholesky solver from Eigen
void SetWorldPos(const cv::Mat &Pos)
int GetWeight(KeyFrame *pKF)
static g2o::SE3Quat toSE3Quat(const cv::Mat &cvT)
Vector2d _principle_point2
Sim3 Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 7d vector (...
static void BundleAdjustment(const std::vector< KeyFrame * > &vpKF, const std::vector< MapPoint * > &vpMP, int nIterations=5, bool *pbStopFlag=NULL, const unsigned long nLoopKF=0, const bool bRobust=true)
static int PoseOptimization(Frame *pFrame)
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
void SetPose(const cv::Mat &Tcw)
std::vector< KeyFrame * > GetVectorCovisibleKeyFrames()
long unsigned int mnBALocalForKF
void setUserLambdaInit(double lambda)
specify the initial lambda used for the first iteraion, if not given the SparseOptimizer tries to com...
static void LocalBundleAdjustment(KeyFrame *pKF, bool *pbStopFlag, Map *pMap)
bool hasChild(KeyFrame *pKF)
7D edge between two Vertex7
vector< float > mvInvLevelSigma2
const double & scale() const
Vector2d _principle_point1
void setMarginalized(bool marginalized)
true => this node should be marginalized out during the optimization
BlockSolver< BlockSolverTraits< 7, 3 > > BlockSolver_7_3
const EstimateType & estimate() const
return the current estimate of the vertex
const std::vector< float > mvuRight
Implementation of a solver operating on the blocks of the Hessian.
int GetIndexInKeyFrame(KeyFrame *pKF)
void SetPose(cv::Mat Tcw)
void setFixed(bool fixed)
true => this node should be considered fixed during the optimization
void setLevel(int l)
sets the level of the edge
Vector3d map(const Vector3d &xyz) const
long unsigned int mnCorrectedReference
virtual bool initializeOptimization(HyperGraph::EdgeSet &eset)
virtual bool removeEdge(Edge *e)
removes a vertex from the graph. Returns true on success (edge was present)
void setInformation(const InformationType &information)
virtual bool addEdge(HyperGraph::Edge *e)
virtual bool addVertex(HyperGraph::Vertex *v, Data *userData)
const Quaterniond & rotation() const
BlockSolver< BlockSolverTraits< Eigen::Dynamic, Eigen::Dynamic > > BlockSolverX
void EraseObservation(KeyFrame *pKF)