cleaned up a few includes to make VSLAMGraph work properly after the move into gtsam.

release/4.3a0
Chris Beall 2009-11-10 22:49:22 +00:00
parent dc3b85e43d
commit 710d396d0b
3 changed files with 11 additions and 9 deletions

View File

@ -139,7 +139,7 @@ testSimulated3D_LDADD = libgtsam.la
check_PROGRAMS += testSimulated3D
# Visual SLAM
sources += CalibratedCamera.cpp SimpleCamera.cpp VSLAMConfig.cpp VSLAMFactor.cpp
sources += CalibratedCamera.cpp SimpleCamera.cpp VSLAMConfig.cpp VSLAMGraph.cpp VSLAMFactor.cpp
check_PROGRAMS += testCalibratedCamera testSimpleCamera testVSLAMFactor
testCalibratedCamera_SOURCES = testCalibratedCamera.cpp
testCalibratedCamera_LDADD = libgtsam.la

View File

@ -9,13 +9,14 @@
#include <fstream>
#include <boost/foreach.hpp>
//#include "VSLAMFactor.h"
#include "VSLAMGraph.h"
using namespace std;
using namespace gtsam;
namespace gtsam{
/* ************************************************************************* */
//TODO: CB: This constructor is specific to loading VO data. Should probably
// get rid of this.
VSLAMGraph::VSLAMGraph(const std::string& path)
{
ifstream ifs(path.c_str(), ios::in);
@ -98,3 +99,5 @@ VSLAMGraph::VSLAMGraph(const std::string& path,
/* ************************************************************************* */
} // namespace gtsam

View File

@ -5,7 +5,6 @@
* @author Carlos Nieto
*/
#pragma once
#include <vector>
@ -13,15 +12,13 @@
#include <set>
#include <fstream>
#include <gtsam/NonlinearFactorGraph.h>
#include <gtsam/FactorGraph-inl.h>
#include "NonlinearFactorGraph.h"
#include "FactorGraph-inl.h"
#include "VSLAMFactor.h"
#include "VSLAMFactor0.h"
#include "StereoFactor.h"
#include "VSLAMConfig.h"
using namespace std;
namespace gtsam{
/**
* Non-linear factor graph for visual SLAM
@ -64,3 +61,5 @@ public:
int Get_nFeat_ids(){return feat_ids.size();};
feat_ids_type* Get_feat_ids_map(){return &feat_ids;};
};
} // namespace gtsam