1 #ifndef SBA_BUNDLER_FILE_H     2 #define SBA_BUNDLER_FILE_H     4 #ifndef EIGEN_USE_NEW_STDVECTOR     5 #define EIGEN_USE_NEW_STDVECTOR     6 #endif // EIGEN_USE_NEW_STDVECTOR    10 #include <Eigen/Eigen>    54                   std::vector< Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > &camp, 
    55                   std::vector< Eigen::Matrix3d, Eigen::aligned_allocator<Eigen::Matrix3d> > &camR, 
    56                   std::vector< Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > &camt, 
    57                   std::vector< Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > &ptp, 
    58                   std::vector< Eigen::Vector3i, Eigen::aligned_allocator<Eigen::Vector3i> > &ptc, 
    59                   std::vector< std::vector< Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > > &ptt 
    73                   std::vector< 
Eigen::Vector5d, Eigen::aligned_allocator<Eigen::Vector5d> > &camps, 
    74                   std::vector< Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > &camqs, 
    75                   std::vector< Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > &camts, 
    76                   std::vector< Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > &ptps, 
    77                   std::vector< std::vector< 
Eigen::Vector11d, Eigen::aligned_allocator<Eigen::Vector11d> > > &ptts 
    83   void writeA(
const char *fname, SysSBA& sba); 
    91   int writeGraphFile(
const char *filename, SysSBA& sba, 
bool mono=
false);
   106    std::vector< Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > &ntrans, 
   107    std::vector< Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > &nqrot,  
   108    std::vector< Eigen::Vector2i, Eigen::aligned_allocator<Eigen::Vector2i> > &cind,   
   109    std::vector< Eigen::Vector3d, Eigen::aligned_allocator<Eigen::Vector3d> > &ctrans, 
   110    std::vector< Eigen::Vector4d, Eigen::aligned_allocator<Eigen::Vector4d> > &cqrot,  
   111    std::vector< Eigen::Matrix<double,6,6>, Eigen::aligned_allocator<Eigen::Matrix<double,6,6> > > &cvar); 
 int readGraphFile(const char *filename, sba::SysSBA &sbaout)
Reads bundle adjustment data from a graph-type file to an instance of SysSBA. 
SysSBA holds a set of nodes and points for sparse bundle adjustment. 
int ParseSPAGraphFile(const char *fin, std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &ntrans, std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > &nqrot, std::vector< Eigen::Vector2i, Eigen::aligned_allocator< Eigen::Vector2i > > &cind, std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &ctrans, std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > &cqrot, std::vector< Eigen::Matrix< double, 6, 6 >, Eigen::aligned_allocator< Eigen::Matrix< double, 6, 6 > > > &cvar)
A low-level parser for graph files. 
Matrix< double, 11, 1 > Vector11d
int readBundlerFile(const char *filename, sba::SysSBA &sbaout)
Reads bundle adjustment data from a Bundler file to an instance of SysSBA. 
int writeGraphFile(const char *filename, SysSBA &sba, bool mono=false)
Writes out the current SBA system as an ascii graph file suitable to be read in by the Freiburg HChol...
Matrix< double, 5, 1 > Vector5d
int readSPAGraphFile(const char *filename, SysSPA &spaout)
Reads 3D pose graph data from a graph-type file to an instance of SysSPA. 
void writeSparseA(const char *fname, SysSBA &sba)
int ParseBundlerFile(const char *fin, std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &camp, std::vector< Eigen::Matrix3d, Eigen::aligned_allocator< Eigen::Matrix3d > > &camR, std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &camt, std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &ptp, std::vector< Eigen::Vector3i, Eigen::aligned_allocator< Eigen::Vector3i > > &ptc, std::vector< std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > > &ptt)
A low-level parser for bundler files. 
int writeBundlerFile(const char *filename, sba::SysSBA &sbain)
Writes bundle adjustment data from an instance of SysSBA to a Bundler file. 
int ParseGraphFile(const char *fin, std::vector< Eigen::Vector5d, Eigen::aligned_allocator< Eigen::Vector5d > > &camps, std::vector< Eigen::Vector4d, Eigen::aligned_allocator< Eigen::Vector4d > > &camqs, std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &camts, std::vector< Eigen::Vector3d, Eigen::aligned_allocator< Eigen::Vector3d > > &ptps, std::vector< std::vector< Eigen::Vector11d, Eigen::aligned_allocator< Eigen::Vector11d > > > &ptts)
A low-level parser for graph files. 
void writeLourakisFile(const char *fname, SysSBA &sba)
write out system in SBA form 
void writeA(const char *fname, SysSBA &sba)